mirror of
https://bitbucket.org/librepilot/librepilot.git
synced 2024-11-29 07:24:13 +01:00
Merge remote-tracking branch 'origin/next' into corvuscorax/OP-1022_AH_improvements_amorale
This commit is contained in:
commit
9997f14d68
@ -46,7 +46,7 @@
|
||||
#include "manualcontrolcommand.h"
|
||||
#include "positionstate.h"
|
||||
#include "pathdesired.h"
|
||||
#include "stabilizationsettings.h"
|
||||
#include "stabilizationbank.h"
|
||||
#include "stabilizationdesired.h"
|
||||
#include "receiveractivity.h"
|
||||
#include "systemsettings.h"
|
||||
@ -668,8 +668,8 @@ static void updateStabilizationDesired(ManualControlCommandData *cmd, ManualCont
|
||||
|
||||
StabilizationDesiredGet(&stabilization);
|
||||
|
||||
StabilizationSettingsData stabSettings;
|
||||
StabilizationSettingsGet(&stabSettings);
|
||||
StabilizationBankData stabSettings;
|
||||
StabilizationBankGet(&stabSettings);
|
||||
|
||||
uint8_t *stab_settings;
|
||||
FlightStatusData flightStatus;
|
||||
@ -864,8 +864,8 @@ static void altitudeHoldDesired(ManualControlCommandData *cmd, bool changed)
|
||||
AltitudeHoldSettingsThrottleExpGet(&throttleExp);
|
||||
AltitudeHoldSettingsThrottleRateGet(&throttleRate);
|
||||
|
||||
StabilizationSettingsData stabSettings;
|
||||
StabilizationSettingsGet(&stabSettings);
|
||||
StabilizationBankData stabSettings;
|
||||
StabilizationBankGet(&stabSettings);
|
||||
|
||||
PositionStateData posState;
|
||||
PositionStateGet(&posState);
|
||||
|
@ -35,6 +35,10 @@
|
||||
#include <pios_struct_helper.h>
|
||||
#include "stabilization.h"
|
||||
#include "stabilizationsettings.h"
|
||||
#include "stabilizationbank.h"
|
||||
#include "stabilizationsettingsbank1.h"
|
||||
#include "stabilizationsettingsbank2.h"
|
||||
#include "stabilizationsettingsbank3.h"
|
||||
#include "actuatordesired.h"
|
||||
#include "ratedesired.h"
|
||||
#include "relaytuning.h"
|
||||
@ -65,7 +69,7 @@
|
||||
#if defined(PIOS_STABILIZATION_STACK_SIZE)
|
||||
#define STACK_SIZE_BYTES PIOS_STABILIZATION_STACK_SIZE
|
||||
#else
|
||||
#define STACK_SIZE_BYTES 724
|
||||
#define STACK_SIZE_BYTES 790
|
||||
#endif
|
||||
|
||||
#define TASK_PRIORITY (tskIDLE_PRIORITY + 4)
|
||||
@ -76,6 +80,8 @@
|
||||
// The PID_RATEA_ROLL set is used by Rattitude mode because it needs to maintain
|
||||
// - two independant rate PIDs because it does rate and attitude simultaneously
|
||||
enum { PID_RATE_ROLL, PID_RATE_PITCH, PID_RATE_YAW, PID_ROLL, PID_PITCH, PID_YAW, PID_RATEA_ROLL, PID_RATEA_PITCH, PID_RATEA_YAW, PID_MAX };
|
||||
enum { RATE_P, RATE_I, RATE_D, RATE_LIMIT, RATE_OFFSET };
|
||||
enum { ATT_P, ATT_I, ATT_LIMIT, ATT_OFFSET };
|
||||
|
||||
// Private variables
|
||||
static xTaskHandle taskHandle;
|
||||
@ -91,6 +97,9 @@ bool lowThrottleZeroIntegral;
|
||||
bool lowThrottleZeroAxis[MAX_AXES];
|
||||
float vbar_decay = 0.991f;
|
||||
struct pid pids[PID_MAX];
|
||||
|
||||
int flight_mode = -1;
|
||||
|
||||
static uint8_t rattitude_anti_windup;
|
||||
|
||||
// Private functions
|
||||
@ -98,6 +107,9 @@ static void stabilizationTask(void *parameters);
|
||||
static float bound(float val, float range);
|
||||
static void ZeroPids(void);
|
||||
static void SettingsUpdatedCb(UAVObjEvent *ev);
|
||||
static void BankUpdatedCb(UAVObjEvent *ev);
|
||||
static void SettingsBankUpdatedCb(UAVObjEvent *ev);
|
||||
|
||||
static float stab_log2f(float x);
|
||||
static float stab_powf(float x, uint8_t p);
|
||||
|
||||
@ -117,6 +129,13 @@ int32_t StabilizationStart()
|
||||
StabilizationSettingsConnectCallback(SettingsUpdatedCb);
|
||||
SettingsUpdatedCb(StabilizationSettingsHandle());
|
||||
|
||||
StabilizationBankConnectCallback(BankUpdatedCb);
|
||||
|
||||
StabilizationSettingsBank1ConnectCallback(SettingsBankUpdatedCb);
|
||||
StabilizationSettingsBank2ConnectCallback(SettingsBankUpdatedCb);
|
||||
StabilizationSettingsBank3ConnectCallback(SettingsBankUpdatedCb);
|
||||
|
||||
|
||||
// Start main task
|
||||
xTaskCreate(stabilizationTask, (signed char *)"Stabilization", STACK_SIZE_BYTES / 4, NULL, TASK_PRIORITY, &taskHandle);
|
||||
PIOS_TASK_MONITOR_RegisterTask(TASKINFO_RUNNING_STABILIZATION, taskHandle);
|
||||
@ -133,6 +152,10 @@ int32_t StabilizationInitialize()
|
||||
{
|
||||
// Initialize variables
|
||||
StabilizationSettingsInitialize();
|
||||
StabilizationBankInitialize();
|
||||
StabilizationSettingsBank1Initialize();
|
||||
StabilizationSettingsBank2Initialize();
|
||||
StabilizationSettingsBank3Initialize();
|
||||
ActuatorDesiredInitialize();
|
||||
#ifdef DIAG_RATEDESIRED
|
||||
RateDesiredInitialize();
|
||||
@ -165,6 +188,8 @@ static void stabilizationTask(__attribute__((unused)) void *parameters)
|
||||
AttitudeStateData attitudeState;
|
||||
GyroStateData gyroStateData;
|
||||
FlightStatusData flightStatus;
|
||||
StabilizationBankData stabBank;
|
||||
|
||||
|
||||
#ifdef REVOLUTION
|
||||
AirspeedStateData airspeedState;
|
||||
@ -194,9 +219,16 @@ static void stabilizationTask(__attribute__((unused)) void *parameters)
|
||||
StabilizationDesiredGet(&stabDesired);
|
||||
AttitudeStateGet(&attitudeState);
|
||||
GyroStateGet(&gyroStateData);
|
||||
StabilizationBankGet(&stabBank);
|
||||
#ifdef DIAG_RATEDESIRED
|
||||
RateDesiredGet(&rateDesired);
|
||||
#endif
|
||||
|
||||
if (flight_mode != flightStatus.FlightMode) {
|
||||
flight_mode = flightStatus.FlightMode;
|
||||
SettingsBankUpdatedCb(NULL);
|
||||
}
|
||||
|
||||
#ifdef REVOLUTION
|
||||
float speedScaleFactor;
|
||||
// Scale PID coefficients based on current airspeed estimation - needed for fixed wing planes
|
||||
@ -294,7 +326,7 @@ static void stabilizationTask(__attribute__((unused)) void *parameters)
|
||||
|
||||
// Store to rate desired variable for storing to UAVO
|
||||
rateDesiredAxis[i] =
|
||||
bound(stabDesiredAxis[i], cast_struct_to_array(settings.ManualRate, settings.ManualRate.Roll)[i]);
|
||||
bound(stabDesiredAxis[i], cast_struct_to_array(stabBank.ManualRate, stabBank.ManualRate.Roll)[i]);
|
||||
|
||||
// Compute the inner loop
|
||||
actuatorDesiredAxis[i] = pid_apply_setpoint(&pids[PID_RATE_ROLL + i], speedScaleFactor, rateDesiredAxis[i], gyro_filtered[i], dT);
|
||||
@ -311,7 +343,7 @@ static void stabilizationTask(__attribute__((unused)) void *parameters)
|
||||
// Compute the outer loop
|
||||
rateDesiredAxis[i] = pid_apply(&pids[PID_ROLL + i], local_error[i], dT);
|
||||
rateDesiredAxis[i] = bound(rateDesiredAxis[i],
|
||||
cast_struct_to_array(settings.MaximumRate, settings.MaximumRate.Roll)[i]);
|
||||
cast_struct_to_array(stabBank.MaximumRate, stabBank.MaximumRate.Roll)[i]);
|
||||
|
||||
// Compute the inner loop
|
||||
actuatorDesiredAxis[i] = pid_apply_setpoint(&pids[PID_RATE_ROLL + i], speedScaleFactor, rateDesiredAxis[i], gyro_filtered[i], dT);
|
||||
@ -336,7 +368,7 @@ static void stabilizationTask(__attribute__((unused)) void *parameters)
|
||||
// Save Rate's rate in a temp for later merging with Attitude's rate
|
||||
float rateDesiredAxisRate;
|
||||
rateDesiredAxisRate = bound(stabDesiredAxis[i], 1.0f)
|
||||
* cast_struct_to_array(settings.ManualRate, settings.ManualRate.Roll)[i];
|
||||
* cast_struct_to_array(stabBank.ManualRate, stabBank.ManualRate.Roll)[i];
|
||||
|
||||
// Compute what Attitude mode would give for this stick angle's rate
|
||||
|
||||
@ -345,15 +377,15 @@ static void stabilizationTask(__attribute__((unused)) void *parameters)
|
||||
// - subtract off the actual angle to get the angle error
|
||||
// This is what local_error[] holds for Attitude mode
|
||||
float attitude_error = stabDesiredAxis[i]
|
||||
* cast_struct_to_array(settings.RollMax, settings.RollMax)[i]
|
||||
* cast_struct_to_array(stabBank.RollMax, stabBank.RollMax)[i]
|
||||
- cast_struct_to_array(attitudeState.Roll, attitudeState.Roll)[i];
|
||||
|
||||
// Compute the outer loop just like Attitude mode does
|
||||
float rateDesiredAxisAttitude;
|
||||
rateDesiredAxisAttitude = pid_apply(&pids[PID_ROLL + i], attitude_error, dT);
|
||||
rateDesiredAxisAttitude = bound(rateDesiredAxisAttitude,
|
||||
cast_struct_to_array(settings.MaximumRate,
|
||||
settings.MaximumRate.Roll)[i]);
|
||||
cast_struct_to_array(stabBank.MaximumRate,
|
||||
stabBank.MaximumRate.Roll)[i]);
|
||||
|
||||
// Compute the weighted average rate desired
|
||||
// Using max() rather than sqrt() for cpu speed;
|
||||
@ -486,7 +518,7 @@ static void stabilizationTask(__attribute__((unused)) void *parameters)
|
||||
}
|
||||
|
||||
rateDesiredAxis[i] = bound(rateDesiredAxis[i],
|
||||
cast_struct_to_array(settings.ManualRate, settings.ManualRate.Roll)[i]);
|
||||
cast_struct_to_array(stabBank.ManualRate, stabBank.ManualRate.Roll)[i]);
|
||||
|
||||
actuatorDesiredAxis[i] = pid_apply_setpoint(&pids[PID_RATE_ROLL + i], speedScaleFactor, rateDesiredAxis[i], gyro_filtered[i], dT);
|
||||
actuatorDesiredAxis[i] = bound(actuatorDesiredAxis[i], 1.0f);
|
||||
@ -496,7 +528,7 @@ static void stabilizationTask(__attribute__((unused)) void *parameters)
|
||||
case STABILIZATIONDESIRED_STABILIZATIONMODE_RELAYRATE:
|
||||
// Store to rate desired variable for storing to UAVO
|
||||
rateDesiredAxis[i] = bound(stabDesiredAxis[i],
|
||||
cast_struct_to_array(settings.ManualRate, settings.ManualRate.Roll)[i]);
|
||||
cast_struct_to_array(stabBank.ManualRate, stabBank.ManualRate.Roll)[i]);
|
||||
|
||||
// Run the relay controller which also estimates the oscillation parameters
|
||||
stabilization_relay_rate(rateDesiredAxis[i] - gyro_filtered[i], &actuatorDesiredAxis[i], i, reinit);
|
||||
@ -512,7 +544,7 @@ static void stabilizationTask(__attribute__((unused)) void *parameters)
|
||||
// Compute the outer loop like attitude mode
|
||||
rateDesiredAxis[i] = pid_apply(&pids[PID_ROLL + i], local_error[i], dT);
|
||||
rateDesiredAxis[i] = bound(rateDesiredAxis[i],
|
||||
cast_struct_to_array(settings.MaximumRate, settings.MaximumRate.Roll)[i]);
|
||||
cast_struct_to_array(stabBank.MaximumRate, stabBank.MaximumRate.Roll)[i]);
|
||||
|
||||
// Run the relay controller which also estimates the oscillation parameters
|
||||
stabilization_relay_rate(rateDesiredAxis[i] - gyro_filtered[i], &actuatorDesiredAxis[i], i, reinit);
|
||||
@ -649,72 +681,145 @@ static float stab_powf(float x, uint8_t p)
|
||||
}
|
||||
|
||||
|
||||
static void SettingsUpdatedCb(__attribute__((unused)) UAVObjEvent *ev)
|
||||
static void SettingsBankUpdatedCb(__attribute__((unused)) UAVObjEvent *ev)
|
||||
{
|
||||
StabilizationSettingsGet(&settings);
|
||||
StabilizationBankData bank, oldBank;
|
||||
|
||||
StabilizationBankGet(&oldBank);
|
||||
|
||||
if (flight_mode < 0) {
|
||||
return;
|
||||
}
|
||||
|
||||
switch (cast_struct_to_array(settings.FlightModeMap, settings.FlightModeMap.Stabilized1)[flight_mode]) {
|
||||
case 0:
|
||||
StabilizationSettingsBank1Get((StabilizationSettingsBank1Data *)&bank);
|
||||
break;
|
||||
|
||||
case 1:
|
||||
StabilizationSettingsBank2Get((StabilizationSettingsBank2Data *)&bank);
|
||||
break;
|
||||
|
||||
case 2:
|
||||
StabilizationSettingsBank3Get((StabilizationSettingsBank3Data *)&bank);
|
||||
break;
|
||||
|
||||
default:
|
||||
memset(&bank, 0, sizeof(StabilizationBankDataPacked));
|
||||
// return; //bank number is invalid. All we can do is ignore it.
|
||||
}
|
||||
|
||||
// Need to do this to prevent an infinite loop
|
||||
if (memcmp(&oldBank, &bank, sizeof(StabilizationBankDataPacked)) != 0) {
|
||||
StabilizationBankSet(&bank);
|
||||
}
|
||||
}
|
||||
|
||||
static void BankUpdatedCb(__attribute__((unused)) UAVObjEvent *ev)
|
||||
{
|
||||
StabilizationBankData bank;
|
||||
|
||||
StabilizationBankGet(&bank);
|
||||
|
||||
// this code will be needed if any other modules alter stabilizationbank
|
||||
/*
|
||||
StabilizationBankData curBank;
|
||||
if(flight_mode < 0) return;
|
||||
|
||||
switch(cast_struct_to_array(settings.FlightModeMap, settings.FlightModeMap.Stabilized1)[flight_mode])
|
||||
{
|
||||
case 0:
|
||||
StabilizationSettingsBank1Get((StabilizationSettingsBank1Data *) &curBank);
|
||||
if(memcmp(&curBank, &bank, sizeof(StabilizationBankDataPacked)) != 0)
|
||||
{
|
||||
StabilizationSettingsBank1Set((StabilizationSettingsBank1Data *) &bank);
|
||||
}
|
||||
break;
|
||||
|
||||
case 1:
|
||||
StabilizationSettingsBank2Get((StabilizationSettingsBank2Data *) &curBank);
|
||||
if(memcmp(&curBank, &bank, sizeof(StabilizationBankDataPacked)) != 0)
|
||||
{
|
||||
StabilizationSettingsBank2Set((StabilizationSettingsBank2Data *) &bank);
|
||||
}
|
||||
break;
|
||||
|
||||
case 2:
|
||||
StabilizationSettingsBank3Get((StabilizationSettingsBank3Data *) &curBank);
|
||||
if(memcmp(&curBank, &bank, sizeof(StabilizationBankDataPacked)) != 0)
|
||||
{
|
||||
StabilizationSettingsBank3Set((StabilizationSettingsBank3Data *) &bank);
|
||||
}
|
||||
break;
|
||||
|
||||
default:
|
||||
return; //invalid bank number
|
||||
}
|
||||
*/
|
||||
|
||||
|
||||
// Set the roll rate PID constants
|
||||
pid_configure(&pids[PID_RATE_ROLL],
|
||||
settings.RollRatePID.Kp,
|
||||
settings.RollRatePID.Ki,
|
||||
settings.RollRatePID.Kd,
|
||||
settings.RollRatePID.ILimit);
|
||||
pid_configure(&pids[PID_RATE_ROLL], bank.RollRatePID.Kp,
|
||||
bank.RollRatePID.Ki,
|
||||
bank.RollRatePID.Kd,
|
||||
bank.RollRatePID.ILimit);
|
||||
|
||||
// Set the pitch rate PID constants
|
||||
pid_configure(&pids[PID_RATE_PITCH],
|
||||
settings.PitchRatePID.Kp,
|
||||
settings.PitchRatePID.Ki,
|
||||
settings.PitchRatePID.Kd,
|
||||
settings.PitchRatePID.ILimit);
|
||||
pid_configure(&pids[PID_RATE_PITCH], bank.PitchRatePID.Kp,
|
||||
bank.PitchRatePID.Ki,
|
||||
bank.PitchRatePID.Kd,
|
||||
bank.PitchRatePID.ILimit);
|
||||
|
||||
// Set the yaw rate PID constants
|
||||
pid_configure(&pids[PID_RATE_YAW],
|
||||
settings.YawRatePID.Kp,
|
||||
settings.YawRatePID.Ki,
|
||||
settings.YawRatePID.Kd,
|
||||
settings.YawRatePID.ILimit);
|
||||
pid_configure(&pids[PID_RATE_YAW], bank.YawRatePID.Kp,
|
||||
bank.YawRatePID.Ki,
|
||||
bank.YawRatePID.Kd,
|
||||
bank.YawRatePID.ILimit);
|
||||
|
||||
// Set the roll attitude PI constants
|
||||
pid_configure(&pids[PID_ROLL],
|
||||
settings.RollPI.Kp,
|
||||
settings.RollPI.Ki,
|
||||
pid_configure(&pids[PID_ROLL], bank.RollPI.Kp,
|
||||
bank.RollPI.Ki,
|
||||
0,
|
||||
settings.RollPI.ILimit);
|
||||
bank.RollPI.ILimit);
|
||||
|
||||
// Set the pitch attitude PI constants
|
||||
pid_configure(&pids[PID_PITCH],
|
||||
settings.PitchPI.Kp,
|
||||
settings.PitchPI.Ki,
|
||||
pid_configure(&pids[PID_PITCH], bank.PitchPI.Kp,
|
||||
bank.PitchPI.Ki,
|
||||
0,
|
||||
settings.PitchPI.ILimit);
|
||||
bank.PitchPI.ILimit);
|
||||
|
||||
// Set the yaw attitude PI constants
|
||||
pid_configure(&pids[PID_YAW],
|
||||
settings.YawPI.Kp,
|
||||
settings.YawPI.Ki,
|
||||
pid_configure(&pids[PID_YAW], bank.YawPI.Kp,
|
||||
bank.YawPI.Ki,
|
||||
0,
|
||||
settings.YawPI.ILimit);
|
||||
bank.YawPI.ILimit);
|
||||
|
||||
// Set the Rattitude roll rate PID constants
|
||||
pid_configure(&pids[PID_RATEA_ROLL],
|
||||
settings.RollRatePID.Kp,
|
||||
settings.RollRatePID.Ki,
|
||||
settings.RollRatePID.Kd,
|
||||
settings.RollRatePID.ILimit);
|
||||
bank.RollRatePID.Kp,
|
||||
bank.RollRatePID.Ki,
|
||||
bank.RollRatePID.Kd,
|
||||
bank.RollRatePID.ILimit);
|
||||
|
||||
// Set the Rattitude pitch rate PID constants
|
||||
pid_configure(&pids[PID_RATEA_PITCH],
|
||||
settings.PitchRatePID.Kp,
|
||||
settings.PitchRatePID.Ki,
|
||||
settings.PitchRatePID.Kd,
|
||||
settings.PitchRatePID.ILimit);
|
||||
bank.PitchRatePID.Kp,
|
||||
bank.PitchRatePID.Ki,
|
||||
bank.PitchRatePID.Kd,
|
||||
bank.PitchRatePID.ILimit);
|
||||
|
||||
// Set the Rattitude yaw rate PID constants
|
||||
pid_configure(&pids[PID_RATEA_YAW],
|
||||
settings.YawRatePID.Kp,
|
||||
settings.YawRatePID.Ki,
|
||||
settings.YawRatePID.Kd,
|
||||
settings.YawRatePID.ILimit);
|
||||
bank.YawRatePID.Kp,
|
||||
bank.YawRatePID.Ki,
|
||||
bank.YawRatePID.Kd,
|
||||
bank.YawRatePID.ILimit);
|
||||
}
|
||||
|
||||
|
||||
static void SettingsUpdatedCb(__attribute__((unused)) UAVObjEvent *ev)
|
||||
{
|
||||
StabilizationSettingsGet(&settings);
|
||||
|
||||
// Set up the derivative term
|
||||
pid_configure_derivative(settings.DerivativeCutoff, settings.DerivativeGamma);
|
||||
@ -748,13 +853,15 @@ static void SettingsUpdatedCb(__attribute__((unused)) UAVObjEvent *ev)
|
||||
}
|
||||
|
||||
// Compute time constant for vbar decay term based on a tau
|
||||
vbar_decay = expf(-fakeDt / settings.VbarTau);
|
||||
vbar_decay = expf(-fakeDt / settings.VbarTau);
|
||||
|
||||
// force flight mode update
|
||||
flight_mode = -1;
|
||||
|
||||
// Rattitude flight mode anti-windup factor
|
||||
rattitude_anti_windup = settings.RattitudeAntiWindup;
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
|
@ -56,6 +56,10 @@
|
||||
#include "accessorydesired.h"
|
||||
#include "manualcontrolcommand.h"
|
||||
#include "stabilizationsettings.h"
|
||||
#include "stabilizationbank.h"
|
||||
#include "stabilizationsettingsbank1.h"
|
||||
#include "stabilizationsettingsbank2.h"
|
||||
#include "stabilizationsettingsbank3.h"
|
||||
#include "flightstatus.h"
|
||||
#include "hwsettings.h"
|
||||
|
||||
@ -163,11 +167,29 @@ static void updatePIDs(UAVObjEvent *ev)
|
||||
return;
|
||||
}
|
||||
|
||||
StabilizationBankData bank;
|
||||
switch (inst.BankNumber) {
|
||||
case 0:
|
||||
StabilizationSettingsBank1Get((StabilizationSettingsBank1Data *)&bank);
|
||||
break;
|
||||
|
||||
case 1:
|
||||
StabilizationSettingsBank2Get((StabilizationSettingsBank2Data *)&bank);
|
||||
break;
|
||||
|
||||
case 2:
|
||||
StabilizationSettingsBank2Get((StabilizationSettingsBank2Data *)&bank);
|
||||
break;
|
||||
|
||||
default:
|
||||
return;
|
||||
}
|
||||
StabilizationSettingsData stab;
|
||||
StabilizationSettingsGet(&stab);
|
||||
AccessoryDesiredData accessory;
|
||||
|
||||
uint8_t needsUpdate = 0;
|
||||
uint8_t needsUpdateBank = 0;
|
||||
uint8_t needsUpdateStab = 0;
|
||||
|
||||
// Loop through every enabled instance
|
||||
for (uint8_t i = 0; i < TXPIDSETTINGS_PIDS_NUMELEM; i++) {
|
||||
@ -192,107 +214,125 @@ static void updatePIDs(UAVObjEvent *ev)
|
||||
|
||||
switch (cast_struct_to_array(inst.PIDs, inst.PIDs.Instance1)[i]) {
|
||||
case TXPIDSETTINGS_PIDS_ROLLRATEKP:
|
||||
needsUpdate |= update(&stab.RollRatePID.Kp, value);
|
||||
needsUpdateBank |= update(&bank.RollRatePID.Kp, value);
|
||||
break;
|
||||
case TXPIDSETTINGS_PIDS_ROLLRATEKI:
|
||||
needsUpdate |= update(&stab.RollRatePID.Ki, value);
|
||||
needsUpdateBank |= update(&bank.RollRatePID.Ki, value);
|
||||
break;
|
||||
case TXPIDSETTINGS_PIDS_ROLLRATEKD:
|
||||
needsUpdate |= update(&stab.RollRatePID.Kd, value);
|
||||
needsUpdateBank |= update(&bank.RollRatePID.Kd, value);
|
||||
break;
|
||||
case TXPIDSETTINGS_PIDS_ROLLRATEILIMIT:
|
||||
needsUpdate |= update(&stab.RollRatePID.ILimit, value);
|
||||
needsUpdateBank |= update(&bank.RollRatePID.ILimit, value);
|
||||
break;
|
||||
case TXPIDSETTINGS_PIDS_ROLLATTITUDEKP:
|
||||
needsUpdate |= update(&stab.RollPI.Kp, value);
|
||||
needsUpdateBank |= update(&bank.RollPI.Kp, value);
|
||||
break;
|
||||
case TXPIDSETTINGS_PIDS_ROLLATTITUDEKI:
|
||||
needsUpdate |= update(&stab.RollPI.Ki, value);
|
||||
needsUpdateBank |= update(&bank.RollPI.Ki, value);
|
||||
break;
|
||||
case TXPIDSETTINGS_PIDS_ROLLATTITUDEILIMIT:
|
||||
needsUpdate |= update(&stab.RollPI.ILimit, value);
|
||||
needsUpdateBank |= update(&bank.RollPI.ILimit, value);
|
||||
break;
|
||||
case TXPIDSETTINGS_PIDS_PITCHRATEKP:
|
||||
needsUpdate |= update(&stab.PitchRatePID.Kp, value);
|
||||
needsUpdateBank |= update(&bank.PitchRatePID.Kp, value);
|
||||
break;
|
||||
case TXPIDSETTINGS_PIDS_PITCHRATEKI:
|
||||
needsUpdate |= update(&stab.PitchRatePID.Ki, value);
|
||||
needsUpdateBank |= update(&bank.PitchRatePID.Ki, value);
|
||||
break;
|
||||
case TXPIDSETTINGS_PIDS_PITCHRATEKD:
|
||||
needsUpdate |= update(&stab.PitchRatePID.Kd, value);
|
||||
needsUpdateBank |= update(&bank.PitchRatePID.Kd, value);
|
||||
break;
|
||||
case TXPIDSETTINGS_PIDS_PITCHRATEILIMIT:
|
||||
needsUpdate |= update(&stab.PitchRatePID.ILimit, value);
|
||||
needsUpdateBank |= update(&bank.PitchRatePID.ILimit, value);
|
||||
break;
|
||||
case TXPIDSETTINGS_PIDS_PITCHATTITUDEKP:
|
||||
needsUpdate |= update(&stab.PitchPI.Kp, value);
|
||||
needsUpdateBank |= update(&bank.PitchPI.Kp, value);
|
||||
break;
|
||||
case TXPIDSETTINGS_PIDS_PITCHATTITUDEKI:
|
||||
needsUpdate |= update(&stab.PitchPI.Ki, value);
|
||||
needsUpdateBank |= update(&bank.PitchPI.Ki, value);
|
||||
break;
|
||||
case TXPIDSETTINGS_PIDS_PITCHATTITUDEILIMIT:
|
||||
needsUpdate |= update(&stab.PitchPI.ILimit, value);
|
||||
needsUpdateBank |= update(&bank.PitchPI.ILimit, value);
|
||||
break;
|
||||
case TXPIDSETTINGS_PIDS_ROLLPITCHRATEKP:
|
||||
needsUpdate |= update(&stab.RollRatePID.Kp, value);
|
||||
needsUpdate |= update(&stab.PitchRatePID.Kp, value);
|
||||
needsUpdateBank |= update(&bank.RollRatePID.Kp, value);
|
||||
needsUpdateBank |= update(&bank.PitchRatePID.Kp, value);
|
||||
break;
|
||||
case TXPIDSETTINGS_PIDS_ROLLPITCHRATEKI:
|
||||
needsUpdate |= update(&stab.RollRatePID.Ki, value);
|
||||
needsUpdate |= update(&stab.PitchRatePID.Ki, value);
|
||||
needsUpdateBank |= update(&bank.RollRatePID.Ki, value);
|
||||
needsUpdateBank |= update(&bank.PitchRatePID.Ki, value);
|
||||
break;
|
||||
case TXPIDSETTINGS_PIDS_ROLLPITCHRATEKD:
|
||||
needsUpdate |= update(&stab.RollRatePID.Kd, value);
|
||||
needsUpdate |= update(&stab.PitchRatePID.Kd, value);
|
||||
needsUpdateBank |= update(&bank.RollRatePID.Kd, value);
|
||||
needsUpdateBank |= update(&bank.PitchRatePID.Kd, value);
|
||||
break;
|
||||
case TXPIDSETTINGS_PIDS_ROLLPITCHRATEILIMIT:
|
||||
needsUpdate |= update(&stab.RollRatePID.ILimit, value);
|
||||
needsUpdate |= update(&stab.PitchRatePID.ILimit, value);
|
||||
needsUpdateBank |= update(&bank.RollRatePID.ILimit, value);
|
||||
needsUpdateBank |= update(&bank.PitchRatePID.ILimit, value);
|
||||
break;
|
||||
case TXPIDSETTINGS_PIDS_ROLLPITCHATTITUDEKP:
|
||||
needsUpdate |= update(&stab.RollPI.Kp, value);
|
||||
needsUpdate |= update(&stab.PitchPI.Kp, value);
|
||||
needsUpdateBank |= update(&bank.RollPI.Kp, value);
|
||||
needsUpdateBank |= update(&bank.PitchPI.Kp, value);
|
||||
break;
|
||||
case TXPIDSETTINGS_PIDS_ROLLPITCHATTITUDEKI:
|
||||
needsUpdate |= update(&stab.RollPI.Ki, value);
|
||||
needsUpdate |= update(&stab.PitchPI.Ki, value);
|
||||
needsUpdateBank |= update(&bank.RollPI.Ki, value);
|
||||
needsUpdateBank |= update(&bank.PitchPI.Ki, value);
|
||||
break;
|
||||
case TXPIDSETTINGS_PIDS_ROLLPITCHATTITUDEILIMIT:
|
||||
needsUpdate |= update(&stab.RollPI.ILimit, value);
|
||||
needsUpdate |= update(&stab.PitchPI.ILimit, value);
|
||||
needsUpdateBank |= update(&bank.RollPI.ILimit, value);
|
||||
needsUpdateBank |= update(&bank.PitchPI.ILimit, value);
|
||||
break;
|
||||
case TXPIDSETTINGS_PIDS_YAWRATEKP:
|
||||
needsUpdate |= update(&stab.YawRatePID.Kp, value);
|
||||
needsUpdateBank |= update(&bank.YawRatePID.Kp, value);
|
||||
break;
|
||||
case TXPIDSETTINGS_PIDS_YAWRATEKI:
|
||||
needsUpdate |= update(&stab.YawRatePID.Ki, value);
|
||||
needsUpdateBank |= update(&bank.YawRatePID.Ki, value);
|
||||
break;
|
||||
case TXPIDSETTINGS_PIDS_YAWRATEKD:
|
||||
needsUpdate |= update(&stab.YawRatePID.Kd, value);
|
||||
needsUpdateBank |= update(&bank.YawRatePID.Kd, value);
|
||||
break;
|
||||
case TXPIDSETTINGS_PIDS_YAWRATEILIMIT:
|
||||
needsUpdate |= update(&stab.YawRatePID.ILimit, value);
|
||||
needsUpdateBank |= update(&bank.YawRatePID.ILimit, value);
|
||||
break;
|
||||
case TXPIDSETTINGS_PIDS_YAWATTITUDEKP:
|
||||
needsUpdate |= update(&stab.YawPI.Kp, value);
|
||||
needsUpdateBank |= update(&bank.YawPI.Kp, value);
|
||||
break;
|
||||
case TXPIDSETTINGS_PIDS_YAWATTITUDEKI:
|
||||
needsUpdate |= update(&stab.YawPI.Ki, value);
|
||||
needsUpdateBank |= update(&bank.YawPI.Ki, value);
|
||||
break;
|
||||
case TXPIDSETTINGS_PIDS_YAWATTITUDEILIMIT:
|
||||
needsUpdate |= update(&stab.YawPI.ILimit, value);
|
||||
needsUpdateBank |= update(&bank.YawPI.ILimit, value);
|
||||
break;
|
||||
case TXPIDSETTINGS_PIDS_GYROTAU:
|
||||
needsUpdate |= update(&stab.GyroTau, value);
|
||||
needsUpdateStab |= update(&stab.GyroTau, value);
|
||||
break;
|
||||
default:
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
}
|
||||
}
|
||||
if (needsUpdate) {
|
||||
if (needsUpdateStab) {
|
||||
StabilizationSettingsSet(&stab);
|
||||
}
|
||||
if (needsUpdateBank) {
|
||||
switch (inst.BankNumber) {
|
||||
case 0:
|
||||
StabilizationSettingsBank1Set((StabilizationSettingsBank1Data *)&bank);
|
||||
break;
|
||||
|
||||
case 1:
|
||||
StabilizationSettingsBank2Set((StabilizationSettingsBank2Data *)&bank);
|
||||
break;
|
||||
|
||||
case 2:
|
||||
StabilizationSettingsBank2Set((StabilizationSettingsBank2Data *)&bank);
|
||||
break;
|
||||
|
||||
default:
|
||||
return;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
|
@ -65,6 +65,7 @@
|
||||
#include "nedaccel.h"
|
||||
#include "stabilizationdesired.h"
|
||||
#include "stabilizationsettings.h"
|
||||
#include "stabilizationbank.h"
|
||||
#include "systemsettings.h"
|
||||
#include "velocitydesired.h"
|
||||
#include "velocitystate.h"
|
||||
@ -575,7 +576,7 @@ static void updateVtolDesiredAttitude(bool yaw_attitude)
|
||||
StabilizationDesiredData stabDesired;
|
||||
AttitudeStateData attitudeState;
|
||||
NedAccelData nedAccel;
|
||||
StabilizationSettingsData stabSettings;
|
||||
StabilizationBankData stabSettings;
|
||||
SystemSettingsData systemSettings;
|
||||
|
||||
float northError;
|
||||
@ -593,7 +594,7 @@ static void updateVtolDesiredAttitude(bool yaw_attitude)
|
||||
StabilizationDesiredGet(&stabDesired);
|
||||
VelocityDesiredGet(&velocityDesired);
|
||||
AttitudeStateGet(&attitudeState);
|
||||
StabilizationSettingsGet(&stabSettings);
|
||||
StabilizationBankGet(&stabSettings);
|
||||
NedAccelGet(&nedAccel);
|
||||
|
||||
float northVel = 0, eastVel = 0, downVel = 0;
|
||||
|
@ -84,6 +84,10 @@ ifndef TESTAPP
|
||||
SRC += $(OPUAVSYNTHDIR)/systemsettings.c
|
||||
SRC += $(OPUAVSYNTHDIR)/stabilizationdesired.c
|
||||
SRC += $(OPUAVSYNTHDIR)/stabilizationsettings.c
|
||||
SRC += $(OPUAVSYNTHDIR)/stabilizationsettingsbank1.c
|
||||
SRC += $(OPUAVSYNTHDIR)/stabilizationsettingsbank2.c
|
||||
SRC += $(OPUAVSYNTHDIR)/stabilizationsettingsbank3.c
|
||||
SRC += $(OPUAVSYNTHDIR)/stabilizationbank.c
|
||||
SRC += $(OPUAVSYNTHDIR)/actuatorcommand.c
|
||||
SRC += $(OPUAVSYNTHDIR)/actuatordesired.c
|
||||
SRC += $(OPUAVSYNTHDIR)/actuatorsettings.c
|
||||
|
@ -156,7 +156,7 @@
|
||||
#define PIOS_ACTUATOR_STACK_SIZE 1020
|
||||
#define PIOS_MANUAL_STACK_SIZE 800
|
||||
#define PIOS_SYSTEM_STACK_SIZE 660
|
||||
#define PIOS_STABILIZATION_STACK_SIZE 524
|
||||
#define PIOS_STABILIZATION_STACK_SIZE 790
|
||||
#define PIOS_TELEM_STACK_SIZE 800
|
||||
#define PIOS_EVENTDISPATCHER_STACK_SIZE 130
|
||||
|
||||
|
@ -81,6 +81,10 @@ UAVOBJSRCFILENAMES += revosettings
|
||||
UAVOBJSRCFILENAMES += sonaraltitude
|
||||
UAVOBJSRCFILENAMES += stabilizationdesired
|
||||
UAVOBJSRCFILENAMES += stabilizationsettings
|
||||
UAVOBJSRCFILENAMES += stabilizationsettingsbank1
|
||||
UAVOBJSRCFILENAMES += stabilizationsettingsbank2
|
||||
UAVOBJSRCFILENAMES += stabilizationsettingsbank3
|
||||
UAVOBJSRCFILENAMES += stabilizationbank
|
||||
UAVOBJSRCFILENAMES += systemalarms
|
||||
UAVOBJSRCFILENAMES += systemsettings
|
||||
UAVOBJSRCFILENAMES += systemstats
|
||||
|
@ -4,7 +4,7 @@
|
||||
# Makefile for OpenPilot UAVObject code
|
||||
#
|
||||
# The OpenPilot Team, http://www.openpilot.org, Copyright (C) 2011.
|
||||
#
|
||||
#
|
||||
# This program is free software; you can redistribute it and/or modify
|
||||
# it under the terms of the GNU General Public License as published by
|
||||
# the Free Software Foundation; either version 3 of the License, or
|
||||
@ -81,6 +81,10 @@ UAVOBJSRCFILENAMES += revosettings
|
||||
UAVOBJSRCFILENAMES += sonaraltitude
|
||||
UAVOBJSRCFILENAMES += stabilizationdesired
|
||||
UAVOBJSRCFILENAMES += stabilizationsettings
|
||||
UAVOBJSRCFILENAMES += stabilizationsettingsbank1
|
||||
UAVOBJSRCFILENAMES += stabilizationsettingsbank2
|
||||
UAVOBJSRCFILENAMES += stabilizationsettingsbank3
|
||||
UAVOBJSRCFILENAMES += stabilizationbank
|
||||
UAVOBJSRCFILENAMES += systemalarms
|
||||
UAVOBJSRCFILENAMES += systemsettings
|
||||
UAVOBJSRCFILENAMES += systemstats
|
||||
|
@ -4,7 +4,7 @@
|
||||
# Makefile for OpenPilot UAVObject code
|
||||
#
|
||||
# The OpenPilot Team, http://www.openpilot.org, Copyright (C) 2011.
|
||||
#
|
||||
#
|
||||
# This program is free software; you can redistribute it and/or modify
|
||||
# it under the terms of the GNU General Public License as published by
|
||||
# the Free Software Foundation; either version 3 of the License, or
|
||||
@ -81,6 +81,10 @@ UAVOBJSRCFILENAMES += relaytuningsettings
|
||||
UAVOBJSRCFILENAMES += sonaraltitude
|
||||
UAVOBJSRCFILENAMES += stabilizationdesired
|
||||
UAVOBJSRCFILENAMES += stabilizationsettings
|
||||
UAVOBJSRCFILENAMES += stabilizationsettingsbank1
|
||||
UAVOBJSRCFILENAMES += stabilizationsettingsbank2
|
||||
UAVOBJSRCFILENAMES += stabilizationsettingsbank3
|
||||
UAVOBJSRCFILENAMES += stabilizationbank
|
||||
UAVOBJSRCFILENAMES += systemalarms
|
||||
UAVOBJSRCFILENAMES += systemsettings
|
||||
UAVOBJSRCFILENAMES += systemstats
|
||||
@ -97,8 +101,8 @@ UAVOBJSRCFILENAMES += hwsettings
|
||||
UAVOBJSRCFILENAMES += receiveractivity
|
||||
UAVOBJSRCFILENAMES += cameradesired
|
||||
UAVOBJSRCFILENAMES += camerastabsettings
|
||||
UAVOBJSRCFILENAMES += altitudeholdsettings
|
||||
UAVOBJSRCFILENAMES += altitudefiltersettings
|
||||
UAVOBJSRCFILENAMES += altitudeholdsettings
|
||||
UAVOBJSRCFILENAMES += altitudefiltersettings
|
||||
UAVOBJSRCFILENAMES += revosettings
|
||||
UAVOBJSRCFILENAMES += altitudeholddesired
|
||||
UAVOBJSRCFILENAMES += altitudeholdstatus
|
||||
|
@ -30,6 +30,7 @@
|
||||
#include <QHBoxLayout>
|
||||
#include <QLabel>
|
||||
#include <QtCore/QDebug>
|
||||
#include <QScrollBar>
|
||||
|
||||
MyTabbedStackWidget::MyTabbedStackWidget(QWidget *parent, bool isVertical, bool iconAbove)
|
||||
: QWidget(parent),
|
||||
@ -37,8 +38,8 @@ MyTabbedStackWidget::MyTabbedStackWidget(QWidget *parent, bool isVertical, bool
|
||||
m_iconAbove(iconAbove)
|
||||
{
|
||||
m_listWidget = new QListWidget();
|
||||
m_listWidget->setObjectName("list");
|
||||
m_stackWidget = new QStackedWidget();
|
||||
m_stackWidget->setSizePolicy(QSizePolicy::Minimum, QSizePolicy::Expanding);
|
||||
|
||||
QBoxLayout *toplevelLayout;
|
||||
if (m_vertical) {
|
||||
@ -58,16 +59,22 @@ MyTabbedStackWidget::MyTabbedStackWidget(QWidget *parent, bool isVertical, bool
|
||||
}
|
||||
|
||||
if (m_iconAbove && m_vertical) {
|
||||
m_listWidget->setFixedWidth(80); // this should be computed instead
|
||||
m_listWidget->setFixedWidth(LIST_VIEW_WIDTH); // this should be computed instead
|
||||
m_listWidget->setWrapping(false);
|
||||
}
|
||||
|
||||
toplevelLayout->setSpacing(0);
|
||||
toplevelLayout->setContentsMargins(0, 0, 0, 0);
|
||||
m_listWidget->setContentsMargins(0, 0, 0, 0);
|
||||
m_listWidget->setSpacing(0);
|
||||
m_listWidget->setViewMode(QListView::IconMode);
|
||||
m_listWidget->setMovement(QListView::Static);
|
||||
m_listWidget->setUniformItemSizes(true);
|
||||
m_listWidget->setStyleSheet("#list {border: 0px; margin-left: 9px; margin-top: 9px; background-color: transparent; }");
|
||||
|
||||
m_stackWidget->setSizePolicy(QSizePolicy::Minimum, QSizePolicy::Expanding);
|
||||
m_stackWidget->setContentsMargins(0, 0, 0, 0);
|
||||
|
||||
toplevelLayout->setSpacing(0);
|
||||
toplevelLayout->setContentsMargins(0, 0, 0, 0);
|
||||
setLayout(toplevelLayout);
|
||||
|
||||
connect(m_listWidget, SIGNAL(currentRowChanged(int)), this, SLOT(showWidget(int)), Qt::QueuedConnection);
|
||||
@ -127,6 +134,12 @@ void MyTabbedStackWidget::showWidget(int index)
|
||||
}
|
||||
}
|
||||
|
||||
void MyTabbedStackWidget::resizeEvent(QResizeEvent *event)
|
||||
{
|
||||
QWidget::resizeEvent(event);
|
||||
m_listWidget->setFixedWidth(m_listWidget->verticalScrollBar()->isVisible() ? LIST_VIEW_WIDTH + 20 : LIST_VIEW_WIDTH);
|
||||
}
|
||||
|
||||
void MyTabbedStackWidget::insertCornerWidget(int index, QWidget *widget)
|
||||
{
|
||||
Q_UNUSED(index);
|
||||
|
@ -76,6 +76,10 @@ private:
|
||||
QStackedWidget *m_stackWidget;
|
||||
bool m_vertical;
|
||||
bool m_iconAbove;
|
||||
static const int LIST_VIEW_WIDTH = 80;
|
||||
|
||||
protected:
|
||||
void resizeEvent(QResizeEvent * event);
|
||||
};
|
||||
|
||||
#endif // MYTABBEDSTACKWIDGET_H
|
||||
|
@ -75,14 +75,14 @@ ConfigCCHWWidget::ConfigCCHWWidget(QWidget *parent) : ConfigTaskWidget(parent)
|
||||
break;
|
||||
}
|
||||
addApplySaveButtons(m_telemetry->saveTelemetryToRAM, m_telemetry->saveTelemetryToSD);
|
||||
addUAVObjectToWidgetRelation("HwSettings", "CC_FlexiPort", m_telemetry->cbFlexi);
|
||||
addUAVObjectToWidgetRelation("HwSettings", "CC_MainPort", m_telemetry->cbTele);
|
||||
addUAVObjectToWidgetRelation("HwSettings", "CC_RcvrPort", m_telemetry->cbRcvr);
|
||||
addUAVObjectToWidgetRelation("HwSettings", "USB_HIDPort", m_telemetry->cbUsbHid);
|
||||
addUAVObjectToWidgetRelation("HwSettings", "USB_VCPPort", m_telemetry->cbUsbVcp);
|
||||
addUAVObjectToWidgetRelation("HwSettings", "TelemetrySpeed", m_telemetry->telemetrySpeed);
|
||||
addUAVObjectToWidgetRelation("HwSettings", "GPSSpeed", m_telemetry->gpsSpeed);
|
||||
addUAVObjectToWidgetRelation("HwSettings", "ComUsbBridgeSpeed", m_telemetry->comUsbBridgeSpeed);
|
||||
addWidgetBinding("HwSettings", "CC_FlexiPort", m_telemetry->cbFlexi);
|
||||
addWidgetBinding("HwSettings", "CC_MainPort", m_telemetry->cbTele);
|
||||
addWidgetBinding("HwSettings", "CC_RcvrPort", m_telemetry->cbRcvr);
|
||||
addWidgetBinding("HwSettings", "USB_HIDPort", m_telemetry->cbUsbHid);
|
||||
addWidgetBinding("HwSettings", "USB_VCPPort", m_telemetry->cbUsbVcp);
|
||||
addWidgetBinding("HwSettings", "TelemetrySpeed", m_telemetry->telemetrySpeed);
|
||||
addWidgetBinding("HwSettings", "GPSSpeed", m_telemetry->gpsSpeed);
|
||||
addWidgetBinding("HwSettings", "ComUsbBridgeSpeed", m_telemetry->comUsbBridgeSpeed);
|
||||
connect(m_telemetry->cchwHelp, SIGNAL(clicked()), this, SLOT(openHelp()));
|
||||
enableSaveButtons(false);
|
||||
populateWidgets();
|
||||
|
@ -58,12 +58,12 @@ ConfigCCAttitudeWidget::ConfigCCAttitudeWidget(QWidget *parent) :
|
||||
// Connect the help button
|
||||
connect(ui->ccAttitudeHelp, SIGNAL(clicked()), this, SLOT(openHelp()));
|
||||
|
||||
addUAVObjectToWidgetRelation("AttitudeSettings", "ZeroDuringArming", ui->zeroGyroBiasOnArming);
|
||||
addUAVObjectToWidgetRelation("AttitudeSettings", "AccelTau", ui->accelTauSpinbox);
|
||||
addWidgetBinding("AttitudeSettings", "ZeroDuringArming", ui->zeroGyroBiasOnArming);
|
||||
addWidgetBinding("AttitudeSettings", "AccelTau", ui->accelTauSpinbox);
|
||||
|
||||
addUAVObjectToWidgetRelation("AttitudeSettings", "BoardRotation", ui->rollBias, AttitudeSettings::BOARDROTATION_ROLL);
|
||||
addUAVObjectToWidgetRelation("AttitudeSettings", "BoardRotation", ui->pitchBias, AttitudeSettings::BOARDROTATION_PITCH);
|
||||
addUAVObjectToWidgetRelation("AttitudeSettings", "BoardRotation", ui->yawBias, AttitudeSettings::BOARDROTATION_YAW);
|
||||
addWidgetBinding("AttitudeSettings", "BoardRotation", ui->rollBias, AttitudeSettings::BOARDROTATION_ROLL);
|
||||
addWidgetBinding("AttitudeSettings", "BoardRotation", ui->pitchBias, AttitudeSettings::BOARDROTATION_PITCH);
|
||||
addWidgetBinding("AttitudeSettings", "BoardRotation", ui->yawBias, AttitudeSettings::BOARDROTATION_YAW);
|
||||
addWidget(ui->zeroBias);
|
||||
refreshWidgetsValues();
|
||||
}
|
||||
|
@ -84,11 +84,11 @@ ConfigInputWidget::ConfigInputWidget(QWidget *parent) :
|
||||
inputChannelForm *inpForm = new inputChannelForm(this, index == 0);
|
||||
ui->channelSettings->layout()->addWidget(inpForm); // Add the row to the UI
|
||||
inpForm->setName(name);
|
||||
addUAVObjectToWidgetRelation("ManualControlSettings", "ChannelGroups", inpForm->ui->channelGroup, index);
|
||||
addUAVObjectToWidgetRelation("ManualControlSettings", "ChannelNumber", inpForm->ui->channelNumber, index);
|
||||
addUAVObjectToWidgetRelation("ManualControlSettings", "ChannelMin", inpForm->ui->channelMin, index);
|
||||
addUAVObjectToWidgetRelation("ManualControlSettings", "ChannelNeutral", inpForm->ui->channelNeutral, index);
|
||||
addUAVObjectToWidgetRelation("ManualControlSettings", "ChannelMax", inpForm->ui->channelMax, index);
|
||||
addWidgetBinding("ManualControlSettings", "ChannelGroups", inpForm->ui->channelGroup, index);
|
||||
addWidgetBinding("ManualControlSettings", "ChannelNumber", inpForm->ui->channelNumber, index);
|
||||
addWidgetBinding("ManualControlSettings", "ChannelMin", inpForm->ui->channelMin, index);
|
||||
addWidgetBinding("ManualControlSettings", "ChannelNeutral", inpForm->ui->channelNeutral, index);
|
||||
addWidgetBinding("ManualControlSettings", "ChannelMax", inpForm->ui->channelMax, index);
|
||||
addWidget(inpForm->ui->channelNumberDropdown);
|
||||
addWidget(inpForm->ui->channelRev);
|
||||
addWidget(inpForm->ui->channelResponseTime);
|
||||
@ -101,7 +101,7 @@ ConfigInputWidget::ConfigInputWidget(QWidget *parent) :
|
||||
case ManualControlSettings::CHANNELGROUPS_ACCESSORY0:
|
||||
case ManualControlSettings::CHANNELGROUPS_ACCESSORY1:
|
||||
case ManualControlSettings::CHANNELGROUPS_ACCESSORY2:
|
||||
addUAVObjectToWidgetRelation("ManualControlSettings", "ResponseTime", inpForm->ui->channelResponseTime, indexRT);
|
||||
addWidgetBinding("ManualControlSettings", "ResponseTime", inpForm->ui->channelResponseTime, indexRT);
|
||||
++indexRT;
|
||||
break;
|
||||
case ManualControlSettings::CHANNELGROUPS_THROTTLE:
|
||||
@ -117,7 +117,7 @@ ConfigInputWidget::ConfigInputWidget(QWidget *parent) :
|
||||
++index;
|
||||
}
|
||||
|
||||
addUAVObjectToWidgetRelation("ManualControlSettings", "Deadband", ui->deadband, 0, 0.01f);
|
||||
addWidgetBinding("ManualControlSettings", "Deadband", ui->deadband, 0, 0.01f);
|
||||
|
||||
connect(ui->configurationWizard, SIGNAL(clicked()), this, SLOT(goToWizard()));
|
||||
connect(ui->stackedWidget, SIGNAL(currentChanged(int)), this, SLOT(disableWizardButton(int)));
|
||||
@ -128,26 +128,30 @@ ConfigInputWidget::ConfigInputWidget(QWidget *parent) :
|
||||
connect(ui->wzBack, SIGNAL(clicked()), this, SLOT(wzBack()));
|
||||
|
||||
ui->stackedWidget->setCurrentIndex(0);
|
||||
addUAVObjectToWidgetRelation("ManualControlSettings", "FlightModePosition", ui->fmsModePos1, 0, 1, true);
|
||||
addUAVObjectToWidgetRelation("ManualControlSettings", "FlightModePosition", ui->fmsModePos2, 1, 1, true);
|
||||
addUAVObjectToWidgetRelation("ManualControlSettings", "FlightModePosition", ui->fmsModePos3, 2, 1, true);
|
||||
addUAVObjectToWidgetRelation("ManualControlSettings", "FlightModePosition", ui->fmsModePos4, 3, 1, true);
|
||||
addUAVObjectToWidgetRelation("ManualControlSettings", "FlightModePosition", ui->fmsModePos5, 4, 1, true);
|
||||
addUAVObjectToWidgetRelation("ManualControlSettings", "FlightModePosition", ui->fmsModePos6, 5, 1, true);
|
||||
addUAVObjectToWidgetRelation("ManualControlSettings", "FlightModeNumber", ui->fmsPosNum);
|
||||
addWidgetBinding("ManualControlSettings", "FlightModePosition", ui->fmsModePos1, 0, 1, true);
|
||||
addWidgetBinding("ManualControlSettings", "FlightModePosition", ui->fmsModePos2, 1, 1, true);
|
||||
addWidgetBinding("ManualControlSettings", "FlightModePosition", ui->fmsModePos3, 2, 1, true);
|
||||
addWidgetBinding("ManualControlSettings", "FlightModePosition", ui->fmsModePos4, 3, 1, true);
|
||||
addWidgetBinding("ManualControlSettings", "FlightModePosition", ui->fmsModePos5, 4, 1, true);
|
||||
addWidgetBinding("ManualControlSettings", "FlightModePosition", ui->fmsModePos6, 5, 1, true);
|
||||
addWidgetBinding("ManualControlSettings", "FlightModeNumber", ui->fmsPosNum);
|
||||
|
||||
addUAVObjectToWidgetRelation("ManualControlSettings", "Stabilization1Settings", ui->fmsSsPos1Roll, "Roll", 1, true);
|
||||
addUAVObjectToWidgetRelation("ManualControlSettings", "Stabilization2Settings", ui->fmsSsPos2Roll, "Roll", 1, true);
|
||||
addUAVObjectToWidgetRelation("ManualControlSettings", "Stabilization3Settings", ui->fmsSsPos3Roll, "Roll", 1, true);
|
||||
addUAVObjectToWidgetRelation("ManualControlSettings", "Stabilization1Settings", ui->fmsSsPos1Pitch, "Pitch", 1, true);
|
||||
addUAVObjectToWidgetRelation("ManualControlSettings", "Stabilization2Settings", ui->fmsSsPos2Pitch, "Pitch", 1, true);
|
||||
addUAVObjectToWidgetRelation("ManualControlSettings", "Stabilization3Settings", ui->fmsSsPos3Pitch, "Pitch", 1, true);
|
||||
addUAVObjectToWidgetRelation("ManualControlSettings", "Stabilization1Settings", ui->fmsSsPos1Yaw, "Yaw", 1, true);
|
||||
addUAVObjectToWidgetRelation("ManualControlSettings", "Stabilization2Settings", ui->fmsSsPos2Yaw, "Yaw", 1, true);
|
||||
addUAVObjectToWidgetRelation("ManualControlSettings", "Stabilization3Settings", ui->fmsSsPos3Yaw, "Yaw", 1, true);
|
||||
addWidgetBinding("ManualControlSettings", "Stabilization1Settings", ui->fmsSsPos1Roll, "Roll", 1, true);
|
||||
addWidgetBinding("ManualControlSettings", "Stabilization2Settings", ui->fmsSsPos2Roll, "Roll", 1, true);
|
||||
addWidgetBinding("ManualControlSettings", "Stabilization3Settings", ui->fmsSsPos3Roll, "Roll", 1, true);
|
||||
addWidgetBinding("ManualControlSettings", "Stabilization1Settings", ui->fmsSsPos1Pitch, "Pitch", 1, true);
|
||||
addWidgetBinding("ManualControlSettings", "Stabilization2Settings", ui->fmsSsPos2Pitch, "Pitch", 1, true);
|
||||
addWidgetBinding("ManualControlSettings", "Stabilization3Settings", ui->fmsSsPos3Pitch, "Pitch", 1, true);
|
||||
addWidgetBinding("ManualControlSettings", "Stabilization1Settings", ui->fmsSsPos1Yaw, "Yaw", 1, true);
|
||||
addWidgetBinding("ManualControlSettings", "Stabilization2Settings", ui->fmsSsPos2Yaw, "Yaw", 1, true);
|
||||
addWidgetBinding("ManualControlSettings", "Stabilization3Settings", ui->fmsSsPos3Yaw, "Yaw", 1, true);
|
||||
|
||||
addUAVObjectToWidgetRelation("ManualControlSettings", "Arming", ui->armControl);
|
||||
addUAVObjectToWidgetRelation("ManualControlSettings", "ArmedTimeout", ui->armTimeout, 0, 1000);
|
||||
addWidgetBinding("StabilizationSettings", "FlightModeMap", ui->pidBankSs1, "Stabilized1", 1, true);
|
||||
addWidgetBinding("StabilizationSettings", "FlightModeMap", ui->pidBankSs2, "Stabilized2", 1, true);
|
||||
addWidgetBinding("StabilizationSettings", "FlightModeMap", ui->pidBankSs3, "Stabilized3", 1, true);
|
||||
|
||||
addWidgetBinding("ManualControlSettings", "Arming", ui->armControl);
|
||||
addWidgetBinding("ManualControlSettings", "ArmedTimeout", ui->armTimeout, 0, 1000);
|
||||
connect(ManualControlCommand::GetInstance(getObjectManager()), SIGNAL(objectUpdated(UAVObject *)), this, SLOT(moveFMSlider()));
|
||||
connect(ManualControlSettings::GetInstance(getObjectManager()), SIGNAL(objectUpdated(UAVObject *)), this, SLOT(updatePositionSlider()));
|
||||
|
||||
|
@ -60,39 +60,39 @@ ConfigPipXtremeWidget::ConfigPipXtremeWidget(QWidget *parent) : ConfigTaskWidget
|
||||
}
|
||||
addApplySaveButtons(m_oplink->Apply, m_oplink->Save);
|
||||
|
||||
addUAVObjectToWidgetRelation("OPLinkSettings", "MainPort", m_oplink->MainPort);
|
||||
addUAVObjectToWidgetRelation("OPLinkSettings", "FlexiPort", m_oplink->FlexiPort);
|
||||
addUAVObjectToWidgetRelation("OPLinkSettings", "VCPPort", m_oplink->VCPPort);
|
||||
addUAVObjectToWidgetRelation("OPLinkSettings", "ComSpeed", m_oplink->ComSpeed);
|
||||
addUAVObjectToWidgetRelation("OPLinkSettings", "MaxRFPower", m_oplink->MaxRFTxPower);
|
||||
addUAVObjectToWidgetRelation("OPLinkSettings", "MinChannel", m_oplink->MinimumChannel);
|
||||
addUAVObjectToWidgetRelation("OPLinkSettings", "MaxChannel", m_oplink->MaximumChannel);
|
||||
addUAVObjectToWidgetRelation("OPLinkSettings", "ChannelSet", m_oplink->ChannelSet);
|
||||
addUAVObjectToWidgetRelation("OPLinkSettings", "CoordID", m_oplink->CoordID);
|
||||
addUAVObjectToWidgetRelation("OPLinkSettings", "Coordinator", m_oplink->Coordinator);
|
||||
addUAVObjectToWidgetRelation("OPLinkSettings", "OneWay", m_oplink->OneWayLink);
|
||||
addUAVObjectToWidgetRelation("OPLinkSettings", "PPMOnly", m_oplink->PPMOnly);
|
||||
addUAVObjectToWidgetRelation("OPLinkSettings", "PPM", m_oplink->PPM);
|
||||
addWidgetBinding("OPLinkSettings", "MainPort", m_oplink->MainPort);
|
||||
addWidgetBinding("OPLinkSettings", "FlexiPort", m_oplink->FlexiPort);
|
||||
addWidgetBinding("OPLinkSettings", "VCPPort", m_oplink->VCPPort);
|
||||
addWidgetBinding("OPLinkSettings", "ComSpeed", m_oplink->ComSpeed);
|
||||
addWidgetBinding("OPLinkSettings", "MaxRFPower", m_oplink->MaxRFTxPower);
|
||||
addWidgetBinding("OPLinkSettings", "MinChannel", m_oplink->MinimumChannel);
|
||||
addWidgetBinding("OPLinkSettings", "MaxChannel", m_oplink->MaximumChannel);
|
||||
addWidgetBinding("OPLinkSettings", "ChannelSet", m_oplink->ChannelSet);
|
||||
addWidgetBinding("OPLinkSettings", "CoordID", m_oplink->CoordID);
|
||||
addWidgetBinding("OPLinkSettings", "Coordinator", m_oplink->Coordinator);
|
||||
addWidgetBinding("OPLinkSettings", "OneWay", m_oplink->OneWayLink);
|
||||
addWidgetBinding("OPLinkSettings", "PPMOnly", m_oplink->PPMOnly);
|
||||
addWidgetBinding("OPLinkSettings", "PPM", m_oplink->PPM);
|
||||
|
||||
addUAVObjectToWidgetRelation("OPLinkStatus", "DeviceID", m_oplink->DeviceID);
|
||||
addUAVObjectToWidgetRelation("OPLinkStatus", "RxGood", m_oplink->Good);
|
||||
addUAVObjectToWidgetRelation("OPLinkStatus", "RxCorrected", m_oplink->Corrected);
|
||||
addUAVObjectToWidgetRelation("OPLinkStatus", "RxErrors", m_oplink->Errors);
|
||||
addUAVObjectToWidgetRelation("OPLinkStatus", "RxMissed", m_oplink->Missed);
|
||||
addUAVObjectToWidgetRelation("OPLinkStatus", "RxFailure", m_oplink->RxFailure);
|
||||
addUAVObjectToWidgetRelation("OPLinkStatus", "UAVTalkErrors", m_oplink->UAVTalkErrors);
|
||||
addUAVObjectToWidgetRelation("OPLinkStatus", "TxDropped", m_oplink->Dropped);
|
||||
addUAVObjectToWidgetRelation("OPLinkStatus", "TxResent", m_oplink->Resent);
|
||||
addUAVObjectToWidgetRelation("OPLinkStatus", "TxFailure", m_oplink->TxFailure);
|
||||
addUAVObjectToWidgetRelation("OPLinkStatus", "Resets", m_oplink->Resets);
|
||||
addUAVObjectToWidgetRelation("OPLinkStatus", "Timeouts", m_oplink->Timeouts);
|
||||
addUAVObjectToWidgetRelation("OPLinkStatus", "RSSI", m_oplink->RSSI);
|
||||
addUAVObjectToWidgetRelation("OPLinkStatus", "HeapRemaining", m_oplink->FreeHeap);
|
||||
addUAVObjectToWidgetRelation("OPLinkStatus", "LinkQuality", m_oplink->LinkQuality);
|
||||
addUAVObjectToWidgetRelation("OPLinkStatus", "RXSeq", m_oplink->RXSeq);
|
||||
addUAVObjectToWidgetRelation("OPLinkStatus", "TXSeq", m_oplink->TXSeq);
|
||||
addUAVObjectToWidgetRelation("OPLinkStatus", "RXRate", m_oplink->RXRate);
|
||||
addUAVObjectToWidgetRelation("OPLinkStatus", "TXRate", m_oplink->TXRate);
|
||||
addWidgetBinding("OPLinkStatus", "DeviceID", m_oplink->DeviceID);
|
||||
addWidgetBinding("OPLinkStatus", "RxGood", m_oplink->Good);
|
||||
addWidgetBinding("OPLinkStatus", "RxCorrected", m_oplink->Corrected);
|
||||
addWidgetBinding("OPLinkStatus", "RxErrors", m_oplink->Errors);
|
||||
addWidgetBinding("OPLinkStatus", "RxMissed", m_oplink->Missed);
|
||||
addWidgetBinding("OPLinkStatus", "RxFailure", m_oplink->RxFailure);
|
||||
addWidgetBinding("OPLinkStatus", "UAVTalkErrors", m_oplink->UAVTalkErrors);
|
||||
addWidgetBinding("OPLinkStatus", "TxDropped", m_oplink->Dropped);
|
||||
addWidgetBinding("OPLinkStatus", "TxResent", m_oplink->Resent);
|
||||
addWidgetBinding("OPLinkStatus", "TxFailure", m_oplink->TxFailure);
|
||||
addWidgetBinding("OPLinkStatus", "Resets", m_oplink->Resets);
|
||||
addWidgetBinding("OPLinkStatus", "Timeouts", m_oplink->Timeouts);
|
||||
addWidgetBinding("OPLinkStatus", "RSSI", m_oplink->RSSI);
|
||||
addWidgetBinding("OPLinkStatus", "HeapRemaining", m_oplink->FreeHeap);
|
||||
addWidgetBinding("OPLinkStatus", "LinkQuality", m_oplink->LinkQuality);
|
||||
addWidgetBinding("OPLinkStatus", "RXSeq", m_oplink->RXSeq);
|
||||
addWidgetBinding("OPLinkStatus", "TXSeq", m_oplink->TXSeq);
|
||||
addWidgetBinding("OPLinkStatus", "RXRate", m_oplink->RXRate);
|
||||
addWidgetBinding("OPLinkStatus", "TXRate", m_oplink->TXRate);
|
||||
|
||||
// Connect the bind buttons
|
||||
connect(m_oplink->Bind1, SIGNAL(clicked()), this, SLOT(bind1()));
|
||||
|
@ -49,21 +49,21 @@ ConfigRevoHWWidget::ConfigRevoHWWidget(QWidget *parent) : ConfigTaskWidget(paren
|
||||
|
||||
addApplySaveButtons(m_ui->saveTelemetryToRAM, m_ui->saveTelemetryToSD);
|
||||
|
||||
addUAVObjectToWidgetRelation("HwSettings", "RM_FlexiPort", m_ui->cbFlexi);
|
||||
addUAVObjectToWidgetRelation("HwSettings", "RM_MainPort", m_ui->cbMain);
|
||||
addUAVObjectToWidgetRelation("HwSettings", "RM_RcvrPort", m_ui->cbRcvr);
|
||||
addWidgetBinding("HwSettings", "RM_FlexiPort", m_ui->cbFlexi);
|
||||
addWidgetBinding("HwSettings", "RM_MainPort", m_ui->cbMain);
|
||||
addWidgetBinding("HwSettings", "RM_RcvrPort", m_ui->cbRcvr);
|
||||
|
||||
addUAVObjectToWidgetRelation("HwSettings", "USB_HIDPort", m_ui->cbUSBHIDFunction);
|
||||
addUAVObjectToWidgetRelation("HwSettings", "USB_VCPPort", m_ui->cbUSBVCPFunction);
|
||||
addUAVObjectToWidgetRelation("HwSettings", "ComUsbBridgeSpeed", m_ui->cbUSBVCPSpeed);
|
||||
addWidgetBinding("HwSettings", "USB_HIDPort", m_ui->cbUSBHIDFunction);
|
||||
addWidgetBinding("HwSettings", "USB_VCPPort", m_ui->cbUSBVCPFunction);
|
||||
addWidgetBinding("HwSettings", "ComUsbBridgeSpeed", m_ui->cbUSBVCPSpeed);
|
||||
|
||||
addUAVObjectToWidgetRelation("HwSettings", "TelemetrySpeed", m_ui->cbFlexiTelemSpeed);
|
||||
addUAVObjectToWidgetRelation("HwSettings", "GPSSpeed", m_ui->cbFlexiGPSSpeed);
|
||||
addUAVObjectToWidgetRelation("HwSettings", "ComUsbBridgeSpeed", m_ui->cbFlexiComSpeed);
|
||||
addWidgetBinding("HwSettings", "TelemetrySpeed", m_ui->cbFlexiTelemSpeed);
|
||||
addWidgetBinding("HwSettings", "GPSSpeed", m_ui->cbFlexiGPSSpeed);
|
||||
addWidgetBinding("HwSettings", "ComUsbBridgeSpeed", m_ui->cbFlexiComSpeed);
|
||||
|
||||
addUAVObjectToWidgetRelation("HwSettings", "TelemetrySpeed", m_ui->cbMainTelemSpeed);
|
||||
addUAVObjectToWidgetRelation("HwSettings", "GPSSpeed", m_ui->cbMainGPSSpeed);
|
||||
addUAVObjectToWidgetRelation("HwSettings", "ComUsbBridgeSpeed", m_ui->cbMainComSpeed);
|
||||
addWidgetBinding("HwSettings", "TelemetrySpeed", m_ui->cbMainTelemSpeed);
|
||||
addWidgetBinding("HwSettings", "GPSSpeed", m_ui->cbMainGPSSpeed);
|
||||
addWidgetBinding("HwSettings", "ComUsbBridgeSpeed", m_ui->cbMainComSpeed);
|
||||
|
||||
connect(m_ui->cchwHelp, SIGNAL(clicked()), this, SLOT(openHelp()));
|
||||
|
||||
|
@ -226,12 +226,12 @@ ConfigRevoWidget::ConfigRevoWidget(QWidget *parent) :
|
||||
|
||||
connect(m_ui->hlClearButton, SIGNAL(clicked()), this, SLOT(clearHomeLocation()));
|
||||
|
||||
addUAVObjectToWidgetRelation("RevoSettings", "FusionAlgorithm", m_ui->FusionAlgorithm);
|
||||
addWidgetBinding("RevoSettings", "FusionAlgorithm", m_ui->FusionAlgorithm);
|
||||
|
||||
addUAVObjectToWidgetRelation("AttitudeSettings", "BoardRotation", m_ui->rollRotation, AttitudeSettings::BOARDROTATION_ROLL);
|
||||
addUAVObjectToWidgetRelation("AttitudeSettings", "BoardRotation", m_ui->pitchRotation, AttitudeSettings::BOARDROTATION_PITCH);
|
||||
addUAVObjectToWidgetRelation("AttitudeSettings", "BoardRotation", m_ui->yawRotation, AttitudeSettings::BOARDROTATION_YAW);
|
||||
addUAVObjectToWidgetRelation("AttitudeSettings", "AccelTau", m_ui->accelTau);
|
||||
addWidgetBinding("AttitudeSettings", "BoardRotation", m_ui->rollRotation, AttitudeSettings::BOARDROTATION_ROLL);
|
||||
addWidgetBinding("AttitudeSettings", "BoardRotation", m_ui->pitchRotation, AttitudeSettings::BOARDROTATION_PITCH);
|
||||
addWidgetBinding("AttitudeSettings", "BoardRotation", m_ui->yawRotation, AttitudeSettings::BOARDROTATION_YAW);
|
||||
addWidgetBinding("AttitudeSettings", "AccelTau", m_ui->accelTau);
|
||||
|
||||
populateWidgets();
|
||||
refreshWidgetsValues();
|
||||
|
@ -35,17 +35,44 @@
|
||||
#include <QDesktopServices>
|
||||
#include <QUrl>
|
||||
#include <QList>
|
||||
#include <QTabBar>
|
||||
#include <QMessageBox>
|
||||
|
||||
#include <extensionsystem/pluginmanager.h>
|
||||
#include <coreplugin/generalsettings.h>
|
||||
#include "altitudeholdsettings.h"
|
||||
#include "stabilizationsettings.h"
|
||||
|
||||
ConfigStabilizationWidget::ConfigStabilizationWidget(QWidget *parent) : ConfigTaskWidget(parent),
|
||||
boardModel(0)
|
||||
boardModel(0), m_pidBankCount(0), m_currentPIDBank(0)
|
||||
{
|
||||
ui = new Ui_StabilizationWidget();
|
||||
ui->setupUi(this);
|
||||
|
||||
StabilizationSettings *stabSettings = qobject_cast<StabilizationSettings *>(getObject("StabilizationSettings"));
|
||||
Q_ASSERT(stabSettings);
|
||||
|
||||
m_pidBankCount = stabSettings->getField("FlightModeMap")->getOptions().count();
|
||||
|
||||
// Set up fake tab widget stuff for pid banks support
|
||||
m_pidTabBars.append(ui->basicPIDBankTabBar);
|
||||
m_pidTabBars.append(ui->advancedPIDBankTabBar);
|
||||
m_pidTabBars.append(ui->expertPIDBankTabBar);
|
||||
foreach(QTabBar * tabBar, m_pidTabBars) {
|
||||
for (int i = 0; i < m_pidBankCount; i++) {
|
||||
tabBar->addTab(tr("PID Bank %1").arg(i + 1));
|
||||
tabBar->setTabData(i, QString("StabilizationSettingsBank%1").arg(i + 1));
|
||||
}
|
||||
tabBar->setExpanding(false);
|
||||
connect(tabBar, SIGNAL(currentChanged(int)), this, SLOT(pidBankChanged(int)));
|
||||
}
|
||||
|
||||
for (int i = 0; i < m_pidBankCount; i++) {
|
||||
if (i > 0) {
|
||||
m_stabilizationObjectsString.append(",");
|
||||
}
|
||||
m_stabilizationObjectsString.append(m_pidTabBars.at(0)->tabData(i).toString());
|
||||
}
|
||||
|
||||
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
|
||||
Core::Internal::GeneralSettings *settings = pm->getObject<Core::Internal::GeneralSettings>();
|
||||
@ -205,6 +232,23 @@ void ConfigStabilizationWidget::onBoardConnected()
|
||||
ui->AltitudeHold->setEnabled((boardModel & 0xff00) == 0x0900);
|
||||
}
|
||||
|
||||
void ConfigStabilizationWidget::pidBankChanged(int index)
|
||||
{
|
||||
foreach(QTabBar * tabBar, m_pidTabBars) {
|
||||
disconnect(tabBar, SIGNAL(currentChanged(int)), this, SLOT(pidBankChanged(int)));
|
||||
tabBar->setCurrentIndex(index);
|
||||
connect(tabBar, SIGNAL(currentChanged(int)), this, SLOT(pidBankChanged(int)));
|
||||
}
|
||||
|
||||
for (int i = 0; i < m_pidTabBars.at(0)->count(); i++) {
|
||||
setWidgetBindingObjectEnabled(m_pidTabBars.at(0)->tabData(i).toString(), false);
|
||||
}
|
||||
|
||||
setWidgetBindingObjectEnabled(m_pidTabBars.at(0)->tabData(index).toString(), true);
|
||||
|
||||
m_currentPIDBank = index;
|
||||
}
|
||||
|
||||
bool ConfigStabilizationWidget::shouldObjectBeSaved(UAVObject *object)
|
||||
{
|
||||
// AltitudeHoldSettings should only be saved for Revolution board to avoid error.
|
||||
@ -214,3 +258,11 @@ bool ConfigStabilizationWidget::shouldObjectBeSaved(UAVObject *object)
|
||||
return true;
|
||||
}
|
||||
}
|
||||
|
||||
QString ConfigStabilizationWidget::mapObjectName(const QString objectName)
|
||||
{
|
||||
if (objectName == "StabilizationSettingsBankX") {
|
||||
return m_stabilizationObjectsString;
|
||||
}
|
||||
return ConfigTaskWidget::mapObjectName(objectName);
|
||||
}
|
||||
|
@ -48,11 +48,17 @@ public:
|
||||
private:
|
||||
Ui_StabilizationWidget *ui;
|
||||
QTimer *realtimeUpdates;
|
||||
QList<QTabBar *> m_pidTabBars;
|
||||
QString m_stabilizationObjectsString;
|
||||
|
||||
// Milliseconds between automatic 'Instant Updates'
|
||||
static const int AUTOMATIC_UPDATE_RATE = 500;
|
||||
|
||||
int m_pidBankCount;
|
||||
int boardModel;
|
||||
int m_currentPIDBank;
|
||||
protected:
|
||||
QString mapObjectName(const QString objectName);
|
||||
|
||||
protected slots:
|
||||
void refreshWidgetsValues(UAVObject *o = NULL);
|
||||
@ -62,6 +68,7 @@ private slots:
|
||||
void linkCheckBoxes(bool value);
|
||||
void processLinkedWidgets(QWidget *);
|
||||
void onBoardConnected();
|
||||
void pidBankChanged(int index);
|
||||
};
|
||||
|
||||
#endif // ConfigStabilizationWidget_H
|
||||
|
@ -51,26 +51,28 @@ ConfigTxPIDWidget::ConfigTxPIDWidget(QWidget *parent) : ConfigTaskWidget(parent)
|
||||
connect(m_txpid->Apply, SIGNAL(clicked()), this, SLOT(applySettings()));
|
||||
connect(m_txpid->Save, SIGNAL(clicked()), this, SLOT(saveSettings()));
|
||||
|
||||
addUAVObjectToWidgetRelation("TxPIDSettings", "PIDs", m_txpid->PID1, TxPIDSettings::PIDS_INSTANCE1);
|
||||
addUAVObjectToWidgetRelation("TxPIDSettings", "PIDs", m_txpid->PID2, TxPIDSettings::PIDS_INSTANCE2);
|
||||
addUAVObjectToWidgetRelation("TxPIDSettings", "PIDs", m_txpid->PID3, TxPIDSettings::PIDS_INSTANCE3);
|
||||
addWidgetBinding("TxPIDSettings", "BankNumber", m_txpid->pidBank, 0, 1, true);
|
||||
|
||||
addUAVObjectToWidgetRelation("TxPIDSettings", "Inputs", m_txpid->Input1, TxPIDSettings::INPUTS_INSTANCE1);
|
||||
addUAVObjectToWidgetRelation("TxPIDSettings", "Inputs", m_txpid->Input2, TxPIDSettings::INPUTS_INSTANCE2);
|
||||
addUAVObjectToWidgetRelation("TxPIDSettings", "Inputs", m_txpid->Input3, TxPIDSettings::INPUTS_INSTANCE3);
|
||||
addWidgetBinding("TxPIDSettings", "PIDs", m_txpid->PID1, TxPIDSettings::PIDS_INSTANCE1);
|
||||
addWidgetBinding("TxPIDSettings", "PIDs", m_txpid->PID2, TxPIDSettings::PIDS_INSTANCE2);
|
||||
addWidgetBinding("TxPIDSettings", "PIDs", m_txpid->PID3, TxPIDSettings::PIDS_INSTANCE3);
|
||||
|
||||
addUAVObjectToWidgetRelation("TxPIDSettings", "MinPID", m_txpid->MinPID1, TxPIDSettings::MINPID_INSTANCE1);
|
||||
addUAVObjectToWidgetRelation("TxPIDSettings", "MinPID", m_txpid->MinPID2, TxPIDSettings::MINPID_INSTANCE2);
|
||||
addUAVObjectToWidgetRelation("TxPIDSettings", "MinPID", m_txpid->MinPID3, TxPIDSettings::MINPID_INSTANCE3);
|
||||
addWidgetBinding("TxPIDSettings", "Inputs", m_txpid->Input1, TxPIDSettings::INPUTS_INSTANCE1);
|
||||
addWidgetBinding("TxPIDSettings", "Inputs", m_txpid->Input2, TxPIDSettings::INPUTS_INSTANCE2);
|
||||
addWidgetBinding("TxPIDSettings", "Inputs", m_txpid->Input3, TxPIDSettings::INPUTS_INSTANCE3);
|
||||
|
||||
addUAVObjectToWidgetRelation("TxPIDSettings", "MaxPID", m_txpid->MaxPID1, TxPIDSettings::MAXPID_INSTANCE1);
|
||||
addUAVObjectToWidgetRelation("TxPIDSettings", "MaxPID", m_txpid->MaxPID2, TxPIDSettings::MAXPID_INSTANCE2);
|
||||
addUAVObjectToWidgetRelation("TxPIDSettings", "MaxPID", m_txpid->MaxPID3, TxPIDSettings::MAXPID_INSTANCE3);
|
||||
addWidgetBinding("TxPIDSettings", "MinPID", m_txpid->MinPID1, TxPIDSettings::MINPID_INSTANCE1);
|
||||
addWidgetBinding("TxPIDSettings", "MinPID", m_txpid->MinPID2, TxPIDSettings::MINPID_INSTANCE2);
|
||||
addWidgetBinding("TxPIDSettings", "MinPID", m_txpid->MinPID3, TxPIDSettings::MINPID_INSTANCE3);
|
||||
|
||||
addUAVObjectToWidgetRelation("TxPIDSettings", "ThrottleRange", m_txpid->ThrottleMin, TxPIDSettings::THROTTLERANGE_MIN);
|
||||
addUAVObjectToWidgetRelation("TxPIDSettings", "ThrottleRange", m_txpid->ThrottleMax, TxPIDSettings::THROTTLERANGE_MAX);
|
||||
addWidgetBinding("TxPIDSettings", "MaxPID", m_txpid->MaxPID1, TxPIDSettings::MAXPID_INSTANCE1);
|
||||
addWidgetBinding("TxPIDSettings", "MaxPID", m_txpid->MaxPID2, TxPIDSettings::MAXPID_INSTANCE2);
|
||||
addWidgetBinding("TxPIDSettings", "MaxPID", m_txpid->MaxPID3, TxPIDSettings::MAXPID_INSTANCE3);
|
||||
|
||||
addUAVObjectToWidgetRelation("TxPIDSettings", "UpdateMode", m_txpid->UpdateMode);
|
||||
addWidgetBinding("TxPIDSettings", "ThrottleRange", m_txpid->ThrottleMin, TxPIDSettings::THROTTLERANGE_MIN);
|
||||
addWidgetBinding("TxPIDSettings", "ThrottleRange", m_txpid->ThrottleMax, TxPIDSettings::THROTTLERANGE_MAX);
|
||||
|
||||
addWidgetBinding("TxPIDSettings", "UpdateMode", m_txpid->UpdateMode);
|
||||
|
||||
addWidget(m_txpid->TxPIDEnable);
|
||||
|
||||
|
@ -14,7 +14,16 @@
|
||||
<string>Form</string>
|
||||
</property>
|
||||
<layout class="QVBoxLayout" name="verticalLayout">
|
||||
<property name="margin">
|
||||
<property name="leftMargin">
|
||||
<number>12</number>
|
||||
</property>
|
||||
<property name="topMargin">
|
||||
<number>12</number>
|
||||
</property>
|
||||
<property name="rightMargin">
|
||||
<number>12</number>
|
||||
</property>
|
||||
<property name="bottomMargin">
|
||||
<number>12</number>
|
||||
</property>
|
||||
<item>
|
||||
@ -30,7 +39,16 @@
|
||||
<property name="spacing">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="margin">
|
||||
<property name="leftMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="topMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="rightMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="bottomMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<item>
|
||||
@ -111,15 +129,24 @@
|
||||
<x>0</x>
|
||||
<y>0</y>
|
||||
<width>850</width>
|
||||
<height>572</height>
|
||||
<height>589</height>
|
||||
</rect>
|
||||
</property>
|
||||
<layout class="QGridLayout" name="gridLayout">
|
||||
<property name="margin">
|
||||
<property name="leftMargin">
|
||||
<number>12</number>
|
||||
</property>
|
||||
<property name="topMargin">
|
||||
<number>12</number>
|
||||
</property>
|
||||
<property name="rightMargin">
|
||||
<number>12</number>
|
||||
</property>
|
||||
<property name="bottomMargin">
|
||||
<number>12</number>
|
||||
</property>
|
||||
<property name="verticalSpacing">
|
||||
<number>-1</number>
|
||||
<number>6</number>
|
||||
</property>
|
||||
<item row="1" column="0">
|
||||
<widget class="QGroupBox" name="groupBox_5">
|
||||
@ -146,7 +173,16 @@
|
||||
</property>
|
||||
<widget class="QWidget" name="advancedPage">
|
||||
<layout class="QVBoxLayout" name="verticalLayout_3">
|
||||
<property name="margin">
|
||||
<property name="leftMargin">
|
||||
<number>12</number>
|
||||
</property>
|
||||
<property name="topMargin">
|
||||
<number>12</number>
|
||||
</property>
|
||||
<property name="rightMargin">
|
||||
<number>12</number>
|
||||
</property>
|
||||
<property name="bottomMargin">
|
||||
<number>12</number>
|
||||
</property>
|
||||
<item>
|
||||
@ -245,11 +281,20 @@
|
||||
</widget>
|
||||
<widget class="QWidget" name="wizard">
|
||||
<layout class="QVBoxLayout" name="verticalLayout_5">
|
||||
<property name="margin">
|
||||
<property name="leftMargin">
|
||||
<number>12</number>
|
||||
</property>
|
||||
<property name="topMargin">
|
||||
<number>12</number>
|
||||
</property>
|
||||
<property name="rightMargin">
|
||||
<number>12</number>
|
||||
</property>
|
||||
<property name="bottomMargin">
|
||||
<number>12</number>
|
||||
</property>
|
||||
<item>
|
||||
<widget class="QLabel" name="wzText">
|
||||
<widget class="QLabel" name="wzText">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Minimum">
|
||||
<horstretch>0</horstretch>
|
||||
@ -260,28 +305,28 @@
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<layout class="QVBoxLayout" name="radioButtonsLayout"/>
|
||||
</item>
|
||||
<item>
|
||||
<layout class="QGridLayout" name="checkBoxesLayout"/>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QLabel" name="wzText2">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Minimum">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="wordWrap">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QGraphicsView" name="graphicsView"/>
|
||||
<layout class="QVBoxLayout" name="radioButtonsLayout"/>
|
||||
</item>
|
||||
<item>
|
||||
<layout class="QGridLayout" name="checkBoxesLayout"/>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QLabel" name="wzText2">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Minimum">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="wordWrap">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QGraphicsView" name="graphicsView"/>
|
||||
</item>
|
||||
<item>
|
||||
<layout class="QHBoxLayout" name="horizontalLayout_3">
|
||||
@ -418,7 +463,16 @@
|
||||
<string>Flight Mode Switch Settings</string>
|
||||
</attribute>
|
||||
<layout class="QVBoxLayout" name="verticalLayout_8">
|
||||
<property name="margin">
|
||||
<property name="leftMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="topMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="rightMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="bottomMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<item>
|
||||
@ -499,284 +553,22 @@
|
||||
<x>0</x>
|
||||
<y>0</y>
|
||||
<width>850</width>
|
||||
<height>572</height>
|
||||
<height>589</height>
|
||||
</rect>
|
||||
</property>
|
||||
<layout class="QGridLayout" name="gridLayout_7" rowstretch="1,0,0">
|
||||
<property name="margin">
|
||||
<property name="leftMargin">
|
||||
<number>12</number>
|
||||
</property>
|
||||
<property name="topMargin">
|
||||
<number>12</number>
|
||||
</property>
|
||||
<property name="rightMargin">
|
||||
<number>12</number>
|
||||
</property>
|
||||
<property name="bottomMargin">
|
||||
<number>12</number>
|
||||
</property>
|
||||
<item row="1" column="0">
|
||||
<widget class="QGroupBox" name="groupBox">
|
||||
<property name="styleSheet">
|
||||
<string notr="true"/>
|
||||
</property>
|
||||
<property name="title">
|
||||
<string>Configure each stabilization mode for each axis</string>
|
||||
</property>
|
||||
<layout class="QGridLayout" name="gridLayout_2" columnstretch="0,0,1,0,1,0,1,0">
|
||||
<property name="leftMargin">
|
||||
<number>9</number>
|
||||
</property>
|
||||
<property name="horizontalSpacing">
|
||||
<number>12</number>
|
||||
</property>
|
||||
<item row="2" column="1">
|
||||
<spacer name="horizontalSpacer_11">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="sizeType">
|
||||
<enum>QSizePolicy::Minimum</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>5</width>
|
||||
<height>20</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item row="3" column="2">
|
||||
<widget class="QComboBox" name="fmsSsPos3Roll">
|
||||
<property name="focusPolicy">
|
||||
<enum>Qt::StrongFocus</enum>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="6">
|
||||
<widget class="QLabel" name="label_10">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>20</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>16777215</width>
|
||||
<height>20</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
|
||||
color: rgb(255, 255, 255);
|
||||
border-radius: 5;
|
||||
font: bold 12px;
|
||||
margin:1px;</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Yaw</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="3">
|
||||
<spacer name="horizontalSpacer_12">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>5</width>
|
||||
<height>20</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item row="1" column="0">
|
||||
<widget class="QLabel" name="label_14">
|
||||
<property name="text">
|
||||
<string>Stabilized1</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="5">
|
||||
<spacer name="horizontalSpacer_13">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>5</width>
|
||||
<height>20</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item row="3" column="6">
|
||||
<widget class="QComboBox" name="fmsSsPos3Yaw">
|
||||
<property name="focusPolicy">
|
||||
<enum>Qt::StrongFocus</enum>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="0">
|
||||
<widget class="QLabel" name="label_21">
|
||||
<property name="text">
|
||||
<string>Stabilized2</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="4">
|
||||
<widget class="QComboBox" name="fmsSsPos3Pitch">
|
||||
<property name="focusPolicy">
|
||||
<enum>Qt::StrongFocus</enum>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="6">
|
||||
<widget class="QComboBox" name="fmsSsPos2Yaw">
|
||||
<property name="focusPolicy">
|
||||
<enum>Qt::StrongFocus</enum>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="4">
|
||||
<widget class="QLabel" name="label_9">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>20</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>16777215</width>
|
||||
<height>20</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
|
||||
color: rgb(255, 255, 255);
|
||||
border-radius: 5;
|
||||
font: bold 12px;
|
||||
margin:1px;</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Pitch</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="2">
|
||||
<widget class="QLabel" name="label_8">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>20</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>16777215</width>
|
||||
<height>20</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
|
||||
color: rgb(255, 255, 255);
|
||||
border-radius: 5;
|
||||
font: bold 12px;
|
||||
margin:1px;</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Roll</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="4">
|
||||
<widget class="QComboBox" name="fmsSsPos2Pitch">
|
||||
<property name="focusPolicy">
|
||||
<enum>Qt::StrongFocus</enum>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="6">
|
||||
<widget class="QComboBox" name="fmsSsPos1Yaw">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>102</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="focusPolicy">
|
||||
<enum>Qt::StrongFocus</enum>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="2">
|
||||
<widget class="QComboBox" name="fmsSsPos2Roll">
|
||||
<property name="focusPolicy">
|
||||
<enum>Qt::StrongFocus</enum>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="2">
|
||||
<widget class="QComboBox" name="fmsSsPos1Roll">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>102</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="focusPolicy">
|
||||
<enum>Qt::StrongFocus</enum>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="4">
|
||||
<widget class="QComboBox" name="fmsSsPos1Pitch">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>102</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="focusPolicy">
|
||||
<enum>Qt::StrongFocus</enum>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="0">
|
||||
<widget class="QLabel" name="label_22">
|
||||
<property name="text">
|
||||
<string>Stabilized3</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="7">
|
||||
<spacer name="horizontalSpacer_14">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>40</width>
|
||||
<height>20</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="0">
|
||||
<widget class="QGroupBox" name="groupBox_2">
|
||||
<property name="minimumSize">
|
||||
@ -795,7 +587,16 @@ margin:1px;</string>
|
||||
<string>FlightMode Switch Positions</string>
|
||||
</property>
|
||||
<layout class="QGridLayout" name="gridLayout_4" rowstretch="0,0,0" columnstretch="0,0,1,0,1,0">
|
||||
<property name="margin">
|
||||
<property name="leftMargin">
|
||||
<number>12</number>
|
||||
</property>
|
||||
<property name="topMargin">
|
||||
<number>12</number>
|
||||
</property>
|
||||
<property name="rightMargin">
|
||||
<number>12</number>
|
||||
</property>
|
||||
<property name="bottomMargin">
|
||||
<number>12</number>
|
||||
</property>
|
||||
<item row="0" column="0" rowspan="3">
|
||||
@ -1070,6 +871,9 @@ Setup the flight mode channel on the RC Input tab if you have not done so alread
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="sizeType">
|
||||
<enum>QSizePolicy::Expanding</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>40</width>
|
||||
@ -1180,6 +984,367 @@ channel value for each flight mode.</string>
|
||||
</layout>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="0">
|
||||
<widget class="QGroupBox" name="groupBox">
|
||||
<property name="styleSheet">
|
||||
<string notr="true"/>
|
||||
</property>
|
||||
<property name="title">
|
||||
<string>Stabilization Modes Configuration</string>
|
||||
</property>
|
||||
<layout class="QGridLayout" name="gridLayout_2" columnstretch="0,0,0,0,0,0,0,0,0,0">
|
||||
<property name="leftMargin">
|
||||
<number>9</number>
|
||||
</property>
|
||||
<property name="horizontalSpacing">
|
||||
<number>12</number>
|
||||
</property>
|
||||
<item row="2" column="1">
|
||||
<spacer name="horizontalSpacer_11">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="sizeType">
|
||||
<enum>QSizePolicy::Minimum</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>5</width>
|
||||
<height>20</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item row="0" column="6">
|
||||
<widget class="QLabel" name="label_10">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>20</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>16777215</width>
|
||||
<height>20</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
|
||||
color: rgb(255, 255, 255);
|
||||
border-radius: 5;
|
||||
font: bold 12px;
|
||||
margin:1px;</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Yaw</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="3">
|
||||
<spacer name="horizontalSpacer_12">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="sizeType">
|
||||
<enum>QSizePolicy::MinimumExpanding</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>20</width>
|
||||
<height>20</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item row="3" column="2">
|
||||
<widget class="QComboBox" name="fmsSsPos3Roll">
|
||||
<property name="focusPolicy">
|
||||
<enum>Qt::StrongFocus</enum>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="0">
|
||||
<widget class="QLabel" name="label_14">
|
||||
<property name="text">
|
||||
<string>Stabilized 1</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="5">
|
||||
<spacer name="horizontalSpacer_13">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="sizeType">
|
||||
<enum>QSizePolicy::MinimumExpanding</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>20</width>
|
||||
<height>20</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item row="2" column="0">
|
||||
<widget class="QLabel" name="label_21">
|
||||
<property name="text">
|
||||
<string>Stabilized 2</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="4">
|
||||
<widget class="QComboBox" name="fmsSsPos3Pitch">
|
||||
<property name="focusPolicy">
|
||||
<enum>Qt::StrongFocus</enum>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="6">
|
||||
<widget class="QComboBox" name="fmsSsPos3Yaw">
|
||||
<property name="focusPolicy">
|
||||
<enum>Qt::StrongFocus</enum>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="6">
|
||||
<widget class="QComboBox" name="fmsSsPos2Yaw">
|
||||
<property name="focusPolicy">
|
||||
<enum>Qt::StrongFocus</enum>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="2">
|
||||
<widget class="QLabel" name="label_8">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>20</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>16777215</width>
|
||||
<height>20</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
|
||||
color: rgb(255, 255, 255);
|
||||
border-radius: 5;
|
||||
font: bold 12px;
|
||||
margin:1px;</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Roll</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="4">
|
||||
<widget class="QLabel" name="label_9">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>20</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>16777215</width>
|
||||
<height>20</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
|
||||
color: rgb(255, 255, 255);
|
||||
border-radius: 5;
|
||||
font: bold 12px;
|
||||
margin:1px;</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Pitch</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="4">
|
||||
<widget class="QComboBox" name="fmsSsPos2Pitch">
|
||||
<property name="focusPolicy">
|
||||
<enum>Qt::StrongFocus</enum>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="6">
|
||||
<widget class="QComboBox" name="fmsSsPos1Yaw">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>102</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="focusPolicy">
|
||||
<enum>Qt::StrongFocus</enum>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="2">
|
||||
<widget class="QComboBox" name="fmsSsPos2Roll">
|
||||
<property name="focusPolicy">
|
||||
<enum>Qt::StrongFocus</enum>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="2">
|
||||
<widget class="QComboBox" name="fmsSsPos1Roll">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>102</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="focusPolicy">
|
||||
<enum>Qt::StrongFocus</enum>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="0">
|
||||
<widget class="QLabel" name="label_22">
|
||||
<property name="text">
|
||||
<string>Stabilized 3</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="4">
|
||||
<widget class="QComboBox" name="fmsSsPos1Pitch">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>102</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="focusPolicy">
|
||||
<enum>Qt::StrongFocus</enum>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="8">
|
||||
<widget class="QComboBox" name="pidBankSs3">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>102</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="focusPolicy">
|
||||
<enum>Qt::StrongFocus</enum>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="8">
|
||||
<widget class="QComboBox" name="pidBankSs2">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>102</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="focusPolicy">
|
||||
<enum>Qt::StrongFocus</enum>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="9">
|
||||
<spacer name="horizontalSpacer_14">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>40</width>
|
||||
<height>20</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item row="0" column="8">
|
||||
<widget class="QLabel" name="label_11">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>20</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>16777215</width>
|
||||
<height>20</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
|
||||
color: rgb(255, 255, 255);
|
||||
border-radius: 5;
|
||||
font: bold 12px;
|
||||
margin:1px;</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>PID Bank</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="8">
|
||||
<widget class="QComboBox" name="pidBankSs1">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>102</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="focusPolicy">
|
||||
<enum>Qt::StrongFocus</enum>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="7">
|
||||
<spacer name="horizontalSpacer_15">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="sizeType">
|
||||
<enum>QSizePolicy::MinimumExpanding</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>20</width>
|
||||
<height>20</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="0">
|
||||
<spacer name="verticalSpacer_5">
|
||||
<property name="orientation">
|
||||
@ -1207,7 +1372,16 @@ channel value for each flight mode.</string>
|
||||
<string>Arming Settings</string>
|
||||
</attribute>
|
||||
<layout class="QVBoxLayout" name="verticalLayout_12">
|
||||
<property name="margin">
|
||||
<property name="leftMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="topMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="rightMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="bottomMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<item>
|
||||
@ -1288,11 +1462,20 @@ channel value for each flight mode.</string>
|
||||
<x>0</x>
|
||||
<y>0</y>
|
||||
<width>850</width>
|
||||
<height>572</height>
|
||||
<height>589</height>
|
||||
</rect>
|
||||
</property>
|
||||
<layout class="QVBoxLayout" name="verticalLayout_2">
|
||||
<property name="margin">
|
||||
<property name="leftMargin">
|
||||
<number>12</number>
|
||||
</property>
|
||||
<property name="topMargin">
|
||||
<number>12</number>
|
||||
</property>
|
||||
<property name="rightMargin">
|
||||
<number>12</number>
|
||||
</property>
|
||||
<property name="bottomMargin">
|
||||
<number>12</number>
|
||||
</property>
|
||||
<item>
|
||||
|
File diff suppressed because it is too large
Load Diff
@ -17,7 +17,16 @@
|
||||
<property name="spacing">
|
||||
<number>6</number>
|
||||
</property>
|
||||
<property name="margin">
|
||||
<property name="leftMargin">
|
||||
<number>12</number>
|
||||
</property>
|
||||
<property name="topMargin">
|
||||
<number>12</number>
|
||||
</property>
|
||||
<property name="rightMargin">
|
||||
<number>12</number>
|
||||
</property>
|
||||
<property name="bottomMargin">
|
||||
<number>12</number>
|
||||
</property>
|
||||
<item>
|
||||
@ -33,7 +42,16 @@
|
||||
<property name="spacing">
|
||||
<number>6</number>
|
||||
</property>
|
||||
<property name="margin">
|
||||
<property name="leftMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="topMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="rightMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="bottomMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<item>
|
||||
@ -113,15 +131,24 @@
|
||||
<rect>
|
||||
<x>0</x>
|
||||
<y>0</y>
|
||||
<width>745</width>
|
||||
<height>469</height>
|
||||
<width>742</width>
|
||||
<height>450</height>
|
||||
</rect>
|
||||
</property>
|
||||
<layout class="QVBoxLayout" name="verticalLayout_2">
|
||||
<property name="spacing">
|
||||
<number>6</number>
|
||||
</property>
|
||||
<property name="margin">
|
||||
<property name="leftMargin">
|
||||
<number>12</number>
|
||||
</property>
|
||||
<property name="topMargin">
|
||||
<number>12</number>
|
||||
</property>
|
||||
<property name="rightMargin">
|
||||
<number>12</number>
|
||||
</property>
|
||||
<property name="bottomMargin">
|
||||
<number>12</number>
|
||||
</property>
|
||||
<item>
|
||||
@ -661,6 +688,16 @@ margin:1px;</string>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item row="0" column="0">
|
||||
<widget class="QLabel" name="label_6">
|
||||
<property name="text">
|
||||
<string>PID Bank</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="1">
|
||||
<widget class="QComboBox" name="pidBank"/>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
</item>
|
||||
|
@ -129,7 +129,6 @@ HEADERS += mainwindow.h \
|
||||
uavgadgetdecorator.h \
|
||||
workspacesettings.h \
|
||||
uavconfiginfo.h \
|
||||
authorsdialog.h \
|
||||
iconfigurableplugin.h \
|
||||
aboutdialog.h
|
||||
|
||||
|
@ -60,6 +60,10 @@ HEADERS += $$UAVOBJECT_SYNTHETICS/accessorydesired.h \
|
||||
$$UAVOBJECT_SYNTHETICS/overosyncsettings.h \
|
||||
$$UAVOBJECT_SYNTHETICS/systemsettings.h \
|
||||
$$UAVOBJECT_SYNTHETICS/stabilizationsettings.h \
|
||||
$$UAVOBJECT_SYNTHETICS/stabilizationsettingsbank1.h \
|
||||
$$UAVOBJECT_SYNTHETICS/stabilizationsettingsbank2.h \
|
||||
$$UAVOBJECT_SYNTHETICS/stabilizationsettingsbank3.h \
|
||||
$$UAVOBJECT_SYNTHETICS/stabilizationbank.h \
|
||||
$$UAVOBJECT_SYNTHETICS/manualcontrolsettings.h \
|
||||
$$UAVOBJECT_SYNTHETICS/manualcontrolcommand.h \
|
||||
$$UAVOBJECT_SYNTHETICS/stabilizationdesired.h \
|
||||
@ -151,6 +155,10 @@ SOURCES += $$UAVOBJECT_SYNTHETICS/accessorydesired.cpp \
|
||||
$$UAVOBJECT_SYNTHETICS/overosyncsettings.cpp \
|
||||
$$UAVOBJECT_SYNTHETICS/systemsettings.cpp \
|
||||
$$UAVOBJECT_SYNTHETICS/stabilizationsettings.cpp \
|
||||
$$UAVOBJECT_SYNTHETICS/stabilizationsettingsbank1.cpp \
|
||||
$$UAVOBJECT_SYNTHETICS/stabilizationsettingsbank2.cpp \
|
||||
$$UAVOBJECT_SYNTHETICS/stabilizationsettingsbank3.cpp \
|
||||
$$UAVOBJECT_SYNTHETICS/stabilizationbank.cpp \
|
||||
$$UAVOBJECT_SYNTHETICS/manualcontrolsettings.cpp \
|
||||
$$UAVOBJECT_SYNTHETICS/manualcontrolcommand.cpp \
|
||||
$$UAVOBJECT_SYNTHETICS/stabilizationdesired.cpp \
|
||||
|
@ -29,218 +29,179 @@
|
||||
#include <QLineEdit>
|
||||
#include "uavsettingsimportexport/uavsettingsimportexportfactory.h"
|
||||
|
||||
/**
|
||||
* Constructor
|
||||
*/
|
||||
ConfigTaskWidget::ConfigTaskWidget(QWidget *parent) : QWidget(parent), isConnected(false), allowWidgetUpdates(true), smartsave(NULL), dirty(false), outOfLimitsStyle("background-color: rgb(255, 0, 0);"), timeOut(NULL)
|
||||
ConfigTaskWidget::ConfigTaskWidget(QWidget *parent) : QWidget(parent), m_isConnected(false), m_isWidgetUpdatesAllowed(true),
|
||||
m_saveButton(NULL), m_isDirty(false), m_outOfLimitsStyle("background-color: rgb(255, 0, 0);"), m_realtimeUpdateTimer(NULL)
|
||||
{
|
||||
pm = ExtensionSystem::PluginManager::instance();
|
||||
objManager = pm->getObject<UAVObjectManager>();
|
||||
TelemetryManager *telMngr = pm->getObject<TelemetryManager>();
|
||||
utilMngr = pm->getObject<UAVObjectUtilManager>();
|
||||
m_pluginManager = ExtensionSystem::PluginManager::instance();
|
||||
TelemetryManager *telMngr = m_pluginManager->getObject<TelemetryManager>();
|
||||
m_objectUtilManager = m_pluginManager->getObject<UAVObjectUtilManager>();
|
||||
connect(telMngr, SIGNAL(connected()), this, SLOT(onAutopilotConnect()), Qt::UniqueConnection);
|
||||
connect(telMngr, SIGNAL(disconnected()), this, SLOT(onAutopilotDisconnect()), Qt::UniqueConnection);
|
||||
connect(telMngr, SIGNAL(connected()), this, SIGNAL(autoPilotConnected()), Qt::UniqueConnection);
|
||||
connect(telMngr, SIGNAL(disconnected()), this, SIGNAL(autoPilotDisconnected()), Qt::UniqueConnection);
|
||||
UAVSettingsImportExportFactory *importexportplugin = pm->getObject<UAVSettingsImportExportFactory>();
|
||||
UAVSettingsImportExportFactory *importexportplugin = m_pluginManager->getObject<UAVSettingsImportExportFactory>();
|
||||
connect(importexportplugin, SIGNAL(importAboutToBegin()), this, SLOT(invalidateObjects()));
|
||||
}
|
||||
|
||||
/**
|
||||
* Add a widget to the dirty detection pool
|
||||
* @param widget to add to the detection pool
|
||||
*/
|
||||
void ConfigTaskWidget::addWidget(QWidget *widget)
|
||||
{
|
||||
addUAVObjectToWidgetRelation("", "", widget);
|
||||
addWidgetBinding("", "", widget);
|
||||
}
|
||||
/**
|
||||
* Add an object to the management system
|
||||
* @param objectName name of the object to add to the management system
|
||||
*/
|
||||
|
||||
void ConfigTaskWidget::addUAVObject(QString objectName, QList<int> *reloadGroups)
|
||||
{
|
||||
addUAVObjectToWidgetRelation(objectName, "", NULL, 0, 1, false, reloadGroups);
|
||||
addWidgetBinding(objectName, "", NULL, 0, 1, false, reloadGroups);
|
||||
}
|
||||
|
||||
void ConfigTaskWidget::addUAVObject(UAVObject *objectName, QList<int> *reloadGroups)
|
||||
{
|
||||
QString objstr;
|
||||
|
||||
if (objectName) {
|
||||
objstr = objectName->getName();
|
||||
}
|
||||
addUAVObject(objstr, reloadGroups);
|
||||
}
|
||||
/**
|
||||
* Add an UAVObject field to widget relation to the management system
|
||||
* @param object name of the object to add
|
||||
* @param field name of the field to add
|
||||
* @param widget pointer to the widget whitch will display/define the field value
|
||||
* @param index index of the field element to add to this relation
|
||||
*/
|
||||
void ConfigTaskWidget::addUAVObjectToWidgetRelation(QString object, QString field, QWidget *widget, QString index)
|
||||
{
|
||||
UAVObject *obj = NULL;
|
||||
UAVObjectField *_field = NULL;
|
||||
|
||||
obj = objManager->getObject(QString(object));
|
||||
Q_ASSERT(obj);
|
||||
_field = obj->getField(QString(field));
|
||||
Q_ASSERT(_field);
|
||||
addUAVObjectToWidgetRelation(object, field, widget, _field->getElementNames().indexOf(index));
|
||||
addUAVObject(objectName ? objectName->getName() : QString(""), reloadGroups);
|
||||
}
|
||||
|
||||
void ConfigTaskWidget::addUAVObjectToWidgetRelation(UAVObject *obj, UAVObjectField *field, QWidget *widget, QString index)
|
||||
int ConfigTaskWidget::fieldIndexFromElementName(QString objectName, QString fieldName, QString elementName)
|
||||
{
|
||||
QString objstr;
|
||||
QString fieldstr;
|
||||
if (elementName.isEmpty() || objectName.isEmpty()) {
|
||||
return 0;
|
||||
}
|
||||
|
||||
if (obj) {
|
||||
objstr = obj->getName();
|
||||
}
|
||||
if (field) {
|
||||
fieldstr = field->getName();
|
||||
}
|
||||
addUAVObjectToWidgetRelation(objstr, fieldstr, widget, index);
|
||||
}
|
||||
/**
|
||||
* Add a UAVObject field to widget relation to the management system
|
||||
* @param object name of the object to add
|
||||
* @param field name of the field to add
|
||||
* @param widget pointer to the widget whitch will display/define the field value
|
||||
* @param element name of the element of the field element to add to this relation
|
||||
* @param scale scale value of this relation
|
||||
* @param isLimited bool to signal if this widget contents is limited in value
|
||||
* @param defaultReloadGroups default and reload groups this relation belongs to
|
||||
* @param instID instance ID of the object used on this relation
|
||||
*/
|
||||
void ConfigTaskWidget::addUAVObjectToWidgetRelation(QString object, QString field, QWidget *widget, QString element, double scale, bool isLimited, QList<int> *defaultReloadGroups, quint32 instID)
|
||||
{
|
||||
UAVObject *obj = objManager->getObject(QString(object), instID);
|
||||
QString singleObjectName = mapObjectName(objectName).split(",").at(0);
|
||||
UAVObject *object = getObject(singleObjectName);
|
||||
Q_ASSERT(object);
|
||||
|
||||
Q_ASSERT(obj);
|
||||
UAVObjectField *_field;
|
||||
int index = 0;
|
||||
if (!field.isEmpty() && obj) {
|
||||
_field = obj->getField(QString(field));
|
||||
if (!element.isEmpty()) {
|
||||
index = _field->getElementNames().indexOf(QString(element));
|
||||
}
|
||||
}
|
||||
addUAVObjectToWidgetRelation(object, field, widget, index, scale, isLimited, defaultReloadGroups, instID);
|
||||
UAVObjectField *field = object->getField(fieldName);
|
||||
Q_ASSERT(field);
|
||||
|
||||
return field->getElementNames().indexOf(elementName);
|
||||
}
|
||||
|
||||
void ConfigTaskWidget::addUAVObjectToWidgetRelation(UAVObject *obj, UAVObjectField *field, QWidget *widget, QString element, double scale, bool isLimited, QList<int> *defaultReloadGroups, quint32 instID)
|
||||
void ConfigTaskWidget::addWidgetBinding(QString objectName, QString fieldName, QWidget *widget, QString elementName)
|
||||
{
|
||||
QString objstr;
|
||||
QString fieldstr;
|
||||
|
||||
if (obj) {
|
||||
objstr = obj->getName();
|
||||
}
|
||||
if (field) {
|
||||
fieldstr = field->getName();
|
||||
}
|
||||
addUAVObjectToWidgetRelation(objstr, fieldstr, widget, element, scale, isLimited, defaultReloadGroups, instID);
|
||||
}
|
||||
void ConfigTaskWidget::addUAVObjectToWidgetRelation(UAVObject *obj, UAVObjectField *field, QWidget *widget, int index, double scale, bool isLimited, QList<int> *defaultReloadGroups, quint32 instID)
|
||||
{
|
||||
QString objstr;
|
||||
QString fieldstr;
|
||||
|
||||
if (obj) {
|
||||
objstr = obj->getName();
|
||||
}
|
||||
if (field) {
|
||||
fieldstr = field->getName();
|
||||
}
|
||||
addUAVObjectToWidgetRelation(objstr, fieldstr, widget, index, scale, isLimited, defaultReloadGroups, instID);
|
||||
addWidgetBinding(objectName, fieldName, widget, fieldIndexFromElementName(objectName, fieldName, elementName));
|
||||
}
|
||||
|
||||
/**
|
||||
* Add an UAVObject field to widget relation to the management system
|
||||
* @param object name of the object to add
|
||||
* @param field name of the field to add
|
||||
* @param widget pointer to the widget whitch will display/define the field value
|
||||
* @param index index of the element of the field to add to this relation
|
||||
* @param scale scale value of this relation
|
||||
* @param isLimited bool to signal if this widget contents is limited in value
|
||||
* @param defaultReloadGroups default and reload groups this relation belongs to
|
||||
* @param instID instance ID of the object used on this relation
|
||||
*/
|
||||
void ConfigTaskWidget::addUAVObjectToWidgetRelation(QString object, QString field, QWidget *widget, int index, double scale, bool isLimited, QList<int> *defaultReloadGroups, quint32 instID)
|
||||
void ConfigTaskWidget::addWidgetBinding(UAVObject *object, UAVObjectField *field, QWidget *widget, QString elementName)
|
||||
{
|
||||
if (addShadowWidget(object, field, widget, index, scale, isLimited, defaultReloadGroups, instID)) {
|
||||
addWidgetBinding(object ? object->getName() : QString(""), field ? field->getName() : QString(""), widget, elementName);
|
||||
}
|
||||
|
||||
void ConfigTaskWidget::addWidgetBinding(QString objectName, QString fieldName, QWidget *widget, QString elementName, double scale,
|
||||
bool isLimited, QList<int> *reloadGroupIDs, quint32 instID)
|
||||
{
|
||||
addWidgetBinding(objectName, fieldName, widget, fieldIndexFromElementName(objectName, fieldName, elementName),
|
||||
scale, isLimited, reloadGroupIDs, instID);
|
||||
}
|
||||
|
||||
void ConfigTaskWidget::addWidgetBinding(UAVObject *object, UAVObjectField *field, QWidget *widget, QString elementName, double scale,
|
||||
bool isLimited, QList<int> *reloadGroupIDs, quint32 instID)
|
||||
{
|
||||
addWidgetBinding(object ? object->getName() : QString(""), field ? field->getName() : QString(""), widget, elementName, scale,
|
||||
isLimited, reloadGroupIDs, instID);
|
||||
}
|
||||
|
||||
void ConfigTaskWidget::addWidgetBinding(UAVObject *object, UAVObjectField *field, QWidget *widget, int index, double scale,
|
||||
bool isLimited, QList<int> *reloadGroupIDs, quint32 instID)
|
||||
{
|
||||
addWidgetBinding(object ? object->getName() : QString(""), field ? field->getName() : QString(""), widget, index, scale,
|
||||
isLimited, reloadGroupIDs, instID);
|
||||
}
|
||||
|
||||
void ConfigTaskWidget::addWidgetBinding(QString objectName, QString fieldName, QWidget *widget, int index, double scale,
|
||||
bool isLimited, QList<int> *reloadGroupIDs, quint32 instID)
|
||||
{
|
||||
QString mappedObjectName = mapObjectName(objectName);
|
||||
|
||||
// If object name is comma separated list of objects, call one time per objectName
|
||||
foreach(QString singleObjectName, mappedObjectName.split(",")) {
|
||||
doAddWidgetBinding(singleObjectName, fieldName, widget, index, scale, isLimited, reloadGroupIDs, instID);
|
||||
}
|
||||
}
|
||||
|
||||
void ConfigTaskWidget::doAddWidgetBinding(QString objectName, QString fieldName, QWidget *widget, int index, double scale,
|
||||
bool isLimited, QList<int> *reloadGroupIDs, quint32 instID)
|
||||
{
|
||||
if (addShadowWidgetBinding(objectName, fieldName, widget, index, scale, isLimited, reloadGroupIDs, instID)) {
|
||||
return;
|
||||
}
|
||||
|
||||
UAVObject *obj = NULL;
|
||||
UAVObjectField *_field = NULL;
|
||||
if (!object.isEmpty()) {
|
||||
obj = objManager->getObject(QString(object), instID);
|
||||
Q_ASSERT(obj);
|
||||
objectUpdates.insert(obj, true);
|
||||
connect(obj, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(objectUpdated(UAVObject *)));
|
||||
connect(obj, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(refreshWidgetsValues(UAVObject *)), Qt::UniqueConnection);
|
||||
UAVObject *object = NULL;
|
||||
UAVObjectField *field = NULL;
|
||||
if (!objectName.isEmpty()) {
|
||||
object = getObject(QString(objectName), instID);
|
||||
Q_ASSERT(object);
|
||||
m_updatedObjects.insert(object, true);
|
||||
connect(object, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(objectUpdated(UAVObject *)));
|
||||
connect(object, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(refreshWidgetsValues(UAVObject *)), Qt::UniqueConnection);
|
||||
}
|
||||
if (!field.isEmpty() && obj) {
|
||||
_field = obj->getField(QString(field));
|
||||
|
||||
if (!fieldName.isEmpty() && object) {
|
||||
field = object->getField(QString(fieldName));
|
||||
}
|
||||
objectToWidget *ow = new objectToWidget();
|
||||
ow->field = _field;
|
||||
ow->object = obj;
|
||||
ow->widget = widget;
|
||||
ow->index = index;
|
||||
ow->scale = scale;
|
||||
ow->isLimited = isLimited;
|
||||
objOfInterest.append(ow);
|
||||
if (obj) {
|
||||
if (smartsave) {
|
||||
smartsave->addObject((UAVDataObject *)obj);
|
||||
|
||||
WidgetBinding *binding = new WidgetBinding(widget, object, field, index, scale, isLimited);
|
||||
// Only the first binding per widget can be enabled.
|
||||
binding->setIsEnabled(m_widgetBindingsPerWidget.count(widget) == 0);
|
||||
m_widgetBindingsPerWidget.insert(widget, binding);
|
||||
|
||||
|
||||
if (object) {
|
||||
m_widgetBindingsPerObject.insert(object, binding);
|
||||
if (m_saveButton) {
|
||||
m_saveButton->addObject((UAVDataObject *)object);
|
||||
}
|
||||
}
|
||||
if (widget == NULL) {
|
||||
if (defaultReloadGroups && obj) {
|
||||
foreach(int i, *defaultReloadGroups) {
|
||||
if (this->defaultReloadGroups.contains(i)) {
|
||||
this->defaultReloadGroups.value(i)->append(ow);
|
||||
} else {
|
||||
this->defaultReloadGroups.insert(i, new QList<objectToWidget *>());
|
||||
this->defaultReloadGroups.value(i)->append(ow);
|
||||
}
|
||||
|
||||
if (!widget) {
|
||||
if (reloadGroupIDs && object) {
|
||||
foreach(int groupId, *reloadGroupIDs) {
|
||||
m_reloadGroups.insert(groupId, binding);
|
||||
}
|
||||
}
|
||||
} else {
|
||||
connectWidgetUpdatesToSlot(widget, SLOT(widgetsContentsChanged()));
|
||||
if (defaultReloadGroups) {
|
||||
addWidgetToDefaultReloadGroups(widget, defaultReloadGroups);
|
||||
if (reloadGroupIDs) {
|
||||
addWidgetToReloadGroups(widget, reloadGroupIDs);
|
||||
}
|
||||
if (binding->isEnabled()) {
|
||||
loadWidgetLimits(widget, field, index, isLimited, scale);
|
||||
}
|
||||
shadowsList.insert(widget, ow);
|
||||
loadWidgetLimits(widget, _field, index, isLimited, scale);
|
||||
}
|
||||
}
|
||||
/**
|
||||
* destructor
|
||||
*/
|
||||
|
||||
void ConfigTaskWidget::setWidgetBindingObjectEnabled(QString objectName, bool enabled)
|
||||
{
|
||||
UAVObject *object = getObject(objectName);
|
||||
|
||||
Q_ASSERT(object);
|
||||
|
||||
bool dirtyBack = isDirty();
|
||||
|
||||
foreach(WidgetBinding * binding, m_widgetBindingsPerObject.values(object)) {
|
||||
binding->setIsEnabled(enabled);
|
||||
if (enabled) {
|
||||
if (binding->value().isValid() && !binding->value().isNull()) {
|
||||
setWidgetFromVariant(binding->widget(), binding->value(), binding->scale());
|
||||
} else {
|
||||
setWidgetFromField(binding->widget(), binding->field(), binding->index(), binding->scale(), binding->isLimited());
|
||||
}
|
||||
}
|
||||
}
|
||||
setDirty(dirtyBack);
|
||||
}
|
||||
|
||||
ConfigTaskWidget::~ConfigTaskWidget()
|
||||
{
|
||||
if (smartsave) {
|
||||
delete smartsave;
|
||||
if (m_saveButton) {
|
||||
delete m_saveButton;
|
||||
}
|
||||
foreach(QList<objectToWidget *> *pointer, defaultReloadGroups.values()) {
|
||||
if (pointer) {
|
||||
delete pointer;
|
||||
QSet<WidgetBinding *> deleteSet = m_widgetBindingsPerWidget.values().toSet();
|
||||
foreach(WidgetBinding * binding, deleteSet) {
|
||||
if (binding) {
|
||||
delete binding;
|
||||
}
|
||||
}
|
||||
foreach(objectToWidget * oTw, objOfInterest) {
|
||||
if (oTw) {
|
||||
delete oTw;
|
||||
}
|
||||
}
|
||||
if (timeOut) {
|
||||
delete timeOut;
|
||||
timeOut = NULL;
|
||||
if (m_realtimeUpdateTimer) {
|
||||
delete m_realtimeUpdateTimer;
|
||||
m_realtimeUpdateTimer = NULL;
|
||||
}
|
||||
}
|
||||
|
||||
@ -254,10 +215,6 @@ void ConfigTaskWidget::saveObjectToSD(UAVObject *obj)
|
||||
utilMngr->saveObjectToSD(obj);
|
||||
}
|
||||
|
||||
/**
|
||||
* Util function to get a pointer to the object manager
|
||||
* @return pointer to the UAVObjectManager
|
||||
*/
|
||||
UAVObjectManager *ConfigTaskWidget::getObjectManager()
|
||||
{
|
||||
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
|
||||
@ -266,11 +223,7 @@ UAVObjectManager *ConfigTaskWidget::getObjectManager()
|
||||
Q_ASSERT(objMngr);
|
||||
return objMngr;
|
||||
}
|
||||
/**
|
||||
* Utility function which calculates the Mean value of a list of values
|
||||
* @param list list of double values
|
||||
* @returns Mean value of the list of parameter values
|
||||
*/
|
||||
|
||||
double ConfigTaskWidget::listMean(QList<double> list)
|
||||
{
|
||||
double accum = 0;
|
||||
@ -281,11 +234,6 @@ double ConfigTaskWidget::listMean(QList<double> list)
|
||||
return accum / list.size();
|
||||
}
|
||||
|
||||
/**
|
||||
* Utility function which calculates the Variance value of a list of values
|
||||
* @param list list of double values
|
||||
* @returns Variance of the list of parameter values
|
||||
*/
|
||||
double ConfigTaskWidget::listVar(QList<double> list)
|
||||
{
|
||||
double mean_accum = 0;
|
||||
@ -305,155 +253,123 @@ double ConfigTaskWidget::listVar(QList<double> list)
|
||||
return var_accum / (list.size() - 1);
|
||||
}
|
||||
|
||||
// ************************************
|
||||
// telemetry start/stop connect/disconnect signals
|
||||
|
||||
void ConfigTaskWidget::onAutopilotDisconnect()
|
||||
{
|
||||
isConnected = false;
|
||||
m_isConnected = false;
|
||||
enableControls(false);
|
||||
invalidateObjects();
|
||||
}
|
||||
|
||||
void ConfigTaskWidget::forceConnectedState() // dynamic widgets don't recieve the connected signal. This should be called instead.
|
||||
{
|
||||
isConnected = true;
|
||||
m_isConnected = true;
|
||||
setDirty(false);
|
||||
}
|
||||
|
||||
void ConfigTaskWidget::onAutopilotConnect()
|
||||
{
|
||||
if (utilMngr) {
|
||||
currentBoard = utilMngr->getBoardModel(); // TODO REMEMBER TO ADD THIS TO FORCE CONNECTED FUNC ON CC3D_RELEASE
|
||||
if (m_objectUtilManager) {
|
||||
m_currentBoardId = m_objectUtilManager->getBoardModel(); // TODO REMEMBER TO ADD THIS TO FORCE CONNECTED FUNC ON CC3D_RELEASE
|
||||
}
|
||||
invalidateObjects();
|
||||
isConnected = true;
|
||||
foreach(objectToWidget * ow, objOfInterest) {
|
||||
loadWidgetLimits(ow->widget, ow->field, ow->index, ow->isLimited, ow->scale);
|
||||
m_isConnected = true;
|
||||
foreach(WidgetBinding * binding, m_widgetBindingsPerObject) {
|
||||
if (!binding->isEnabled()) {
|
||||
continue;
|
||||
}
|
||||
loadWidgetLimits(binding->widget(), binding->field(), binding->index(), binding->isLimited(), binding->scale());
|
||||
}
|
||||
setDirty(false);
|
||||
enableControls(true);
|
||||
refreshWidgetsValues();
|
||||
}
|
||||
/**
|
||||
* SLOT Function used to populate the widgets with the initial values
|
||||
* Overwrite this if you need to change the default behavior
|
||||
*/
|
||||
|
||||
void ConfigTaskWidget::populateWidgets()
|
||||
{
|
||||
bool dirtyBack = dirty;
|
||||
bool dirtyBack = isDirty();
|
||||
emit populateWidgetsRequested();
|
||||
|
||||
foreach(objectToWidget * ow, objOfInterest) {
|
||||
if (ow->object == NULL || ow->field == NULL || ow->widget == NULL) {
|
||||
// do nothing
|
||||
} else {
|
||||
setWidgetFromField(ow->widget, ow->field, ow->index, ow->scale, ow->isLimited);
|
||||
foreach(WidgetBinding * binding, m_widgetBindingsPerObject) {
|
||||
if (binding->isEnabled() && binding->object() != NULL && binding->field() != NULL && binding->widget() != NULL) {
|
||||
setWidgetFromField(binding->widget(), binding->field(), binding->index(), binding->scale(), binding->isLimited());
|
||||
}
|
||||
}
|
||||
setDirty(dirtyBack);
|
||||
}
|
||||
/**
|
||||
* SLOT function used to refresh the widgets contents of the widgets with relation to
|
||||
* object field added to the framework pool
|
||||
* Overwrite this if you need to change the default behavior
|
||||
*/
|
||||
|
||||
void ConfigTaskWidget::refreshWidgetsValues(UAVObject *obj)
|
||||
{
|
||||
if (!allowWidgetUpdates) {
|
||||
if (!m_isWidgetUpdatesAllowed) {
|
||||
return;
|
||||
}
|
||||
|
||||
bool dirtyBack = dirty;
|
||||
bool dirtyBack = isDirty();
|
||||
emit refreshWidgetsValuesRequested();
|
||||
foreach(objectToWidget * ow, objOfInterest) {
|
||||
if (ow->object == NULL || ow->field == NULL || ow->widget == NULL) {
|
||||
// do nothing
|
||||
} else {
|
||||
if (ow->object == obj || obj == NULL) {
|
||||
setWidgetFromField(ow->widget, ow->field, ow->index, ow->scale, ow->isLimited);
|
||||
}
|
||||
foreach(WidgetBinding * binding, m_widgetBindingsPerObject.values(obj)) {
|
||||
if (binding->isEnabled() && binding->field() != NULL && binding->widget() != NULL) {
|
||||
setWidgetFromField(binding->widget(), binding->field(), binding->index(), binding->scale(), binding->isLimited());
|
||||
}
|
||||
}
|
||||
setDirty(dirtyBack);
|
||||
}
|
||||
/**
|
||||
* SLOT function used to update the uavobject fields from widgets with relation to
|
||||
* object field added to the framework pool
|
||||
* Overwrite this if you need to change the default behavior
|
||||
*/
|
||||
|
||||
void ConfigTaskWidget::updateObjectsFromWidgets()
|
||||
{
|
||||
emit updateObjectsFromWidgetsRequested();
|
||||
|
||||
foreach(objectToWidget * ow, objOfInterest) {
|
||||
if (ow->object == NULL || ow->field == NULL) {} else {
|
||||
setFieldFromWidget(ow->widget, ow->field, ow->index, ow->scale);
|
||||
foreach(WidgetBinding * binding, m_widgetBindingsPerObject) {
|
||||
if (binding->object() != NULL && binding->field() != NULL) {
|
||||
binding->updateObjectFieldFromValue();
|
||||
}
|
||||
}
|
||||
}
|
||||
/**
|
||||
* SLOT function used handle help button presses
|
||||
* Overwrite this if you need to change the default behavior
|
||||
*/
|
||||
|
||||
void ConfigTaskWidget::helpButtonPressed()
|
||||
{
|
||||
QString url = helpButtonList.value((QPushButton *)sender(), QString());
|
||||
QString url = m_helpButtons.value((QPushButton *)sender(), QString());
|
||||
|
||||
if (!url.isEmpty()) {
|
||||
QDesktopServices::openUrl(QUrl(url, QUrl::StrictMode));
|
||||
}
|
||||
}
|
||||
/**
|
||||
* Add update and save buttons to the form
|
||||
* multiple buttons can be added for the same function
|
||||
* @param update pointer to the update button
|
||||
* @param save pointer to the save button
|
||||
*/
|
||||
|
||||
void ConfigTaskWidget::addApplySaveButtons(QPushButton *update, QPushButton *save)
|
||||
{
|
||||
if (!smartsave) {
|
||||
smartsave = new smartSaveButton(this);
|
||||
connect(smartsave, SIGNAL(preProcessOperations()), this, SLOT(updateObjectsFromWidgets()));
|
||||
connect(smartsave, SIGNAL(saveSuccessfull()), this, SLOT(clearDirty()));
|
||||
connect(smartsave, SIGNAL(beginOp()), this, SLOT(disableObjUpdates()));
|
||||
connect(smartsave, SIGNAL(endOp()), this, SLOT(enableObjUpdates()));
|
||||
if (!m_saveButton) {
|
||||
m_saveButton = new SmartSaveButton(this);
|
||||
connect(m_saveButton, SIGNAL(preProcessOperations()), this, SLOT(updateObjectsFromWidgets()));
|
||||
connect(m_saveButton, SIGNAL(saveSuccessfull()), this, SLOT(clearDirty()));
|
||||
connect(m_saveButton, SIGNAL(beginOp()), this, SLOT(disableObjectUpdates()));
|
||||
connect(m_saveButton, SIGNAL(endOp()), this, SLOT(enableObjectUpdates()));
|
||||
}
|
||||
if (update && save) {
|
||||
smartsave->addButtons(save, update);
|
||||
m_saveButton->addButtons(save, update);
|
||||
} else if (update) {
|
||||
smartsave->addApplyButton(update);
|
||||
m_saveButton->addApplyButton(update);
|
||||
} else if (save) {
|
||||
smartsave->addSaveButton(save);
|
||||
m_saveButton->addSaveButton(save);
|
||||
}
|
||||
if (objOfInterest.count() > 0) {
|
||||
foreach(objectToWidget * oTw, objOfInterest) {
|
||||
smartsave->addObject((UAVDataObject *)oTw->object);
|
||||
}
|
||||
foreach(WidgetBinding * binding, m_widgetBindingsPerWidget) {
|
||||
m_saveButton->addObject((UAVDataObject *)binding->object());
|
||||
}
|
||||
updateEnableControls();
|
||||
}
|
||||
|
||||
/**
|
||||
* SLOT function used the enable or disable the SAVE, UPLOAD and RELOAD buttons
|
||||
* @param enable set to true to enable the buttons or false to disable them
|
||||
* @param field name of the field to add
|
||||
*/
|
||||
void ConfigTaskWidget::enableControls(bool enable)
|
||||
{
|
||||
if (smartsave) {
|
||||
smartsave->enableControls(enable);
|
||||
if (m_saveButton) {
|
||||
m_saveButton->enableControls(enable);
|
||||
}
|
||||
|
||||
foreach(QPushButton * button, reloadButtonList) {
|
||||
foreach(QPushButton * button, m_reloadButtons) {
|
||||
button->setEnabled(enable);
|
||||
}
|
||||
|
||||
foreach(objectToWidget * ow, objOfInterest) {
|
||||
if (ow->widget) {
|
||||
ow->widget->setEnabled(enable);
|
||||
foreach(shadow * sh, ow->shadowsList) {
|
||||
sh->widget->setEnabled(enable);
|
||||
foreach(WidgetBinding * binding, m_widgetBindingsPerObject) {
|
||||
if (binding->isEnabled() && binding->widget()) {
|
||||
binding->widget()->setEnabled(enable);
|
||||
foreach(ShadowWidgetBinding * shadow, binding->shadows()) {
|
||||
shadow->widget()->setEnabled(enable);
|
||||
}
|
||||
}
|
||||
}
|
||||
@ -465,233 +381,187 @@ bool ConfigTaskWidget::shouldObjectBeSaved(UAVObject *object)
|
||||
return true;
|
||||
}
|
||||
|
||||
/**
|
||||
* SLOT function called when on of the widgets contents added to the framework changes
|
||||
*/
|
||||
void ConfigTaskWidget::forceShadowUpdates()
|
||||
{
|
||||
foreach(objectToWidget * oTw, objOfInterest) {
|
||||
foreach(shadow * sh, oTw->shadowsList) {
|
||||
disconnectWidgetUpdatesToSlot((QWidget *)sh->widget, SLOT(widgetsContentsChanged()));
|
||||
checkWidgetsLimits(sh->widget, oTw->field, oTw->index, sh->isLimited, getVariantFromWidget(oTw->widget, oTw->scale, oTw->getUnits()), sh->scale);
|
||||
setWidgetFromVariant(sh->widget, getVariantFromWidget(oTw->widget, oTw->scale, oTw->getUnits()), sh->scale);
|
||||
emit widgetContentsChanged((QWidget *)sh->widget);
|
||||
connectWidgetUpdatesToSlot((QWidget *)sh->widget, SLOT(widgetsContentsChanged()));
|
||||
foreach(WidgetBinding * binding, m_widgetBindingsPerObject) {
|
||||
if (!binding->isEnabled()) {
|
||||
continue;
|
||||
}
|
||||
QVariant widgetValue = getVariantFromWidget(binding->widget(), binding->scale(), binding->units());
|
||||
|
||||
foreach(ShadowWidgetBinding * shadow, binding->shadows()) {
|
||||
disconnectWidgetUpdatesToSlot(shadow->widget(), SLOT(widgetsContentsChanged()));
|
||||
|
||||
checkWidgetsLimits(shadow->widget(), binding->field(), binding->index(), shadow->isLimited(), widgetValue, shadow->scale());
|
||||
setWidgetFromVariant(shadow->widget(), widgetValue, shadow->scale());
|
||||
|
||||
emit widgetContentsChanged(shadow->widget());
|
||||
connectWidgetUpdatesToSlot(shadow->widget(), SLOT(widgetsContentsChanged()));
|
||||
}
|
||||
}
|
||||
setDirty(true);
|
||||
}
|
||||
/**
|
||||
* SLOT function called when one of the widgets contents added to the framework changes
|
||||
*/
|
||||
|
||||
void ConfigTaskWidget::widgetsContentsChanged()
|
||||
{
|
||||
emit widgetContentsChanged((QWidget *)sender());
|
||||
QWidget *emitter = ((QWidget *)sender());
|
||||
emit widgetContentsChanged(emitter);
|
||||
double scale;
|
||||
objectToWidget *oTw = shadowsList.value((QWidget *)sender(), NULL);
|
||||
QVariant value;
|
||||
|
||||
if (oTw) {
|
||||
if (oTw->widget == (QWidget *)sender()) {
|
||||
scale = oTw->scale;
|
||||
checkWidgetsLimits((QWidget *)sender(), oTw->field, oTw->index, oTw->isLimited, getVariantFromWidget((QWidget *)sender(),
|
||||
oTw->scale, oTw->getUnits()), oTw->scale);
|
||||
} else {
|
||||
foreach(shadow * sh, oTw->shadowsList) {
|
||||
if (sh->widget == (QWidget *)sender()) {
|
||||
scale = sh->scale;
|
||||
checkWidgetsLimits((QWidget *)sender(), oTw->field, oTw->index, sh->isLimited, getVariantFromWidget((QWidget *)sender(),
|
||||
scale, oTw->getUnits()), scale);
|
||||
foreach(WidgetBinding * binding, m_widgetBindingsPerWidget.values(emitter)) {
|
||||
if (binding && binding->isEnabled()) {
|
||||
if (binding->widget() == emitter) {
|
||||
scale = binding->scale();
|
||||
checkWidgetsLimits(emitter, binding->field(), binding->index(), binding->isLimited(),
|
||||
getVariantFromWidget(emitter, scale, binding->units()), scale);
|
||||
} else {
|
||||
foreach(ShadowWidgetBinding * shadow, binding->shadows()) {
|
||||
if (shadow->widget() == emitter) {
|
||||
scale = shadow->scale();
|
||||
checkWidgetsLimits(emitter, binding->field(), binding->index(), shadow->isLimited(),
|
||||
getVariantFromWidget(emitter, scale, binding->units()), scale);
|
||||
}
|
||||
}
|
||||
}
|
||||
value = getVariantFromWidget(emitter, scale, binding->units());
|
||||
binding->setValue(value);
|
||||
|
||||
if (binding->widget() != emitter) {
|
||||
disconnectWidgetUpdatesToSlot(binding->widget(), SLOT(widgetsContentsChanged()));
|
||||
|
||||
checkWidgetsLimits(binding->widget(), binding->field(), binding->index(), binding->isLimited(),
|
||||
value, binding->scale());
|
||||
setWidgetFromVariant(binding->widget(), value, binding->scale());
|
||||
emit widgetContentsChanged(binding->widget());
|
||||
|
||||
connectWidgetUpdatesToSlot(binding->widget(), SLOT(widgetsContentsChanged()));
|
||||
}
|
||||
foreach(ShadowWidgetBinding * shadow, binding->shadows()) {
|
||||
if (shadow->widget() != emitter) {
|
||||
disconnectWidgetUpdatesToSlot(shadow->widget(), SLOT(widgetsContentsChanged()));
|
||||
|
||||
checkWidgetsLimits(shadow->widget(), binding->field(), binding->index(), shadow->isLimited(),
|
||||
value, shadow->scale());
|
||||
setWidgetFromVariant(shadow->widget(), value, shadow->scale());
|
||||
emit widgetContentsChanged(shadow->widget());
|
||||
|
||||
connectWidgetUpdatesToSlot(shadow->widget(), SLOT(widgetsContentsChanged()));
|
||||
}
|
||||
}
|
||||
}
|
||||
if (oTw->widget != (QWidget *)sender()) {
|
||||
disconnectWidgetUpdatesToSlot((QWidget *)oTw->widget, SLOT(widgetsContentsChanged()));
|
||||
checkWidgetsLimits(oTw->widget, oTw->field, oTw->index, oTw->isLimited, getVariantFromWidget((QWidget *)sender(), scale, oTw->getUnits()), oTw->scale);
|
||||
setWidgetFromVariant(oTw->widget, getVariantFromWidget((QWidget *)sender(), scale, oTw->getUnits()), oTw->scale);
|
||||
emit widgetContentsChanged((QWidget *)oTw->widget);
|
||||
connectWidgetUpdatesToSlot((QWidget *)oTw->widget, SLOT(widgetsContentsChanged()));
|
||||
}
|
||||
foreach(shadow * sh, oTw->shadowsList) {
|
||||
if (sh->widget != (QWidget *)sender()) {
|
||||
disconnectWidgetUpdatesToSlot((QWidget *)sh->widget, SLOT(widgetsContentsChanged()));
|
||||
checkWidgetsLimits(sh->widget, oTw->field, oTw->index, sh->isLimited, getVariantFromWidget((QWidget *)sender(), scale, oTw->getUnits()), sh->scale);
|
||||
setWidgetFromVariant(sh->widget, getVariantFromWidget((QWidget *)sender(), scale, oTw->getUnits()), sh->scale);
|
||||
emit widgetContentsChanged((QWidget *)sh->widget);
|
||||
connectWidgetUpdatesToSlot((QWidget *)sh->widget, SLOT(widgetsContentsChanged()));
|
||||
}
|
||||
}
|
||||
}
|
||||
if (smartsave) {
|
||||
smartsave->resetIcons();
|
||||
if (m_saveButton) {
|
||||
m_saveButton->resetIcons();
|
||||
}
|
||||
setDirty(true);
|
||||
}
|
||||
/**
|
||||
* SLOT function used clear the forms dirty status flag
|
||||
*/
|
||||
|
||||
void ConfigTaskWidget::clearDirty()
|
||||
{
|
||||
setDirty(false);
|
||||
}
|
||||
/**
|
||||
* Sets the form's dirty status flag
|
||||
* @param value
|
||||
*/
|
||||
|
||||
void ConfigTaskWidget::setDirty(bool value)
|
||||
{
|
||||
dirty = value;
|
||||
m_isDirty = value;
|
||||
}
|
||||
/**
|
||||
* Checks if the form is dirty (unsaved changes)
|
||||
* @return true if the form has unsaved changes
|
||||
*/
|
||||
|
||||
bool ConfigTaskWidget::isDirty()
|
||||
{
|
||||
if (isConnected) {
|
||||
return dirty;
|
||||
if (m_isConnected) {
|
||||
return m_isDirty;
|
||||
} else {
|
||||
return false;
|
||||
}
|
||||
}
|
||||
/**
|
||||
* SLOT function used to disable widget contents changes when related object field changes
|
||||
*/
|
||||
void ConfigTaskWidget::disableObjUpdates()
|
||||
|
||||
void ConfigTaskWidget::disableObjectUpdates()
|
||||
{
|
||||
allowWidgetUpdates = false;
|
||||
foreach(objectToWidget * obj, objOfInterest) {
|
||||
if (obj->object) {
|
||||
disconnect(obj->object, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(refreshWidgetsValues(UAVObject *)));
|
||||
m_isWidgetUpdatesAllowed = false;
|
||||
foreach(WidgetBinding * binding, m_widgetBindingsPerWidget) {
|
||||
if (binding->object()) {
|
||||
disconnect(binding->object(), SIGNAL(objectUpdated(UAVObject *)), this, SLOT(refreshWidgetsValues(UAVObject *)));
|
||||
}
|
||||
}
|
||||
}
|
||||
/**
|
||||
* SLOT function used to enable widget contents changes when related object field changes
|
||||
*/
|
||||
void ConfigTaskWidget::enableObjUpdates()
|
||||
|
||||
void ConfigTaskWidget::enableObjectUpdates()
|
||||
{
|
||||
allowWidgetUpdates = true;
|
||||
foreach(objectToWidget * obj, objOfInterest) {
|
||||
if (obj->object) {
|
||||
connect(obj->object, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(refreshWidgetsValues(UAVObject *)), Qt::UniqueConnection);
|
||||
m_isWidgetUpdatesAllowed = true;
|
||||
foreach(WidgetBinding * binding, m_widgetBindingsPerWidget) {
|
||||
if (binding->object()) {
|
||||
connect(binding->object(), SIGNAL(objectUpdated(UAVObject *)), this, SLOT(refreshWidgetsValues(UAVObject *)), Qt::UniqueConnection);
|
||||
}
|
||||
}
|
||||
}
|
||||
/**
|
||||
* Called when an uav object is updated
|
||||
* @param obj pointer to the object whitch has just been updated
|
||||
*/
|
||||
void ConfigTaskWidget::objectUpdated(UAVObject *obj)
|
||||
|
||||
void ConfigTaskWidget::objectUpdated(UAVObject *object)
|
||||
{
|
||||
objectUpdates[obj] = true;
|
||||
m_updatedObjects[object] = true;
|
||||
}
|
||||
/**
|
||||
* Checks if all objects added to the pool have already been updated
|
||||
* @return true if all objects added to the pool have already been updated
|
||||
*/
|
||||
|
||||
bool ConfigTaskWidget::allObjectsUpdated()
|
||||
{
|
||||
qDebug() << "ConfigTaskWidge:allObjectsUpdated called";
|
||||
bool ret = true;
|
||||
foreach(UAVObject * obj, objectUpdates.keys()) {
|
||||
ret = ret & objectUpdates[obj];
|
||||
bool result = true;
|
||||
|
||||
foreach(UAVObject * object, m_updatedObjects.keys()) {
|
||||
result = result & m_updatedObjects[object];
|
||||
}
|
||||
qDebug() << "Returned:" << ret;
|
||||
return ret;
|
||||
return result;
|
||||
}
|
||||
/**
|
||||
* Adds a new help button
|
||||
* @param button pointer to the help button
|
||||
* @param url url to open in the browser when the help button is pressed
|
||||
*/
|
||||
|
||||
void ConfigTaskWidget::addHelpButton(QPushButton *button, QString url)
|
||||
{
|
||||
helpButtonList.insert(button, url);
|
||||
m_helpButtons.insert(button, url);
|
||||
connect(button, SIGNAL(clicked()), this, SLOT(helpButtonPressed()));
|
||||
}
|
||||
/**
|
||||
* Invalidates all the uav objects "is updated" flag
|
||||
*/
|
||||
|
||||
void ConfigTaskWidget::invalidateObjects()
|
||||
{
|
||||
foreach(UAVObject * obj, objectUpdates.keys()) {
|
||||
objectUpdates[obj] = false;
|
||||
foreach(UAVObject * obj, m_updatedObjects.keys()) {
|
||||
m_updatedObjects[obj] = false;
|
||||
}
|
||||
}
|
||||
/**
|
||||
* SLOT call this to apply changes to uav objects
|
||||
*/
|
||||
|
||||
void ConfigTaskWidget::apply()
|
||||
{
|
||||
if (smartsave) {
|
||||
smartsave->apply();
|
||||
if (m_saveButton) {
|
||||
m_saveButton->apply();
|
||||
}
|
||||
}
|
||||
/**
|
||||
* SLOT call this to save changes to uav objects
|
||||
*/
|
||||
|
||||
void ConfigTaskWidget::save()
|
||||
{
|
||||
if (smartsave) {
|
||||
smartsave->save();
|
||||
if (m_saveButton) {
|
||||
m_saveButton->save();
|
||||
}
|
||||
}
|
||||
/**
|
||||
* Adds a new shadow widget
|
||||
* shadow widgets are widgets whitch have a relation to an object already present on the framework pool i.e. already added trough addUAVObjectToWidgetRelation
|
||||
* This function doesn't have to be used directly, addUAVObjectToWidgetRelation will call it if a previous relation exhists.
|
||||
* @return returns false if the shadow widget relation failed to be added (no previous relation exhisted)
|
||||
*/
|
||||
bool ConfigTaskWidget::addShadowWidget(QString object, QString field, QWidget *widget, int index, double scale, bool isLimited,
|
||||
QList<int> *defaultReloadGroups, quint32 instID)
|
||||
|
||||
bool ConfigTaskWidget::addShadowWidgetBinding(QString objectName, QString fieldName, QWidget *widget, int index, double scale, bool isLimited,
|
||||
QList<int> *defaultReloadGroups, quint32 instID)
|
||||
{
|
||||
foreach(objectToWidget * oTw, objOfInterest) {
|
||||
if (!oTw->object || !oTw->widget || !oTw->field) {
|
||||
foreach(WidgetBinding * binding, m_widgetBindingsPerWidget) {
|
||||
if (!binding->object() || !binding->widget() || !binding->field()) {
|
||||
continue;
|
||||
}
|
||||
if (oTw->object->getName() == object && oTw->field->getName() == field && oTw->index == index && oTw->object->getInstID() == instID) {
|
||||
shadow *sh = NULL;
|
||||
// prefer anything else to QLabel
|
||||
if (qobject_cast<QLabel *>(oTw->widget) && !qobject_cast<QLabel *>(widget)) {
|
||||
sh = new shadow;
|
||||
sh->isLimited = oTw->isLimited;
|
||||
sh->scale = oTw->scale;
|
||||
sh->widget = oTw->widget;
|
||||
oTw->isLimited = isLimited;
|
||||
oTw->scale = scale;
|
||||
oTw->widget = widget;
|
||||
}
|
||||
// prefer QDoubleSpinBox to anything else
|
||||
else if (!qobject_cast<QDoubleSpinBox *>(oTw->widget) && qobject_cast<QDoubleSpinBox *>(widget)) {
|
||||
sh = new shadow;
|
||||
sh->isLimited = oTw->isLimited;
|
||||
sh->scale = oTw->scale;
|
||||
sh->widget = oTw->widget;
|
||||
oTw->isLimited = isLimited;
|
||||
oTw->scale = scale;
|
||||
oTw->widget = widget;
|
||||
} else {
|
||||
sh = new shadow;
|
||||
sh->isLimited = isLimited;
|
||||
sh->scale = scale;
|
||||
sh->widget = widget;
|
||||
}
|
||||
shadowsList.insert(widget, oTw);
|
||||
oTw->shadowsList.append(sh);
|
||||
if (binding->matches(objectName, fieldName, index, instID)) {
|
||||
binding->addShadow(widget, scale, isLimited);
|
||||
|
||||
m_widgetBindingsPerWidget.insert(widget, binding);
|
||||
connectWidgetUpdatesToSlot(widget, SLOT(widgetsContentsChanged()));
|
||||
if (defaultReloadGroups) {
|
||||
addWidgetToDefaultReloadGroups(widget, defaultReloadGroups);
|
||||
addWidgetToReloadGroups(widget, defaultReloadGroups);
|
||||
}
|
||||
if (!binding->isEnabled()) {
|
||||
loadWidgetLimits(widget, binding->field(), binding->index(), isLimited, scale);
|
||||
}
|
||||
loadWidgetLimits(widget, oTw->field, oTw->index, isLimited, scale);
|
||||
return true;
|
||||
}
|
||||
}
|
||||
return false;
|
||||
}
|
||||
/**
|
||||
* Auto loads widgets based on the Dynamic property named "objrelation"
|
||||
* Check the wiki for more information
|
||||
*/
|
||||
|
||||
void ConfigTaskWidget::autoLoadWidgets()
|
||||
{
|
||||
QPushButton *saveButtonWidget = NULL;
|
||||
@ -701,7 +571,7 @@ void ConfigTaskWidget::autoLoadWidgets()
|
||||
QVariant info = widget->property("objrelation");
|
||||
|
||||
if (info.isValid()) {
|
||||
uiRelationAutomation uiRelation;
|
||||
bindingStruct uiRelation;
|
||||
uiRelation.buttonType = none;
|
||||
uiRelation.scale = 1;
|
||||
uiRelation.element = QString();
|
||||
@ -788,119 +658,105 @@ void ConfigTaskWidget::autoLoadWidgets()
|
||||
} else {
|
||||
QWidget *wid = qobject_cast<QWidget *>(widget);
|
||||
if (wid) {
|
||||
addUAVObjectToWidgetRelation(uiRelation.objname, uiRelation.fieldname, wid, uiRelation.element, uiRelation.scale, uiRelation.haslimits, &uiRelation.buttonGroup);
|
||||
addWidgetBinding(uiRelation.objname, uiRelation.fieldname, wid, uiRelation.element, uiRelation.scale, uiRelation.haslimits, &uiRelation.buttonGroup);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
refreshWidgetsValues();
|
||||
forceShadowUpdates();
|
||||
foreach(objectToWidget * ow, objOfInterest) {
|
||||
if (ow->widget) {
|
||||
qDebug() << "Master:" << ow->widget->objectName();
|
||||
}
|
||||
foreach(shadow * sh, ow->shadowsList) {
|
||||
if (sh->widget) {
|
||||
qDebug() << "Child" << sh->widget->objectName();
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
/**
|
||||
* Adds a widget to a list of default/reload groups
|
||||
* default/reload groups are groups of widgets to be set with default or reloaded (values from persistent memory) when a defined button is pressed
|
||||
* @param widget pointer to the widget to be added to the groups
|
||||
* @param groups list of the groups on which to add the widget
|
||||
*/
|
||||
void ConfigTaskWidget::addWidgetToDefaultReloadGroups(QWidget *widget, QList<int> *groups)
|
||||
{
|
||||
foreach(objectToWidget * oTw, objOfInterest) {
|
||||
bool addOTW = false;
|
||||
|
||||
if (oTw->widget == widget) {
|
||||
addOTW = true;
|
||||
/*
|
||||
foreach(WidgetBinding * binding, m_widgetBindingsPerObject) {
|
||||
if (binding->widget()) {
|
||||
qDebug() << "Binding :" << binding->widget()->objectName();
|
||||
qDebug() << " Object :" << binding->object()->getName();
|
||||
qDebug() << " Field :" << binding->field()->getName();
|
||||
qDebug() << " Scale :" << binding->scale();
|
||||
qDebug() << " Enabled:" << binding->isEnabled();
|
||||
}
|
||||
foreach(ShadowWidgetBinding * shadow, binding->shadows()) {
|
||||
if (shadow->widget()) {
|
||||
qDebug() << " Shadow:" << shadow->widget()->objectName();
|
||||
qDebug() << " Scale :" << shadow->scale();
|
||||
}
|
||||
}
|
||||
}
|
||||
*/
|
||||
}
|
||||
|
||||
void ConfigTaskWidget::addWidgetToReloadGroups(QWidget *widget, QList<int> *reloadGroupIDs)
|
||||
{
|
||||
foreach(WidgetBinding * binding, m_widgetBindingsPerWidget) {
|
||||
bool addBinding = false;
|
||||
|
||||
if (binding->widget() == widget) {
|
||||
addBinding = true;
|
||||
} else {
|
||||
foreach(shadow * sh, oTw->shadowsList) {
|
||||
if (sh->widget == widget) {
|
||||
addOTW = true;
|
||||
foreach(ShadowWidgetBinding * shadow, binding->shadows()) {
|
||||
if (shadow->widget() == widget) {
|
||||
addBinding = true;
|
||||
}
|
||||
}
|
||||
}
|
||||
if (addOTW) {
|
||||
foreach(int i, *groups) {
|
||||
if (defaultReloadGroups.contains(i)) {
|
||||
defaultReloadGroups.value(i)->append(oTw);
|
||||
} else {
|
||||
defaultReloadGroups.insert(i, new QList<objectToWidget *>());
|
||||
defaultReloadGroups.value(i)->append(oTw);
|
||||
}
|
||||
if (addBinding) {
|
||||
foreach(int groupID, *reloadGroupIDs) {
|
||||
m_reloadGroups.insert(groupID, binding);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
/**
|
||||
* Adds a button to a default group
|
||||
* @param button pointer to the default button
|
||||
* @param buttongroup number of the group
|
||||
*/
|
||||
|
||||
void ConfigTaskWidget::addDefaultButton(QPushButton *button, int buttonGroup)
|
||||
{
|
||||
button->setProperty("group", buttonGroup);
|
||||
connect(button, SIGNAL(clicked()), this, SLOT(defaultButtonClicked()));
|
||||
}
|
||||
/**
|
||||
* Adds a button to a reload group
|
||||
* @param button pointer to the reload button
|
||||
* @param buttongroup number of the group
|
||||
*/
|
||||
|
||||
void ConfigTaskWidget::addReloadButton(QPushButton *button, int buttonGroup)
|
||||
{
|
||||
button->setProperty("group", buttonGroup);
|
||||
reloadButtonList.append(button);
|
||||
m_reloadButtons.append(button);
|
||||
connect(button, SIGNAL(clicked()), this, SLOT(reloadButtonClicked()));
|
||||
}
|
||||
/**
|
||||
* Called when a default button is clicked
|
||||
*/
|
||||
|
||||
void ConfigTaskWidget::defaultButtonClicked()
|
||||
{
|
||||
int group = sender()->property("group").toInt();
|
||||
emit defaultRequested(group);
|
||||
int groupID = sender()->property("group").toInt();
|
||||
emit defaultRequested(groupID);
|
||||
|
||||
QList<objectToWidget *> *list = defaultReloadGroups.value(group);
|
||||
foreach(objectToWidget * oTw, *list) {
|
||||
if (!oTw->object || !oTw->field) {
|
||||
QList<WidgetBinding *> bindings = m_reloadGroups.values(groupID);
|
||||
foreach(WidgetBinding * binding, bindings) {
|
||||
if (!binding->isEnabled() || !binding->object() || !binding->field()) {
|
||||
continue;
|
||||
}
|
||||
UAVDataObject *temp = ((UAVDataObject *)oTw->object)->dirtyClone();
|
||||
setWidgetFromField(oTw->widget, temp->getField(oTw->field->getName()), oTw->index, oTw->scale, oTw->isLimited);
|
||||
UAVDataObject *temp = ((UAVDataObject *)binding->object())->dirtyClone();
|
||||
setWidgetFromField(binding->widget(), temp->getField(binding->field()->getName()), binding->index(), binding->scale(), binding->isLimited());
|
||||
}
|
||||
}
|
||||
/**
|
||||
* Called when a reload button is clicked
|
||||
*/
|
||||
|
||||
void ConfigTaskWidget::reloadButtonClicked()
|
||||
{
|
||||
if (timeOut) {
|
||||
if (m_realtimeUpdateTimer) {
|
||||
return;
|
||||
}
|
||||
int group = sender()->property("group").toInt();
|
||||
QList<objectToWidget *> *list = defaultReloadGroups.value(group, NULL);
|
||||
if (!list) {
|
||||
int groupID = sender()->property("group").toInt();
|
||||
QList<WidgetBinding *> bindings = m_reloadGroups.values(groupID);
|
||||
if (!bindings.isEmpty()) {
|
||||
return;
|
||||
}
|
||||
ObjectPersistence *objper = dynamic_cast<ObjectPersistence *>(getObjectManager()->getObject(ObjectPersistence::NAME));
|
||||
timeOut = new QTimer(this);
|
||||
m_realtimeUpdateTimer = new QTimer(this);
|
||||
QEventLoop *eventLoop = new QEventLoop(this);
|
||||
connect(timeOut, SIGNAL(timeout()), eventLoop, SLOT(quit()));
|
||||
connect(m_realtimeUpdateTimer, SIGNAL(timeout()), eventLoop, SLOT(quit()));
|
||||
connect(objper, SIGNAL(objectUpdated(UAVObject *)), eventLoop, SLOT(quit()));
|
||||
|
||||
QList<temphelper> temp;
|
||||
foreach(objectToWidget * oTw, *list) {
|
||||
if (oTw->object != NULL) {
|
||||
temphelper value;
|
||||
value.objid = oTw->object->getObjID();
|
||||
value.objinstid = oTw->object->getInstID();
|
||||
QList<objectComparator> temp;
|
||||
foreach(WidgetBinding * binding, bindings) {
|
||||
if (binding->isEnabled() && binding->object() != NULL) {
|
||||
objectComparator value;
|
||||
value.objid = binding->object()->getObjID();
|
||||
value.objinstid = binding->object()->getInstID();
|
||||
if (temp.contains(value)) {
|
||||
continue;
|
||||
} else {
|
||||
@ -909,62 +765,57 @@ void ConfigTaskWidget::reloadButtonClicked()
|
||||
ObjectPersistence::DataFields data;
|
||||
data.Operation = ObjectPersistence::OPERATION_LOAD;
|
||||
data.Selection = ObjectPersistence::SELECTION_SINGLEOBJECT;
|
||||
data.ObjectID = oTw->object->getObjID();
|
||||
data.InstanceID = oTw->object->getInstID();
|
||||
data.ObjectID = binding->object()->getObjID();
|
||||
data.InstanceID = binding->object()->getInstID();
|
||||
objper->setData(data);
|
||||
objper->updated();
|
||||
timeOut->start(500);
|
||||
m_realtimeUpdateTimer->start(500);
|
||||
eventLoop->exec();
|
||||
if (timeOut->isActive()) {
|
||||
oTw->object->requestUpdate();
|
||||
if (oTw->widget) {
|
||||
setWidgetFromField(oTw->widget, oTw->field, oTw->index, oTw->scale, oTw->isLimited);
|
||||
if (m_realtimeUpdateTimer->isActive()) {
|
||||
binding->object()->requestUpdate();
|
||||
if (binding->widget()) {
|
||||
setWidgetFromField(binding->widget(), binding->field(), binding->index(), binding->scale(), binding->isLimited());
|
||||
}
|
||||
}
|
||||
timeOut->stop();
|
||||
m_realtimeUpdateTimer->stop();
|
||||
}
|
||||
}
|
||||
if (eventLoop) {
|
||||
delete eventLoop;
|
||||
eventLoop = NULL;
|
||||
}
|
||||
if (timeOut) {
|
||||
delete timeOut;
|
||||
timeOut = NULL;
|
||||
if (m_realtimeUpdateTimer) {
|
||||
delete m_realtimeUpdateTimer;
|
||||
m_realtimeUpdateTimer = NULL;
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Connects widgets "contents changed" signals to a slot
|
||||
*/
|
||||
void ConfigTaskWidget::connectWidgetUpdatesToSlot(QWidget *widget, const char *function)
|
||||
{
|
||||
if (!widget) {
|
||||
return;
|
||||
}
|
||||
if (QComboBox * cb = qobject_cast<QComboBox *>(widget)) {
|
||||
connect(cb, SIGNAL(currentIndexChanged(int)), this, function);
|
||||
connect(cb, SIGNAL(currentIndexChanged(int)), this, function, Qt::UniqueConnection);
|
||||
} else if (QSlider * cb = qobject_cast<QSlider *>(widget)) {
|
||||
connect(cb, SIGNAL(valueChanged(int)), this, function);
|
||||
connect(cb, SIGNAL(valueChanged(int)), this, function, Qt::UniqueConnection);
|
||||
} else if (MixerCurveWidget * cb = qobject_cast<MixerCurveWidget *>(widget)) {
|
||||
connect(cb, SIGNAL(curveUpdated()), this, function);
|
||||
connect(cb, SIGNAL(curveUpdated()), this, function, Qt::UniqueConnection);
|
||||
} else if (QTableWidget * cb = qobject_cast<QTableWidget *>(widget)) {
|
||||
connect(cb, SIGNAL(cellChanged(int, int)), this, function);
|
||||
connect(cb, SIGNAL(cellChanged(int, int)), this, function, Qt::UniqueConnection);
|
||||
} else if (QSpinBox * cb = qobject_cast<QSpinBox *>(widget)) {
|
||||
connect(cb, SIGNAL(valueChanged(int)), this, function);
|
||||
connect(cb, SIGNAL(valueChanged(int)), this, function, Qt::UniqueConnection);
|
||||
} else if (QDoubleSpinBox * cb = qobject_cast<QDoubleSpinBox *>(widget)) {
|
||||
connect(cb, SIGNAL(valueChanged(double)), this, function);
|
||||
connect(cb, SIGNAL(valueChanged(double)), this, function, Qt::UniqueConnection);
|
||||
} else if (QCheckBox * cb = qobject_cast<QCheckBox *>(widget)) {
|
||||
connect(cb, SIGNAL(stateChanged(int)), this, function);
|
||||
connect(cb, SIGNAL(stateChanged(int)), this, function, Qt::UniqueConnection);
|
||||
} else if (QPushButton * cb = qobject_cast<QPushButton *>(widget)) {
|
||||
connect(cb, SIGNAL(clicked()), this, function);
|
||||
connect(cb, SIGNAL(clicked()), this, function, Qt::UniqueConnection);
|
||||
} else {
|
||||
qDebug() << __FUNCTION__ << "widget to uavobject relation not implemented" << widget->metaObject()->className();
|
||||
qDebug() << __FUNCTION__ << "widget binding not implemented" << widget->metaObject()->className();
|
||||
}
|
||||
}
|
||||
/**
|
||||
* Disconnects widgets "contents changed" signals to a slot
|
||||
*/
|
||||
|
||||
void ConfigTaskWidget::disconnectWidgetUpdatesToSlot(QWidget *widget, const char *function)
|
||||
{
|
||||
if (!widget) {
|
||||
@ -987,38 +838,10 @@ void ConfigTaskWidget::disconnectWidgetUpdatesToSlot(QWidget *widget, const char
|
||||
} else if (QPushButton * cb = qobject_cast<QPushButton *>(widget)) {
|
||||
disconnect(cb, SIGNAL(clicked()), this, function);
|
||||
} else {
|
||||
qDebug() << __FUNCTION__ << "widget to uavobject relation not implemented" << widget->metaObject()->className();
|
||||
qDebug() << __FUNCTION__ << "widget binding not implemented" << widget->metaObject()->className();
|
||||
}
|
||||
}
|
||||
/**
|
||||
* Sets a widget value from an UAVObject field
|
||||
* @param widget pointer for the widget to set
|
||||
* @param field pointer to the UAVObject field to use
|
||||
* @param index index of the element to use
|
||||
* @param scale scale to be used on the assignement
|
||||
* @return returns true if the assignement was successfull
|
||||
*/
|
||||
bool ConfigTaskWidget::setFieldFromWidget(QWidget *widget, UAVObjectField *field, int index, double scale)
|
||||
{
|
||||
if (!widget || !field) {
|
||||
return false;
|
||||
}
|
||||
QVariant ret = getVariantFromWidget(widget, scale, field->getUnits());
|
||||
if (ret.isValid()) {
|
||||
field->setValue(ret, index);
|
||||
return true;
|
||||
}
|
||||
{
|
||||
qDebug() << __FUNCTION__ << "widget to uavobject relation not implemented" << widget->metaObject()->className();
|
||||
return false;
|
||||
}
|
||||
}
|
||||
/**
|
||||
* Gets a variant from a widget
|
||||
* @param widget pointer to the widget from where to get the value
|
||||
* @param scale scale to be used on the assignement
|
||||
* @return returns the value of the widget times the scale
|
||||
*/
|
||||
|
||||
QVariant ConfigTaskWidget::getVariantFromWidget(QWidget *widget, double scale, QString units)
|
||||
{
|
||||
if (QComboBox * cb = qobject_cast<QComboBox *>(widget)) {
|
||||
@ -1043,14 +866,7 @@ QVariant ConfigTaskWidget::getVariantFromWidget(QWidget *widget, double scale, Q
|
||||
return QVariant();
|
||||
}
|
||||
}
|
||||
/**
|
||||
* Sets a widget from a variant
|
||||
* @param widget pointer for the widget to set
|
||||
* @param value value to be used on the assignement
|
||||
* @param scale scale to be used on the assignement
|
||||
* @param units the units for the value
|
||||
* @return returns true if the assignement was successfull
|
||||
*/
|
||||
|
||||
bool ConfigTaskWidget::setWidgetFromVariant(QWidget *widget, QVariant value, double scale, QString units)
|
||||
{
|
||||
if (QComboBox * cb = qobject_cast<QComboBox *>(widget)) {
|
||||
@ -1092,27 +908,11 @@ bool ConfigTaskWidget::setWidgetFromVariant(QWidget *widget, QVariant value, dou
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Sets a widget from a variant
|
||||
* @param widget pointer for the widget to set
|
||||
* @param value value to be used on the assignement
|
||||
* @param scale scale to be used on the assignement
|
||||
* @return returns true if the assignement was successfull
|
||||
*/
|
||||
bool ConfigTaskWidget::setWidgetFromVariant(QWidget *widget, QVariant value, double scale)
|
||||
{
|
||||
return setWidgetFromVariant(widget, value, scale, QString(""));
|
||||
}
|
||||
|
||||
/**
|
||||
* Sets a widget from a UAVObject field
|
||||
* @param widget pointer to the widget to set
|
||||
* @param field pointer to the field from where to get the value from
|
||||
* @param index index of the element to use
|
||||
* @param scale scale to be used on the assignement
|
||||
* @param hasLimits set to true if you want to limit the values (check wiki)
|
||||
* @return returns true if the assignement was successfull
|
||||
*/
|
||||
bool ConfigTaskWidget::setWidgetFromField(QWidget *widget, UAVObjectField *field, int index, double scale, bool hasLimits)
|
||||
{
|
||||
if (!widget || !field) {
|
||||
@ -1123,26 +923,27 @@ bool ConfigTaskWidget::setWidgetFromField(QWidget *widget, UAVObjectField *field
|
||||
loadWidgetLimits(cb, field, index, hasLimits, scale);
|
||||
}
|
||||
}
|
||||
QVariant var = field->getValue(index);
|
||||
checkWidgetsLimits(widget, field, index, hasLimits, var, scale);
|
||||
bool ret = setWidgetFromVariant(widget, var, scale, field->getUnits());
|
||||
if (ret) {
|
||||
QVariant value = field->getValue(index);
|
||||
checkWidgetsLimits(widget, field, index, hasLimits, value, scale);
|
||||
bool result = setWidgetFromVariant(widget, value, scale, field->getUnits());
|
||||
if (result) {
|
||||
return true;
|
||||
} else {
|
||||
qDebug() << __FUNCTION__ << "widget to uavobject relation not implemented" << widget->metaObject()->className();
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
void ConfigTaskWidget::checkWidgetsLimits(QWidget *widget, UAVObjectField *field, int index, bool hasLimits, QVariant value, double scale)
|
||||
{
|
||||
if (!hasLimits) {
|
||||
return;
|
||||
}
|
||||
if (!field->isWithinLimits(value, index, currentBoard)) {
|
||||
if (!field->isWithinLimits(value, index, m_currentBoardId)) {
|
||||
if (!widget->property("styleBackup").isValid()) {
|
||||
widget->setProperty("styleBackup", widget->styleSheet());
|
||||
}
|
||||
widget->setStyleSheet(outOfLimitsStyle);
|
||||
widget->setStyleSheet(m_outOfLimitsStyle);
|
||||
widget->setProperty("wasOverLimits", (bool)true);
|
||||
if (QComboBox * cb = qobject_cast<QComboBox *>(widget)) {
|
||||
if (cb->findText(value.toString()) == -1) {
|
||||
@ -1189,7 +990,7 @@ void ConfigTaskWidget::loadWidgetLimits(QWidget *widget, UAVObjectField *field,
|
||||
QStringList option = field->getOptions();
|
||||
if (hasLimits) {
|
||||
foreach(QString str, option) {
|
||||
if (field->isWithinLimits(str, index, currentBoard)) {
|
||||
if (field->isWithinLimits(str, index, m_currentBoardId)) {
|
||||
cb->addItem(str);
|
||||
}
|
||||
}
|
||||
@ -1201,31 +1002,41 @@ void ConfigTaskWidget::loadWidgetLimits(QWidget *widget, UAVObjectField *field,
|
||||
return;
|
||||
} else if (QDoubleSpinBox * cb = qobject_cast<QDoubleSpinBox *>(widget)) {
|
||||
if (field->getMaxLimit(index).isValid()) {
|
||||
cb->setMaximum((double)(field->getMaxLimit(index, currentBoard).toDouble() / scale));
|
||||
cb->setMaximum((double)(field->getMaxLimit(index, m_currentBoardId).toDouble() / scale));
|
||||
}
|
||||
if (field->getMinLimit(index, currentBoard).isValid()) {
|
||||
cb->setMinimum((double)(field->getMinLimit(index, currentBoard).toDouble() / scale));
|
||||
if (field->getMinLimit(index, m_currentBoardId).isValid()) {
|
||||
cb->setMinimum((double)(field->getMinLimit(index, m_currentBoardId).toDouble() / scale));
|
||||
}
|
||||
} else if (QSpinBox * cb = qobject_cast<QSpinBox *>(widget)) {
|
||||
if (field->getMaxLimit(index, currentBoard).isValid()) {
|
||||
cb->setMaximum((int)qRound(field->getMaxLimit(index, currentBoard).toDouble() / scale));
|
||||
if (field->getMaxLimit(index, m_currentBoardId).isValid()) {
|
||||
cb->setMaximum((int)qRound(field->getMaxLimit(index, m_currentBoardId).toDouble() / scale));
|
||||
}
|
||||
if (field->getMinLimit(index, currentBoard).isValid()) {
|
||||
cb->setMinimum((int)qRound(field->getMinLimit(index, currentBoard).toDouble() / scale));
|
||||
if (field->getMinLimit(index, m_currentBoardId).isValid()) {
|
||||
cb->setMinimum((int)qRound(field->getMinLimit(index, m_currentBoardId).toDouble() / scale));
|
||||
}
|
||||
} else if (QSlider * cb = qobject_cast<QSlider *>(widget)) {
|
||||
if (field->getMaxLimit(index, currentBoard).isValid()) {
|
||||
cb->setMaximum((int)qRound(field->getMaxLimit(index, currentBoard).toDouble() / scale));
|
||||
if (field->getMaxLimit(index, m_currentBoardId).isValid()) {
|
||||
cb->setMaximum((int)qRound(field->getMaxLimit(index, m_currentBoardId).toDouble() / scale));
|
||||
}
|
||||
if (field->getMinLimit(index, currentBoard).isValid()) {
|
||||
cb->setMinimum((int)(field->getMinLimit(index, currentBoard).toDouble() / scale));
|
||||
if (field->getMinLimit(index, m_currentBoardId).isValid()) {
|
||||
cb->setMinimum((int)(field->getMinLimit(index, m_currentBoardId).toDouble() / scale));
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
UAVObject *ConfigTaskWidget::getObject(const QString name, quint32 instId)
|
||||
{
|
||||
return m_pluginManager->getObject<UAVObjectManager>()->getObject(name, instId);
|
||||
}
|
||||
|
||||
QString ConfigTaskWidget::mapObjectName(const QString objectName)
|
||||
{
|
||||
return objectName;
|
||||
}
|
||||
|
||||
void ConfigTaskWidget::updateEnableControls()
|
||||
{
|
||||
TelemetryManager *telMngr = pm->getObject<TelemetryManager>();
|
||||
TelemetryManager *telMngr = m_pluginManager->getObject<TelemetryManager>();
|
||||
|
||||
Q_ASSERT(telMngr);
|
||||
enableControls(telMngr->isConnected());
|
||||
@ -1260,7 +1071,126 @@ bool ConfigTaskWidget::eventFilter(QObject *obj, QEvent *evt)
|
||||
}
|
||||
return QWidget::eventFilter(obj, evt);
|
||||
}
|
||||
/**
|
||||
@}
|
||||
@}
|
||||
*/
|
||||
|
||||
WidgetBinding::WidgetBinding(QWidget *widget, UAVObject *object, UAVObjectField *field, int index, double scale, bool isLimited) :
|
||||
ShadowWidgetBinding(widget, scale, isLimited), m_isEnabled(true)
|
||||
{
|
||||
m_object = object;
|
||||
m_field = field;
|
||||
m_index = index;
|
||||
}
|
||||
|
||||
WidgetBinding::~WidgetBinding()
|
||||
{}
|
||||
|
||||
QString WidgetBinding::units() const
|
||||
{
|
||||
if (m_field) {
|
||||
return m_field->getUnits();
|
||||
}
|
||||
return QString("");
|
||||
}
|
||||
|
||||
UAVObject *WidgetBinding::object() const
|
||||
{
|
||||
return m_object;
|
||||
}
|
||||
|
||||
UAVObjectField *WidgetBinding::field() const
|
||||
{
|
||||
return m_field;
|
||||
}
|
||||
|
||||
int WidgetBinding::index() const
|
||||
{
|
||||
return m_index;
|
||||
}
|
||||
|
||||
QList<ShadowWidgetBinding *> WidgetBinding::shadows() const
|
||||
{
|
||||
return m_shadows;
|
||||
}
|
||||
|
||||
void WidgetBinding::addShadow(QWidget *widget, double scale, bool isLimited)
|
||||
{
|
||||
ShadowWidgetBinding *shadow = NULL;
|
||||
|
||||
// Prefer anything else to QLabel and prefer QDoubleSpinBox to anything else
|
||||
if ((qobject_cast<QLabel *>(m_widget) && !qobject_cast<QLabel *>(widget)) ||
|
||||
(!qobject_cast<QDoubleSpinBox *>(m_widget) && qobject_cast<QDoubleSpinBox *>(widget))) {
|
||||
shadow = new ShadowWidgetBinding(m_widget, m_scale, m_isLimited);
|
||||
m_isLimited = isLimited;
|
||||
m_scale = scale;
|
||||
m_widget = widget;
|
||||
} else {
|
||||
shadow = new ShadowWidgetBinding(widget, scale, isLimited);
|
||||
}
|
||||
m_shadows.append(shadow);
|
||||
}
|
||||
|
||||
bool WidgetBinding::matches(QString objectName, QString fieldName, int index, quint32 instanceId)
|
||||
{
|
||||
if (m_object && m_field) {
|
||||
return m_object->getName() == objectName && m_object->getInstID() == instanceId &&
|
||||
m_field->getName() == fieldName && m_index == index;
|
||||
} else {
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
bool WidgetBinding::isEnabled() const
|
||||
{
|
||||
return m_isEnabled;
|
||||
}
|
||||
|
||||
void WidgetBinding::setIsEnabled(bool isEnabled)
|
||||
{
|
||||
m_isEnabled = isEnabled;
|
||||
}
|
||||
|
||||
QVariant WidgetBinding::value() const
|
||||
{
|
||||
return m_value;
|
||||
}
|
||||
|
||||
void WidgetBinding::setValue(const QVariant &value)
|
||||
{
|
||||
m_value = value;
|
||||
/*
|
||||
if (m_object && m_field) {
|
||||
qDebug() << "WidgetBinding" << m_object->getName() << ":" << m_field->getName() << "value =" << value.toString();
|
||||
}
|
||||
*/
|
||||
}
|
||||
|
||||
void WidgetBinding::updateObjectFieldFromValue()
|
||||
{
|
||||
if (m_value.isValid()) {
|
||||
m_field->setValue(m_value, m_index);
|
||||
}
|
||||
}
|
||||
|
||||
ShadowWidgetBinding::ShadowWidgetBinding(QWidget *widget, double scale, bool isLimited)
|
||||
{
|
||||
m_widget = widget;
|
||||
m_scale = scale;
|
||||
m_isLimited = isLimited;
|
||||
}
|
||||
|
||||
ShadowWidgetBinding::~ShadowWidgetBinding()
|
||||
{}
|
||||
|
||||
QWidget *ShadowWidgetBinding::widget() const
|
||||
{
|
||||
return m_widget;
|
||||
}
|
||||
|
||||
double ShadowWidgetBinding::scale() const
|
||||
{
|
||||
return m_scale;
|
||||
}
|
||||
|
||||
bool ShadowWidgetBinding::isLimited() const
|
||||
{
|
||||
return m_isLimited;
|
||||
}
|
||||
|
@ -27,7 +27,6 @@
|
||||
#ifndef CONFIGTASKWIDGET_H
|
||||
#define CONFIGTASKWIDGET_H
|
||||
|
||||
|
||||
#include "extensionsystem/pluginmanager.h"
|
||||
#include "uavobjectmanager.h"
|
||||
#include "uavobject.h"
|
||||
@ -48,53 +47,57 @@
|
||||
#include <QUrl>
|
||||
#include <QEvent>
|
||||
|
||||
class ShadowWidgetBinding : public QObject {
|
||||
Q_OBJECT
|
||||
public:
|
||||
ShadowWidgetBinding(QWidget *widget, double scale, bool isLimited);
|
||||
~ShadowWidgetBinding();
|
||||
QWidget *widget() const;
|
||||
double scale() const;
|
||||
bool isLimited() const;
|
||||
|
||||
protected:
|
||||
QWidget *m_widget;
|
||||
double m_scale;
|
||||
bool m_isLimited;
|
||||
};
|
||||
|
||||
class WidgetBinding : public ShadowWidgetBinding {
|
||||
Q_OBJECT
|
||||
public:
|
||||
WidgetBinding(QWidget *widget, UAVObject *object, UAVObjectField *field, int index, double scale, bool isLimited);
|
||||
~WidgetBinding();
|
||||
|
||||
QString units() const;
|
||||
UAVObject *object() const;
|
||||
UAVObjectField *field() const;
|
||||
int index() const;
|
||||
QList<ShadowWidgetBinding *> shadows() const;
|
||||
|
||||
void addShadow(QWidget *widget, double scale, bool isLimited);
|
||||
bool matches(QString objectName, QString fieldName, int index, quint32 instanceId);
|
||||
|
||||
bool isEnabled() const;
|
||||
void setIsEnabled(bool isEnabled);
|
||||
|
||||
QVariant value() const;
|
||||
void setValue(const QVariant &value);
|
||||
|
||||
void updateObjectFieldFromValue();
|
||||
|
||||
private:
|
||||
UAVObject *m_object;
|
||||
UAVObjectField *m_field;
|
||||
int m_index;
|
||||
bool m_isEnabled;
|
||||
QList<ShadowWidgetBinding *> m_shadows;
|
||||
QVariant m_value;
|
||||
};
|
||||
|
||||
class UAVOBJECTWIDGETUTILS_EXPORT ConfigTaskWidget : public QWidget {
|
||||
Q_OBJECT
|
||||
|
||||
public:
|
||||
struct shadow {
|
||||
QWidget *widget;
|
||||
double scale;
|
||||
bool isLimited;
|
||||
};
|
||||
struct objectToWidget {
|
||||
UAVObject *object;
|
||||
UAVObjectField *field;
|
||||
QWidget *widget;
|
||||
int index;
|
||||
double scale;
|
||||
bool isLimited;
|
||||
QList<shadow *> shadowsList;
|
||||
QString getUnits() const
|
||||
{
|
||||
if (field) {
|
||||
return field->getUnits();
|
||||
}
|
||||
return QString("");
|
||||
}
|
||||
};
|
||||
|
||||
struct temphelper {
|
||||
quint32 objid;
|
||||
quint32 objinstid;
|
||||
bool operator==(const temphelper & lhs)
|
||||
{
|
||||
return lhs.objid == this->objid && lhs.objinstid == this->objinstid;
|
||||
}
|
||||
};
|
||||
|
||||
enum buttonTypeEnum { none, save_button, apply_button, reload_button, default_button, help_button };
|
||||
struct uiRelationAutomation {
|
||||
QString objname;
|
||||
QString fieldname;
|
||||
QString element;
|
||||
QString url;
|
||||
buttonTypeEnum buttonType;
|
||||
QList<int> buttonGroup;
|
||||
double scale;
|
||||
bool haslimits;
|
||||
};
|
||||
|
||||
ConfigTaskWidget(QWidget *parent = 0);
|
||||
virtual ~ConfigTaskWidget();
|
||||
|
||||
@ -111,25 +114,27 @@ public:
|
||||
|
||||
void addWidget(QWidget *widget);
|
||||
|
||||
void addUAVObjectToWidgetRelation(QString object, QString field, QWidget *widget, int index = 0, double scale = 1, bool isLimited = false, QList<int> *defaultReloadGroups = 0, quint32 instID = 0);
|
||||
void addUAVObjectToWidgetRelation(UAVObject *obj, UAVObjectField *field, QWidget *widget, int index = 0, double scale = 1, bool isLimited = false, QList<int> *defaultReloadGroups = 0, quint32 instID = 0);
|
||||
void addWidgetBinding(QString objectName, QString fieldName, QWidget *widget, int index = 0, double scale = 1,
|
||||
bool isLimited = false, QList<int> *reloadGroupIDs = 0, quint32 instID = 0);
|
||||
void addWidgetBinding(UAVObject *object, UAVObjectField *field, QWidget *widget, int index = 0, double scale = 1,
|
||||
bool isLimited = false, QList<int> *reloadGroupIDs = 0, quint32 instID = 0);
|
||||
|
||||
void addUAVObjectToWidgetRelation(QString object, QString field, QWidget *widget, QString element, double scale, bool isLimited = false, QList<int> *defaultReloadGroups = 0, quint32 instID = 0);
|
||||
void addUAVObjectToWidgetRelation(UAVObject *obj, UAVObjectField *field, QWidget *widget, QString element, double scale, bool isLimited = false, QList<int> *defaultReloadGroups = 0, quint32 instID = 0);
|
||||
void addWidgetBinding(QString objectName, QString fieldName, QWidget *widget, QString elementName, double scale,
|
||||
bool isLimited = false, QList<int> *reloadGroupIDs = 0, quint32 instID = 0);
|
||||
void addWidgetBinding(UAVObject *object, UAVObjectField *field, QWidget *widget, QString elementName, double scale,
|
||||
bool isLimited = false, QList<int> *reloadGroupIDs = 0, quint32 instID = 0);
|
||||
|
||||
void addUAVObjectToWidgetRelation(QString object, QString field, QWidget *widget, QString index);
|
||||
void addUAVObjectToWidgetRelation(UAVObject *obj, UAVObjectField *field, QWidget *widget, QString index);
|
||||
void addWidgetBinding(QString objectName, QString fieldName, QWidget *widget, QString elementName);
|
||||
void addWidgetBinding(UAVObject *object, UAVObjectField *field, QWidget *widget, QString elementName);
|
||||
|
||||
// BUTTONS//
|
||||
void addApplySaveButtons(QPushButton *update, QPushButton *save);
|
||||
void addReloadButton(QPushButton *button, int buttonGroup);
|
||||
void addDefaultButton(QPushButton *button, int buttonGroup);
|
||||
//////////
|
||||
|
||||
void addWidgetToDefaultReloadGroups(QWidget *widget, QList<int> *groups);
|
||||
void addWidgetToReloadGroups(QWidget *widget, QList<int> *reloadGroupIDs);
|
||||
|
||||
bool addShadowWidget(QWidget *masterWidget, QWidget *shadowWidget, double shadowScale = 1, bool shadowIsLimited = false);
|
||||
bool addShadowWidget(QString object, QString field, QWidget *widget, int index = 0, double scale = 1, bool isLimited = false, QList<int> *defaultReloadGroups = NULL, quint32 instID = 0);
|
||||
bool addShadowWidgetBinding(QString objectName, QString fieldName, QWidget *widget, int index = 0, double scale = 1,
|
||||
bool isLimited = false, QList<int> *m_reloadGroups = NULL, quint32 instID = 0);
|
||||
|
||||
void autoLoadWidgets();
|
||||
|
||||
@ -139,18 +144,21 @@ public:
|
||||
bool allObjectsUpdated();
|
||||
void setOutOfLimitsStyle(QString style)
|
||||
{
|
||||
outOfLimitsStyle = style;
|
||||
m_outOfLimitsStyle = style;
|
||||
}
|
||||
void addHelpButton(QPushButton *button, QString url);
|
||||
void forceShadowUpdates();
|
||||
void forceConnectedState();
|
||||
virtual bool shouldObjectBeSaved(UAVObject *object);
|
||||
|
||||
public slots:
|
||||
void onAutopilotDisconnect();
|
||||
void onAutopilotConnect();
|
||||
void invalidateObjects();
|
||||
void apply();
|
||||
void save();
|
||||
void setWidgetBindingObjectEnabled(QString objectName, bool enabled);
|
||||
|
||||
signals:
|
||||
// fired when a widgets contents changes
|
||||
void widgetContentsChanged(QWidget *widget);
|
||||
@ -165,40 +173,72 @@ signals:
|
||||
// fired when the autopilot disconnects
|
||||
void autoPilotDisconnected();
|
||||
void defaultRequested(int group);
|
||||
|
||||
private slots:
|
||||
void objectUpdated(UAVObject *);
|
||||
void objectUpdated(UAVObject *object);
|
||||
void defaultButtonClicked();
|
||||
void reloadButtonClicked();
|
||||
|
||||
private:
|
||||
int currentBoard;
|
||||
bool isConnected;
|
||||
bool allowWidgetUpdates;
|
||||
QStringList objectsList;
|
||||
QList <objectToWidget *> objOfInterest;
|
||||
ExtensionSystem::PluginManager *pm;
|
||||
UAVObjectManager *objManager;
|
||||
UAVObjectUtilManager *utilMngr;
|
||||
smartSaveButton *smartsave;
|
||||
QMap<UAVObject *, bool> objectUpdates;
|
||||
QMap<int, QList<objectToWidget *> *> defaultReloadGroups;
|
||||
QMap<QWidget *, objectToWidget *> shadowsList;
|
||||
QMap<QPushButton *, QString> helpButtonList;
|
||||
QList<QPushButton *> reloadButtonList;
|
||||
bool dirty;
|
||||
bool setFieldFromWidget(QWidget *widget, UAVObjectField *field, int index, double scale);
|
||||
struct objectComparator {
|
||||
quint32 objid;
|
||||
quint32 objinstid;
|
||||
bool operator==(const objectComparator & lhs)
|
||||
{
|
||||
return lhs.objid == this->objid && lhs.objinstid == this->objinstid;
|
||||
}
|
||||
};
|
||||
|
||||
enum buttonTypeEnum { none, save_button, apply_button, reload_button, default_button, help_button };
|
||||
struct bindingStruct {
|
||||
QString objname;
|
||||
QString fieldname;
|
||||
QString element;
|
||||
QString url;
|
||||
buttonTypeEnum buttonType;
|
||||
QList<int> buttonGroup;
|
||||
double scale;
|
||||
bool haslimits;
|
||||
};
|
||||
|
||||
int m_currentBoardId;
|
||||
bool m_isConnected;
|
||||
bool m_isWidgetUpdatesAllowed;
|
||||
QStringList m_objects;
|
||||
|
||||
QMultiHash<int, WidgetBinding *> m_reloadGroups;
|
||||
QMultiHash<QWidget *, WidgetBinding *> m_widgetBindingsPerWidget;
|
||||
QMultiHash<UAVObject *, WidgetBinding *> m_widgetBindingsPerObject;
|
||||
|
||||
ExtensionSystem::PluginManager *m_pluginManager;
|
||||
UAVObjectUtilManager *m_objectUtilManager;
|
||||
SmartSaveButton *m_saveButton;
|
||||
QHash<UAVObject *, bool> m_updatedObjects;
|
||||
QHash<QPushButton *, QString> m_helpButtons;
|
||||
QList<QPushButton *> m_reloadButtons;
|
||||
bool m_isDirty;
|
||||
QString m_outOfLimitsStyle;
|
||||
QTimer *m_realtimeUpdateTimer;
|
||||
|
||||
bool setWidgetFromField(QWidget *widget, UAVObjectField *field, int index, double scale, bool hasLimits);
|
||||
QVariant getVariantFromWidget(QWidget *widget, double scale, QString units);
|
||||
|
||||
QVariant getVariantFromWidget(QWidget *widget, double scale, const QString units);
|
||||
bool setWidgetFromVariant(QWidget *widget, QVariant value, double scale, QString units);
|
||||
bool setWidgetFromVariant(QWidget *widget, QVariant value, double scale);
|
||||
|
||||
void connectWidgetUpdatesToSlot(QWidget *widget, const char *function);
|
||||
void disconnectWidgetUpdatesToSlot(QWidget *widget, const char *function);
|
||||
|
||||
void loadWidgetLimits(QWidget *widget, UAVObjectField *field, int index, bool hasLimits, double sclale);
|
||||
QString outOfLimitsStyle;
|
||||
QTimer *timeOut;
|
||||
|
||||
int fieldIndexFromElementName(QString objectName, QString fieldName, QString elementName);
|
||||
|
||||
void doAddWidgetBinding(QString objectName, QString fieldName, QWidget *widget, int index = 0, double scale = 1,
|
||||
bool isLimited = false, QList<int> *reloadGroupIDs = 0, quint32 instID = 0);
|
||||
|
||||
protected slots:
|
||||
virtual void disableObjUpdates();
|
||||
virtual void enableObjUpdates();
|
||||
virtual void disableObjectUpdates();
|
||||
virtual void enableObjectUpdates();
|
||||
virtual void clearDirty();
|
||||
virtual void widgetsContentsChanged();
|
||||
virtual void populateWidgets();
|
||||
@ -208,7 +248,8 @@ protected slots:
|
||||
|
||||
protected:
|
||||
virtual void enableControls(bool enable);
|
||||
|
||||
virtual QString mapObjectName(const QString objectName);
|
||||
virtual UAVObject *getObject(const QString name, quint32 instId = 0);
|
||||
void checkWidgetsLimits(QWidget *widget, UAVObjectField *field, int index, bool hasLimits, QVariant value, double scale);
|
||||
void updateEnableControls();
|
||||
};
|
||||
|
@ -27,27 +27,27 @@
|
||||
#include "smartsavebutton.h"
|
||||
#include "configtaskwidget.h"
|
||||
|
||||
smartSaveButton::smartSaveButton(ConfigTaskWidget *configTaskWidget) : configWidget(configTaskWidget)
|
||||
SmartSaveButton::SmartSaveButton(ConfigTaskWidget *configTaskWidget) : configWidget(configTaskWidget)
|
||||
{}
|
||||
|
||||
void smartSaveButton::addButtons(QPushButton *save, QPushButton *apply)
|
||||
void SmartSaveButton::addButtons(QPushButton *save, QPushButton *apply)
|
||||
{
|
||||
buttonList.insert(save, save_button);
|
||||
buttonList.insert(apply, apply_button);
|
||||
connect(save, SIGNAL(clicked()), this, SLOT(processClick()));
|
||||
connect(apply, SIGNAL(clicked()), this, SLOT(processClick()));
|
||||
}
|
||||
void smartSaveButton::addApplyButton(QPushButton *apply)
|
||||
void SmartSaveButton::addApplyButton(QPushButton *apply)
|
||||
{
|
||||
buttonList.insert(apply, apply_button);
|
||||
connect(apply, SIGNAL(clicked()), this, SLOT(processClick()));
|
||||
}
|
||||
void smartSaveButton::addSaveButton(QPushButton *save)
|
||||
void SmartSaveButton::addSaveButton(QPushButton *save)
|
||||
{
|
||||
buttonList.insert(save, save_button);
|
||||
connect(save, SIGNAL(clicked()), this, SLOT(processClick()));
|
||||
}
|
||||
void smartSaveButton::processClick()
|
||||
void SmartSaveButton::processClick()
|
||||
{
|
||||
emit beginOp();
|
||||
bool save = false;
|
||||
@ -62,7 +62,7 @@ void smartSaveButton::processClick()
|
||||
processOperation(button, save);
|
||||
}
|
||||
|
||||
void smartSaveButton::processOperation(QPushButton *button, bool save)
|
||||
void SmartSaveButton::processOperation(QPushButton *button, bool save)
|
||||
{
|
||||
emit preProcessOperations();
|
||||
|
||||
@ -157,33 +157,33 @@ void smartSaveButton::processOperation(QPushButton *button, bool save)
|
||||
emit endOp();
|
||||
}
|
||||
|
||||
void smartSaveButton::setObjects(QList<UAVDataObject *> list)
|
||||
void SmartSaveButton::setObjects(QList<UAVDataObject *> list)
|
||||
{
|
||||
objects = list;
|
||||
}
|
||||
|
||||
void smartSaveButton::addObject(UAVDataObject *obj)
|
||||
void SmartSaveButton::addObject(UAVDataObject *obj)
|
||||
{
|
||||
Q_ASSERT(obj);
|
||||
if (!objects.contains(obj)) {
|
||||
objects.append(obj);
|
||||
}
|
||||
}
|
||||
void smartSaveButton::removeObject(UAVDataObject *obj)
|
||||
void SmartSaveButton::removeObject(UAVDataObject *obj)
|
||||
{
|
||||
if (objects.contains(obj)) {
|
||||
objects.removeAll(obj);
|
||||
}
|
||||
}
|
||||
void smartSaveButton::removeAllObjects()
|
||||
void SmartSaveButton::removeAllObjects()
|
||||
{
|
||||
objects.clear();
|
||||
}
|
||||
void smartSaveButton::clearObjects()
|
||||
void SmartSaveButton::clearObjects()
|
||||
{
|
||||
objects.clear();
|
||||
}
|
||||
void smartSaveButton::transaction_finished(UAVObject *obj, bool result)
|
||||
void SmartSaveButton::transaction_finished(UAVObject *obj, bool result)
|
||||
{
|
||||
if (current_object == obj) {
|
||||
up_result = result;
|
||||
@ -191,32 +191,32 @@ void smartSaveButton::transaction_finished(UAVObject *obj, bool result)
|
||||
}
|
||||
}
|
||||
|
||||
void smartSaveButton::saving_finished(int id, bool result)
|
||||
void SmartSaveButton::saving_finished(int id, bool result)
|
||||
{
|
||||
if (id == current_objectID) {
|
||||
if (id == (int)current_objectID) {
|
||||
sv_result = result;
|
||||
loop.quit();
|
||||
}
|
||||
}
|
||||
|
||||
void smartSaveButton::enableControls(bool value)
|
||||
void SmartSaveButton::enableControls(bool value)
|
||||
{
|
||||
foreach(QPushButton * button, buttonList.keys())
|
||||
button->setEnabled(value);
|
||||
}
|
||||
|
||||
void smartSaveButton::resetIcons()
|
||||
void SmartSaveButton::resetIcons()
|
||||
{
|
||||
foreach(QPushButton * button, buttonList.keys())
|
||||
button->setIcon(QIcon());
|
||||
}
|
||||
|
||||
void smartSaveButton::apply()
|
||||
void SmartSaveButton::apply()
|
||||
{
|
||||
processOperation(NULL, false);
|
||||
}
|
||||
|
||||
void smartSaveButton::save()
|
||||
void SmartSaveButton::save()
|
||||
{
|
||||
processOperation(NULL, true);
|
||||
}
|
||||
|
@ -40,13 +40,13 @@
|
||||
|
||||
class ConfigTaskWidget;
|
||||
|
||||
class smartSaveButton : public QObject {
|
||||
class SmartSaveButton : public QObject {
|
||||
enum buttonTypeEnum { save_button, apply_button };
|
||||
public:
|
||||
Q_OBJECT
|
||||
|
||||
public:
|
||||
smartSaveButton(ConfigTaskWidget *configTaskWidget);
|
||||
SmartSaveButton(ConfigTaskWidget *configTaskWidget);
|
||||
void addButtons(QPushButton *save, QPushButton *apply);
|
||||
void setObjects(QList<UAVDataObject *>);
|
||||
void addObject(UAVDataObject *);
|
||||
|
23
shared/uavobjectdefinition/stabilizationbank.xml
Normal file
23
shared/uavobjectdefinition/stabilizationbank.xml
Normal file
@ -0,0 +1,23 @@
|
||||
<xml>
|
||||
<object name="StabilizationBank" singleinstance="true" settings="false" category="Control">
|
||||
<description>Currently selected PID bank</description>
|
||||
|
||||
<field name="RollMax" units="degrees" type="uint8" elements="1" defaultvalue="42" limits="%BE:0:180"/>
|
||||
<field name="PitchMax" units="degrees" type="uint8" elements="1" defaultvalue="42" limits="%BE:0:180"/>
|
||||
<field name="YawMax" units="degrees" type="uint8" elements="1" defaultvalue="42" limits="%BE:0:180"/>
|
||||
<field name="ManualRate" units="degrees/sec" type="float" elementnames="Roll,Pitch,Yaw" defaultvalue="150,150,175" limits="%BE:0:500; %BE:0:500; %BE:0:500"/>
|
||||
<field name="MaximumRate" units="degrees/sec" type="float" elementnames="Roll,Pitch,Yaw" defaultvalue="300,300,50" limits="%BE:0:500; %BE:0:500; %BE:0:500"/>
|
||||
|
||||
<field name="RollRatePID" units="" type="float" elementnames="Kp,Ki,Kd,ILimit" defaultvalue="0.003,0.003,0.00002,0.3" limits="%BE:0:0.01; %BE:0:0.01; ; "/>
|
||||
<field name="PitchRatePID" units="" type="float" elementnames="Kp,Ki,Kd,ILimit" defaultvalue="0.003,0.003,0.00002,0.3" limits="%BE:0:0.01; %BE:0:0.01; ; "/>
|
||||
<field name="YawRatePID" units="" type="float" elementnames="Kp,Ki,Kd,ILimit" defaultvalue="0.0035,0.0035,0,0.3" limits="%BE:0:0.01; %BE:0:0.01 ; ; "/>
|
||||
<field name="RollPI" units="" type="float" elementnames="Kp,Ki,ILimit" defaultvalue="2.5,0,50" limits="%BE:0:10; %BE:0:10; "/>
|
||||
<field name="PitchPI" units="" type="float" elementnames="Kp,Ki,ILimit" defaultvalue="2.5,0,50" limits="%BE:0:10; %BE:0:10; "/>
|
||||
<field name="YawPI" units="" type="float" elementnames="Kp,Ki,ILimit"/>
|
||||
<access gcs="readwrite" flight="readwrite"/>
|
||||
<telemetrygcs acked="false" updatemode="manual" period="0"/>
|
||||
<telemetryflight acked="false" updatemode="periodic" period="1000"/>
|
||||
<logging updatemode="manual" period="0"/>
|
||||
</object>
|
||||
|
||||
</xml>
|
@ -1,18 +1,13 @@
|
||||
<xml>
|
||||
|
||||
<object name="StabilizationSettings" singleinstance="true" settings="true" category="Control">
|
||||
<description>PID settings used by the Stabilization module to combine the @ref AttitudeActual and @ref AttitudeDesired to compute @ref ActuatorDesired</description>
|
||||
<field name="RollMax" units="degrees" type="uint8" elements="1" defaultvalue="42" limits="%BE:0:180"/>
|
||||
<field name="PitchMax" units="degrees" type="uint8" elements="1" defaultvalue="42" limits="%BE:0:180"/>
|
||||
<field name="YawMax" units="degrees" type="uint8" elements="1" defaultvalue="42" limits="%BE:0:180"/>
|
||||
<field name="ManualRate" units="degrees/sec" type="float" elementnames="Roll,Pitch,Yaw" defaultvalue="150,150,175" limits="%BE:0:500; %BE:0:500; %BE:0:500"/>
|
||||
<field name="MaximumRate" units="degrees/sec" type="float" elementnames="Roll,Pitch,Yaw" defaultvalue="300,300,50" limits="%BE:0:500; %BE:0:500; %BE:0:500"/>
|
||||
|
||||
<field name="RollRatePID" units="" type="float" elementnames="Kp,Ki,Kd,ILimit" defaultvalue="0.003,0.003,0.00002,0.3" limits="%BE:0:0.01; %BE:0:0.01; ; "/>
|
||||
<field name="PitchRatePID" units="" type="float" elementnames="Kp,Ki,Kd,ILimit" defaultvalue="0.003,0.003,0.00002,0.3" limits="%BE:0:0.01; %BE:0:0.01; ; "/>
|
||||
<field name="YawRatePID" units="" type="float" elementnames="Kp,Ki,Kd,ILimit" defaultvalue="0.0035,0.0035,0,0.3" limits="%BE:0:0.01; %BE:0:0.01 ; ; "/>
|
||||
<field name="RollPI" units="" type="float" elementnames="Kp,Ki,ILimit" defaultvalue="2.5,0,50" limits="%BE:0:10; %BE:0:10; "/>
|
||||
<field name="PitchPI" units="" type="float" elementnames="Kp,Ki,ILimit" defaultvalue="2.5,0,50" limits="%BE:0:10; %BE:0:10; "/>
|
||||
<field name="YawPI" units="" type="float" elementnames="Kp,Ki,ILimit" defaultvalue="2,0,50" limits="%BE:0:10; %BE:0:10; "/>
|
||||
<!-- Note: The number of elements here must match the number of available flight modes -->
|
||||
<field name="FlightModeMap" units="" type="enum"
|
||||
options="Bank1,Bank2,Bank3"
|
||||
elementnames="Manual,Stabilized1,Stabilized2,Stabilized3,Autotune,AltitudeHold,AltitudeVario,VelocityControl,PositionHold,ReturnToBase,Land,PathPlanner,POI"
|
||||
defaultvalue="Bank1,Bank1,Bank1,Bank1,Bank1,Bank1,Bank1,Bank1,Bank1,Bank1,Bank1,Bank1,Bank1"/>
|
||||
|
||||
<field name="VbarSensitivity" units="frac" type="float" elementnames="Roll,Pitch,Yaw" defaultvalue="0.5,0.5,0.5"/>
|
||||
<field name="VbarRollPI" units="1/(deg/s)" type="float" elementnames="Kp,Ki" defaultvalue="0.005,0.002"/>
|
||||
|
23
shared/uavobjectdefinition/stabilizationsettingsbank1.xml
Normal file
23
shared/uavobjectdefinition/stabilizationsettingsbank1.xml
Normal file
@ -0,0 +1,23 @@
|
||||
<xml>
|
||||
<object name="StabilizationSettingsBank1" singleinstance="true" settings="true" category="Control">
|
||||
<description>Currently selected PID bank</description>
|
||||
|
||||
<field name="RollMax" units="degrees" type="uint8" elements="1" defaultvalue="42" limits="%BE:0:180"/>
|
||||
<field name="PitchMax" units="degrees" type="uint8" elements="1" defaultvalue="42" limits="%BE:0:180"/>
|
||||
<field name="YawMax" units="degrees" type="uint8" elements="1" defaultvalue="42" limits="%BE:0:180"/>
|
||||
<field name="ManualRate" units="degrees/sec" type="float" elementnames="Roll,Pitch,Yaw" defaultvalue="150,150,175" limits="%BE:0:500; %BE:0:500; %BE:0:500"/>
|
||||
<field name="MaximumRate" units="degrees/sec" type="float" elementnames="Roll,Pitch,Yaw" defaultvalue="300,300,50" limits="%BE:0:500; %BE:0:500; %BE:0:500"/>
|
||||
|
||||
<field name="RollRatePID" units="" type="float" elementnames="Kp,Ki,Kd,ILimit" defaultvalue="0.003,0.003,0.00002,0.3" limits="%BE:0:0.01; %BE:0:0.01; ; "/>
|
||||
<field name="PitchRatePID" units="" type="float" elementnames="Kp,Ki,Kd,ILimit" defaultvalue="0.003,0.003,0.00002,0.3" limits="%BE:0:0.01; %BE:0:0.01; ; "/>
|
||||
<field name="YawRatePID" units="" type="float" elementnames="Kp,Ki,Kd,ILimit" defaultvalue="0.0035,0.0035,0,0.3" limits="%BE:0:0.01; %BE:0:0.01 ; ; "/>
|
||||
<field name="RollPI" units="" type="float" elementnames="Kp,Ki,ILimit" defaultvalue="2.5,0,50" limits="%BE:0:10; %BE:0:10; "/>
|
||||
<field name="PitchPI" units="" type="float" elementnames="Kp,Ki,ILimit" defaultvalue="2.5,0,50" limits="%BE:0:10; %BE:0:10; "/>
|
||||
<field name="YawPI" units="" type="float" elementnames="Kp,Ki,ILimit" defaultvalue="2.5,0,50" limits="%BE:0:10; %BE:0:10; "/>
|
||||
<access gcs="readwrite" flight="readwrite"/>
|
||||
<telemetrygcs acked="true" updatemode="onchange" period="0"/>
|
||||
<telemetryflight acked="true" updatemode="onchange" period="0"/>
|
||||
<logging updatemode="manual" period="0"/>
|
||||
</object>
|
||||
|
||||
</xml>
|
23
shared/uavobjectdefinition/stabilizationsettingsbank2.xml
Normal file
23
shared/uavobjectdefinition/stabilizationsettingsbank2.xml
Normal file
@ -0,0 +1,23 @@
|
||||
<xml>
|
||||
<object name="StabilizationSettingsBank2" singleinstance="true" settings="true" category="Control">
|
||||
<description>Currently selected PID bank</description>
|
||||
|
||||
<field name="RollMax" units="degrees" type="uint8" elements="1" defaultvalue="42" limits="%BE:0:180"/>
|
||||
<field name="PitchMax" units="degrees" type="uint8" elements="1" defaultvalue="42" limits="%BE:0:180"/>
|
||||
<field name="YawMax" units="degrees" type="uint8" elements="1" defaultvalue="42" limits="%BE:0:180"/>
|
||||
<field name="ManualRate" units="degrees/sec" type="float" elementnames="Roll,Pitch,Yaw" defaultvalue="150,150,175" limits="%BE:0:500; %BE:0:500; %BE:0:500"/>
|
||||
<field name="MaximumRate" units="degrees/sec" type="float" elementnames="Roll,Pitch,Yaw" defaultvalue="300,300,50" limits="%BE:0:500; %BE:0:500; %BE:0:500"/>
|
||||
|
||||
<field name="RollRatePID" units="" type="float" elementnames="Kp,Ki,Kd,ILimit" defaultvalue="0.003,0.003,0.00002,0.3" limits="%BE:0:0.01; %BE:0:0.01; ; "/>
|
||||
<field name="PitchRatePID" units="" type="float" elementnames="Kp,Ki,Kd,ILimit" defaultvalue="0.003,0.003,0.00002,0.3" limits="%BE:0:0.01; %BE:0:0.01; ; "/>
|
||||
<field name="YawRatePID" units="" type="float" elementnames="Kp,Ki,Kd,ILimit" defaultvalue="0.0035,0.0035,0,0.3" limits="%BE:0:0.01; %BE:0:0.01 ; ; "/>
|
||||
<field name="RollPI" units="" type="float" elementnames="Kp,Ki,ILimit" defaultvalue="2.5,0,50" limits="%BE:0:10; %BE:0:10; "/>
|
||||
<field name="PitchPI" units="" type="float" elementnames="Kp,Ki,ILimit" defaultvalue="2.5,0,50" limits="%BE:0:10; %BE:0:10; "/>
|
||||
<field name="YawPI" units="" type="float" elementnames="Kp,Ki,ILimit" defaultvalue="2.5,0,50" limits="%BE:0:10; %BE:0:10; "/>
|
||||
<access gcs="readwrite" flight="readwrite"/>
|
||||
<telemetrygcs acked="true" updatemode="onchange" period="0"/>
|
||||
<telemetryflight acked="true" updatemode="onchange" period="0"/>
|
||||
<logging updatemode="manual" period="0"/>
|
||||
</object>
|
||||
|
||||
</xml>
|
23
shared/uavobjectdefinition/stabilizationsettingsbank3.xml
Normal file
23
shared/uavobjectdefinition/stabilizationsettingsbank3.xml
Normal file
@ -0,0 +1,23 @@
|
||||
<xml>
|
||||
<object name="StabilizationSettingsBank3" singleinstance="true" settings="true" category="Control">
|
||||
<description>Currently selected PID bank</description>
|
||||
|
||||
<field name="RollMax" units="degrees" type="uint8" elements="1" defaultvalue="42" limits="%BE:0:180"/>
|
||||
<field name="PitchMax" units="degrees" type="uint8" elements="1" defaultvalue="42" limits="%BE:0:180"/>
|
||||
<field name="YawMax" units="degrees" type="uint8" elements="1" defaultvalue="42" limits="%BE:0:180"/>
|
||||
<field name="ManualRate" units="degrees/sec" type="float" elementnames="Roll,Pitch,Yaw" defaultvalue="150,150,175" limits="%BE:0:500; %BE:0:500; %BE:0:500"/>
|
||||
<field name="MaximumRate" units="degrees/sec" type="float" elementnames="Roll,Pitch,Yaw" defaultvalue="300,300,50" limits="%BE:0:500; %BE:0:500; %BE:0:500"/>
|
||||
|
||||
<field name="RollRatePID" units="" type="float" elementnames="Kp,Ki,Kd,ILimit" defaultvalue="0.003,0.003,0.00002,0.3" limits="%BE:0:0.01; %BE:0:0.01; ; "/>
|
||||
<field name="PitchRatePID" units="" type="float" elementnames="Kp,Ki,Kd,ILimit" defaultvalue="0.003,0.003,0.00002,0.3" limits="%BE:0:0.01; %BE:0:0.01; ; "/>
|
||||
<field name="YawRatePID" units="" type="float" elementnames="Kp,Ki,Kd,ILimit" defaultvalue="0.0035,0.0035,0,0.3" limits="%BE:0:0.01; %BE:0:0.01 ; ; "/>
|
||||
<field name="RollPI" units="" type="float" elementnames="Kp,Ki,ILimit" defaultvalue="2.5,0,50" limits="%BE:0:10; %BE:0:10; "/>
|
||||
<field name="PitchPI" units="" type="float" elementnames="Kp,Ki,ILimit" defaultvalue="2.5,0,50" limits="%BE:0:10; %BE:0:10; "/>
|
||||
<field name="YawPI" units="" type="float" elementnames="Kp,Ki,ILimit" defaultvalue="2.5,0,50" limits="%BE:0:10; %BE:0:10; "/>
|
||||
<access gcs="readwrite" flight="readwrite"/>
|
||||
<telemetrygcs acked="true" updatemode="onchange" period="0"/>
|
||||
<telemetryflight acked="true" updatemode="onchange" period="0"/>
|
||||
<logging updatemode="manual" period="0"/>
|
||||
</object>
|
||||
|
||||
</xml>
|
@ -2,6 +2,7 @@
|
||||
<object name="TxPIDSettings" singleinstance="true" settings="true" category="Control">
|
||||
<description>Settings used by @ref TxPID optional module to tune PID settings using R/C transmitter</description>
|
||||
<field name="UpdateMode" units="option" type="enum" elements="1" options="Never,When Armed,Always" defaultvalue="When Armed"/>
|
||||
<field name="BankNumber" units="" type="enum" options="Bank1,Bank2,Bank3" elements="1" defaultvalue="Bank1"/>
|
||||
<field name="Inputs" units="channel" type="enum"
|
||||
elementnames="Instance1,Instance2,Instance3"
|
||||
options="Throttle,Accessory0,Accessory1,Accessory2,Accessory3,Accessory4,Accessory5"
|
||||
@ -10,7 +11,7 @@
|
||||
<field name="PIDs" units="option" type="enum"
|
||||
elementnames="Instance1,Instance2,Instance3"
|
||||
options="Disabled,
|
||||
Roll Rate.Kp, Pitch Rate.Kp, Roll+Pitch Rate.Kp, Yaw Rate.Kp,
|
||||
Roll Rate.Kp, Pitch Rate.Kp, Roll+Pitch Rate.Kp, Yaw Rate.Kp,
|
||||
Roll Rate.Ki, Pitch Rate.Ki, Roll+Pitch Rate.Ki, Yaw Rate.Ki,
|
||||
Roll Rate.Kd, Pitch Rate.Kd, Roll+Pitch Rate.Kd, Yaw Rate.Kd,
|
||||
Roll Rate.ILimit, Pitch Rate.ILimit, Roll+Pitch Rate.ILimit, Yaw Rate.ILimit,
|
||||
|
Loading…
Reference in New Issue
Block a user