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

Merge branch 'revo-next' into corvuscorax/new_navigation

Conflicts:
	flight/Libraries/paths.c
	flight/Modules/ManualControl/manualcontrol.c
	flight/Revolution/Makefile
	shared/uavobjectdefinition/taskinfo.xml
This commit is contained in:
Corvus Corax 2012-05-30 00:51:52 +02:00
commit 298b6233ed
30 changed files with 1938 additions and 2937 deletions

View File

@ -1,5 +1,12 @@
Short summary of changes. For a complete list see the git log. Short summary of changes. For a complete list see the git log.
2012-05-26
Revert some UI changes that didn't work consistently between OSX and Windows.
2012-05-24
Merged the updated firmware for the PipXtreme, thanks to Brian for a lot of
work on this.
2012-05-04 2012-05-04
Support for CC3D. This involved changes to various things such as the sensors Support for CC3D. This involved changes to various things such as the sensors
being split from AttitudeRaw to Accels,Gyros,Magnetometer. A single firmware being split from AttitudeRaw to Accels,Gyros,Magnetometer. A single firmware

View File

@ -634,6 +634,12 @@ endef
ALL_BOARDS := coptercontrol pipxtreme revolution simposix ALL_BOARDS := coptercontrol pipxtreme revolution simposix
# SimPosix only builds on Linux so drop it from the list for
# all other platforms.
ifneq ($(UNAME), Linux)
ALL_BOARDS := $(filter-out simposix, $(ALL_BOARDS))
endif
# Friendly names of each board (used to find source tree) # Friendly names of each board (used to find source tree)
coptercontrol_friendly := CopterControl coptercontrol_friendly := CopterControl
pipxtreme_friendly := PipXtreme pipxtreme_friendly := PipXtreme

View File

@ -152,14 +152,16 @@ static void path_vector( float * start_point, float * end_point, float * cur_poi
status->error = normal[0] * diff_north + normal[1] * diff_east; status->error = normal[0] * diff_north + normal[1] * diff_east;
// Compute direction to correct error // Compute direction to correct error
status->correction_direction[0] = (status->error>0?1:-1) * -normal[0]; status->correction_direction[0] = (status->error > 0) ? -normal[0] : normal[0];
status->correction_direction[1] = (status->error>0?1:-1) * -normal[1]; status->correction_direction[1] = (status->error > 0) ? -normal[1] : normal[1];
// Now just want magnitude of error
status->error = fabs(status->error);
// Compute direction to travel // Compute direction to travel
status->path_direction[0] = path_north / dist_path; status->path_direction[0] = path_north / dist_path;
status->path_direction[1] = path_east / dist_path; status->path_direction[1] = path_east / dist_path;
status->error = fabs(status->error);
} }
/** /**

View File

@ -55,15 +55,6 @@
// //
#define SAMPLE_PERIOD_MS 500 #define SAMPLE_PERIOD_MS 500
//#define ENABLE_DEBUG_MSG
#ifdef ENABLE_DEBUG_MSG
#define DEBUG_PORT PIOS_COM_GPS
#define DEBUG_MSG(format, ...) PIOS_COM_SendFormattedString(DEBUG_PORT, format, ## __VA_ARGS__)
#else
#define DEBUG_MSG(format, ...)
#endif
// Private types // Private types
// Private variables // Private variables
@ -75,12 +66,10 @@ static void onTimer(UAVObjEvent* ev);
* Initialise the module, called on startup * Initialise the module, called on startup
* \returns 0 on success or -1 if initialisation failed * \returns 0 on success or -1 if initialisation failed
*/ */
MODULE_INITCALL(BatteryInitialize, 0)
int32_t BatteryInitialize(void) int32_t BatteryInitialize(void)
{ {
BatteryStateInitialze(); FlightBatteryStateInitialize();
BatterySettingsInitialize(); FlightBatterySettingsInitialize();
static UAVObjEvent ev; static UAVObjEvent ev;
@ -90,48 +79,23 @@ int32_t BatteryInitialize(void)
return 0; return 0;
} }
MODULE_INITCALL(BatteryInitialize, 0)
static void onTimer(UAVObjEvent* ev) static void onTimer(UAVObjEvent* ev)
{ {
static portTickType lastSysTime;
static bool firstRun = true;
static FlightBatteryStateData flightBatteryData; static FlightBatteryStateData flightBatteryData;
if (firstRun) {
#ifdef ENABLE_DEBUG_MSG
PIOS_COM_ChangeBaud(DEBUG_PORT, 57600);
#endif
lastSysTime = xTaskGetTickCount();
//FlightBatteryStateGet(&flightBatteryData);
firstRun = false;
}
AlarmsSet(SYSTEMALARMS_ALARM_BATTERY, SYSTEMALARMS_ALARM_ERROR);
portTickType thisSysTime;
FlightBatterySettingsData batterySettings; FlightBatterySettingsData batterySettings;
static float dT = SAMPLE_PERIOD_MS / 1000; static float dT = SAMPLE_PERIOD_MS / 1000.0;
float Bob;
float energyRemaining; float energyRemaining;
// Check how long since last update
thisSysTime = xTaskGetTickCount();
if(thisSysTime > lastSysTime) // reuse dt in case of wraparound
dT = (float)(thisSysTime - lastSysTime) / (float)(portTICK_RATE_MS * 1000.0f);
//lastSysTime = thisSysTime;
FlightBatterySettingsGet(&batterySettings); FlightBatterySettingsGet(&batterySettings);
//calculate the battery parameters //calculate the battery parameters
flightBatteryData.Voltage = ((float)PIOS_ADC_PinGet(2)) * batterySettings.SensorCalibrations[FLIGHTBATTERYSETTINGS_SENSORCALIBRATIONS_VOLTAGEFACTOR]; //in Volts flightBatteryData.Voltage = ((float)PIOS_ADC_PinGet(0)) * batterySettings.SensorCalibrations[FLIGHTBATTERYSETTINGS_SENSORCALIBRATIONS_VOLTAGEFACTOR]; //in Volts
flightBatteryData.Current = ((float)PIOS_ADC_PinGet(1)) * batterySettings.SensorCalibrations[FLIGHTBATTERYSETTINGS_SENSORCALIBRATIONS_CURRENTFACTOR]; //in Amps flightBatteryData.Current = ((float)PIOS_ADC_PinGet(1)) * batterySettings.SensorCalibrations[FLIGHTBATTERYSETTINGS_SENSORCALIBRATIONS_CURRENTFACTOR]; //in Amps
Bob =dT; // FIXME: something funky happens if I don't do this... Andrew
flightBatteryData.ConsumedEnergy += (flightBatteryData.Current * 1000.0 * dT / 3600.0) ;//in mAh
flightBatteryData.ConsumedEnergy += (flightBatteryData.Current * 1000.0f * dT / 3600.0f) ;//in mAh
if (flightBatteryData.Current > flightBatteryData.PeakCurrent)flightBatteryData.PeakCurrent = flightBatteryData.Current; //in Amps if (flightBatteryData.Current > flightBatteryData.PeakCurrent)flightBatteryData.PeakCurrent = flightBatteryData.Current; //in Amps
flightBatteryData.AvgCurrent=(flightBatteryData.AvgCurrent*0.8)+(flightBatteryData.Current*0.2); //in Amps flightBatteryData.AvgCurrent=(flightBatteryData.AvgCurrent*0.8)+(flightBatteryData.Current*0.2); //in Amps
@ -162,7 +126,6 @@ Bob =dT; // FIXME: something funky happens if I don't do this... Andrew
AlarmsSet(SYSTEMALARMS_ALARM_BATTERY, SYSTEMALARMS_ALARM_WARNING); AlarmsSet(SYSTEMALARMS_ALARM_BATTERY, SYSTEMALARMS_ALARM_WARNING);
else AlarmsClear(SYSTEMALARMS_ALARM_BATTERY); else AlarmsClear(SYSTEMALARMS_ALARM_BATTERY);
} }
lastSysTime = thisSysTime;
FlightBatteryStateSet(&flightBatteryData); FlightBatteryStateSet(&flightBatteryData);
} }

View File

@ -720,6 +720,10 @@ static void altitudeHoldDesired(ManualControlCommandData * cmd, bool changed)
AltitudeHoldDesiredSet(&altitudeHoldDesired); AltitudeHoldDesiredSet(&altitudeHoldDesired);
} }
#else #else
// TODO: These functions should never be accessible on CC. Any configuration that
// could allow them to be called sholud already throw an error to prevent this happening
// in flight
static void updatePathDesired(ManualControlCommandData * cmd, bool changed, bool home) static void updatePathDesired(ManualControlCommandData * cmd, bool changed, bool home)
{ {
AlarmsSet(SYSTEMALARMS_ALARM_MANUALCONTROL, SYSTEMALARMS_ALARM_ERROR); AlarmsSet(SYSTEMALARMS_ALARM_MANUALCONTROL, SYSTEMALARMS_ALARM_ERROR);

View File

@ -275,6 +275,9 @@ static void updatePIDs(UAVObjEvent* ev)
case TXPIDSETTINGS_PIDS_YAWATTITUDEILIMIT: case TXPIDSETTINGS_PIDS_YAWATTITUDEILIMIT:
needsUpdate |= update(&stab.YawPI[STABILIZATIONSETTINGS_YAWPI_ILIMIT], value); needsUpdate |= update(&stab.YawPI[STABILIZATIONSETTINGS_YAWPI_ILIMIT], value);
break; break;
case TXPIDSETTINGS_PIDS_GYROTAU:
needsUpdate |= update(&stab.GyroTau, value);
break;
default: default:
PIOS_Assert(0); PIOS_Assert(0);
} }

View File

@ -233,8 +233,25 @@ extern uint32_t pios_com_vcp_id;
//------------------------- //-------------------------
// ADC // ADC
// None. // PIOS_ADC_PinGet(0) = Current sensor
// PIOS_ADC_PinGet(1) = Voltage sensor
// PIOS_ADC_PinGet(4) = VREF
// PIOS_ADC_PinGet(5) = Temperature sensor
//------------------------- //-------------------------
#define PIOS_DMA_PIN_CONFIG \
{ \
{GPIOC, GPIO_Pin_0, ADC_Channel_10}, \
{GPIOC, GPIO_Pin_1, ADC_Channel_11}, \
{NULL, 0, ADC_Channel_Vrefint}, /* Voltage reference */ \
{NULL, 0, ADC_Channel_TempSensor} /* Temperature sensor */ \
}
/* we have to do all this to satisfy the PIOS_ADC_MAX_SAMPLES define in pios_adc.h */
/* which is annoying because this then determines the rate at which we generate buffer turnover events */
/* the objective here is to get enough buffer space to support 100Hz averaging rate */
#define PIOS_ADC_NUM_CHANNELS 4
#define PIOS_ADC_MAX_OVERSAMPLING 2
#define PIOS_ADC_USE_ADC2 0
//------------------------- //-------------------------
// USB // USB

View File

@ -78,9 +78,9 @@ struct pios_adc_dev {
volatile uint8_t adc_oversample; volatile uint8_t adc_oversample;
uint8_t dma_block_size; uint8_t dma_block_size;
uint16_t dma_half_buffer_size; uint16_t dma_half_buffer_size;
int16_t fir_coeffs[PIOS_ADC_MAX_SAMPLES+1] __attribute__ ((aligned(4))); // int16_t fir_coeffs[PIOS_ADC_MAX_SAMPLES+1] __attribute__ ((aligned(4)));
volatile int16_t raw_data_buffer[PIOS_ADC_MAX_SAMPLES] __attribute__ ((aligned(4))); // Double buffer that DMA just used // volatile int16_t raw_data_buffer[PIOS_ADC_MAX_SAMPLES] __attribute__ ((aligned(4)));
float downsampled_buffer[PIOS_ADC_NUM_CHANNELS] __attribute__ ((aligned(4))); // float downsampled_buffer[PIOS_ADC_NUM_CHANNELS] __attribute__ ((aligned(4)));
enum pios_adc_dev_magic magic; enum pios_adc_dev_magic magic;
}; };
@ -94,7 +94,6 @@ static bool PIOS_ADC_validate(struct pios_adc_dev *);
#if defined(PIOS_INCLUDE_ADC) #if defined(PIOS_INCLUDE_ADC)
static void init_pins(void); static void init_pins(void);
static void init_dma(void); static void init_dma(void);
static void init_timer(void);
static void init_adc(void); static void init_adc(void);
#endif #endif
@ -110,17 +109,15 @@ struct adc_accumulator {
}; };
#if defined(PIOS_INCLUDE_ADC) #if defined(PIOS_INCLUDE_ADC)
static struct dma_config config[] = PIOS_DMA_PIN_CONFIG; static const struct dma_config config[] = PIOS_DMA_PIN_CONFIG;
#define PIOS_ADC_NUM_PINS (sizeof(config) / sizeof(config[0])) #define PIOS_ADC_NUM_PINS (sizeof(config) / sizeof(config[0]))
static struct adc_accumulator accumulator[PIOS_ADC_NUM_PINS]; static struct adc_accumulator accumulator[PIOS_ADC_NUM_PINS];
// Two buffers here for double buffering
static uint16_t adc_raw_buffer[2][PIOS_ADC_MAX_SAMPLES][PIOS_ADC_NUM_PINS]; static uint16_t adc_raw_buffer[2][PIOS_ADC_MAX_SAMPLES][PIOS_ADC_NUM_PINS];
#endif #endif
#define PIOS_ADC_TIMER TIM3 /* might want this to come from the config */
#define PIOS_LOWRATE_ADC ADC1
#if defined(PIOS_INCLUDE_ADC) #if defined(PIOS_INCLUDE_ADC)
static void static void
init_pins(void) init_pins(void)
@ -132,6 +129,8 @@ init_pins(void)
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AIN; GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AIN;
for (int32_t i = 0; i < PIOS_ADC_NUM_PINS; i++) { for (int32_t i = 0; i < PIOS_ADC_NUM_PINS; i++) {
if (config[i].port == NULL)
continue;
GPIO_InitStructure.GPIO_Pin = config[i].pin; GPIO_InitStructure.GPIO_Pin = config[i].pin;
GPIO_Init(config[i].port, &GPIO_InitStructure); GPIO_Init(config[i].port, &GPIO_InitStructure);
} }
@ -166,48 +165,21 @@ init_dma(void)
DMA_DoubleBufferModeConfig(pios_adc_dev->cfg->dma.rx.channel, (uint32_t)&adc_raw_buffer[1], DMA_Memory_0); DMA_DoubleBufferModeConfig(pios_adc_dev->cfg->dma.rx.channel, (uint32_t)&adc_raw_buffer[1], DMA_Memory_0);
DMA_DoubleBufferModeCmd(pios_adc_dev->cfg->dma.rx.channel, ENABLE); DMA_DoubleBufferModeCmd(pios_adc_dev->cfg->dma.rx.channel, ENABLE);
DMA_ITConfig(pios_adc_dev->cfg->dma.rx.channel, DMA_IT_TC, ENABLE); DMA_ITConfig(pios_adc_dev->cfg->dma.rx.channel, DMA_IT_TC, ENABLE);
//DMA_ITConfig(pios_adc_dev->cfg->dma.rx.channel, DMA_IT_HT, ENABLE);
/* enable DMA */ /* enable DMA */
DMA_Cmd(pios_adc_dev->cfg->dma.rx.channel, ENABLE); DMA_Cmd(pios_adc_dev->cfg->dma.rx.channel, ENABLE);
/* Configure DMA interrupt */ /* Configure DMA interrupt */
NVIC_InitTypeDef NVICInit = pios_adc_dev->cfg->dma.irq.init; NVIC_InitTypeDef NVICInit = pios_adc_dev->cfg->dma.irq.init;
NVICInit.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_LOW;
NVICInit.NVIC_IRQChannelSubPriority = 0;
NVICInit.NVIC_IRQChannelCmd = ENABLE;
NVIC_Init(&NVICInit); NVIC_Init(&NVICInit);
} }
static void
init_timer(void)
{
RCC_ClocksTypeDef clocks;
TIM_TimeBaseInitTypeDef TIMInit;
/* get clock info */
RCC_GetClocksFreq(&clocks);
/* reset/disable the timer */
TIM_DeInit(PIOS_ADC_TIMER);
/* configure for 1kHz auto-reload cycle */
TIM_TimeBaseStructInit(&TIMInit);
TIMInit.TIM_Prescaler = clocks.PCLK1_Frequency / 1000000; /* 1MHz base clock*/
TIMInit.TIM_CounterMode = TIM_CounterMode_Down;
TIMInit.TIM_Period = 1000; /* 1kHz conversion rate */
TIMInit.TIM_ClockDivision = TIM_CKD_DIV1; /* no additional divisor */
TIM_TimeBaseInit(PIOS_ADC_TIMER, &TIMInit);
PIOS_COM_SendFormattedString(PIOS_COM_DEBUG, "TIM_Prescaler %d\r\n",TIMInit.TIM_Prescaler);
/* configure trigger output on reload */
TIM_SelectOutputTrigger(PIOS_ADC_TIMER, TIM_TRGOSource_Update);
TIM_Cmd(PIOS_ADC_TIMER, ENABLE);
}
static void static void
init_adc(void) init_adc(void)
{ {
RCC_APB2PeriphClockCmd(RCC_APB2Periph_ADC1, ENABLE);
ADC_DeInit(); ADC_DeInit();
/* turn on VREFInt in case we need it */ /* turn on VREFInt in case we need it */
@ -217,7 +189,7 @@ init_adc(void)
ADC_CommonInitTypeDef ADC_CommonInitStructure; ADC_CommonInitTypeDef ADC_CommonInitStructure;
ADC_CommonStructInit(&ADC_CommonInitStructure); ADC_CommonStructInit(&ADC_CommonInitStructure);
ADC_CommonInitStructure.ADC_Mode = ADC_Mode_Independent; ADC_CommonInitStructure.ADC_Mode = ADC_Mode_Independent;
ADC_CommonInitStructure.ADC_Prescaler = ADC_Prescaler_Div2; ADC_CommonInitStructure.ADC_Prescaler = ADC_Prescaler_Div8;
ADC_CommonInitStructure.ADC_DMAAccessMode = ADC_DMAAccessMode_Disabled; ADC_CommonInitStructure.ADC_DMAAccessMode = ADC_DMAAccessMode_Disabled;
ADC_CommonInitStructure.ADC_TwoSamplingDelay = ADC_TwoSamplingDelay_5Cycles; ADC_CommonInitStructure.ADC_TwoSamplingDelay = ADC_TwoSamplingDelay_5Cycles;
ADC_CommonInit(&ADC_CommonInitStructure); ADC_CommonInit(&ADC_CommonInitStructure);
@ -226,28 +198,29 @@ init_adc(void)
ADC_StructInit(&ADC_InitStructure); ADC_StructInit(&ADC_InitStructure);
ADC_InitStructure.ADC_Resolution = ADC_Resolution_12b; ADC_InitStructure.ADC_Resolution = ADC_Resolution_12b;
ADC_InitStructure.ADC_ScanConvMode = ENABLE; ADC_InitStructure.ADC_ScanConvMode = ENABLE;
ADC_InitStructure.ADC_ContinuousConvMode = DISABLE; ADC_InitStructure.ADC_ContinuousConvMode = ENABLE;
ADC_InitStructure.ADC_ExternalTrigConv = ADC_ExternalTrigConv_T3_TRGO; ADC_InitStructure.ADC_ExternalTrigConvEdge = ADC_ExternalTrigConvEdge_None;
ADC_InitStructure.ADC_ExternalTrigConvEdge = ADC_ExternalTrigConvEdge_Rising;
ADC_InitStructure.ADC_DataAlign = ADC_DataAlign_Right; ADC_InitStructure.ADC_DataAlign = ADC_DataAlign_Right;
ADC_InitStructure.ADC_NbrOfConversion = ((PIOS_ADC_NUM_PINS)/* >> 1*/); ADC_InitStructure.ADC_NbrOfConversion = ((PIOS_ADC_NUM_PINS)/* >> 1*/);
ADC_Init(PIOS_LOWRATE_ADC, &ADC_InitStructure); ADC_Init(pios_adc_dev->cfg->adc_dev, &ADC_InitStructure);
/* Enable PIOS_LOWRATE_ADC->DMA request */ /* Enable DMA request */
ADC_DMACmd(PIOS_LOWRATE_ADC, ENABLE); ADC_DMACmd(pios_adc_dev->cfg->adc_dev, ENABLE);
/* Configure input scan */ /* Configure input scan */
for (int32_t i = 0; i < PIOS_ADC_NUM_PINS; i++) { for (int32_t i = 0; i < PIOS_ADC_NUM_PINS; i++) {
ADC_RegularChannelConfig(PIOS_LOWRATE_ADC, ADC_RegularChannelConfig(pios_adc_dev->cfg->adc_dev,
config[i].channel, config[i].channel,
i+1, i+1,
ADC_SampleTime_56Cycles); /* XXX this is totally arbitrary... */ ADC_SampleTime_56Cycles); /* XXX this is totally arbitrary... */
} }
ADC_DMARequestAfterLastTransferCmd(PIOS_LOWRATE_ADC, ENABLE); ADC_DMARequestAfterLastTransferCmd(pios_adc_dev->cfg->adc_dev, ENABLE);
/* Finally start initial conversion */ /* Finally start initial conversion */
ADC_Cmd(PIOS_LOWRATE_ADC, ENABLE); ADC_Cmd(pios_adc_dev->cfg->adc_dev, ENABLE);
ADC_ContinuousModeCmd(pios_adc_dev->cfg->adc_dev, ENABLE);
ADC_SoftwareStartConv(pios_adc_dev->cfg->adc_dev);
} }
#endif #endif
@ -299,7 +272,6 @@ int32_t PIOS_ADC_Init(const struct pios_adc_cfg * cfg)
#if defined(PIOS_INCLUDE_ADC) #if defined(PIOS_INCLUDE_ADC)
init_pins(); init_pins();
init_dma(); init_dma();
init_timer();
init_adc(); init_adc();
#endif #endif
@ -321,6 +293,7 @@ void PIOS_ADC_Config(uint32_t oversampling)
* @return ADC pin value averaged over the set of samples since the last reading. * @return ADC pin value averaged over the set of samples since the last reading.
* @return -1 if pin doesn't exist * @return -1 if pin doesn't exist
*/ */
int32_t last_conv_value;
int32_t PIOS_ADC_PinGet(uint32_t pin) int32_t PIOS_ADC_PinGet(uint32_t pin)
{ {
#if defined(PIOS_INCLUDE_ADC) #if defined(PIOS_INCLUDE_ADC)
@ -432,15 +405,15 @@ void accumulate(uint16_t *buffer, uint32_t count)
// XXX should do something with this // XXX should do something with this
if (pios_adc_dev->data_queue) { if (pios_adc_dev->data_queue) {
static portBASE_TYPE xHigherPriorityTaskWoken; static portBASE_TYPE xHigherPriorityTaskWoken;
xQueueSendFromISR(pios_adc_dev->data_queue, pios_adc_dev->downsampled_buffer, &xHigherPriorityTaskWoken); // xQueueSendFromISR(pios_adc_dev->data_queue, pios_adc_dev->downsampled_buffer, &xHigherPriorityTaskWoken);
portEND_SWITCHING_ISR(xHigherPriorityTaskWoken); portEND_SWITCHING_ISR(xHigherPriorityTaskWoken);
} }
#endif #endif
#endif #endif
if(pios_adc_dev->callback_function) // if(pios_adc_dev->callback_function)
pios_adc_dev->callback_function(pios_adc_dev->downsampled_buffer); // pios_adc_dev->callback_function(pios_adc_dev->downsampled_buffer);
} }

View File

@ -37,6 +37,7 @@
#include <fifo_buffer.h> #include <fifo_buffer.h>
struct pios_adc_cfg { struct pios_adc_cfg {
ADC_TypeDef* adc_dev;
struct stm32_dma dma; struct stm32_dma dma;
uint32_t half_flag; uint32_t half_flag;
uint32_t full_flag; uint32_t full_flag;

View File

@ -50,9 +50,10 @@ FLASH_TOOL = OPENOCD
# List of modules to include # List of modules to include
MODULES = Sensors Attitude/revolution ManualControl Stabilization Actuator MODULES = Sensors Attitude/revolution ManualControl Stabilization Actuator
MODULES += Battery
MODULES += Altitude/revolution GPS FirmwareIAP MODULES += Altitude/revolution GPS FirmwareIAP
MODULES += AltitudeHold VtolPathFollower FixedWingPathFollower PathPlanner
MODULES += Airspeed/revolution MODULES += Airspeed/revolution
MODULES += AltitudeHold VtolPathFollower FixedWingPathFollower PathPlanner
MODULES += CameraStab MODULES += CameraStab
MODULES += OveroSync MODULES += OveroSync
MODULES += Telemetry MODULES += Telemetry

View File

@ -39,7 +39,7 @@
#define PIOS_INCLUDE_BL_HELPER #define PIOS_INCLUDE_BL_HELPER
/* Enable/Disable PiOS Modules */ /* Enable/Disable PiOS Modules */
//#define PIOS_INCLUDE_ADC #define PIOS_INCLUDE_ADC
#define PIOS_INCLUDE_DELAY #define PIOS_INCLUDE_DELAY
#define PIOS_INCLUDE_I2C #define PIOS_INCLUDE_I2C
#define PIOS_INCLUDE_IRQ #define PIOS_INCLUDE_IRQ

View File

@ -45,6 +45,43 @@
/** /**
* Sensor configurations * Sensor configurations
*/ */
#if defined(PIOS_INCLUDE_ADC)
#include "pios_adc_priv.h"
void PIOS_ADC_DMC_irq_handler(void);
void DMA2_Stream4_IRQHandler(void) __attribute__((alias("PIOS_ADC_DMC_irq_handler")));
struct pios_adc_cfg pios_adc_cfg = {
.adc_dev = ADC1,
.dma = {
.irq = {
.flags = (DMA_FLAG_TCIF4 | DMA_FLAG_TEIF4 | DMA_FLAG_HTIF4),
.init = {
.NVIC_IRQChannel = DMA2_Stream4_IRQn,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_LOW,
.NVIC_IRQChannelSubPriority = 0,
.NVIC_IRQChannelCmd = ENABLE,
},
},
.rx = {
.channel = DMA2_Stream4,
.init = {
.DMA_Channel = DMA_Channel_0,
.DMA_PeripheralBaseAddr = (uint32_t) & ADC1->DR
},
}
},
.half_flag = DMA_IT_HTIF4,
.full_flag = DMA_IT_TCIF4,
};
void PIOS_ADC_DMC_irq_handler(void)
{
/* Call into the generic code to handle the IRQ for this specific device */
PIOS_ADC_DMA_Handler();
}
#endif
#if defined(PIOS_INCLUDE_HMC5883) #if defined(PIOS_INCLUDE_HMC5883)
#include "pios_hmc5883.h" #include "pios_hmc5883.h"
static const struct pios_exti_cfg pios_exti_hmc5883_cfg __exti_config = { static const struct pios_exti_cfg pios_exti_hmc5883_cfg __exti_config = {
@ -788,6 +825,10 @@ void PIOS_Board_Init(void) {
PIOS_DELAY_WaitmS(50); PIOS_DELAY_WaitmS(50);
#if defined(PIOS_INCLUDE_ADC)
PIOS_ADC_Init(&pios_adc_cfg);
#endif
#if defined(PIOS_INCLUDE_HMC5883) #if defined(PIOS_INCLUDE_HMC5883)
PIOS_HMC5883_Init(&pios_hmc5883_cfg); PIOS_HMC5883_Init(&pios_hmc5883_cfg);
#endif #endif

View File

@ -6,8 +6,8 @@
<rect> <rect>
<x>0</x> <x>0</x>
<y>0</y> <y>0</y>
<width>730</width> <width>796</width>
<height>602</height> <height>605</height>
</rect> </rect>
</property> </property>
<property name="windowTitle"> <property name="windowTitle">
@ -73,25 +73,8 @@
</item> </item>
<item> <item>
<widget class="QStackedWidget" name="airframesWidget"> <widget class="QStackedWidget" name="airframesWidget">
<property name="styleSheet">
<string notr="true">#groupBox,#groupBox_2,#groupBox_3,#groupBox_6,#elevonMixBox{
background-color: qlineargradient(spread:pad, x1:0.507, y1:0.869318, x2:0.507, y2:0.0965909, stop:0 rgba(243, 243, 243, 255), stop:1 rgba(250, 250, 250, 255));
border: 1px outset #999;
border-radius: 3;
font:bold;
}
QGroupBox::title {
subcontrol-origin: margin;
subcontrol-position: top center; /* position at the top center */
padding: 0 3px;
background-color: qlineargradient(x1: 0, y1: 0, x2: 0, y2: 1,
stop: 0 #FFOECE, stop: 1 #FFFFFF);
top: 5px;
}</string>
</property>
<property name="currentIndex"> <property name="currentIndex">
<number>2</number> <number>1</number>
</property> </property>
<widget class="QWidget" name="fixedWing"> <widget class="QWidget" name="fixedWing">
<property name="enabled"> <property name="enabled">
@ -2801,14 +2784,14 @@ p, li { white-space: pre-wrap; }
<string>&lt;!DOCTYPE HTML PUBLIC &quot;-//W3C//DTD HTML 4.0//EN&quot; &quot;http://www.w3.org/TR/REC-html40/strict.dtd&quot;&gt; <string>&lt;!DOCTYPE HTML PUBLIC &quot;-//W3C//DTD HTML 4.0//EN&quot; &quot;http://www.w3.org/TR/REC-html40/strict.dtd&quot;&gt;
&lt;html&gt;&lt;head&gt;&lt;meta name=&quot;qrichtext&quot; content=&quot;1&quot; /&gt;&lt;style type=&quot;text/css&quot;&gt; &lt;html&gt;&lt;head&gt;&lt;meta name=&quot;qrichtext&quot; content=&quot;1&quot; /&gt;&lt;style type=&quot;text/css&quot;&gt;
p, li { white-space: pre-wrap; } p, li { white-space: pre-wrap; }
&lt;/style&gt;&lt;/head&gt;&lt;body style=&quot; font-family:'Ubuntu'; font-size:11pt; font-weight:400; font-style:normal;&quot;&gt; &lt;/style&gt;&lt;/head&gt;&lt;body style=&quot; font-family:'Lucida Grande'; font-size:13pt; font-weight:400; font-style:normal;&quot;&gt;
&lt;table border=&quot;0&quot; style=&quot;-qt-table-type: root; margin-top:4px; margin-bottom:4px; margin-left:4px; margin-right:4px;&quot;&gt; &lt;table border=&quot;0&quot; style=&quot;-qt-table-type: root; margin-top:4px; margin-bottom:4px; margin-left:4px; margin-right:4px;&quot;&gt;
&lt;tr&gt; &lt;tr&gt;
&lt;td style=&quot;border: none;&quot;&gt; &lt;td style=&quot;border: none;&quot;&gt;
&lt;p align=&quot;center&quot; style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:14pt; font-weight:600; color:#ff0000;&quot;&gt;SETTING UP FEED FORWARD IS DANGEROUS&lt;/span&gt;&lt;/p&gt; &lt;p align=&quot;center&quot; style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:'Ubuntu'; font-size:14pt; font-weight:600; color:#ff0000;&quot;&gt;SETTING UP FEED FORWARD IS DANGEROUS&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;/p&gt; &lt;p style=&quot;-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'Ubuntu'; font-size:11pt;&quot;&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:'Lucida Grande'; font-size:13pt;&quot;&gt;Beware: Feed Forward Tuning will launch all engines around mid-throttle, you have been warned!&lt;/span&gt;&lt;/p&gt; &lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;Beware: Feed Forward Tuning will launch all engines around mid-throttle, you have been warned!&lt;/p&gt;
&lt;p style=&quot; margin-top:12px; margin-bottom:12px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:'Lucida Grande'; font-size:13pt;&quot;&gt;Remove your props initially, and for fine-tuning, make sure your airframe is safely held in place. Wear glasses and protect your face and body.&lt;/span&gt;&lt;/p&gt;&lt;/td&gt;&lt;/tr&gt;&lt;/table&gt;&lt;/body&gt;&lt;/html&gt;</string> &lt;p style=&quot; margin-top:12px; margin-bottom:12px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;Remove your props initially, and for fine-tuning, make sure your airframe is safely held in place. Wear glasses and protect your face and body.&lt;/p&gt;&lt;/td&gt;&lt;/tr&gt;&lt;/table&gt;&lt;/body&gt;&lt;/html&gt;</string>
</property> </property>
</widget> </widget>
</item> </item>

View File

@ -7,7 +7,7 @@
<x>0</x> <x>0</x>
<y>0</y> <y>0</y>
<width>720</width> <width>720</width>
<height>567</height> <height>739</height>
</rect> </rect>
</property> </property>
<property name="windowTitle"> <property name="windowTitle">
@ -16,23 +16,6 @@
<layout class="QVBoxLayout" name="verticalLayout_3"> <layout class="QVBoxLayout" name="verticalLayout_3">
<item> <item>
<widget class="QScrollArea" name="scrollArea"> <widget class="QScrollArea" name="scrollArea">
<property name="styleSheet">
<string notr="true">#groupBox_5,#groupBox{
background-color: qlineargradient(spread:pad, x1:0.507, y1:0.869318, x2:0.507, y2:0.0965909, stop:0 rgba(243, 243, 243, 255), stop:1 rgba(250, 250, 250, 255));
border: 1px outset #999;
border-radius: 3;
font:bold;
}
QGroupBox::title {
subcontrol-origin: margin;
subcontrol-position: top center; /* position at the top center */
padding: 0 3px;
background-color: qlineargradient(x1: 0, y1: 0, x2: 0, y2: 1,
stop: 0 #FFOECE, stop: 1 #FFFFFF);
top: 5px;
}</string>
</property>
<property name="frameShape"> <property name="frameShape">
<enum>QFrame::NoFrame</enum> <enum>QFrame::NoFrame</enum>
</property> </property>
@ -44,8 +27,8 @@ QGroupBox::title {
<rect> <rect>
<x>0</x> <x>0</x>
<y>0</y> <y>0</y>
<width>702</width> <width>696</width>
<height>484</height> <height>635</height>
</rect> </rect>
</property> </property>
<layout class="QVBoxLayout" name="verticalLayout_2"> <layout class="QVBoxLayout" name="verticalLayout_2">
@ -107,7 +90,7 @@ QGroupBox::title {
<string>Basic Settings (Stabilization)</string> <string>Basic Settings (Stabilization)</string>
</property> </property>
<layout class="QGridLayout" name="gridLayout_9"> <layout class="QGridLayout" name="gridLayout_9">
<item row="3" column="3"> <item row="2" column="3">
<widget class="QSpinBox" name="yawOutputRange"> <widget class="QSpinBox" name="yawOutputRange">
<property name="focusPolicy"> <property name="focusPolicy">
<enum>Qt::StrongFocus</enum> <enum>Qt::StrongFocus</enum>
@ -126,7 +109,7 @@ have to define channel output range using Output configuration tab.</string>
</property> </property>
</widget> </widget>
</item> </item>
<item row="3" column="2"> <item row="2" column="2">
<widget class="QSpinBox" name="pitchOutputRange"> <widget class="QSpinBox" name="pitchOutputRange">
<property name="focusPolicy"> <property name="focusPolicy">
<enum>Qt::StrongFocus</enum> <enum>Qt::StrongFocus</enum>
@ -145,7 +128,7 @@ have to define channel output range using Output configuration tab.</string>
</property> </property>
</widget> </widget>
</item> </item>
<item row="3" column="1"> <item row="2" column="1">
<widget class="QSpinBox" name="rollOutputRange"> <widget class="QSpinBox" name="rollOutputRange">
<property name="focusPolicy"> <property name="focusPolicy">
<enum>Qt::StrongFocus</enum> <enum>Qt::StrongFocus</enum>
@ -164,7 +147,7 @@ have to define channel output range using Output configuration tab.</string>
</property> </property>
</widget> </widget>
</item> </item>
<item row="2" column="3"> <item row="1" column="3">
<widget class="QComboBox" name="yawChannel"> <widget class="QComboBox" name="yawChannel">
<property name="focusPolicy"> <property name="focusPolicy">
<enum>Qt::StrongFocus</enum> <enum>Qt::StrongFocus</enum>
@ -179,7 +162,7 @@ have to define channel output range using Output configuration tab.</string>
</item> </item>
</widget> </widget>
</item> </item>
<item row="2" column="2"> <item row="1" column="2">
<widget class="QComboBox" name="pitchChannel"> <widget class="QComboBox" name="pitchChannel">
<property name="focusPolicy"> <property name="focusPolicy">
<enum>Qt::StrongFocus</enum> <enum>Qt::StrongFocus</enum>
@ -194,7 +177,7 @@ have to define channel output range using Output configuration tab.</string>
</item> </item>
</widget> </widget>
</item> </item>
<item row="2" column="1"> <item row="1" column="1">
<widget class="QComboBox" name="rollChannel"> <widget class="QComboBox" name="rollChannel">
<property name="focusPolicy"> <property name="focusPolicy">
<enum>Qt::StrongFocus</enum> <enum>Qt::StrongFocus</enum>
@ -209,21 +192,21 @@ have to define channel output range using Output configuration tab.</string>
</item> </item>
</widget> </widget>
</item> </item>
<item row="2" column="0"> <item row="1" column="0">
<widget class="QLabel" name="label_42"> <widget class="QLabel" name="label_42">
<property name="text"> <property name="text">
<string>Output Channel</string> <string>Output Channel</string>
</property> </property>
</widget> </widget>
</item> </item>
<item row="3" column="0"> <item row="2" column="0">
<widget class="QLabel" name="label_43"> <widget class="QLabel" name="label_43">
<property name="text"> <property name="text">
<string>Output Range</string> <string>Output Range</string>
</property> </property>
</widget> </widget>
</item> </item>
<item row="1" column="3"> <item row="0" column="3">
<widget class="QLabel" name="label_44"> <widget class="QLabel" name="label_44">
<property name="styleSheet"> <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)); <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));
@ -240,7 +223,7 @@ margin:1px;</string>
</property> </property>
</widget> </widget>
</item> </item>
<item row="1" column="2"> <item row="0" column="2">
<widget class="QLabel" name="label_45"> <widget class="QLabel" name="label_45">
<property name="styleSheet"> <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)); <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));
@ -257,7 +240,7 @@ margin:1px;</string>
</property> </property>
</widget> </widget>
</item> </item>
<item row="1" column="1"> <item row="0" column="1">
<widget class="QLabel" name="label_46"> <widget class="QLabel" name="label_46">
<property name="styleSheet"> <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)); <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));
@ -274,38 +257,9 @@ margin:1px;</string>
</property> </property>
</widget> </widget>
</item> </item>
<item row="0" column="2">
<spacer name="verticalSpacer_4">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>40</height>
</size>
</property>
</spacer>
</item>
</layout> </layout>
</widget> </widget>
</item> </item>
<item>
<spacer name="verticalSpacer_2">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Preferred</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>10</height>
</size>
</property>
</spacer>
</item>
<item> <item>
<widget class="QGroupBox" name="groupBox"> <widget class="QGroupBox" name="groupBox">
<property name="sizePolicy"> <property name="sizePolicy">
@ -324,7 +278,7 @@ margin:1px;</string>
<string>Advanced Settings (Control)</string> <string>Advanced Settings (Control)</string>
</property> </property>
<layout class="QGridLayout" name="gridLayout_8"> <layout class="QGridLayout" name="gridLayout_8">
<item row="1" column="3"> <item row="0" column="3">
<widget class="QLabel" name="label_32"> <widget class="QLabel" name="label_32">
<property name="styleSheet"> <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)); <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));
@ -341,7 +295,7 @@ margin:1px;</string>
</property> </property>
</widget> </widget>
</item> </item>
<item row="1" column="2"> <item row="0" column="2">
<widget class="QLabel" name="label_33"> <widget class="QLabel" name="label_33">
<property name="styleSheet"> <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)); <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));
@ -358,7 +312,7 @@ margin:1px;</string>
</property> </property>
</widget> </widget>
</item> </item>
<item row="1" column="1"> <item row="0" column="1">
<widget class="QLabel" name="label_34"> <widget class="QLabel" name="label_34">
<property name="styleSheet"> <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)); <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));
@ -375,7 +329,7 @@ margin:1px;</string>
</property> </property>
</widget> </widget>
</item> </item>
<item row="2" column="3"> <item row="1" column="3">
<widget class="QComboBox" name="yawInputChannel"> <widget class="QComboBox" name="yawInputChannel">
<property name="focusPolicy"> <property name="focusPolicy">
<enum>Qt::StrongFocus</enum> <enum>Qt::StrongFocus</enum>
@ -392,7 +346,7 @@ Don't forget to map this channel using Input configuration tab.</string>
</item> </item>
</widget> </widget>
</item> </item>
<item row="2" column="2"> <item row="1" column="2">
<widget class="QComboBox" name="pitchInputChannel"> <widget class="QComboBox" name="pitchInputChannel">
<property name="focusPolicy"> <property name="focusPolicy">
<enum>Qt::StrongFocus</enum> <enum>Qt::StrongFocus</enum>
@ -409,7 +363,7 @@ Don't forget to map this channel using Input configuration tab.</string>
</item> </item>
</widget> </widget>
</item> </item>
<item row="2" column="1"> <item row="1" column="1">
<widget class="QComboBox" name="rollInputChannel"> <widget class="QComboBox" name="rollInputChannel">
<property name="focusPolicy"> <property name="focusPolicy">
<enum>Qt::StrongFocus</enum> <enum>Qt::StrongFocus</enum>
@ -426,14 +380,14 @@ Don't forget to map this channel using Input configuration tab.</string>
</item> </item>
</widget> </widget>
</item> </item>
<item row="2" column="0"> <item row="1" column="0">
<widget class="QLabel" name="label_35"> <widget class="QLabel" name="label_35">
<property name="text"> <property name="text">
<string>Input Channel</string> <string>Input Channel</string>
</property> </property>
</widget> </widget>
</item> </item>
<item row="3" column="3"> <item row="2" column="3">
<widget class="QComboBox" name="yawStabilizationMode"> <widget class="QComboBox" name="yawStabilizationMode">
<property name="focusPolicy"> <property name="focusPolicy">
<enum>Qt::StrongFocus</enum> <enum>Qt::StrongFocus</enum>
@ -451,7 +405,7 @@ AxisLock: camera remembers tracking attitude. Input controls the rate of deflect
</item> </item>
</widget> </widget>
</item> </item>
<item row="4" column="3"> <item row="3" column="3">
<widget class="QSpinBox" name="yawInputRange"> <widget class="QSpinBox" name="yawInputRange">
<property name="focusPolicy"> <property name="focusPolicy">
<enum>Qt::StrongFocus</enum> <enum>Qt::StrongFocus</enum>
@ -467,7 +421,7 @@ AxisLock: camera remembers tracking attitude. Input controls the rate of deflect
</property> </property>
</widget> </widget>
</item> </item>
<item row="5" column="3"> <item row="4" column="3">
<widget class="QSpinBox" name="yawInputRate"> <widget class="QSpinBox" name="yawInputRate">
<property name="focusPolicy"> <property name="focusPolicy">
<enum>Qt::StrongFocus</enum> <enum>Qt::StrongFocus</enum>
@ -483,7 +437,7 @@ AxisLock: camera remembers tracking attitude. Input controls the rate of deflect
</property> </property>
</widget> </widget>
</item> </item>
<item row="6" column="3"> <item row="5" column="3">
<widget class="QSpinBox" name="yawResponseTime"> <widget class="QSpinBox" name="yawResponseTime">
<property name="focusPolicy"> <property name="focusPolicy">
<enum>Qt::StrongFocus</enum> <enum>Qt::StrongFocus</enum>
@ -501,7 +455,7 @@ This option smoothes the stick input. Zero value disables LPF.</string>
</property> </property>
</widget> </widget>
</item> </item>
<item row="3" column="2"> <item row="2" column="2">
<widget class="QComboBox" name="pitchStabilizationMode"> <widget class="QComboBox" name="pitchStabilizationMode">
<property name="focusPolicy"> <property name="focusPolicy">
<enum>Qt::StrongFocus</enum> <enum>Qt::StrongFocus</enum>
@ -519,7 +473,7 @@ AxisLock: camera remembers tracking attitude. Input controls the rate of deflect
</item> </item>
</widget> </widget>
</item> </item>
<item row="4" column="2"> <item row="3" column="2">
<widget class="QSpinBox" name="pitchInputRange"> <widget class="QSpinBox" name="pitchInputRange">
<property name="focusPolicy"> <property name="focusPolicy">
<enum>Qt::StrongFocus</enum> <enum>Qt::StrongFocus</enum>
@ -535,7 +489,7 @@ AxisLock: camera remembers tracking attitude. Input controls the rate of deflect
</property> </property>
</widget> </widget>
</item> </item>
<item row="5" column="2"> <item row="4" column="2">
<widget class="QSpinBox" name="pitchInputRate"> <widget class="QSpinBox" name="pitchInputRate">
<property name="focusPolicy"> <property name="focusPolicy">
<enum>Qt::StrongFocus</enum> <enum>Qt::StrongFocus</enum>
@ -551,7 +505,7 @@ AxisLock: camera remembers tracking attitude. Input controls the rate of deflect
</property> </property>
</widget> </widget>
</item> </item>
<item row="6" column="2"> <item row="5" column="2">
<widget class="QSpinBox" name="pitchResponseTime"> <widget class="QSpinBox" name="pitchResponseTime">
<property name="focusPolicy"> <property name="focusPolicy">
<enum>Qt::StrongFocus</enum> <enum>Qt::StrongFocus</enum>
@ -569,7 +523,7 @@ This option smoothes the stick input. Zero value disables LPF.</string>
</property> </property>
</widget> </widget>
</item> </item>
<item row="3" column="1"> <item row="2" column="1">
<widget class="QComboBox" name="rollStabilizationMode"> <widget class="QComboBox" name="rollStabilizationMode">
<property name="focusPolicy"> <property name="focusPolicy">
<enum>Qt::StrongFocus</enum> <enum>Qt::StrongFocus</enum>
@ -587,7 +541,7 @@ AxisLock: camera remembers tracking attitude. Input controls the rate of deflect
</item> </item>
</widget> </widget>
</item> </item>
<item row="4" column="1"> <item row="3" column="1">
<widget class="QSpinBox" name="rollInputRange"> <widget class="QSpinBox" name="rollInputRange">
<property name="focusPolicy"> <property name="focusPolicy">
<enum>Qt::StrongFocus</enum> <enum>Qt::StrongFocus</enum>
@ -603,7 +557,7 @@ AxisLock: camera remembers tracking attitude. Input controls the rate of deflect
</property> </property>
</widget> </widget>
</item> </item>
<item row="5" column="1"> <item row="4" column="1">
<widget class="QSpinBox" name="rollInputRate"> <widget class="QSpinBox" name="rollInputRate">
<property name="focusPolicy"> <property name="focusPolicy">
<enum>Qt::StrongFocus</enum> <enum>Qt::StrongFocus</enum>
@ -619,7 +573,7 @@ AxisLock: camera remembers tracking attitude. Input controls the rate of deflect
</property> </property>
</widget> </widget>
</item> </item>
<item row="6" column="1"> <item row="5" column="1">
<widget class="QSpinBox" name="rollResponseTime"> <widget class="QSpinBox" name="rollResponseTime">
<property name="focusPolicy"> <property name="focusPolicy">
<enum>Qt::StrongFocus</enum> <enum>Qt::StrongFocus</enum>
@ -637,49 +591,49 @@ This option smoothes the stick input. Zero value disables LPF.</string>
</property> </property>
</widget> </widget>
</item> </item>
<item row="7" column="0"> <item row="6" column="0">
<widget class="QLabel" name="label_36"> <widget class="QLabel" name="label_36">
<property name="text"> <property name="text">
<string>MaxAxisLockRate</string> <string>MaxAxisLockRate</string>
</property> </property>
</widget> </widget>
</item> </item>
<item row="6" column="0"> <item row="5" column="0">
<widget class="QLabel" name="label_37"> <widget class="QLabel" name="label_37">
<property name="text"> <property name="text">
<string>Response Time</string> <string>Response Time</string>
</property> </property>
</widget> </widget>
</item> </item>
<item row="5" column="0"> <item row="4" column="0">
<widget class="QLabel" name="label_38"> <widget class="QLabel" name="label_38">
<property name="text"> <property name="text">
<string>Input Rate</string> <string>Input Rate</string>
</property> </property>
</widget> </widget>
</item> </item>
<item row="4" column="0"> <item row="3" column="0">
<widget class="QLabel" name="label_39"> <widget class="QLabel" name="label_39">
<property name="text"> <property name="text">
<string>Input Range</string> <string>Input Range</string>
</property> </property>
</widget> </widget>
</item> </item>
<item row="3" column="0"> <item row="2" column="0">
<widget class="QLabel" name="label_40"> <widget class="QLabel" name="label_40">
<property name="text"> <property name="text">
<string>Stabilization Mode</string> <string>Stabilization Mode</string>
</property> </property>
</widget> </widget>
</item> </item>
<item row="7" column="2" colspan="2"> <item row="6" column="2" colspan="2">
<widget class="QLabel" name="label_41"> <widget class="QLabel" name="label_41">
<property name="text"> <property name="text">
<string>(the same value for Roll, Pitch, Yaw)</string> <string>(the same value for Roll, Pitch, Yaw)</string>
</property> </property>
</widget> </widget>
</item> </item>
<item row="7" column="1"> <item row="6" column="1">
<widget class="QDoubleSpinBox" name="MaxAxisLockRate"> <widget class="QDoubleSpinBox" name="MaxAxisLockRate">
<property name="focusPolicy"> <property name="focusPolicy">
<enum>Qt::StrongFocus</enum> <enum>Qt::StrongFocus</enum>
@ -705,19 +659,6 @@ value.</string>
</property> </property>
</widget> </widget>
</item> </item>
<item row="0" column="2">
<spacer name="verticalSpacer_5">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>40</height>
</size>
</property>
</spacer>
</item>
</layout> </layout>
</widget> </widget>
</item> </item>

View File

@ -50,15 +50,10 @@ ConfigOutputWidget::ConfigOutputWidget(QWidget *parent) : ConfigTaskWidget(paren
m_config->setupUi(this); m_config->setupUi(this);
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
addApplySaveButtons(m_config->saveRCOutputToRAM,m_config->saveRCOutputToSD);
addUAVObject("ActuatorSettings");
UAVSettingsImportExportFactory * importexportplugin = pm->getObject<UAVSettingsImportExportFactory>(); UAVSettingsImportExportFactory * importexportplugin = pm->getObject<UAVSettingsImportExportFactory>();
connect(importexportplugin,SIGNAL(importAboutToBegin()),this,SLOT(stopTests())); connect(importexportplugin,SIGNAL(importAboutToBegin()),this,SLOT(stopTests()));
addApplySaveButtons(m_config->saveRCOutputToRAM,m_config->saveRCOutputToSD);
addUAVObject("ActuatorSettings");
// NOTE: we have channel indices from 0 to 9, but the convention for OP is Channel 1 to Channel 10. // NOTE: we have channel indices from 0 to 9, but the convention for OP is Channel 1 to Channel 10.
// Register for ActuatorSettings changes: // Register for ActuatorSettings changes:
for (unsigned int i = 0; i < ActuatorCommand::CHANNEL_NUMELEM; i++) for (unsigned int i = 0; i < ActuatorCommand::CHANNEL_NUMELEM; i++)
@ -73,25 +68,37 @@ ConfigOutputWidget::ConfigOutputWidget(QWidget *parent) : ConfigTaskWidget(paren
connect(m_config->channelOutTest, SIGNAL(toggled(bool)), this, SLOT(runChannelTests(bool))); connect(m_config->channelOutTest, SIGNAL(toggled(bool)), this, SLOT(runChannelTests(bool)));
refreshWidgetsValues();
firstUpdate = true; firstUpdate = true;
connect(m_config->spinningArmed, SIGNAL(toggled(bool)), this, SLOT(setSpinningArmed(bool))); // Configure the task widget
// Connect the help button // Connect the help button
connect(m_config->outputHelp, SIGNAL(clicked()), this, SLOT(openHelp())); connect(m_config->outputHelp, SIGNAL(clicked()), this, SLOT(openHelp()));
// Add custom handling of displaying things
connect(this,SIGNAL(refreshWidgetsValuesRequested()), this, SLOT(refreshOutputWidgetsValues()));
addApplySaveButtons(m_config->saveRCOutputToRAM,m_config->saveRCOutputToSD);
// Track the ActuatorSettings object
addUAVObject("ActuatorSettings");
// Associate the buttons with their UAVO fields
addWidget(m_config->cb_outputRate4); addWidget(m_config->cb_outputRate4);
addWidget(m_config->cb_outputRate3); addWidget(m_config->cb_outputRate3);
addWidget(m_config->cb_outputRate2); addWidget(m_config->cb_outputRate2);
addWidget(m_config->cb_outputRate1); addWidget(m_config->cb_outputRate1);
addWidget(m_config->spinningArmed); addWidget(m_config->spinningArmed);
disconnect(this, SLOT(refreshWidgetsValues(UAVObject*)));
UAVObjectManager *objManager = pm->getObject<UAVObjectManager>(); UAVObjectManager *objManager = pm->getObject<UAVObjectManager>();
UAVObject* obj = objManager->getObject(QString("ActuatorCommand")); UAVObject* obj = objManager->getObject(QString("ActuatorCommand"));
if(UAVObject::GetGcsTelemetryUpdateMode(obj->getMetadata()) == UAVObject::UPDATEMODE_ONCHANGE) if(UAVObject::GetGcsTelemetryUpdateMode(obj->getMetadata()) == UAVObject::UPDATEMODE_ONCHANGE)
this->setEnabled(false); this->setEnabled(false);
connect(obj,SIGNAL(objectUpdated(UAVObject*)),this,SLOT(disableIfNotMe(UAVObject*))); connect(obj,SIGNAL(objectUpdated(UAVObject*)),this,SLOT(disableIfNotMe(UAVObject*)));
refreshWidgetsValues();
} }
void ConfigOutputWidget::enableControls(bool enable) void ConfigOutputWidget::enableControls(bool enable)
{ {
@ -196,24 +203,6 @@ void ConfigOutputWidget::assignOutputChannel(UAVDataObject *obj, QString str)
outputChannelForm->setAssignment(str); outputChannelForm->setAssignment(str);
} }
/**
* Set the "Spin motors at neutral when armed" flag in ActuatorSettings
*/
void ConfigOutputWidget::setSpinningArmed(bool val)
{
ActuatorSettings *actuatorSettings = ActuatorSettings::GetInstance(getObjectManager());
Q_ASSERT(actuatorSettings);
ActuatorSettings::DataFields actuatorSettingsData = actuatorSettings->getData();
if(val)
actuatorSettingsData.MotorsSpinWhileArmed = ActuatorSettings::MOTORSSPINWHILEARMED_TRUE;
else
actuatorSettingsData.MotorsSpinWhileArmed = ActuatorSettings::MOTORSSPINWHILEARMED_FALSE;
// Apply settings
actuatorSettings->setData(actuatorSettingsData);
}
/** /**
Sends the channel value to the UAV to move the servo. Sends the channel value to the UAV to move the servo.
Returns immediately if we are not in testing mode Returns immediately if we are not in testing mode
@ -242,10 +231,8 @@ void ConfigOutputWidget::sendChannelTest(int index, int value)
/** /**
Request the current config from the board (RC Output) Request the current config from the board (RC Output)
*/ */
void ConfigOutputWidget::refreshWidgetsValues(UAVObject *) void ConfigOutputWidget::refreshOutputWidgetsValues(UAVObject *)
{ {
bool dirty=isDirty();
// Reset all channel assignements: // Reset all channel assignements:
QList<OutputChannelForm*> outputChannelForms = findChildren<OutputChannelForm*>(); QList<OutputChannelForm*> outputChannelForms = findChildren<OutputChannelForm*>();
foreach(OutputChannelForm *outputChannelForm, outputChannelForms) foreach(OutputChannelForm *outputChannelForm, outputChannelForms)
@ -338,8 +325,6 @@ void ConfigOutputWidget::refreshWidgetsValues(UAVObject *)
int neutral = actuatorSettingsData.ChannelNeutral[outputChannelForm->index()]; int neutral = actuatorSettingsData.ChannelNeutral[outputChannelForm->index()];
outputChannelForm->neutral(neutral); outputChannelForm->neutral(neutral);
} }
setDirty(dirty);
} }
/** /**
@ -347,8 +332,11 @@ void ConfigOutputWidget::refreshWidgetsValues(UAVObject *)
*/ */
void ConfigOutputWidget::updateObjectsFromWidgets() void ConfigOutputWidget::updateObjectsFromWidgets()
{ {
emit updateObjectsFromWidgetsRequested();
ActuatorSettings *actuatorSettings = ActuatorSettings::GetInstance(getObjectManager()); ActuatorSettings *actuatorSettings = ActuatorSettings::GetInstance(getObjectManager());
Q_ASSERT(actuatorSettings); Q_ASSERT(actuatorSettings);
if(actuatorSettings) {
ActuatorSettings::DataFields actuatorSettingsData = actuatorSettings->getData(); ActuatorSettings::DataFields actuatorSettingsData = actuatorSettings->getData();
// Set channel ranges // Set channel ranges
@ -365,8 +353,15 @@ void ConfigOutputWidget::updateObjectsFromWidgets()
actuatorSettingsData.ChannelUpdateFreq[1] = m_config->cb_outputRate2->currentText().toUInt(); actuatorSettingsData.ChannelUpdateFreq[1] = m_config->cb_outputRate2->currentText().toUInt();
actuatorSettingsData.ChannelUpdateFreq[2] = m_config->cb_outputRate3->currentText().toUInt(); actuatorSettingsData.ChannelUpdateFreq[2] = m_config->cb_outputRate3->currentText().toUInt();
actuatorSettingsData.ChannelUpdateFreq[3] = m_config->cb_outputRate4->currentText().toUInt(); actuatorSettingsData.ChannelUpdateFreq[3] = m_config->cb_outputRate4->currentText().toUInt();
if(m_config->spinningArmed->isChecked() == true)
actuatorSettingsData.MotorsSpinWhileArmed = ActuatorSettings::MOTORSSPINWHILEARMED_TRUE;
else
actuatorSettingsData.MotorsSpinWhileArmed = ActuatorSettings::MOTORSSPINWHILEARMED_FALSE;
// Apply settings // Apply settings
actuatorSettings->setData(actuatorSettingsData); actuatorSettings->setData(actuatorSettingsData);
}
} }
void ConfigOutputWidget::openHelp() void ConfigOutputWidget::openHelp()

View File

@ -69,11 +69,10 @@ private:
private slots: private slots:
void stopTests(); void stopTests();
void disableIfNotMe(UAVObject *obj); void disableIfNotMe(UAVObject *obj);
virtual void refreshWidgetsValues(UAVObject * obj = NULL); void refreshOutputWidgetsValues(UAVObject * obj = NULL);
void updateObjectsFromWidgets(); void updateObjectsFromWidgets();
void runChannelTests(bool state); void runChannelTests(bool state);
void sendChannelTest(int index, int value); void sendChannelTest(int index, int value);
void setSpinningArmed(bool val);
void openHelp(); void openHelp();
protected: protected:
void enableControls(bool enable); void enableControls(bool enable);

View File

@ -97,6 +97,9 @@ ConfigPipXtremeWidget::ConfigPipXtremeWidget(QWidget *parent) : ConfigTaskWidget
// Request and update of the setting object. // Request and update of the setting object.
settingsUpdated = false; settingsUpdated = false;
pipxSettingsObj->requestUpdate(); pipxSettingsObj->requestUpdate();
disableMouseWheelEvents();
} }
ConfigPipXtremeWidget::~ConfigPipXtremeWidget() ConfigPipXtremeWidget::~ConfigPipXtremeWidget()

View File

@ -40,6 +40,11 @@ ConfigStabilizationWidget::ConfigStabilizationWidget(QWidget *parent) : ConfigTa
{ {
m_stabilization = new Ui_StabilizationWidget(); m_stabilization = new Ui_StabilizationWidget();
m_stabilization->setupUi(this); m_stabilization->setupUi(this);
// To bring old style sheet back without adding it manually do this:
// Alternatively apply a global stylesheet to the QGroupBox
// setStyleSheet("QGroupBox {background-color: qlineargradient(spread:pad, x1:0.507, y1:0.869318, x2:0.507, y2:0.0965909, stop:0 rgba(243, 243, 243, 255), stop:1 rgba(250, 250, 250, 255)); border: 1px outset #999; border-radius: 3; }");
autoLoadWidgets(); autoLoadWidgets();
realtimeUpdates=new QTimer(this); realtimeUpdates=new QTimer(this);
connect(m_stabilization->realTimeUpdates_6,SIGNAL(stateChanged(int)),this,SLOT(realtimeUpdatesSlot(int))); connect(m_stabilization->realTimeUpdates_6,SIGNAL(stateChanged(int)),this,SLOT(realtimeUpdatesSlot(int)));
@ -54,6 +59,24 @@ ConfigStabilizationWidget::ConfigStabilizationWidget(QWidget *parent) : ConfigTa
connect(this,SIGNAL(widgetContentsChanged(QWidget*)),this,SLOT(processLinkedWidgets(QWidget*))); connect(this,SIGNAL(widgetContentsChanged(QWidget*)),this,SLOT(processLinkedWidgets(QWidget*)));
disableMouseWheelEvents(); disableMouseWheelEvents();
// This is needed because new style tries to compact things as much as possible in grid
// and on OSX the widget sizes of PushButtons is reported incorrectly:
// https://bugreports.qt-project.org/browse/QTBUG-14591
m_stabilization->saveStabilizationToRAM_6->setAttribute(Qt::WA_LayoutUsesWidgetRect);
m_stabilization->saveStabilizationToSD_6->setAttribute(Qt::WA_LayoutUsesWidgetRect);
m_stabilization->stabilizationReloadBoardData_6->setAttribute(Qt::WA_LayoutUsesWidgetRect);
m_stabilization->saveStabilizationToRAM_7->setAttribute(Qt::WA_LayoutUsesWidgetRect);
m_stabilization->saveStabilizationToSD_7->setAttribute(Qt::WA_LayoutUsesWidgetRect);
m_stabilization->pushButton_2->setAttribute(Qt::WA_LayoutUsesWidgetRect);
m_stabilization->pushButton_3->setAttribute(Qt::WA_LayoutUsesWidgetRect);
m_stabilization->pushButton_4->setAttribute(Qt::WA_LayoutUsesWidgetRect);
m_stabilization->pushButton_19->setAttribute(Qt::WA_LayoutUsesWidgetRect);
m_stabilization->pushButton_20->setAttribute(Qt::WA_LayoutUsesWidgetRect);
m_stabilization->pushButton_21->setAttribute(Qt::WA_LayoutUsesWidgetRect);
m_stabilization->pushButton_22->setAttribute(Qt::WA_LayoutUsesWidgetRect);
m_stabilization->pushButton_23->setAttribute(Qt::WA_LayoutUsesWidgetRect);
m_stabilization->pushButton_24->setAttribute(Qt::WA_LayoutUsesWidgetRect);
} }

View File

@ -16,23 +16,6 @@
<layout class="QVBoxLayout" name="verticalLayout"> <layout class="QVBoxLayout" name="verticalLayout">
<item> <item>
<widget class="QTabWidget" name="tabWidget"> <widget class="QTabWidget" name="tabWidget">
<property name="styleSheet">
<string notr="true">#groupBox_2,#groupBox{
background-color: qlineargradient(spread:pad, x1:0.507, y1:0.869318, x2:0.507, y2:0.0965909, stop:0 rgba(243, 243, 243, 255), stop:1 rgba(250, 250, 250, 255));
border: 1px outset #999;
border-radius: 3;
font:bold;
}
QGroupBox::title {
subcontrol-origin: margin;
subcontrol-position: top center; /* position at the top center */
padding: 0 3px;
background-color: qlineargradient(x1: 0, y1: 0, x2: 0, y2: 1,
stop: 0 #FFOECE, stop: 1 #FFFFFF);
top: 5px;
}</string>
</property>
<property name="currentIndex"> <property name="currentIndex">
<number>0</number> <number>0</number>
</property> </property>
@ -246,7 +229,7 @@ QGroupBox::title {
<x>30</x> <x>30</x>
<y>160</y> <y>160</y>
<width>451</width> <width>451</width>
<height>141</height> <height>161</height>
</rect> </rect>
</property> </property>
<property name="styleSheet"> <property name="styleSheet">
@ -442,9 +425,6 @@ margin:1px;</string>
<height>121</height> <height>121</height>
</rect> </rect>
</property> </property>
<property name="styleSheet">
<string notr="true"/>
</property>
<property name="title"> <property name="title">
<string>FlightMode Switch Positions</string> <string>FlightMode Switch Positions</string>
</property> </property>

View File

@ -23,6 +23,96 @@
<enum>QFrame::Raised</enum> <enum>QFrame::Raised</enum>
</property> </property>
<layout class="QGridLayout" name="gridLayout"> <layout class="QGridLayout" name="gridLayout">
<item row="1" column="0" colspan="2">
<layout class="QHBoxLayout" name="horizontalLayout_12">
<item>
<widget class="QGraphicsView" name="graphicsView_Spectrum">
<property name="backgroundBrush">
<brush brushstyle="NoBrush">
<color alpha="255">
<red>0</red>
<green>0</green>
<blue>0</blue>
</color>
</brush>
</property>
<property name="foregroundBrush">
<brush brushstyle="NoBrush">
<color alpha="255">
<red>0</red>
<green>0</green>
<blue>0</blue>
</color>
</brush>
</property>
<property name="interactive">
<bool>true</bool>
</property>
</widget>
</item>
</layout>
</item>
<item row="2" column="0" colspan="2">
<layout class="QVBoxLayout" name="verticalLayout">
<item>
<widget class="QLabel" name="message">
<property name="text">
<string/>
</property>
</widget>
</item>
<item>
<layout class="QHBoxLayout" name="submitButtons">
<item>
<widget class="QFrame" name="frame">
<property name="frameShape">
<enum>QFrame::StyledPanel</enum>
</property>
<property name="frameShadow">
<enum>QFrame::Raised</enum>
</property>
</widget>
</item>
<item>
<spacer name="horizontalSpacer">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item>
<widget class="QPushButton" name="Apply">
<property name="toolTip">
<string>Send settings to the board but do not save to the non-volatile memory</string>
</property>
<property name="text">
<string>Apply</string>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="Save">
<property name="toolTip">
<string>Send settings to the board and save to the non-volatile memory</string>
</property>
<property name="text">
<string>Save</string>
</property>
<property name="checked">
<bool>false</bool>
</property>
</widget>
</item>
</layout>
</item>
</layout>
</item>
<item row="0" column="0"> <item row="0" column="0">
<widget class="QFrame" name="frame_2"> <widget class="QFrame" name="frame_2">
<property name="frameShape"> <property name="frameShape">
@ -1216,106 +1306,54 @@
</layout> </layout>
</widget> </widget>
</item> </item>
<item row="1" column="0" colspan="2">
<layout class="QHBoxLayout" name="horizontalLayout_12">
<item>
<widget class="QGraphicsView" name="graphicsView_Spectrum">
<property name="backgroundBrush">
<brush brushstyle="NoBrush">
<color alpha="255">
<red>0</red>
<green>0</green>
<blue>0</blue>
</color>
</brush>
</property>
<property name="foregroundBrush">
<brush brushstyle="NoBrush">
<color alpha="255">
<red>0</red>
<green>0</green>
<blue>0</blue>
</color>
</brush>
</property>
<property name="interactive">
<bool>true</bool>
</property>
</widget>
</item>
</layout> </layout>
</item>
<item row="2" column="0" colspan="2">
<layout class="QVBoxLayout" name="verticalLayout">
<item>
<widget class="QLabel" name="message">
<property name="text">
<string/>
</property>
</widget>
</item>
<item>
<layout class="QHBoxLayout" name="submitButtons">
<item>
<widget class="QFrame" name="frame">
<property name="frameShape">
<enum>QFrame::StyledPanel</enum>
</property>
<property name="frameShadow">
<enum>QFrame::Raised</enum>
</property>
</widget>
</item>
<item>
<spacer name="horizontalSpacer">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item>
<widget class="QPushButton" name="Apply">
<property name="toolTip">
<string>Send settings to the board but do not save to the non-volatile memory</string>
</property>
<property name="text">
<string>Apply</string>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="Save">
<property name="toolTip">
<string>Send settings to the board and save to the non-volatile memory</string>
</property>
<property name="text">
<string>Save</string>
</property>
<property name="checked">
<bool>false</bool>
</property>
</widget>
</item>
</layout>
</item>
</layout>
</item>
</layout>
<zorder>frame_2</zorder>
<zorder>groupBox</zorder>
<zorder>layoutWidget</zorder>
<zorder>layoutWidget_2</zorder>
<zorder>graphicsView_Spectrum</zorder>
</widget> </widget>
</item> </item>
</layout> </layout>
</widget> </widget>
<tabstops>
<tabstop>PairSelect1</tabstop>
<tabstop>PairID1</tabstop>
<tabstop>PairSelect2</tabstop>
<tabstop>PairID2</tabstop>
<tabstop>PairSelect3</tabstop>
<tabstop>PairID3</tabstop>
<tabstop>PairSelect4</tabstop>
<tabstop>PairID4</tabstop>
<tabstop>FirmwareVersion</tabstop>
<tabstop>SerialNumber</tabstop>
<tabstop>DeviceID</tabstop>
<tabstop>MinFrequency</tabstop>
<tabstop>MaxFrequency</tabstop>
<tabstop>FrequencyStepSize</tabstop>
<tabstop>LinkState</tabstop>
<tabstop>RxAFC</tabstop>
<tabstop>Retries</tabstop>
<tabstop>Errors</tabstop>
<tabstop>UAVTalkErrors</tabstop>
<tabstop>Resets</tabstop>
<tabstop>TXRate</tabstop>
<tabstop>RXRate</tabstop>
<tabstop>TelemPortConfig</tabstop>
<tabstop>TelemPortSpeed</tabstop>
<tabstop>FlexiPortConfig</tabstop>
<tabstop>FlexiPortSpeed</tabstop>
<tabstop>VCPConfig</tabstop>
<tabstop>VCPSpeed</tabstop>
<tabstop>MaxRFDatarate</tabstop>
<tabstop>MaxRFTxPower</tabstop>
<tabstop>SendTimeout</tabstop>
<tabstop>MinPacketSize</tabstop>
<tabstop>FrequencyCalibration</tabstop>
<tabstop>Frequency</tabstop>
<tabstop>ScanSpectrum</tabstop>
<tabstop>AESKey</tabstop>
<tabstop>AESKeyRandom</tabstop>
<tabstop>AESEnable</tabstop>
<tabstop>graphicsView_Spectrum</tabstop>
<tabstop>Apply</tabstop>
<tabstop>Save</tabstop>
</tabstops>
<resources/> <resources/>
<connections/> <connections/>
</ui> </ui>

View File

@ -495,29 +495,13 @@
<property name="geometry"> <property name="geometry">
<rect> <rect>
<x>0</x> <x>0</x>
<y>0</y> <y>-114</y>
<width>673</width> <width>673</width>
<height>880</height> <height>790</height>
</rect> </rect>
</property> </property>
<layout class="QGridLayout" name="gridLayout_23"> <layout class="QGridLayout" name="gridLayout_23">
<item row="0" column="3"> <item row="0" column="0">
<spacer name="verticalSpacer_6">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Fixed</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>10</height>
</size>
</property>
</spacer>
</item>
<item row="1" column="1">
<spacer name="horizontalSpacer_15"> <spacer name="horizontalSpacer_15">
<property name="orientation"> <property name="orientation">
<enum>Qt::Horizontal</enum> <enum>Qt::Horizontal</enum>
@ -533,7 +517,7 @@
</property> </property>
</spacer> </spacer>
</item> </item>
<item row="1" column="2"> <item row="0" column="1">
<widget class="QLabel" name="label_137"> <widget class="QLabel" name="label_137">
<property name="minimumSize"> <property name="minimumSize">
<size> <size>
@ -541,19 +525,12 @@
<height>16</height> <height>16</height>
</size> </size>
</property> </property>
<property name="font">
<font>
<pointsize>9</pointsize>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="text"> <property name="text">
<string>Rate Stabilization (Inner Loop)</string> <string>Rate Stabilization (Inner Loop)</string>
</property> </property>
</widget> </widget>
</item> </item>
<item row="2" column="1" colspan="4"> <item row="1" column="0" colspan="3">
<widget class="QGroupBox" name="RateStabilizationGroup_15"> <widget class="QGroupBox" name="RateStabilizationGroup_15">
<property name="sizePolicy"> <property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Fixed"> <sizepolicy hsizetype="Preferred" vsizetype="Fixed">
@ -573,530 +550,6 @@
<height>181</height> <height>181</height>
</size> </size>
</property> </property>
<property name="palette">
<palette>
<active>
<colorrole role="WindowText">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>0</red>
<green>0</green>
<blue>0</blue>
</color>
</brush>
</colorrole>
<colorrole role="Button">
<brush brushstyle="LinearGradientPattern">
<gradient startx="0.507000000000000" starty="0.869318000000000" endx="0.507000000000000" endy="0.096590900000000" type="LinearGradient" spread="PadSpread" coordinatemode="ObjectBoundingMode">
<gradientstop position="0.000000000000000">
<color alpha="255">
<red>243</red>
<green>243</green>
<blue>243</blue>
</color>
</gradientstop>
<gradientstop position="1.000000000000000">
<color alpha="255">
<red>250</red>
<green>250</green>
<blue>250</blue>
</color>
</gradientstop>
</gradient>
</brush>
</colorrole>
<colorrole role="Light">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>255</red>
<green>255</green>
<blue>255</blue>
</color>
</brush>
</colorrole>
<colorrole role="Midlight">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>251</red>
<green>251</green>
<blue>251</blue>
</color>
</brush>
</colorrole>
<colorrole role="Dark">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>124</red>
<green>124</green>
<blue>124</blue>
</color>
</brush>
</colorrole>
<colorrole role="Mid">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>165</red>
<green>165</green>
<blue>165</blue>
</color>
</brush>
</colorrole>
<colorrole role="Text">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>0</red>
<green>0</green>
<blue>0</blue>
</color>
</brush>
</colorrole>
<colorrole role="BrightText">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>255</red>
<green>255</green>
<blue>255</blue>
</color>
</brush>
</colorrole>
<colorrole role="ButtonText">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>0</red>
<green>0</green>
<blue>0</blue>
</color>
</brush>
</colorrole>
<colorrole role="Base">
<brush brushstyle="LinearGradientPattern">
<gradient startx="0.507000000000000" starty="0.869318000000000" endx="0.507000000000000" endy="0.096590900000000" type="LinearGradient" spread="PadSpread" coordinatemode="ObjectBoundingMode">
<gradientstop position="0.000000000000000">
<color alpha="255">
<red>243</red>
<green>243</green>
<blue>243</blue>
</color>
</gradientstop>
<gradientstop position="1.000000000000000">
<color alpha="255">
<red>250</red>
<green>250</green>
<blue>250</blue>
</color>
</gradientstop>
</gradient>
</brush>
</colorrole>
<colorrole role="Window">
<brush brushstyle="LinearGradientPattern">
<gradient startx="0.507000000000000" starty="0.869318000000000" endx="0.507000000000000" endy="0.096590900000000" type="LinearGradient" spread="PadSpread" coordinatemode="ObjectBoundingMode">
<gradientstop position="0.000000000000000">
<color alpha="255">
<red>243</red>
<green>243</green>
<blue>243</blue>
</color>
</gradientstop>
<gradientstop position="1.000000000000000">
<color alpha="255">
<red>250</red>
<green>250</green>
<blue>250</blue>
</color>
</gradientstop>
</gradient>
</brush>
</colorrole>
<colorrole role="Shadow">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>0</red>
<green>0</green>
<blue>0</blue>
</color>
</brush>
</colorrole>
<colorrole role="AlternateBase">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>251</red>
<green>251</green>
<blue>251</blue>
</color>
</brush>
</colorrole>
<colorrole role="ToolTipBase">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>255</red>
<green>255</green>
<blue>220</blue>
</color>
</brush>
</colorrole>
<colorrole role="ToolTipText">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>0</red>
<green>0</green>
<blue>0</blue>
</color>
</brush>
</colorrole>
</active>
<inactive>
<colorrole role="WindowText">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>0</red>
<green>0</green>
<blue>0</blue>
</color>
</brush>
</colorrole>
<colorrole role="Button">
<brush brushstyle="LinearGradientPattern">
<gradient startx="0.507000000000000" starty="0.869318000000000" endx="0.507000000000000" endy="0.096590900000000" type="LinearGradient" spread="PadSpread" coordinatemode="ObjectBoundingMode">
<gradientstop position="0.000000000000000">
<color alpha="255">
<red>243</red>
<green>243</green>
<blue>243</blue>
</color>
</gradientstop>
<gradientstop position="1.000000000000000">
<color alpha="255">
<red>250</red>
<green>250</green>
<blue>250</blue>
</color>
</gradientstop>
</gradient>
</brush>
</colorrole>
<colorrole role="Light">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>255</red>
<green>255</green>
<blue>255</blue>
</color>
</brush>
</colorrole>
<colorrole role="Midlight">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>251</red>
<green>251</green>
<blue>251</blue>
</color>
</brush>
</colorrole>
<colorrole role="Dark">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>124</red>
<green>124</green>
<blue>124</blue>
</color>
</brush>
</colorrole>
<colorrole role="Mid">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>165</red>
<green>165</green>
<blue>165</blue>
</color>
</brush>
</colorrole>
<colorrole role="Text">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>0</red>
<green>0</green>
<blue>0</blue>
</color>
</brush>
</colorrole>
<colorrole role="BrightText">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>255</red>
<green>255</green>
<blue>255</blue>
</color>
</brush>
</colorrole>
<colorrole role="ButtonText">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>0</red>
<green>0</green>
<blue>0</blue>
</color>
</brush>
</colorrole>
<colorrole role="Base">
<brush brushstyle="LinearGradientPattern">
<gradient startx="0.507000000000000" starty="0.869318000000000" endx="0.507000000000000" endy="0.096590900000000" type="LinearGradient" spread="PadSpread" coordinatemode="ObjectBoundingMode">
<gradientstop position="0.000000000000000">
<color alpha="255">
<red>243</red>
<green>243</green>
<blue>243</blue>
</color>
</gradientstop>
<gradientstop position="1.000000000000000">
<color alpha="255">
<red>250</red>
<green>250</green>
<blue>250</blue>
</color>
</gradientstop>
</gradient>
</brush>
</colorrole>
<colorrole role="Window">
<brush brushstyle="LinearGradientPattern">
<gradient startx="0.507000000000000" starty="0.869318000000000" endx="0.507000000000000" endy="0.096590900000000" type="LinearGradient" spread="PadSpread" coordinatemode="ObjectBoundingMode">
<gradientstop position="0.000000000000000">
<color alpha="255">
<red>243</red>
<green>243</green>
<blue>243</blue>
</color>
</gradientstop>
<gradientstop position="1.000000000000000">
<color alpha="255">
<red>250</red>
<green>250</green>
<blue>250</blue>
</color>
</gradientstop>
</gradient>
</brush>
</colorrole>
<colorrole role="Shadow">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>0</red>
<green>0</green>
<blue>0</blue>
</color>
</brush>
</colorrole>
<colorrole role="AlternateBase">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>251</red>
<green>251</green>
<blue>251</blue>
</color>
</brush>
</colorrole>
<colorrole role="ToolTipBase">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>255</red>
<green>255</green>
<blue>220</blue>
</color>
</brush>
</colorrole>
<colorrole role="ToolTipText">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>0</red>
<green>0</green>
<blue>0</blue>
</color>
</brush>
</colorrole>
</inactive>
<disabled>
<colorrole role="WindowText">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>124</red>
<green>124</green>
<blue>124</blue>
</color>
</brush>
</colorrole>
<colorrole role="Button">
<brush brushstyle="LinearGradientPattern">
<gradient startx="0.507000000000000" starty="0.869318000000000" endx="0.507000000000000" endy="0.096590900000000" type="LinearGradient" spread="PadSpread" coordinatemode="ObjectBoundingMode">
<gradientstop position="0.000000000000000">
<color alpha="255">
<red>243</red>
<green>243</green>
<blue>243</blue>
</color>
</gradientstop>
<gradientstop position="1.000000000000000">
<color alpha="255">
<red>250</red>
<green>250</green>
<blue>250</blue>
</color>
</gradientstop>
</gradient>
</brush>
</colorrole>
<colorrole role="Light">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>255</red>
<green>255</green>
<blue>255</blue>
</color>
</brush>
</colorrole>
<colorrole role="Midlight">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>251</red>
<green>251</green>
<blue>251</blue>
</color>
</brush>
</colorrole>
<colorrole role="Dark">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>124</red>
<green>124</green>
<blue>124</blue>
</color>
</brush>
</colorrole>
<colorrole role="Mid">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>165</red>
<green>165</green>
<blue>165</blue>
</color>
</brush>
</colorrole>
<colorrole role="Text">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>124</red>
<green>124</green>
<blue>124</blue>
</color>
</brush>
</colorrole>
<colorrole role="BrightText">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>255</red>
<green>255</green>
<blue>255</blue>
</color>
</brush>
</colorrole>
<colorrole role="ButtonText">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>124</red>
<green>124</green>
<blue>124</blue>
</color>
</brush>
</colorrole>
<colorrole role="Base">
<brush brushstyle="LinearGradientPattern">
<gradient startx="0.507000000000000" starty="0.869318000000000" endx="0.507000000000000" endy="0.096590900000000" type="LinearGradient" spread="PadSpread" coordinatemode="ObjectBoundingMode">
<gradientstop position="0.000000000000000">
<color alpha="255">
<red>243</red>
<green>243</green>
<blue>243</blue>
</color>
</gradientstop>
<gradientstop position="1.000000000000000">
<color alpha="255">
<red>250</red>
<green>250</green>
<blue>250</blue>
</color>
</gradientstop>
</gradient>
</brush>
</colorrole>
<colorrole role="Window">
<brush brushstyle="LinearGradientPattern">
<gradient startx="0.507000000000000" starty="0.869318000000000" endx="0.507000000000000" endy="0.096590900000000" type="LinearGradient" spread="PadSpread" coordinatemode="ObjectBoundingMode">
<gradientstop position="0.000000000000000">
<color alpha="255">
<red>243</red>
<green>243</green>
<blue>243</blue>
</color>
</gradientstop>
<gradientstop position="1.000000000000000">
<color alpha="255">
<red>250</red>
<green>250</green>
<blue>250</blue>
</color>
</gradientstop>
</gradient>
</brush>
</colorrole>
<colorrole role="Shadow">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>0</red>
<green>0</green>
<blue>0</blue>
</color>
</brush>
</colorrole>
<colorrole role="AlternateBase">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>248</red>
<green>248</green>
<blue>248</blue>
</color>
</brush>
</colorrole>
<colorrole role="ToolTipBase">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>255</red>
<green>255</green>
<blue>220</blue>
</color>
</brush>
</colorrole>
<colorrole role="ToolTipText">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>0</red>
<green>0</green>
<blue>0</blue>
</color>
</brush>
</colorrole>
</disabled>
</palette>
</property>
<property name="autoFillBackground">
<bool>false</bool>
</property>
<property name="styleSheet">
<string notr="true">#RateStabilizationGroup_15{background-color: qlineargradient(spread:pad, x1:0.507, y1:0.869318, x2:0.507, y2:0.0965909, stop:0 rgba(243, 243, 243, 255), stop:1 rgba(250, 250, 250, 255));
border: 1px outset #999;
border-radius: 3;
}</string>
</property>
<property name="title"> <property name="title">
<string/> <string/>
</property> </property>
@ -3966,23 +3419,7 @@ value as the Kp.</string>
</layout> </layout>
</widget> </widget>
</item> </item>
<item row="3" column="2"> <item row="2" column="0">
<spacer name="verticalSpacer_7">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Fixed</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>15</height>
</size>
</property>
</spacer>
</item>
<item row="4" column="1">
<spacer name="horizontalSpacer_18"> <spacer name="horizontalSpacer_18">
<property name="orientation"> <property name="orientation">
<enum>Qt::Horizontal</enum> <enum>Qt::Horizontal</enum>
@ -3998,7 +3435,7 @@ value as the Kp.</string>
</property> </property>
</spacer> </spacer>
</item> </item>
<item row="4" column="2"> <item row="2" column="1">
<widget class="QLabel" name="label_149"> <widget class="QLabel" name="label_149">
<property name="minimumSize"> <property name="minimumSize">
<size> <size>
@ -4006,19 +3443,12 @@ value as the Kp.</string>
<height>16</height> <height>16</height>
</size> </size>
</property> </property>
<property name="font">
<font>
<pointsize>9</pointsize>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="text"> <property name="text">
<string>Attitude Stabilization (Outer Loop)</string> <string>Attitude Stabilization (Outer Loop)</string>
</property> </property>
</widget> </widget>
</item> </item>
<item row="5" column="1" colspan="4"> <item row="3" column="0" colspan="3">
<widget class="QGroupBox" name="RateStabilizationGroup_17"> <widget class="QGroupBox" name="RateStabilizationGroup_17">
<property name="sizePolicy"> <property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Fixed"> <sizepolicy hsizetype="Preferred" vsizetype="Fixed">
@ -4555,13 +3985,6 @@ value as the Kp.</string>
<property name="autoFillBackground"> <property name="autoFillBackground">
<bool>false</bool> <bool>false</bool>
</property> </property>
<property name="styleSheet">
<string notr="true">#RateStabilizationGroup_17{background-color: qlineargradient(spread:pad, x1:0.507, y1:0.869318, x2:0.507, y2:0.0965909, stop:0 rgba(243, 243, 243, 255), stop:1 rgba(250, 250, 250, 255));
border: 1px outset #999;
border-radius: 3;
}</string>
</property>
<property name="title"> <property name="title">
<string/> <string/>
</property> </property>
@ -4604,26 +4027,14 @@ border-radius: 3;
</property> </property>
</widget> </widget>
</item> </item>
<item row="0" column="3"> <item row="0" column="4">
<widget class="QPushButton" name="pushButton_22"> <widget class="QPushButton" name="pushButton_22">
<property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize"> <property name="minimumSize">
<size> <size>
<width>81</width> <width>81</width>
<height>28</height> <height>28</height>
</size> </size>
</property> </property>
<property name="maximumSize">
<size>
<width>81</width>
<height>28</height>
</size>
</property>
<property name="styleSheet"> <property name="styleSheet">
<string notr="true">QPushButton { <string notr="true">QPushButton {
border: 1px outset #999; border: 1px outset #999;
@ -4656,7 +4067,7 @@ border-radius: 4;
</property> </property>
</widget> </widget>
</item> </item>
<item row="1" column="0" colspan="4"> <item row="1" column="0" colspan="5">
<widget class="QGroupBox" name="RateStabilizationGroup_18"> <widget class="QGroupBox" name="RateStabilizationGroup_18">
<property name="sizePolicy"> <property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Fixed"> <sizepolicy hsizetype="Preferred" vsizetype="Fixed">
@ -7335,26 +6746,14 @@ border-radius: 5;</string>
</layout> </layout>
</widget> </widget>
</item> </item>
<item row="0" column="2"> <item row="0" column="3">
<widget class="QPushButton" name="pushButton_21"> <widget class="QPushButton" name="pushButton_21">
<property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize"> <property name="minimumSize">
<size> <size>
<width>51</width> <width>51</width>
<height>28</height> <height>28</height>
</size> </size>
</property> </property>
<property name="maximumSize">
<size>
<width>51</width>
<height>28</height>
</size>
</property>
<property name="styleSheet"> <property name="styleSheet">
<string notr="true">QPushButton { <string notr="true">QPushButton {
border: 1px outset #999; border: 1px outset #999;
@ -7387,42 +6786,23 @@ border-radius: 4;
</property> </property>
</widget> </widget>
</item> </item>
</layout> <item row="0" column="2">
</widget> <spacer name="horizontalSpacer_4">
</item>
<item row="5" column="5">
<spacer name="horizontalSpacer_20">
<property name="orientation"> <property name="orientation">
<enum>Qt::Horizontal</enum> <enum>Qt::Horizontal</enum>
</property> </property>
<property name="sizeType">
<enum>QSizePolicy::Fixed</enum>
</property>
<property name="sizeHint" stdset="0"> <property name="sizeHint" stdset="0">
<size> <size>
<width>2</width> <width>40</width>
<height>10</height> <height>20</height>
</size> </size>
</property> </property>
</spacer> </spacer>
</item> </item>
<item row="6" column="2"> </layout>
<spacer name="verticalSpacer_8"> </widget>
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Fixed</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>15</height>
</size>
</property>
</spacer>
</item> </item>
<item row="7" column="1"> <item row="4" column="0">
<spacer name="horizontalSpacer_21"> <spacer name="horizontalSpacer_21">
<property name="orientation"> <property name="orientation">
<enum>Qt::Horizontal</enum> <enum>Qt::Horizontal</enum>
@ -7438,7 +6818,7 @@ border-radius: 4;
</property> </property>
</spacer> </spacer>
</item> </item>
<item row="7" column="2"> <item row="4" column="1">
<widget class="QLabel" name="label_161"> <widget class="QLabel" name="label_161">
<property name="minimumSize"> <property name="minimumSize">
<size> <size>
@ -7446,19 +6826,12 @@ border-radius: 4;
<height>16</height> <height>16</height>
</size> </size>
</property> </property>
<property name="font">
<font>
<pointsize>9</pointsize>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="text"> <property name="text">
<string>Stick Range and Limits</string> <string>Stick Range and Limits</string>
</property> </property>
</widget> </widget>
</item> </item>
<item row="8" column="1" colspan="4"> <item row="5" column="0" colspan="3">
<widget class="QGroupBox" name="RateStabilizationGroup_19"> <widget class="QGroupBox" name="RateStabilizationGroup_19">
<property name="sizePolicy"> <property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Fixed"> <sizepolicy hsizetype="Preferred" vsizetype="Fixed">
@ -7992,16 +7365,6 @@ border-radius: 4;
</disabled> </disabled>
</palette> </palette>
</property> </property>
<property name="autoFillBackground">
<bool>false</bool>
</property>
<property name="styleSheet">
<string notr="true">#RateStabilizationGroup_19{background-color: qlineargradient(spread:pad, x1:0.507, y1:0.869318, x2:0.507, y2:0.0965909, stop:0 rgba(243, 243, 243, 255), stop:1 rgba(250, 250, 250, 255));
border: 1px outset #999;
border-radius: 3;
}</string>
</property>
<property name="title"> <property name="title">
<string/> <string/>
</property> </property>
@ -8019,7 +7382,7 @@ border-radius: 3;
</property> </property>
<property name="sizeHint" stdset="0"> <property name="sizeHint" stdset="0">
<size> <size>
<width>10</width> <width>1000</width>
<height>10</height> <height>10</height>
</size> </size>
</property> </property>
@ -8027,24 +7390,12 @@ border-radius: 3;
</item> </item>
<item row="0" column="1"> <item row="0" column="1">
<widget class="QPushButton" name="pushButton_23"> <widget class="QPushButton" name="pushButton_23">
<property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize"> <property name="minimumSize">
<size> <size>
<width>51</width> <width>51</width>
<height>28</height> <height>28</height>
</size> </size>
</property> </property>
<property name="maximumSize">
<size>
<width>51</width>
<height>28</height>
</size>
</property>
<property name="styleSheet"> <property name="styleSheet">
<string notr="true">QPushButton { <string notr="true">QPushButton {
border: 1px outset #999; border: 1px outset #999;
@ -8091,12 +7442,6 @@ border-radius: 4;
<height>28</height> <height>28</height>
</size> </size>
</property> </property>
<property name="maximumSize">
<size>
<width>81</width>
<height>28</height>
</size>
</property>
<property name="styleSheet"> <property name="styleSheet">
<string notr="true">QPushButton { <string notr="true">QPushButton {
border: 1px outset #999; border: 1px outset #999;
@ -11063,23 +10408,7 @@ Attitude</string>
</layout> </layout>
</widget> </widget>
</item> </item>
<item row="9" column="3"> <item row="7" column="2">
<spacer name="verticalSpacer_9">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Fixed</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>10</height>
</size>
</property>
</spacer>
</item>
<item row="11" column="4">
<spacer name="verticalSpacer_10"> <spacer name="verticalSpacer_10">
<property name="orientation"> <property name="orientation">
<enum>Qt::Vertical</enum> <enum>Qt::Vertical</enum>
@ -11095,23 +10424,7 @@ Attitude</string>
</property> </property>
</spacer> </spacer>
</item> </item>
<item row="2" column="0"> <item row="6" column="0" colspan="3">
<spacer name="horizontalSpacer_16">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Fixed</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>2</width>
<height>10</height>
</size>
</property>
</spacer>
</item>
<item row="10" column="1" colspan="4">
<widget class="QGroupBox" name="RateStabilizationGroup_21"> <widget class="QGroupBox" name="RateStabilizationGroup_21">
<property name="sizePolicy"> <property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Fixed"> <sizepolicy hsizetype="Preferred" vsizetype="Fixed">
@ -11648,13 +10961,6 @@ Attitude</string>
<property name="autoFillBackground"> <property name="autoFillBackground">
<bool>false</bool> <bool>false</bool>
</property> </property>
<property name="styleSheet">
<string notr="true">#RateStabilizationGroup_21{background-color: qlineargradient(spread:pad, x1:0.507, y1:0.869318, x2:0.507, y2:0.0965909, stop:0 rgba(243, 243, 243, 255), stop:1 rgba(250, 250, 250, 255));
border: 1px outset #999;
border-radius: 3;
}</string>
</property>
<property name="title"> <property name="title">
<string/> <string/>
</property> </property>
@ -11734,29 +11040,12 @@ automatically every 300ms, which will help for fast tuning.</string>
</item> </item>
<item row="1" column="2"> <item row="1" column="2">
<widget class="QPushButton" name="stabilizationReloadBoardData_6"> <widget class="QPushButton" name="stabilizationReloadBoardData_6">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize"> <property name="minimumSize">
<size> <size>
<width>120</width> <width>120</width>
<height>28</height> <height>28</height>
</size> </size>
</property> </property>
<property name="maximumSize">
<size>
<width>120</width>
<height>28</height>
</size>
</property>
<property name="font">
<font>
<pointsize>8</pointsize>
</font>
</property>
<property name="toolTip"> <property name="toolTip">
<string>Reloads the saved settings into GCS. <string>Reloads the saved settings into GCS.
Useful if you have accidentally changed some settings.</string> Useful if you have accidentally changed some settings.</string>
@ -11795,29 +11084,12 @@ border-radius: 4;
</item> </item>
<item row="1" column="3"> <item row="1" column="3">
<widget class="QPushButton" name="saveStabilizationToRAM_6"> <widget class="QPushButton" name="saveStabilizationToRAM_6">
<property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize"> <property name="minimumSize">
<size> <size>
<width>60</width> <width>60</width>
<height>28</height> <height>28</height>
</size> </size>
</property> </property>
<property name="maximumSize">
<size>
<width>60</width>
<height>28</height>
</size>
</property>
<property name="font">
<font>
<pointsize>8</pointsize>
</font>
</property>
<property name="toolTip"> <property name="toolTip">
<string>Send settings to the board but do not save to the non-volatile memory</string> <string>Send settings to the board but do not save to the non-volatile memory</string>
</property> </property>
@ -11854,29 +11126,12 @@ border-radius: 4;
</item> </item>
<item row="1" column="4"> <item row="1" column="4">
<widget class="QPushButton" name="saveStabilizationToSD_6"> <widget class="QPushButton" name="saveStabilizationToSD_6">
<property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize"> <property name="minimumSize">
<size> <size>
<width>60</width> <width>60</width>
<height>28</height> <height>28</height>
</size> </size>
</property> </property>
<property name="maximumSize">
<size>
<width>60</width>
<height>28</height>
</size>
</property>
<property name="font">
<font>
<pointsize>8</pointsize>
</font>
</property>
<property name="toolTip"> <property name="toolTip">
<string>Send settings to the board and save to the non-volatile memory</string> <string>Send settings to the board and save to the non-volatile memory</string>
</property> </property>
@ -11939,27 +11194,11 @@ border-radius: 4;
<x>0</x> <x>0</x>
<y>0</y> <y>0</y>
<width>673</width> <width>673</width>
<height>1079</height> <height>981</height>
</rect> </rect>
</property> </property>
<layout class="QGridLayout" name="gridLayout_15"> <layout class="QGridLayout" name="gridLayout_15">
<item row="0" column="2"> <item row="0" column="0">
<spacer name="verticalSpacer_11">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Fixed</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>25</width>
<height>10</height>
</size>
</property>
</spacer>
</item>
<item row="1" column="1">
<spacer name="horizontalSpacer_25"> <spacer name="horizontalSpacer_25">
<property name="orientation"> <property name="orientation">
<enum>Qt::Horizontal</enum> <enum>Qt::Horizontal</enum>
@ -11975,7 +11214,7 @@ border-radius: 4;
</property> </property>
</spacer> </spacer>
</item> </item>
<item row="1" column="2" colspan="2"> <item row="0" column="1" colspan="2">
<widget class="QLabel" name="label_41"> <widget class="QLabel" name="label_41">
<property name="minimumSize"> <property name="minimumSize">
<size> <size>
@ -11983,19 +11222,12 @@ border-radius: 4;
<height>16</height> <height>16</height>
</size> </size>
</property> </property>
<property name="font">
<font>
<pointsize>9</pointsize>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="text"> <property name="text">
<string>Rate Stabization Coefficients (Inner Loop)</string> <string>Rate Stabization Coefficients (Inner Loop)</string>
</property> </property>
</widget> </widget>
</item> </item>
<item row="2" column="1" rowspan="2" colspan="3"> <item row="1" column="0" rowspan="2" colspan="3">
<widget class="QGroupBox" name="RateStabilizationGroup_8"> <widget class="QGroupBox" name="RateStabilizationGroup_8">
<property name="sizePolicy"> <property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Fixed"> <sizepolicy hsizetype="Preferred" vsizetype="Fixed">
@ -12529,16 +11761,6 @@ border-radius: 4;
</disabled> </disabled>
</palette> </palette>
</property> </property>
<property name="autoFillBackground">
<bool>false</bool>
</property>
<property name="styleSheet">
<string notr="true">#RateStabilizationGroup_8{background-color: qlineargradient(spread:pad, x1:0.507, y1:0.869318, x2:0.507, y2:0.0965909, stop:0 rgba(243, 243, 243, 255), stop:1 rgba(250, 250, 250, 255));
border: 1px outset #999;
border-radius: 3;
}</string>
</property>
<property name="title"> <property name="title">
<string/> <string/>
</property> </property>
@ -15474,55 +14696,7 @@ value as the Kp.</string>
</layout> </layout>
</widget> </widget>
</item> </item>
<item row="2" column="4">
<spacer name="horizontalSpacer">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Fixed</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>2</width>
<height>10</height>
</size>
</property>
</spacer>
</item>
<item row="3" column="0"> <item row="3" column="0">
<spacer name="horizontalSpacer_2">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Fixed</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>2</width>
<height>10</height>
</size>
</property>
</spacer>
</item>
<item row="4" column="2">
<spacer name="verticalSpacer_12">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Fixed</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>15</height>
</size>
</property>
</spacer>
</item>
<item row="5" column="1">
<spacer name="horizontalSpacer_12"> <spacer name="horizontalSpacer_12">
<property name="orientation"> <property name="orientation">
<enum>Qt::Horizontal</enum> <enum>Qt::Horizontal</enum>
@ -15538,7 +14712,7 @@ value as the Kp.</string>
</property> </property>
</spacer> </spacer>
</item> </item>
<item row="5" column="2" colspan="2"> <item row="3" column="1" colspan="2">
<widget class="QLabel" name="label_35"> <widget class="QLabel" name="label_35">
<property name="minimumSize"> <property name="minimumSize">
<size> <size>
@ -15546,19 +14720,12 @@ value as the Kp.</string>
<height>16</height> <height>16</height>
</size> </size>
</property> </property>
<property name="font">
<font>
<pointsize>9</pointsize>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="text"> <property name="text">
<string>Attitude Stabization Coefficients (Outer Loop)</string> <string>Attitude Stabization Coefficients (Outer Loop)</string>
</property> </property>
</widget> </widget>
</item> </item>
<item row="6" column="1" colspan="3"> <item row="4" column="0" colspan="3">
<widget class="QGroupBox" name="RateStabilizationGroup_4"> <widget class="QGroupBox" name="RateStabilizationGroup_4">
<property name="sizePolicy"> <property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Fixed"> <sizepolicy hsizetype="Preferred" vsizetype="Fixed">
@ -16095,13 +15262,6 @@ value as the Kp.</string>
<property name="autoFillBackground"> <property name="autoFillBackground">
<bool>false</bool> <bool>false</bool>
</property> </property>
<property name="styleSheet">
<string notr="true">#RateStabilizationGroup_4{background-color: qlineargradient(spread:pad, x1:0.507, y1:0.869318, x2:0.507, y2:0.0965909, stop:0 rgba(243, 243, 243, 255), stop:1 rgba(250, 250, 250, 255));
border: 1px outset #999;
border-radius: 3;
}</string>
</property>
<property name="title"> <property name="title">
<string/> <string/>
</property> </property>
@ -16112,85 +15272,6 @@ border-radius: 3;
<bool>false</bool> <bool>false</bool>
</property> </property>
<layout class="QGridLayout" name="gridLayout_4"> <layout class="QGridLayout" name="gridLayout_4">
<item row="0" column="0">
<spacer name="horizontalSpacer_7">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Fixed</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>10</width>
<height>10</height>
</size>
</property>
</spacer>
</item>
<item row="0" column="1">
<widget class="QCheckBox" name="checkBox_2">
<property name="styleSheet">
<string notr="true"/>
</property>
<property name="text">
<string>Link Roll and Pitch</string>
</property>
</widget>
</item>
<item row="0" column="2">
<widget class="QPushButton" name="pushButton_2">
<property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>81</width>
<height>28</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>81</width>
<height>28</height>
</size>
</property>
<property name="styleSheet">
<string notr="true">QPushButton {
border: 1px outset #999;
border-radius: 5;
background-color: qlineargradient(spread:pad, x1:0.507, y1:0.869318, x2:0.507, y2:0.0965909, stop:0.28 rgba(236, 236, 236, 255), stop:1 rgba(252, 252, 252, 255));
}
QPushButton:pressed {
border-style: inset;
background-color: qlineargradient(spread:pad, x1:0.502, y1:0.664864, x2:0.502, y2:0.034, stop:0.358209 rgba(250, 250, 250, 255), stop:0.626866 rgba(235, 235, 235, 255));
}
QPushButton:hover {
border: 1px outset #999;
border-color: rgb(83, 83, 83);
border-radius: 4;
}</string>
</property>
<property name="text">
<string>Default</string>
</property>
<property name="objrelation" stdset="0">
<stringlist>
<string>objname:StabilizationSettings</string>
<string>button:default</string>
<string>buttongroup:5</string>
</stringlist>
</property>
</widget>
</item>
<item row="1" column="0" colspan="3"> <item row="1" column="0" colspan="3">
<widget class="QGroupBox" name="RateStabilizationGroup_5"> <widget class="QGroupBox" name="RateStabilizationGroup_5">
<property name="sizePolicy"> <property name="sizePolicy">
@ -18839,26 +17920,89 @@ border-radius: 5;</string>
</layout> </layout>
</widget> </widget>
</item> </item>
</layout> <item row="0" column="0">
</widget> <spacer name="horizontalSpacer_7">
</item>
<item row="7" column="2">
<spacer name="verticalSpacer_13">
<property name="orientation"> <property name="orientation">
<enum>Qt::Vertical</enum> <enum>Qt::Horizontal</enum>
</property> </property>
<property name="sizeType"> <property name="sizeType">
<enum>QSizePolicy::Fixed</enum> <enum>QSizePolicy::Fixed</enum>
</property> </property>
<property name="sizeHint" stdset="0"> <property name="sizeHint" stdset="0">
<size> <size>
<width>20</width> <width>10</width>
<height>15</height> <height>10</height>
</size> </size>
</property> </property>
</spacer> </spacer>
</item> </item>
<item row="8" column="1"> <item row="0" column="2">
<widget class="QPushButton" name="pushButton_2">
<property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>81</width>
<height>28</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>81</width>
<height>28</height>
</size>
</property>
<property name="styleSheet">
<string notr="true">QPushButton {
border: 1px outset #999;
border-radius: 5;
background-color: qlineargradient(spread:pad, x1:0.507, y1:0.869318, x2:0.507, y2:0.0965909, stop:0.28 rgba(236, 236, 236, 255), stop:1 rgba(252, 252, 252, 255));
}
QPushButton:pressed {
border-style: inset;
background-color: qlineargradient(spread:pad, x1:0.502, y1:0.664864, x2:0.502, y2:0.034, stop:0.358209 rgba(250, 250, 250, 255), stop:0.626866 rgba(235, 235, 235, 255));
}
QPushButton:hover {
border: 1px outset #999;
border-color: rgb(83, 83, 83);
border-radius: 4;
}</string>
</property>
<property name="text">
<string>Default</string>
</property>
<property name="objrelation" stdset="0">
<stringlist>
<string>objname:StabilizationSettings</string>
<string>button:default</string>
<string>buttongroup:5</string>
</stringlist>
</property>
</widget>
</item>
<item row="0" column="1">
<widget class="QCheckBox" name="checkBox_2">
<property name="styleSheet">
<string notr="true"/>
</property>
<property name="text">
<string>Link Roll and Pitch</string>
</property>
</widget>
</item>
</layout>
</widget>
</item>
<item row="5" column="0">
<spacer name="horizontalSpacer_13"> <spacer name="horizontalSpacer_13">
<property name="orientation"> <property name="orientation">
<enum>Qt::Horizontal</enum> <enum>Qt::Horizontal</enum>
@ -18874,7 +18018,7 @@ border-radius: 5;</string>
</property> </property>
</spacer> </spacer>
</item> </item>
<item row="8" column="2" colspan="2"> <item row="5" column="1" colspan="2">
<widget class="QLabel" name="label_36"> <widget class="QLabel" name="label_36">
<property name="minimumSize"> <property name="minimumSize">
<size> <size>
@ -18882,19 +18026,12 @@ border-radius: 5;</string>
<height>16</height> <height>16</height>
</size> </size>
</property> </property>
<property name="font">
<font>
<pointsize>9</pointsize>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="text"> <property name="text">
<string>Stick Range and Limits</string> <string>Stick Range and Limits</string>
</property> </property>
</widget> </widget>
</item> </item>
<item row="9" column="1" colspan="3"> <item row="6" column="0" colspan="3">
<widget class="QGroupBox" name="RateStabilizationGroup_6"> <widget class="QGroupBox" name="RateStabilizationGroup_6">
<property name="sizePolicy"> <property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Fixed"> <sizepolicy hsizetype="Preferred" vsizetype="Fixed">
@ -19428,16 +18565,6 @@ border-radius: 5;</string>
</disabled> </disabled>
</palette> </palette>
</property> </property>
<property name="autoFillBackground">
<bool>false</bool>
</property>
<property name="styleSheet">
<string notr="true">#RateStabilizationGroup_6{background-color: qlineargradient(spread:pad, x1:0.507, y1:0.869318, x2:0.507, y2:0.0965909, stop:0 rgba(243, 243, 243, 255), stop:1 rgba(250, 250, 250, 255));
border: 1px outset #999;
border-radius: 3;
}</string>
</property>
<property name="title"> <property name="title">
<string/> <string/>
</property> </property>
@ -19455,7 +18582,7 @@ border-radius: 3;
</property> </property>
<property name="sizeHint" stdset="0"> <property name="sizeHint" stdset="0">
<size> <size>
<width>10</width> <width>10000</width>
<height>10</height> <height>10</height>
</size> </size>
</property> </property>
@ -19463,24 +18590,12 @@ border-radius: 3;
</item> </item>
<item row="0" column="1"> <item row="0" column="1">
<widget class="QPushButton" name="pushButton_3"> <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"> <property name="minimumSize">
<size> <size>
<width>81</width> <width>81</width>
<height>28</height> <height>28</height>
</size> </size>
</property> </property>
<property name="maximumSize">
<size>
<width>81</width>
<height>28</height>
</size>
</property>
<property name="styleSheet"> <property name="styleSheet">
<string notr="true">QPushButton { <string notr="true">QPushButton {
border: 1px outset #999; border: 1px outset #999;
@ -22192,23 +21307,7 @@ rate(deg/s)</string>
</layout> </layout>
</widget> </widget>
</item> </item>
<item row="10" column="3"> <item row="7" column="0">
<spacer name="verticalSpacer_14">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Fixed</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>10</height>
</size>
</property>
</spacer>
</item>
<item row="11" column="1">
<spacer name="horizontalSpacer_41"> <spacer name="horizontalSpacer_41">
<property name="orientation"> <property name="orientation">
<enum>Qt::Horizontal</enum> <enum>Qt::Horizontal</enum>
@ -22224,7 +21323,7 @@ rate(deg/s)</string>
</property> </property>
</spacer> </spacer>
</item> </item>
<item row="11" column="2" colspan="2"> <item row="7" column="1" colspan="2">
<widget class="QLabel" name="label_45"> <widget class="QLabel" name="label_45">
<property name="minimumSize"> <property name="minimumSize">
<size> <size>
@ -22232,26 +21331,13 @@ rate(deg/s)</string>
<height>16</height> <height>16</height>
</size> </size>
</property> </property>
<property name="font">
<font>
<pointsize>9</pointsize>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="text"> <property name="text">
<string>Sensor Tunning</string> <string>Sensor Tunning</string>
</property> </property>
</widget> </widget>
</item> </item>
<item row="12" column="1" colspan="3"> <item row="8" column="0" colspan="3">
<widget class="QGroupBox" name="RateStabilizationGroup_23"> <widget class="QGroupBox" name="RateStabilizationGroup_23">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize"> <property name="minimumSize">
<size> <size>
<width>0</width> <width>0</width>
@ -22781,13 +21867,6 @@ rate(deg/s)</string>
<property name="autoFillBackground"> <property name="autoFillBackground">
<bool>false</bool> <bool>false</bool>
</property> </property>
<property name="styleSheet">
<string notr="true">#RateStabilizationGroup_23{background-color: qlineargradient(spread:pad, x1:0.507, y1:0.869318, x2:0.507, y2:0.0965909, stop:0 rgba(243, 243, 243, 255), stop:1 rgba(250, 250, 250, 255));
border: 1px outset #999;
border-radius: 3;
}</string>
</property>
<property name="title"> <property name="title">
<string/> <string/>
</property> </property>
@ -25118,23 +24197,7 @@ border-radius: 5;</string>
</layout> </layout>
</widget> </widget>
</item> </item>
<item row="13" column="1" colspan="2"> <item row="9" column="0" colspan="3">
<spacer name="verticalSpacer_15">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Fixed</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>10</height>
</size>
</property>
</spacer>
</item>
<item row="14" column="1" colspan="3">
<widget class="QGroupBox" name="RateStabilizationGroup_22"> <widget class="QGroupBox" name="RateStabilizationGroup_22">
<property name="sizePolicy"> <property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Fixed"> <sizepolicy hsizetype="Preferred" vsizetype="Fixed">
@ -25671,13 +24734,6 @@ border-radius: 5;</string>
<property name="autoFillBackground"> <property name="autoFillBackground">
<bool>false</bool> <bool>false</bool>
</property> </property>
<property name="styleSheet">
<string notr="true">#RateStabilizationGroup_22{background-color: qlineargradient(spread:pad, x1:0.507, y1:0.869318, x2:0.507, y2:0.0965909, stop:0 rgba(243, 243, 243, 255), stop:1 rgba(250, 250, 250, 255));
border: 1px outset #999;
border-radius: 3;
}</string>
</property>
<property name="title"> <property name="title">
<string/> <string/>
</property> </property>
@ -25724,13 +24780,6 @@ border-radius: 3;
<verstretch>0</verstretch> <verstretch>0</verstretch>
</sizepolicy> </sizepolicy>
</property> </property>
<property name="font">
<font>
<pointsize>9</pointsize>
<weight>50</weight>
<bold>false</bold>
</font>
</property>
<property name="toolTip"> <property name="toolTip">
<string>If you check this, the GCS will udpate the stabilization factors <string>If you check this, the GCS will udpate the stabilization factors
automatically every 300ms, which will help for fast tuning.</string> automatically every 300ms, which will help for fast tuning.</string>
@ -25776,11 +24825,6 @@ automatically every 300ms, which will help for fast tuning.</string>
<height>28</height> <height>28</height>
</size> </size>
</property> </property>
<property name="font">
<font>
<pointsize>8</pointsize>
</font>
</property>
<property name="toolTip"> <property name="toolTip">
<string>Send settings to the board but do not save to the non-volatile memory</string> <string>Send settings to the board but do not save to the non-volatile memory</string>
</property> </property>
@ -25835,11 +24879,6 @@ border-radius: 4;
<height>28</height> <height>28</height>
</size> </size>
</property> </property>
<property name="font">
<font>
<pointsize>8</pointsize>
</font>
</property>
<property name="toolTip"> <property name="toolTip">
<string>Send settings to the board and save to the non-volatile memory</string> <string>Send settings to the board and save to the non-volatile memory</string>
</property> </property>

View File

@ -27,8 +27,8 @@
<rect> <rect>
<x>0</x> <x>0</x>
<y>0</y> <y>0</y>
<width>702</width> <width>696</width>
<height>489</height> <height>475</height>
</rect> </rect>
</property> </property>
<layout class="QVBoxLayout" name="verticalLayout_2"> <layout class="QVBoxLayout" name="verticalLayout_2">
@ -84,6 +84,9 @@ Up to 3 separate PID options (or option pairs) can be selected and updated.</str
</item> </item>
<item> <item>
<widget class="QGroupBox" name="groupBox_6"> <widget class="QGroupBox" name="groupBox_6">
<property name="enabled">
<bool>true</bool>
</property>
<property name="sizePolicy"> <property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Minimum"> <sizepolicy hsizetype="Preferred" vsizetype="Minimum">
<horstretch>0</horstretch> <horstretch>0</horstretch>
@ -96,23 +99,6 @@ Up to 3 separate PID options (or option pairs) can be selected and updated.</str
<height>100</height> <height>100</height>
</size> </size>
</property> </property>
<property name="styleSheet">
<string notr="true">#groupBox_6{
background-color: qlineargradient(spread:pad, x1:0.507, y1:0.869318, x2:0.507, y2:0.0965909, stop:0 rgba(243, 243, 243, 255), stop:1 rgba(250, 250, 250, 255));
border: 1px outset #999;
border-radius: 3;
font:bold;
}
QGroupBox::title {
subcontrol-origin: margin;
subcontrol-position: top center; /* position at the top center */
padding: 0 3px;
background-color: qlineargradient(x1: 0, y1: 0, x2: 0, y2: 1,
stop: 0 #FFOECE, stop: 1 #FFFFFF);
top: 5px;
}</string>
</property>
<property name="title"> <property name="title">
<string>Module Settings</string> <string>Module Settings</string>
</property> </property>
@ -509,19 +495,6 @@ margin:1px;</string>
</property> </property>
</widget> </widget>
</item> </item>
<item row="0" column="2">
<spacer name="verticalSpacer_4">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item row="5" column="1"> <item row="5" column="1">
<spacer name="verticalSpacer_3"> <spacer name="verticalSpacer_3">
<property name="orientation"> <property name="orientation">
@ -549,7 +522,7 @@ margin:1px;</string>
<property name="sizeHint" stdset="0"> <property name="sizeHint" stdset="0">
<size> <size>
<width>20</width> <width>20</width>
<height>40</height> <height>20</height>
</size> </size>
</property> </property>
</spacer> </spacer>

View File

@ -30,6 +30,11 @@ public:
// for firmware compatibility and the filename path that would break // for firmware compatibility and the filename path that would break
return QString("CopterControl"); return QString("CopterControl");
break; break;
case 0x0901://Revolution
// It would be nice to say CC3D here but since currently we use string comparisons
// for firmware compatibility and the filename path that would break
return QString("Revolution");
break;
default: default:
return QString(""); return QString("");
break; break;

View File

@ -32,7 +32,7 @@
/** /**
* Constructor * Constructor
*/ */
ConfigTaskWidget::ConfigTaskWidget(QWidget *parent) : QWidget(parent),isConnected(false),smartsave(NULL),dirty(false),outOfLimitsStyle("background-color: rgb(255, 0, 0);"),timeOut(NULL) ConfigTaskWidget::ConfigTaskWidget(QWidget *parent) : QWidget(parent),isConnected(false),smartsave(NULL),dirty(false),outOfLimitsStyle("background-color: rgb(255, 0, 0);"),timeOut(NULL),allowWidgetUpdates(true)
{ {
pm = ExtensionSystem::PluginManager::instance(); pm = ExtensionSystem::PluginManager::instance();
objManager = pm->getObject<UAVObjectManager>(); objManager = pm->getObject<UAVObjectManager>();
@ -127,7 +127,7 @@ void ConfigTaskWidget::addUAVObjectToWidgetRelation(QString object, QString fiel
Q_ASSERT(obj); Q_ASSERT(obj);
objectUpdates.insert(obj,true); objectUpdates.insert(obj,true);
connect(obj, SIGNAL(objectUpdated(UAVObject*)),this, SLOT(objectUpdated(UAVObject*))); connect(obj, SIGNAL(objectUpdated(UAVObject*)),this, SLOT(objectUpdated(UAVObject*)));
connect(obj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(refreshWidgetsValues(UAVObject*))); connect(obj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(refreshWidgetsValues(UAVObject*)), Qt::UniqueConnection);
} }
if(!field.isEmpty() && obj) if(!field.isEmpty() && obj)
_field = obj->getField(QString(field)); _field = obj->getField(QString(field));
@ -258,6 +258,9 @@ void ConfigTaskWidget::populateWidgets()
*/ */
void ConfigTaskWidget::refreshWidgetsValues(UAVObject * obj) void ConfigTaskWidget::refreshWidgetsValues(UAVObject * obj)
{ {
if (!allowWidgetUpdates)
return;
bool dirtyBack=dirty; bool dirtyBack=dirty;
emit refreshWidgetsValuesRequested(); emit refreshWidgetsValuesRequested();
foreach(objectToWidget * ow,objOfInterest) foreach(objectToWidget * ow,objOfInterest)
@ -452,10 +455,10 @@ bool ConfigTaskWidget::isDirty()
*/ */
void ConfigTaskWidget::disableObjUpdates() void ConfigTaskWidget::disableObjUpdates()
{ {
allowWidgetUpdates = false;
foreach(objectToWidget * obj,objOfInterest) foreach(objectToWidget * obj,objOfInterest)
{ {
if(obj->object) if(obj->object)disconnect(obj->object, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(refreshWidgetsValues(UAVObject*)));
disconnect(obj->object, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(refreshWidgetsValues()));
} }
} }
/** /**
@ -463,10 +466,11 @@ void ConfigTaskWidget::disableObjUpdates()
*/ */
void ConfigTaskWidget::enableObjUpdates() void ConfigTaskWidget::enableObjUpdates()
{ {
allowWidgetUpdates = true;
foreach(objectToWidget * obj,objOfInterest) foreach(objectToWidget * obj,objOfInterest)
{ {
if(obj->object) if(obj->object)
connect(obj->object, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(refreshWidgetsValues(UAVObject*))); connect(obj->object, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(refreshWidgetsValues(UAVObject*)), Qt::UniqueConnection);
} }
} }
/** /**

View File

@ -145,6 +145,7 @@ private slots:
void reloadButtonClicked(); void reloadButtonClicked();
private: private:
bool isConnected; bool isConnected;
bool allowWidgetUpdates;
QStringList objectsList; QStringList objectsList;
QList <objectToWidget*> objOfInterest; QList <objectToWidget*> objOfInterest;
ExtensionSystem::PluginManager *pm; ExtensionSystem::PluginManager *pm;

View File

@ -1049,7 +1049,7 @@ int DFUObject::receiveData(void * data,int size)
#define BOARD_ID_INS 2 #define BOARD_ID_INS 2
#define BOARD_ID_PIP 3 #define BOARD_ID_PIP 3
#define BOARD_ID_CC 4 #define BOARD_ID_CC 4
//#define BOARD_ID_PRO ? #define BOARD_ID_REVO 9
/** /**
Gets the type of board connected Gets the type of board connected
@ -1074,11 +1074,9 @@ OP_DFU::eBoardType DFUObject::GetBoardType(int boardNum)
case BOARD_ID_CC: // CopterControl family case BOARD_ID_CC: // CopterControl family
brdType = eBoardCC; brdType = eBoardCC;
break; break;
#if 0 // Someday ;-) case BOARD_ID_REVO: // Revo board
case BOARD_ID_PRO: // Pro board brdType = eBoardRevo;
brdType = eBoardPro;
break; break;
#endif
} }
return brdType; return brdType;
} }

View File

@ -98,9 +98,9 @@ namespace OP_DFU {
eBoardUnkwn = 0, eBoardUnkwn = 0,
eBoardMainbrd = 1, eBoardMainbrd = 1,
eBoardINS, eBoardINS,
eBoardPip, eBoardPip = 3,
eBoardCC, eBoardCC = 4,
eBoardPro, eBoardRevo = 9,
}; };
struct device struct device

View File

@ -517,7 +517,7 @@ void UploaderGadgetWidget::systemRescue()
m_config->rescueButton->setEnabled(true); m_config->rescueButton->setEnabled(true);
return; return;
} }
if ((eBoardCC != dfu->GetBoardType(0)) && (QMessageBox::question(this,tr("OpenPilot Uploader"),tr("If you want to search for other boards connect power now and press Yes"),QMessageBox::Yes,QMessageBox::No)==QMessageBox::Yes)) if ((dfu->GetBoardType(0) != eBoardRevo) && (eBoardCC != dfu->GetBoardType(0)) && (QMessageBox::question(this,tr("OpenPilot Uploader"),tr("If you want to search for other boards connect power now and press Yes"),QMessageBox::Yes,QMessageBox::No)==QMessageBox::Yes))
{ {
log("\nWaiting..."); log("\nWaiting...");
QTimer::singleShot(3000, &m_eventloop, SLOT(quit())); QTimer::singleShot(3000, &m_eventloop, SLOT(quit()));

View File

@ -1,9 +1,9 @@
<xml> <xml>
<object name="TaskInfo" singleinstance="true" settings="false"> <object name="TaskInfo" singleinstance="true" settings="false">
<description>Task information</description> <description>Task information</description>
<field name="StackRemaining" units="bytes" type="uint16" elementnames="System,Actuator,Attitude,Sensors,TelemetryTx,TelemetryTxPri,TelemetryRx,GPS,ManualControl,Altitude,Airspeed,Stabilization,AltitudeHold,PathFollower,FlightPlan,PathPlanner,Com2UsbBridge,Usb2ComBridge,OveroSync"/> <field name="StackRemaining" units="bytes" type="uint16" elementnames="System,Actuator,Attitude,Sensors,TelemetryTx,TelemetryTxPri,TelemetryRx,GPS,ManualControl,Altitude,Airspeed,Stabilization,AltitudeHold,PathPlanner,PathFollower,FlightPlan,Com2UsbBridge,Usb2ComBridge,OveroSync"/>
<field name="Running" units="bool" type="enum" options="False,True" elementnames="System,Actuator,Attitude,Sensors,TelemetryTx,TelemetryTxPri,TelemetryRx,GPS,ManualControl,Altitude,Airspeed,Stabilization,AltitudeHold,PathFollower,FlightPlan,PathPlanner,Com2UsbBridge,Usb2ComBridge,OveroSync"/> <field name="Running" units="bool" type="enum" options="False,True" elementnames="System,Actuator,Attitude,Sensors,TelemetryTx,TelemetryTxPri,TelemetryRx,GPS,ManualControl,Altitude,Airspeed,Stabilization,AltitudeHold,PathPlanner,PathFollower,FlightPlan,Com2UsbBridge,Usb2ComBridge,OveroSync"/>
<field name="RunningTime" units="%" type="uint8" elementnames="System,Actuator,Attitude,Sensors,TelemetryTx,TelemetryTxPri,TelemetryRx,GPS,ManualControl,Altitude,Airspeed,Stabilization,AltitudeHold,PathFollower,FlightPlan,PathPlanner,Com2UsbBridge,Usb2ComBridge,OveroSync"/> <field name="RunningTime" units="%" type="uint8" elementnames="System,Actuator,Attitude,Sensors,TelemetryTx,TelemetryTxPri,TelemetryRx,GPS,ManualControl,Altitude,Airspeed,Stabilization,AltitudeHold,PathPlanner,PathFollower,FlightPlan,Com2UsbBridge,Usb2ComBridge,OveroSync"/>
<access gcs="readwrite" flight="readwrite"/> <access gcs="readwrite" flight="readwrite"/>
<telemetrygcs acked="true" updatemode="onchange" period="0"/> <telemetrygcs acked="true" updatemode="onchange" period="0"/>
<telemetryflight acked="true" updatemode="periodic" period="10000"/> <telemetryflight acked="true" updatemode="periodic" period="10000"/>

View File

@ -16,7 +16,8 @@
Roll Rate.ILimit, Pitch Rate.ILimit, Roll+Pitch Rate.ILimit, Yaw Rate.ILimit, Roll Rate.ILimit, Pitch Rate.ILimit, Roll+Pitch Rate.ILimit, Yaw Rate.ILimit,
Roll Attitude.Kp, Pitch Attitude.Kp, Roll+Pitch Attitude.Kp, Yaw Attitude.Kp, Roll Attitude.Kp, Pitch Attitude.Kp, Roll+Pitch Attitude.Kp, Yaw Attitude.Kp,
Roll Attitude.Ki, Pitch Attitude.Ki, Roll+Pitch Attitude.Ki, Yaw Attitude.Ki, Roll Attitude.Ki, Pitch Attitude.Ki, Roll+Pitch Attitude.Ki, Yaw Attitude.Ki,
Roll Attitude.ILimit, Pitch Attitude.ILimit, Roll+Pitch Attitude.ILimit, Yaw Attitude.ILimit" Roll Attitude.ILimit, Pitch Attitude.ILimit, Roll+Pitch Attitude.ILimit, Yaw Attitude.ILimit,
GyroTau"
defaultvalue="Disabled"/> defaultvalue="Disabled"/>
<field name="MinPID" units="" type="float" elementnames="Instance1,Instance2,Instance3" defaultvalue="0"/> <field name="MinPID" units="" type="float" elementnames="Instance1,Instance2,Instance3" defaultvalue="0"/>
<field name="MaxPID" units="" type="float" elementnames="Instance1,Instance2,Instance3" defaultvalue="0"/> <field name="MaxPID" units="" type="float" elementnames="Instance1,Instance2,Instance3" defaultvalue="0"/>