1
0
mirror of https://bitbucket.org/librepilot/librepilot.git synced 2025-01-29 14:52:12 +01:00

Merge branch 'next' into MikeL

Conflicts:
	ground/openpilotgcs/src/plugins/config/airframe.ui
	ground/openpilotgcs/src/plugins/config/configoutputwidget.cpp
	ground/openpilotgcs/src/plugins/config/configoutputwidget.h
	ground/openpilotgcs/src/plugins/config/configvehicletypewidget.cpp
	ground/openpilotgcs/src/plugins/config/configvehicletypewidget.h
This commit is contained in:
James Cotton 2012-06-06 11:58:06 -05:00
commit 5e01617cbd
72 changed files with 7742 additions and 3057 deletions

View File

@ -1,5 +1,19 @@
Short summary of changes. For a complete list see the git log.
2012-06-04
AeroSimRC support merged into next
2012-05-26
VirtualFlybar which allows a more aggressive flight mode than rate mode
support. Also PiroCompensation added.
2012-05-26
Revert some UI changes that didn't work consistently between OSX and Windows.
2012-05-24
Merged the updated firmware for the PipXtreme, thanks to Brian for a lot of
work on this.
2012-05-04
Support for CC3D. This involved changes to various things such as the sensors
being split from AttitudeRaw to Accels,Gyros,Magnetometer. A single firmware

View File

@ -630,7 +630,7 @@ all_$(1)_clean: $$(addsuffix _clean, $$(filter bu_$(1), $$(BU_TARGETS)))
all_$(1)_clean: $$(addsuffix _clean, $$(filter ef_$(1), $$(EF_TARGETS)))
endef
ALL_BOARDS := coptercontrol pipxtreme revolution simposix
ALL_BOARDS := coptercontrol pipxtreme
# Friendly names of each board (used to find source tree)
coptercontrol_friendly := CopterControl

View File

@ -122,6 +122,7 @@ static const struct flashfs_cfg flashfs_w25x_cfg = {
.obj_table_start = 0x00000010,
.obj_table_end = 0x00001000,
.sector_size = 0x00001000,
.chip_size = 0x00080000,
};
static const struct pios_flash_jedec_cfg flash_w25x_cfg = {
@ -135,6 +136,7 @@ static const struct flashfs_cfg flashfs_m25p_cfg = {
.obj_table_start = 0x00000010,
.obj_table_end = 0x00010000,
.sector_size = 0x00010000,
.chip_size = 0x00200000,
};
static const struct pios_flash_jedec_cfg flash_m25p_cfg = {

View File

@ -234,17 +234,21 @@ static void AttitudeTask(void *parameters)
AccelsData accels;
GyrosData gyros;
int32_t retval;
if(cc3d)
int32_t retval = 0;
if (cc3d)
retval = updateSensorsCC3D(&accels, &gyros);
else
retval = updateSensors(&accels, &gyros);
if(retval != 0)
// Only update attitude when sensor data is good
if (retval != 0)
AlarmsSet(SYSTEMALARMS_ALARM_ATTITUDE, SYSTEMALARMS_ALARM_ERROR);
else {
// Only update attitude when sensor data is good
updateAttitude(&accels, &gyros);
// Do not update attitude data in simulation mode
if (!AttitudeActualReadOnly())
updateAttitude(&accels, &gyros);
AlarmsClear(SYSTEMALARMS_ALARM_ATTITUDE);
}
}
@ -267,7 +271,11 @@ static int32_t updateSensors(AccelsData * accels, GyrosData * gyros)
AlarmsSet(SYSTEMALARMS_ALARM_ATTITUDE, SYSTEMALARMS_ALARM_ERROR);
return -1;
}
// Do not read raw sensor data in simulation mode
if (GyrosReadOnly() || AccelsReadOnly())
return 0;
// No accel data available
if(PIOS_ADXL345_FifoElements() == 0)
return -1;

View File

@ -586,6 +586,7 @@ static void updateStabilizationDesired(ManualControlCommandData * cmd, ManualCon
(stab_settings[0] == STABILIZATIONDESIRED_STABILIZATIONMODE_WEAKLEVELING) ? cmd->Roll * stabSettings.ManualRate[STABILIZATIONSETTINGS_MANUALRATE_ROLL] :
(stab_settings[0] == STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE) ? cmd->Roll * stabSettings.RollMax :
(stab_settings[0] == STABILIZATIONDESIRED_STABILIZATIONMODE_AXISLOCK) ? cmd->Roll * stabSettings.ManualRate[STABILIZATIONSETTINGS_MANUALRATE_ROLL] :
(stab_settings[0] == STABILIZATIONDESIRED_STABILIZATIONMODE_VIRTUALBAR) ? cmd->Roll :
0; // this is an invalid mode
;
stabilization.Pitch = (stab_settings[1] == STABILIZATIONDESIRED_STABILIZATIONMODE_NONE) ? cmd->Pitch :
@ -593,6 +594,7 @@ static void updateStabilizationDesired(ManualControlCommandData * cmd, ManualCon
(stab_settings[1] == STABILIZATIONDESIRED_STABILIZATIONMODE_WEAKLEVELING) ? cmd->Pitch * stabSettings.ManualRate[STABILIZATIONSETTINGS_MANUALRATE_PITCH] :
(stab_settings[1] == STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE) ? cmd->Pitch * stabSettings.PitchMax :
(stab_settings[1] == STABILIZATIONDESIRED_STABILIZATIONMODE_AXISLOCK) ? cmd->Pitch * stabSettings.ManualRate[STABILIZATIONSETTINGS_MANUALRATE_PITCH] :
(stab_settings[1] == STABILIZATIONDESIRED_STABILIZATIONMODE_VIRTUALBAR) ? cmd->Pitch :
0; // this is an invalid mode
stabilization.Yaw = (stab_settings[2] == STABILIZATIONDESIRED_STABILIZATIONMODE_NONE) ? cmd->Yaw :
@ -600,6 +602,7 @@ static void updateStabilizationDesired(ManualControlCommandData * cmd, ManualCon
(stab_settings[2] == STABILIZATIONDESIRED_STABILIZATIONMODE_WEAKLEVELING) ? cmd->Yaw * stabSettings.ManualRate[STABILIZATIONSETTINGS_MANUALRATE_YAW] :
(stab_settings[2] == STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE) ? cmd->Yaw * stabSettings.YawMax :
(stab_settings[2] == STABILIZATIONDESIRED_STABILIZATIONMODE_AXISLOCK) ? cmd->Yaw * stabSettings.ManualRate[STABILIZATIONSETTINGS_MANUALRATE_YAW] :
(stab_settings[2] == STABILIZATIONDESIRED_STABILIZATIONMODE_VIRTUALBAR) ? cmd->Yaw :
0; // this is an invalid mode
stabilization.Throttle = (cmd->Throttle < 0) ? -1 : cmd->Throttle;

View File

@ -55,7 +55,7 @@
#define TASK_PRIORITY (tskIDLE_PRIORITY+4)
#define FAILSAFE_TIMEOUT_MS 30
enum {PID_RATE_ROLL, PID_RATE_PITCH, PID_RATE_YAW, PID_ROLL, PID_PITCH, PID_YAW, PID_MAX};
enum {PID_RATE_ROLL, PID_RATE_PITCH, PID_RATE_YAW, PID_ROLL, PID_PITCH, PID_YAW, PID_VBAR_ROLL, PID_VBAR_PITCH, PID_VBAR_YAW, PID_MAX};
enum {ROLL,PITCH,YAW,MAX_AXES};
@ -74,21 +74,24 @@ typedef struct {
static xTaskHandle taskHandle;
static StabilizationSettingsData settings;
static xQueueHandle queue;
float dT = 1;
float gyro_alpha = 0;
float gyro_filtered[3] = {0,0,0};
float axis_lock_accum[3] = {0,0,0};
float vbar_sensitivity[3] = {1, 1, 1};
uint8_t max_axis_lock = 0;
uint8_t max_axislock_rate = 0;
float weak_leveling_kp = 0;
uint8_t weak_leveling_max = 0;
bool lowThrottleZeroIntegral;
float vbar_integral[3] = {0, 0, 0};
float vbar_decay = 0.991f;
pid_type pids[PID_MAX];
int8_t vbar_gyros_suppress;
bool vbar_piro_comp = false;
// Private functions
static void stabilizationTask(void* parameters);
static float ApplyPid(pid_type * pid, const float err);
static float ApplyPid(pid_type * pid, const float err, float dT);
static float bound(float val);
static void ZeroPids(void);
static void SettingsUpdatedCb(UAVObjEvent * ev);
@ -154,6 +157,8 @@ static void stabilizationTask(void* parameters)
// Main task loop
ZeroPids();
while(1) {
float dT;
PIOS_WDG_UpdateFlag(PIOS_WDG_STABILIZATION);
// Wait until the AttitudeRaw object is updated, if a timeout then go to failsafe
@ -227,6 +232,7 @@ static void stabilizationTask(void* parameters)
switch(stabDesired.StabilizationMode[i])
{
case STABILIZATIONDESIRED_STABILIZATIONMODE_RATE:
case STABILIZATIONDESIRED_STABILIZATIONMODE_VIRTUALBAR:
rateDesiredAxis[i] = attitudeDesiredAxis[i];
// Zero attitude and axis lock accumulators
@ -251,7 +257,7 @@ static void stabilizationTask(void* parameters)
break;
}
case STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE:
rateDesiredAxis[i] = ApplyPid(&pids[PID_ROLL + i], local_error[i]);
rateDesiredAxis[i] = ApplyPid(&pids[PID_ROLL + i], local_error[i], dT);
if(rateDesiredAxis[i] > settings.MaximumRate[i])
rateDesiredAxis[i] = settings.MaximumRate[i];
@ -275,7 +281,7 @@ static void stabilizationTask(void* parameters)
else if(axis_lock_accum[i] < -max_axis_lock)
axis_lock_accum[i] = -max_axis_lock;
rateDesiredAxis[i] = ApplyPid(&pids[PID_ROLL + i], axis_lock_accum[i]);
rateDesiredAxis[i] = ApplyPid(&pids[PID_ROLL + i], axis_lock_accum[i], dT);
}
if(rateDesiredAxis[i] > settings.MaximumRate[i])
@ -287,42 +293,78 @@ static void stabilizationTask(void* parameters)
}
}
// Piro compensation rotates the virtual flybar by yaw step to keep it
// rotated to external world
if (vbar_piro_comp) {
const float F_PI = 3.14159f;
float cy = cosf(gyro_filtered[2] / 180.0f * F_PI * dT);
float sy = sinf(gyro_filtered[2] / 180.0f * F_PI * dT);
float vbar_pitch = cy * vbar_integral[1] - sy * vbar_integral[0];
float vbar_roll = sy * vbar_integral[1] + cy * vbar_integral[0];
vbar_integral[1] = vbar_pitch;
vbar_integral[0] = vbar_roll;
}
uint8_t shouldUpdate = 1;
#if defined(DIAGNOSTICS)
RateDesiredSet(&rateDesired);
#endif
ActuatorDesiredGet(&actuatorDesired);
//Calculate desired command
for(int8_t ct=0; ct< MAX_AXES; ct++)
for(uint32_t i = 0; i < MAX_AXES; i++)
{
switch(stabDesired.StabilizationMode[ct])
switch(stabDesired.StabilizationMode[i])
{
case STABILIZATIONDESIRED_STABILIZATIONMODE_RATE:
case STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE:
case STABILIZATIONDESIRED_STABILIZATIONMODE_AXISLOCK:
case STABILIZATIONDESIRED_STABILIZATIONMODE_WEAKLEVELING:
{
float command = ApplyPid(&pids[PID_RATE_ROLL + ct], rateDesiredAxis[ct] - gyro_filtered[ct]);
actuatorDesiredAxis[ct] = bound(command);
float command = ApplyPid(&pids[PID_RATE_ROLL + i], rateDesiredAxis[i] - gyro_filtered[i], dT);
actuatorDesiredAxis[i] = bound(command);
break;
}
case STABILIZATIONDESIRED_STABILIZATIONMODE_VIRTUALBAR:
{
// Track the angle of the virtual flybar which includes a slow decay
vbar_integral[i] = vbar_integral[i] * vbar_decay + gyro_filtered[i] * dT;
if (vbar_integral[i] > settings.VbarMaxAngle)
vbar_integral[i] = settings.VbarMaxAngle;
if (-vbar_integral[i] < -settings.VbarMaxAngle)
vbar_integral[i] = -settings.VbarMaxAngle;
// Command signal is composed of stick input added to the gyro and virtual flybar
float gyro_gain = 1.0f;
if (vbar_gyros_suppress > 0) {
gyro_gain = (1.0f - fabs(rateDesiredAxis[i]) * vbar_gyros_suppress / 100.0f);
gyro_gain = (gyro_gain < 0) ? 0 : gyro_gain;
}
float command = rateDesiredAxis[i] * vbar_sensitivity[i] - gyro_gain * (
vbar_integral[i] * pids[PID_VBAR_ROLL + i].i +
gyro_filtered[i] * pids[PID_VBAR_ROLL + i].p);
actuatorDesiredAxis[i] = bound(command);
break;
}
case STABILIZATIONDESIRED_STABILIZATIONMODE_NONE:
switch (ct)
switch (i)
{
case ROLL:
actuatorDesiredAxis[ct] = bound(attitudeDesiredAxis[ct]);
actuatorDesiredAxis[i] = bound(attitudeDesiredAxis[i]);
shouldUpdate = 1;
pids[PID_RATE_ROLL].iAccumulator = 0;
pids[PID_ROLL].iAccumulator = 0;
break;
case PITCH:
actuatorDesiredAxis[ct] = bound(attitudeDesiredAxis[ct]);
actuatorDesiredAxis[i] = bound(attitudeDesiredAxis[i]);
shouldUpdate = 1;
pids[PID_RATE_PITCH].iAccumulator = 0;
pids[PID_PITCH].iAccumulator = 0;
break;
case YAW:
actuatorDesiredAxis[ct] = bound(attitudeDesiredAxis[ct]);
actuatorDesiredAxis[i] = bound(attitudeDesiredAxis[i]);
shouldUpdate = 1;
pids[PID_RATE_YAW].iAccumulator = 0;
pids[PID_YAW].iAccumulator = 0;
@ -360,7 +402,7 @@ static void stabilizationTask(void* parameters)
}
}
float ApplyPid(pid_type * pid, const float err)
float ApplyPid(pid_type * pid, const float err, float dT)
{
float diff = (err - pid->lastErr);
pid->lastErr = err;
@ -400,44 +442,60 @@ static float bound(float val)
return val;
}
static void SettingsUpdatedCb(UAVObjEvent * ev)
{
memset(pids,0,sizeof (pid_type) * PID_MAX);
StabilizationSettingsGet(&settings);
// Set the roll rate PID constants
pids[0].p = settings.RollRatePID[STABILIZATIONSETTINGS_ROLLRATEPID_KP];
pids[0].i = settings.RollRatePID[STABILIZATIONSETTINGS_ROLLRATEPID_KI];
pids[0].d = settings.RollRatePID[STABILIZATIONSETTINGS_ROLLRATEPID_KD];
pids[0].iLim = settings.RollRatePID[STABILIZATIONSETTINGS_ROLLRATEPID_ILIMIT];
pids[PID_RATE_ROLL].p = settings.RollRatePID[STABILIZATIONSETTINGS_ROLLRATEPID_KP];
pids[PID_RATE_ROLL].i = settings.RollRatePID[STABILIZATIONSETTINGS_ROLLRATEPID_KI];
pids[PID_RATE_ROLL].d = settings.RollRatePID[STABILIZATIONSETTINGS_ROLLRATEPID_KD];
pids[PID_RATE_ROLL].iLim = settings.RollRatePID[STABILIZATIONSETTINGS_ROLLRATEPID_ILIMIT];
// Set the pitch rate PID constants
pids[1].p = settings.PitchRatePID[STABILIZATIONSETTINGS_PITCHRATEPID_KP];
pids[1].i = settings.PitchRatePID[STABILIZATIONSETTINGS_PITCHRATEPID_KI];
pids[1].d = settings.PitchRatePID[STABILIZATIONSETTINGS_PITCHRATEPID_KD];
pids[1].iLim = settings.PitchRatePID[STABILIZATIONSETTINGS_PITCHRATEPID_ILIMIT];
pids[PID_RATE_PITCH].p = settings.PitchRatePID[STABILIZATIONSETTINGS_PITCHRATEPID_KP];
pids[PID_RATE_PITCH].i = settings.PitchRatePID[STABILIZATIONSETTINGS_PITCHRATEPID_KI];
pids[PID_RATE_PITCH].d = settings.PitchRatePID[STABILIZATIONSETTINGS_PITCHRATEPID_KD];
pids[PID_RATE_PITCH].iLim = settings.PitchRatePID[STABILIZATIONSETTINGS_PITCHRATEPID_ILIMIT];
// Set the yaw rate PID constants
pids[2].p = settings.YawRatePID[STABILIZATIONSETTINGS_YAWRATEPID_KP];
pids[2].i = settings.YawRatePID[STABILIZATIONSETTINGS_YAWRATEPID_KI];
pids[2].d = settings.YawRatePID[STABILIZATIONSETTINGS_YAWRATEPID_KD];
pids[2].iLim = settings.YawRatePID[STABILIZATIONSETTINGS_YAWRATEPID_ILIMIT];
pids[PID_RATE_YAW].p = settings.YawRatePID[STABILIZATIONSETTINGS_YAWRATEPID_KP];
pids[PID_RATE_YAW].i = settings.YawRatePID[STABILIZATIONSETTINGS_YAWRATEPID_KI];
pids[PID_RATE_YAW].d = settings.YawRatePID[STABILIZATIONSETTINGS_YAWRATEPID_KD];
pids[PID_RATE_YAW].iLim = settings.YawRatePID[STABILIZATIONSETTINGS_YAWRATEPID_ILIMIT];
// Set the roll attitude PI constants
pids[3].p = settings.RollPI[STABILIZATIONSETTINGS_ROLLPI_KP];
pids[3].i = settings.RollPI[STABILIZATIONSETTINGS_ROLLPI_KI];
pids[3].iLim = settings.RollPI[STABILIZATIONSETTINGS_ROLLPI_ILIMIT];
pids[PID_ROLL].p = settings.RollPI[STABILIZATIONSETTINGS_ROLLPI_KP];
pids[PID_ROLL].i = settings.RollPI[STABILIZATIONSETTINGS_ROLLPI_KI];
pids[PID_ROLL].iLim = settings.RollPI[STABILIZATIONSETTINGS_ROLLPI_ILIMIT];
// Set the pitch attitude PI constants
pids[4].p = settings.PitchPI[STABILIZATIONSETTINGS_PITCHPI_KP];
pids[4].i = settings.PitchPI[STABILIZATIONSETTINGS_PITCHPI_KI];
pids[4].iLim = settings.PitchPI[STABILIZATIONSETTINGS_PITCHPI_ILIMIT];
pids[PID_PITCH].p = settings.PitchPI[STABILIZATIONSETTINGS_PITCHPI_KP];
pids[PID_PITCH].i = settings.PitchPI[STABILIZATIONSETTINGS_PITCHPI_KI];
pids[PID_PITCH].iLim = settings.PitchPI[STABILIZATIONSETTINGS_PITCHPI_ILIMIT];
// Set the yaw attitude PI constants
pids[5].p = settings.YawPI[STABILIZATIONSETTINGS_YAWPI_KP];
pids[5].i = settings.YawPI[STABILIZATIONSETTINGS_YAWPI_KI];
pids[5].iLim = settings.YawPI[STABILIZATIONSETTINGS_YAWPI_ILIMIT];
pids[PID_YAW].p = settings.YawPI[STABILIZATIONSETTINGS_YAWPI_KP];
pids[PID_YAW].i = settings.YawPI[STABILIZATIONSETTINGS_YAWPI_KI];
pids[PID_YAW].iLim = settings.YawPI[STABILIZATIONSETTINGS_YAWPI_ILIMIT];
// Set the roll attitude PI constants
pids[PID_VBAR_ROLL].p = settings.VbarRollPI[STABILIZATIONSETTINGS_VBARROLLPI_KP];
pids[PID_VBAR_ROLL].i = settings.VbarRollPI[STABILIZATIONSETTINGS_VBARROLLPI_KI];
// Set the pitch attitude PI constants
pids[PID_VBAR_PITCH].p = settings.VbarPitchPI[STABILIZATIONSETTINGS_VBARPITCHPI_KP];
pids[PID_VBAR_PITCH].i = settings.VbarPitchPI[STABILIZATIONSETTINGS_VBARPITCHPI_KI];
// Set the yaw attitude PI constants
pids[PID_VBAR_YAW].p = settings.VbarYawPI[STABILIZATIONSETTINGS_VBARYAWPI_KP];
pids[PID_VBAR_YAW].i = settings.VbarYawPI[STABILIZATIONSETTINGS_VBARYAWPI_KI];
// Need to store the vbar sensitivity
vbar_sensitivity[0] = settings.VbarSensitivity[0];
vbar_sensitivity[1] = settings.VbarSensitivity[1];
vbar_sensitivity[2] = settings.VbarSensitivity[2];
// Maximum deviation to accumulate for axis lock
max_axis_lock = settings.MaxAxisLock;
@ -460,6 +518,11 @@ static void SettingsUpdatedCb(UAVObjEvent * ev)
gyro_alpha = 0; // not trusting this to resolve to 0
else
gyro_alpha = expf(-fakeDt / settings.GyroTau);
// Compute time constant for vbar decay term based on a tau
vbar_decay = expf(-fakeDt / settings.VbarTau);
vbar_gyros_suppress = settings.VbarGyroSuppress;
vbar_piro_comp = settings.VbarPiroComp == STABILIZATIONSETTINGS_VBARPIROCOMP_TRUE;
}

View File

@ -215,7 +215,7 @@ static void objectUpdatedCb(UAVObjEvent * ev)
// Get object data
ObjectPersistenceGet(&objper);
int retval = -1;
int retval = 1;
// Execute action
if (objper.Operation == OBJECTPERSISTENCE_OPERATION_LOAD) {
if (objper.Selection == OBJECTPERSISTENCE_SELECTION_SINGLEOBJECT) {
@ -242,6 +242,13 @@ static void objectUpdatedCb(UAVObjEvent * ev)
}
// Save selected instance
retval = UAVObjSave(obj, objper.InstanceID);
// Not sure why this is needed
vTaskDelay(10);
// Verify saving worked
if (retval == 0)
retval = UAVObjLoad(obj, objper.InstanceID);
} else if (objper.Selection == OBJECTPERSISTENCE_SELECTION_ALLSETTINGS
|| objper.Selection == OBJECTPERSISTENCE_SELECTION_ALLOBJECTS) {
retval = UAVObjSaveSettings();
@ -271,9 +278,17 @@ static void objectUpdatedCb(UAVObjEvent * ev)
retval = PIOS_FLASHFS_Format();
#endif
}
if(retval == 0) {
objper.Operation = OBJECTPERSISTENCE_OPERATION_COMPLETED;
ObjectPersistenceSet(&objper);
switch(retval) {
case 0:
objper.Operation = OBJECTPERSISTENCE_OPERATION_COMPLETED;
ObjectPersistenceSet(&objper);
break;
case -1:
objper.Operation = OBJECTPERSISTENCE_OPERATION_ERROR;
ObjectPersistenceSet(&objper);
break;
default:
break;
}
}
}

View File

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

View File

@ -186,6 +186,7 @@ static int32_t PIOS_FLASHFS_GetObjAddress(uint32_t objId, uint16_t instId)
* @retval -2 No room in object table
* @retval -3 Unable to write entry into object table
* @retval -4 FS not initialized
* @retval -5
*/
int32_t PIOS_FLASHFS_GetNewAddress(uint32_t objId, uint16_t instId)
{
@ -206,6 +207,10 @@ int32_t PIOS_FLASHFS_GetNewAddress(uint32_t objId, uint16_t instId)
if((addr + sizeof(header)) > cfg->obj_table_end)
return -2;
// Verify the address is within the chip
if((addr + cfg->sector_size) > cfg->chip_size)
return -5;
if(PIOS_Flash_Jedec_WriteData(addr, (uint8_t *) &header, sizeof(header)) != 0)
return -3;

View File

@ -37,6 +37,7 @@ struct flashfs_cfg {
uint32_t obj_table_start;
uint32_t obj_table_end;
uint32_t sector_size;
uint32_t chip_size;
};
int32_t PIOS_FLASHFS_Init(const struct flashfs_cfg * cfg);

View File

@ -234,6 +234,7 @@ static const struct flashfs_cfg flashfs_m25p_cfg = {
.obj_table_start = 0x00000010,
.obj_table_end = 0x00010000,
.sector_size = 0x00010000,
.chip_size = 0x00200000,
};
static const struct pios_flash_jedec_cfg flash_m25p_cfg = {

View File

@ -74,8 +74,8 @@ typedef enum {
*
* Bit(s) Name Meaning
* ------ ---- -------
* 0 access Defines the access level for the local transactions (readonly=0 and readwrite=1)
* 1 gcsAccess Defines the access level for the local GCS transactions (readonly=0 and readwrite=1), not used in the flight s/w
* 0 access Defines the access level for the local transactions (readonly=1 and readwrite=0)
* 1 gcsAccess Defines the access level for the local GCS transactions (readonly=1 and readwrite=0), not used in the flight s/w
* 2 telemetryAcked Defines if an ack is required for the transactions of this object (1:acked, 0:not acked)
* 3 gcsTelemetryAcked Defines if an ack is required for the transactions of this object (1:acked, 0:not acked)
* 4-5 telemetryUpdateMode Update mode used by the telemetry module (UAVObjUpdateMode)

View File

@ -721,10 +721,11 @@ int32_t UAVObjLoad(UAVObjHandle obj, uint16_t instId)
return -1;
// Fire event on success
if (PIOS_FLASHFS_ObjLoad(obj, instId, instEntry->data) == 0)
int32_t retval;
if ((retval = PIOS_FLASHFS_ObjLoad(obj, instId, instEntry->data)) == 0)
sendEvent(objEntry, instId, EV_UNPACKED);
else
return -1;
return retval;
#endif
#if defined(PIOS_INCLUDE_SDCARD)

View File

@ -1,894 +1,835 @@
<?xml version="1.0" encoding="UTF-8"?>
<ui version="4.0">
<class>CameraStabilizationWidget</class>
<widget class="QWidget" name="CameraStabilizationWidget">
<property name="geometry">
<rect>
<x>0</x>
<y>0</y>
<width>720</width>
<height>567</height>
</rect>
</property>
<property name="windowTitle">
<string>Form</string>
</property>
<layout class="QVBoxLayout" name="verticalLayout_3">
<item>
<widget class="QScrollArea" name="scrollArea">
<property name="styleSheet">
<string notr="true">#groupBox_5,#groupBox{
background-color: qlineargradient(spread:pad, x1:0.507, y1:0.869318, x2:0.507, y2:0.0965909, stop:0 rgba(243, 243, 243, 255), stop:1 rgba(250, 250, 250, 255));
border: 1px outset #999;
border-radius: 3;
font:bold;
}
QGroupBox::title {
subcontrol-origin: margin;
subcontrol-position: top center; /* position at the top center */
padding: 0 3px;
background-color: qlineargradient(x1: 0, y1: 0, x2: 0, y2: 1,
stop: 0 #FFOECE, stop: 1 #FFFFFF);
top: 5px;
}</string>
</property>
<property name="frameShape">
<enum>QFrame::NoFrame</enum>
</property>
<property name="widgetResizable">
<bool>true</bool>
</property>
<widget class="QWidget" name="scrollAreaWidgetContents_2">
<property name="geometry">
<rect>
<x>0</x>
<y>0</y>
<width>702</width>
<height>484</height>
</rect>
</property>
<layout class="QVBoxLayout" name="verticalLayout_2">
<item>
<widget class="QCheckBox" name="enableCameraStabilization">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="text">
<string>Enable CameraStabilization module</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="label_7">
<property name="text">
<string>After enabling the module, you must power cycle before using and configuring.</string>
</property>
</widget>
</item>
<item>
<widget class="Line" name="line">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
</widget>
</item>
<item>
<spacer name="verticalSpacer_3">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Preferred</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>10</height>
</size>
</property>
</spacer>
</item>
<item>
<widget class="QGroupBox" name="groupBox_5">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Minimum">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>100</height>
</size>
</property>
<property name="title">
<string>Basic Settings (Stabilization)</string>
</property>
<layout class="QGridLayout" name="gridLayout_9">
<item row="3" column="3">
<widget class="QSpinBox" name="yawOutputRange">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Camera yaw angle for 100% output value, deg.
This value should be tuned for particular gimbal and servo. You also
have to define channel output range using Output configuration tab.</string>
</property>
<property name="maximum">
<number>180</number>
</property>
<property name="value">
<number>20</number>
</property>
</widget>
</item>
<item row="3" column="2">
<widget class="QSpinBox" name="pitchOutputRange">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Camera pitch angle for 100% output value, deg.
This value should be tuned for particular gimbal and servo. You also
have to define channel output range using Output configuration tab.</string>
</property>
<property name="maximum">
<number>180</number>
</property>
<property name="value">
<number>20</number>
</property>
</widget>
</item>
<item row="3" column="1">
<widget class="QSpinBox" name="rollOutputRange">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Camera roll angle for 100% output value, deg.
This value should be tuned for particular gimbal and servo. You also
have to define channel output range using Output configuration tab.</string>
</property>
<property name="maximum">
<number>180</number>
</property>
<property name="value">
<number>20</number>
</property>
</widget>
</item>
<item row="2" column="3">
<widget class="QComboBox" name="yawChannel">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Yaw output channel for camera gimbal</string>
</property>
<item>
<property name="text">
<string>None</string>
</property>
</item>
</widget>
</item>
<item row="2" column="2">
<widget class="QComboBox" name="pitchChannel">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Pitch output channel for camera gimbal</string>
</property>
<item>
<property name="text">
<string>None</string>
</property>
</item>
</widget>
</item>
<item row="2" column="1">
<widget class="QComboBox" name="rollChannel">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Roll output channel for camera gimbal</string>
</property>
<item>
<property name="text">
<string>None</string>
</property>
</item>
</widget>
</item>
<item row="2" column="0">
<widget class="QLabel" name="label_42">
<property name="text">
<string>Output Channel</string>
</property>
</widget>
</item>
<item row="3" column="0">
<widget class="QLabel" name="label_43">
<property name="text">
<string>Output Range</string>
</property>
</widget>
</item>
<item row="1" column="3">
<widget class="QLabel" name="label_44">
<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="1" column="2">
<widget class="QLabel" name="label_45">
<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="1" column="1">
<widget class="QLabel" name="label_46">
<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="2">
<spacer name="verticalSpacer_4">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>40</height>
</size>
</property>
</spacer>
</item>
</layout>
</widget>
</item>
<item>
<spacer name="verticalSpacer_2">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Preferred</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>10</height>
</size>
</property>
</spacer>
</item>
<item>
<widget class="QGroupBox" name="groupBox">
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Minimum">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>204</height>
</size>
</property>
<property name="title">
<string>Advanced Settings (Control)</string>
</property>
<layout class="QGridLayout" name="gridLayout_8">
<item row="1" column="3">
<widget class="QLabel" name="label_32">
<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="1" column="2">
<widget class="QLabel" name="label_33">
<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="1" column="1">
<widget class="QLabel" name="label_34">
<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="3">
<widget class="QComboBox" name="yawInputChannel">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Input channel to control camera yaw
Don't forget to map this channel using Input configuration tab.</string>
</property>
<item>
<property name="text">
<string>None</string>
</property>
</item>
</widget>
</item>
<item row="2" column="2">
<widget class="QComboBox" name="pitchInputChannel">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Input channel to control camera pitch
Don't forget to map this channel using Input configuration tab.</string>
</property>
<item>
<property name="text">
<string>None</string>
</property>
</item>
</widget>
</item>
<item row="2" column="1">
<widget class="QComboBox" name="rollInputChannel">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Input channel to control camera roll
Don't forget to map this channel using Input configuration tab.</string>
</property>
<item>
<property name="text">
<string>None</string>
</property>
</item>
</widget>
</item>
<item row="2" column="0">
<widget class="QLabel" name="label_35">
<property name="text">
<string>Input Channel</string>
</property>
</widget>
</item>
<item row="3" column="3">
<widget class="QComboBox" name="yawStabilizationMode">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Axis stabilization mode
Attitude: camera tracks level for the axis. Input controls the deflection.
AxisLock: camera remembers tracking attitude. Input controls the rate of deflection.</string>
</property>
<item>
<property name="text">
<string>Attitude</string>
</property>
</item>
</widget>
</item>
<item row="4" column="3">
<widget class="QSpinBox" name="yawInputRange">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Maximum camera yaw deflection for 100% input in Attitude mode, deg.</string>
</property>
<property name="maximum">
<number>180</number>
</property>
<property name="value">
<number>20</number>
</property>
</widget>
</item>
<item row="5" column="3">
<widget class="QSpinBox" name="yawInputRate">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Maximum camera yaw rate for 100% input in AxisLock mode, deg/s.</string>
</property>
<property name="maximum">
<number>180</number>
</property>
<property name="value">
<number>50</number>
</property>
</widget>
</item>
<item row="6" column="3">
<widget class="QSpinBox" name="yawResponseTime">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Input low-pass filter response time for yaw axis, ms.
This option smoothes the stick input. Zero value disables LPF.</string>
</property>
<property name="maximum">
<number>1000</number>
</property>
<property name="value">
<number>150</number>
</property>
</widget>
</item>
<item row="3" column="2">
<widget class="QComboBox" name="pitchStabilizationMode">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Axis stabilization mode
Attitude: camera tracks level for the axis. Input controls the deflection.
AxisLock: camera remembers tracking attitude. Input controls the rate of deflection.</string>
</property>
<item>
<property name="text">
<string>Attitude</string>
</property>
</item>
</widget>
</item>
<item row="4" column="2">
<widget class="QSpinBox" name="pitchInputRange">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Maximum camera pitch deflection for 100% input in Attitude mode, deg.</string>
</property>
<property name="maximum">
<number>180</number>
</property>
<property name="value">
<number>20</number>
</property>
</widget>
</item>
<item row="5" column="2">
<widget class="QSpinBox" name="pitchInputRate">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Maximum camera pitch rate for 100% input in AxisLock mode, deg/s.</string>
</property>
<property name="maximum">
<number>180</number>
</property>
<property name="value">
<number>50</number>
</property>
</widget>
</item>
<item row="6" column="2">
<widget class="QSpinBox" name="pitchResponseTime">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Input low-pass filter response time for pitch axis, ms.
This option smoothes the stick input. Zero value disables LPF.</string>
</property>
<property name="maximum">
<number>1000</number>
</property>
<property name="value">
<number>150</number>
</property>
</widget>
</item>
<item row="3" column="1">
<widget class="QComboBox" name="rollStabilizationMode">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Axis stabilization mode
Attitude: camera tracks level for the axis. Input controls the deflection.
AxisLock: camera remembers tracking attitude. Input controls the rate of deflection.</string>
</property>
<item>
<property name="text">
<string>Attitude</string>
</property>
</item>
</widget>
</item>
<item row="4" column="1">
<widget class="QSpinBox" name="rollInputRange">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Maximum camera roll deflection for 100% input in Attitude mode, deg.</string>
</property>
<property name="maximum">
<number>180</number>
</property>
<property name="value">
<number>20</number>
</property>
</widget>
</item>
<item row="5" column="1">
<widget class="QSpinBox" name="rollInputRate">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Maximum camera roll rate for 100% input in AxisLock mode, deg/s.</string>
</property>
<property name="maximum">
<number>180</number>
</property>
<property name="value">
<number>50</number>
</property>
</widget>
</item>
<item row="6" column="1">
<widget class="QSpinBox" name="rollResponseTime">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Input low-pass filter response time for roll axis, ms.
This option smoothes the stick input. Zero value disables LPF.</string>
</property>
<property name="maximum">
<number>1000</number>
</property>
<property name="value">
<number>150</number>
</property>
</widget>
</item>
<item row="7" column="0">
<widget class="QLabel" name="label_36">
<property name="text">
<string>MaxAxisLockRate</string>
</property>
</widget>
</item>
<item row="6" column="0">
<widget class="QLabel" name="label_37">
<property name="text">
<string>Response Time</string>
</property>
</widget>
</item>
<item row="5" column="0">
<widget class="QLabel" name="label_38">
<property name="text">
<string>Input Rate</string>
</property>
</widget>
</item>
<item row="4" column="0">
<widget class="QLabel" name="label_39">
<property name="text">
<string>Input Range</string>
</property>
</widget>
</item>
<item row="3" column="0">
<widget class="QLabel" name="label_40">
<property name="text">
<string>Stabilization Mode</string>
</property>
</widget>
</item>
<item row="7" column="2" colspan="2">
<widget class="QLabel" name="label_41">
<property name="text">
<string>(the same value for Roll, Pitch, Yaw)</string>
</property>
</widget>
</item>
<item row="7" column="1">
<widget class="QDoubleSpinBox" name="MaxAxisLockRate">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Stick input deadband for all axes in AxisLock mode, deg/s.
When stick input is within the MaxAxisLockRate range, camera tracks
current attitude. Otherwise it starts moving according to input with
rate depending on input value.
If you have drift in your Tx controls, you may want to increase this
value.</string>
</property>
<property name="decimals">
<number>1</number>
</property>
<property name="singleStep">
<double>0.100000000000000</double>
</property>
<property name="value">
<double>1.000000000000000</double>
</property>
</widget>
</item>
<item row="0" column="2">
<spacer name="verticalSpacer_5">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>40</height>
</size>
</property>
</spacer>
</item>
</layout>
</widget>
</item>
<item>
<spacer name="verticalSpacer">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>40</height>
</size>
</property>
</spacer>
</item>
</layout>
</widget>
</widget>
</item>
<item>
<layout class="QVBoxLayout" name="verticalLayout">
<item>
<widget class="QLabel" name="message">
<property name="text">
<string/>
</property>
</widget>
</item>
<item>
<layout class="QHBoxLayout" name="submitButtons">
<item>
<widget class="QFrame" name="frame">
<property name="frameShape">
<enum>QFrame::StyledPanel</enum>
</property>
<property name="frameShadow">
<enum>QFrame::Raised</enum>
</property>
</widget>
</item>
<item>
<spacer name="horizontalSpacer">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item>
<widget class="QPushButton" name="camerastabilizationHelp">
<property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="maximumSize">
<size>
<width>32</width>
<height>32</height>
</size>
</property>
<property name="font">
<font>
<kerning>true</kerning>
</font>
</property>
<property name="text">
<string/>
</property>
<property name="icon">
<iconset resource="../coreplugin/core.qrc">
<normaloff>:/core/images/helpicon.svg</normaloff>:/core/images/helpicon.svg</iconset>
</property>
<property name="iconSize">
<size>
<width>32</width>
<height>32</height>
</size>
</property>
<property name="shortcut">
<string>Ctrl+S</string>
</property>
<property name="default">
<bool>false</bool>
</property>
<property name="flat">
<bool>true</bool>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="camerastabilizationResetToDefaults">
<property name="toolTip">
<string>Load default CameraStabilization settings except output channels
Loaded settings are not applied automatically. You have to click the
Apply or Save button afterwards.</string>
</property>
<property name="text">
<string>Reset To Defaults</string>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="camerastabilizationSaveRAM">
<property name="toolTip">
<string>Send settings to the board but do not save to the non-volatile memory</string>
</property>
<property name="text">
<string>Apply</string>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="camerastabilizationSaveSD">
<property name="toolTip">
<string>Send settings to the board and save to the non-volatile memory</string>
</property>
<property name="text">
<string>Save</string>
</property>
<property name="checked">
<bool>false</bool>
</property>
</widget>
</item>
</layout>
</item>
</layout>
</item>
</layout>
</widget>
<tabstops>
<tabstop>enableCameraStabilization</tabstop>
<tabstop>rollChannel</tabstop>
<tabstop>pitchChannel</tabstop>
<tabstop>yawChannel</tabstop>
<tabstop>rollOutputRange</tabstop>
<tabstop>pitchOutputRange</tabstop>
<tabstop>yawOutputRange</tabstop>
<tabstop>rollInputChannel</tabstop>
<tabstop>pitchInputChannel</tabstop>
<tabstop>yawInputChannel</tabstop>
<tabstop>rollStabilizationMode</tabstop>
<tabstop>pitchStabilizationMode</tabstop>
<tabstop>yawStabilizationMode</tabstop>
<tabstop>rollInputRange</tabstop>
<tabstop>pitchInputRange</tabstop>
<tabstop>yawInputRange</tabstop>
<tabstop>rollInputRate</tabstop>
<tabstop>pitchInputRate</tabstop>
<tabstop>yawInputRate</tabstop>
<tabstop>rollResponseTime</tabstop>
<tabstop>pitchResponseTime</tabstop>
<tabstop>yawResponseTime</tabstop>
<tabstop>MaxAxisLockRate</tabstop>
<tabstop>camerastabilizationHelp</tabstop>
<tabstop>camerastabilizationResetToDefaults</tabstop>
<tabstop>camerastabilizationSaveRAM</tabstop>
<tabstop>camerastabilizationSaveSD</tabstop>
<tabstop>scrollArea</tabstop>
</tabstops>
<resources>
<include location="../coreplugin/core.qrc"/>
</resources>
<connections/>
</ui>
<?xml version="1.0" encoding="UTF-8"?>
<ui version="4.0">
<class>CameraStabilizationWidget</class>
<widget class="QWidget" name="CameraStabilizationWidget">
<property name="geometry">
<rect>
<x>0</x>
<y>0</y>
<width>720</width>
<height>739</height>
</rect>
</property>
<property name="windowTitle">
<string>Form</string>
</property>
<layout class="QVBoxLayout" name="verticalLayout_3">
<item>
<widget class="QScrollArea" name="scrollArea">
<property name="frameShape">
<enum>QFrame::NoFrame</enum>
</property>
<property name="widgetResizable">
<bool>true</bool>
</property>
<widget class="QWidget" name="scrollAreaWidgetContents_2">
<property name="geometry">
<rect>
<x>0</x>
<y>0</y>
<width>696</width>
<height>635</height>
</rect>
</property>
<layout class="QVBoxLayout" name="verticalLayout_2">
<item>
<widget class="QCheckBox" name="enableCameraStabilization">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="text">
<string>Enable CameraStabilization module</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="label_7">
<property name="text">
<string>After enabling the module, you must power cycle before using and configuring.</string>
</property>
</widget>
</item>
<item>
<widget class="Line" name="line">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
</widget>
</item>
<item>
<spacer name="verticalSpacer_3">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Preferred</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>10</height>
</size>
</property>
</spacer>
</item>
<item>
<widget class="QGroupBox" name="groupBox_5">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Minimum">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>100</height>
</size>
</property>
<property name="title">
<string>Basic Settings (Stabilization)</string>
</property>
<layout class="QGridLayout" name="gridLayout_9">
<item row="2" column="3">
<widget class="QSpinBox" name="yawOutputRange">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Camera yaw angle for 100% output value, deg.
This value should be tuned for particular gimbal and servo. You also
have to define channel output range using Output configuration tab.</string>
</property>
<property name="maximum">
<number>180</number>
</property>
<property name="value">
<number>20</number>
</property>
</widget>
</item>
<item row="2" column="2">
<widget class="QSpinBox" name="pitchOutputRange">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Camera pitch angle for 100% output value, deg.
This value should be tuned for particular gimbal and servo. You also
have to define channel output range using Output configuration tab.</string>
</property>
<property name="maximum">
<number>180</number>
</property>
<property name="value">
<number>20</number>
</property>
</widget>
</item>
<item row="2" column="1">
<widget class="QSpinBox" name="rollOutputRange">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Camera roll angle for 100% output value, deg.
This value should be tuned for particular gimbal and servo. You also
have to define channel output range using Output configuration tab.</string>
</property>
<property name="maximum">
<number>180</number>
</property>
<property name="value">
<number>20</number>
</property>
</widget>
</item>
<item row="1" column="3">
<widget class="QComboBox" name="yawChannel">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Yaw output channel for camera gimbal</string>
</property>
<item>
<property name="text">
<string>None</string>
</property>
</item>
</widget>
</item>
<item row="1" column="2">
<widget class="QComboBox" name="pitchChannel">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Pitch output channel for camera gimbal</string>
</property>
<item>
<property name="text">
<string>None</string>
</property>
</item>
</widget>
</item>
<item row="1" column="1">
<widget class="QComboBox" name="rollChannel">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Roll output channel for camera gimbal</string>
</property>
<item>
<property name="text">
<string>None</string>
</property>
</item>
</widget>
</item>
<item row="1" column="0">
<widget class="QLabel" name="label_42">
<property name="text">
<string>Output Channel</string>
</property>
</widget>
</item>
<item row="2" column="0">
<widget class="QLabel" name="label_43">
<property name="text">
<string>Output Range</string>
</property>
</widget>
</item>
<item row="0" column="3">
<widget class="QLabel" name="label_44">
<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="0" column="2">
<widget class="QLabel" name="label_45">
<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="1">
<widget class="QLabel" name="label_46">
<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>
</layout>
</widget>
</item>
<item>
<widget class="QGroupBox" name="groupBox">
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Minimum">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>204</height>
</size>
</property>
<property name="title">
<string>Advanced Settings (Control)</string>
</property>
<layout class="QGridLayout" name="gridLayout_8">
<item row="0" column="3">
<widget class="QLabel" name="label_32">
<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="0" column="2">
<widget class="QLabel" name="label_33">
<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="1">
<widget class="QLabel" name="label_34">
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font: bold 12px;
margin:1px;</string>
</property>
<property name="text">
<string>Roll</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="1" column="3">
<widget class="QComboBox" name="yawInputChannel">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Input channel to control camera yaw
Don't forget to map this channel using Input configuration tab.</string>
</property>
<item>
<property name="text">
<string>None</string>
</property>
</item>
</widget>
</item>
<item row="1" column="2">
<widget class="QComboBox" name="pitchInputChannel">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Input channel to control camera pitch
Don't forget to map this channel using Input configuration tab.</string>
</property>
<item>
<property name="text">
<string>None</string>
</property>
</item>
</widget>
</item>
<item row="1" column="1">
<widget class="QComboBox" name="rollInputChannel">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Input channel to control camera roll
Don't forget to map this channel using Input configuration tab.</string>
</property>
<item>
<property name="text">
<string>None</string>
</property>
</item>
</widget>
</item>
<item row="1" column="0">
<widget class="QLabel" name="label_35">
<property name="text">
<string>Input Channel</string>
</property>
</widget>
</item>
<item row="2" column="3">
<widget class="QComboBox" name="yawStabilizationMode">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Axis stabilization mode
Attitude: camera tracks level for the axis. Input controls the deflection.
AxisLock: camera remembers tracking attitude. Input controls the rate of deflection.</string>
</property>
<item>
<property name="text">
<string>Attitude</string>
</property>
</item>
</widget>
</item>
<item row="3" column="3">
<widget class="QSpinBox" name="yawInputRange">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Maximum camera yaw deflection for 100% input in Attitude mode, deg.</string>
</property>
<property name="maximum">
<number>180</number>
</property>
<property name="value">
<number>20</number>
</property>
</widget>
</item>
<item row="4" column="3">
<widget class="QSpinBox" name="yawInputRate">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Maximum camera yaw rate for 100% input in AxisLock mode, deg/s.</string>
</property>
<property name="maximum">
<number>180</number>
</property>
<property name="value">
<number>50</number>
</property>
</widget>
</item>
<item row="5" column="3">
<widget class="QSpinBox" name="yawResponseTime">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Input low-pass filter response time for yaw axis, ms.
This option smoothes the stick input. Zero value disables LPF.</string>
</property>
<property name="maximum">
<number>1000</number>
</property>
<property name="value">
<number>150</number>
</property>
</widget>
</item>
<item row="2" column="2">
<widget class="QComboBox" name="pitchStabilizationMode">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Axis stabilization mode
Attitude: camera tracks level for the axis. Input controls the deflection.
AxisLock: camera remembers tracking attitude. Input controls the rate of deflection.</string>
</property>
<item>
<property name="text">
<string>Attitude</string>
</property>
</item>
</widget>
</item>
<item row="3" column="2">
<widget class="QSpinBox" name="pitchInputRange">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Maximum camera pitch deflection for 100% input in Attitude mode, deg.</string>
</property>
<property name="maximum">
<number>180</number>
</property>
<property name="value">
<number>20</number>
</property>
</widget>
</item>
<item row="4" column="2">
<widget class="QSpinBox" name="pitchInputRate">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Maximum camera pitch rate for 100% input in AxisLock mode, deg/s.</string>
</property>
<property name="maximum">
<number>180</number>
</property>
<property name="value">
<number>50</number>
</property>
</widget>
</item>
<item row="5" column="2">
<widget class="QSpinBox" name="pitchResponseTime">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Input low-pass filter response time for pitch axis, ms.
This option smoothes the stick input. Zero value disables LPF.</string>
</property>
<property name="maximum">
<number>1000</number>
</property>
<property name="value">
<number>150</number>
</property>
</widget>
</item>
<item row="2" column="1">
<widget class="QComboBox" name="rollStabilizationMode">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Axis stabilization mode
Attitude: camera tracks level for the axis. Input controls the deflection.
AxisLock: camera remembers tracking attitude. Input controls the rate of deflection.</string>
</property>
<item>
<property name="text">
<string>Attitude</string>
</property>
</item>
</widget>
</item>
<item row="3" column="1">
<widget class="QSpinBox" name="rollInputRange">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Maximum camera roll deflection for 100% input in Attitude mode, deg.</string>
</property>
<property name="maximum">
<number>180</number>
</property>
<property name="value">
<number>20</number>
</property>
</widget>
</item>
<item row="4" column="1">
<widget class="QSpinBox" name="rollInputRate">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Maximum camera roll rate for 100% input in AxisLock mode, deg/s.</string>
</property>
<property name="maximum">
<number>180</number>
</property>
<property name="value">
<number>50</number>
</property>
</widget>
</item>
<item row="5" column="1">
<widget class="QSpinBox" name="rollResponseTime">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Input low-pass filter response time for roll axis, ms.
This option smoothes the stick input. Zero value disables LPF.</string>
</property>
<property name="maximum">
<number>1000</number>
</property>
<property name="value">
<number>150</number>
</property>
</widget>
</item>
<item row="6" column="0">
<widget class="QLabel" name="label_36">
<property name="text">
<string>MaxAxisLockRate</string>
</property>
</widget>
</item>
<item row="5" column="0">
<widget class="QLabel" name="label_37">
<property name="text">
<string>Response Time</string>
</property>
</widget>
</item>
<item row="4" column="0">
<widget class="QLabel" name="label_38">
<property name="text">
<string>Input Rate</string>
</property>
</widget>
</item>
<item row="3" column="0">
<widget class="QLabel" name="label_39">
<property name="text">
<string>Input Range</string>
</property>
</widget>
</item>
<item row="2" column="0">
<widget class="QLabel" name="label_40">
<property name="text">
<string>Stabilization Mode</string>
</property>
</widget>
</item>
<item row="6" column="2" colspan="2">
<widget class="QLabel" name="label_41">
<property name="text">
<string>(the same value for Roll, Pitch, Yaw)</string>
</property>
</widget>
</item>
<item row="6" column="1">
<widget class="QDoubleSpinBox" name="MaxAxisLockRate">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Stick input deadband for all axes in AxisLock mode, deg/s.
When stick input is within the MaxAxisLockRate range, camera tracks
current attitude. Otherwise it starts moving according to input with
rate depending on input value.
If you have drift in your Tx controls, you may want to increase this
value.</string>
</property>
<property name="decimals">
<number>1</number>
</property>
<property name="singleStep">
<double>0.100000000000000</double>
</property>
<property name="value">
<double>1.000000000000000</double>
</property>
</widget>
</item>
</layout>
</widget>
</item>
<item>
<spacer name="verticalSpacer">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>40</height>
</size>
</property>
</spacer>
</item>
</layout>
</widget>
</widget>
</item>
<item>
<layout class="QVBoxLayout" name="verticalLayout">
<item>
<widget class="QLabel" name="message">
<property name="text">
<string/>
</property>
</widget>
</item>
<item>
<layout class="QHBoxLayout" name="submitButtons">
<item>
<widget class="QFrame" name="frame">
<property name="frameShape">
<enum>QFrame::StyledPanel</enum>
</property>
<property name="frameShadow">
<enum>QFrame::Raised</enum>
</property>
</widget>
</item>
<item>
<spacer name="horizontalSpacer">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item>
<widget class="QPushButton" name="camerastabilizationHelp">
<property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="maximumSize">
<size>
<width>32</width>
<height>32</height>
</size>
</property>
<property name="font">
<font>
<kerning>true</kerning>
</font>
</property>
<property name="text">
<string/>
</property>
<property name="icon">
<iconset resource="../coreplugin/core.qrc">
<normaloff>:/core/images/helpicon.svg</normaloff>:/core/images/helpicon.svg</iconset>
</property>
<property name="iconSize">
<size>
<width>32</width>
<height>32</height>
</size>
</property>
<property name="shortcut">
<string>Ctrl+S</string>
</property>
<property name="default">
<bool>false</bool>
</property>
<property name="flat">
<bool>true</bool>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="camerastabilizationResetToDefaults">
<property name="toolTip">
<string>Load default CameraStabilization settings except output channels
Loaded settings are not applied automatically. You have to click the
Apply or Save button afterwards.</string>
</property>
<property name="text">
<string>Reset To Defaults</string>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="camerastabilizationSaveRAM">
<property name="toolTip">
<string>Send settings to the board but do not save to the non-volatile memory</string>
</property>
<property name="text">
<string>Apply</string>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="camerastabilizationSaveSD">
<property name="toolTip">
<string>Send settings to the board and save to the non-volatile memory</string>
</property>
<property name="text">
<string>Save</string>
</property>
<property name="checked">
<bool>false</bool>
</property>
</widget>
</item>
</layout>
</item>
</layout>
</item>
</layout>
</widget>
<tabstops>
<tabstop>enableCameraStabilization</tabstop>
<tabstop>rollChannel</tabstop>
<tabstop>pitchChannel</tabstop>
<tabstop>yawChannel</tabstop>
<tabstop>rollOutputRange</tabstop>
<tabstop>pitchOutputRange</tabstop>
<tabstop>yawOutputRange</tabstop>
<tabstop>rollInputChannel</tabstop>
<tabstop>pitchInputChannel</tabstop>
<tabstop>yawInputChannel</tabstop>
<tabstop>rollStabilizationMode</tabstop>
<tabstop>pitchStabilizationMode</tabstop>
<tabstop>yawStabilizationMode</tabstop>
<tabstop>rollInputRange</tabstop>
<tabstop>pitchInputRange</tabstop>
<tabstop>yawInputRange</tabstop>
<tabstop>rollInputRate</tabstop>
<tabstop>pitchInputRate</tabstop>
<tabstop>yawInputRate</tabstop>
<tabstop>rollResponseTime</tabstop>
<tabstop>pitchResponseTime</tabstop>
<tabstop>yawResponseTime</tabstop>
<tabstop>MaxAxisLockRate</tabstop>
<tabstop>camerastabilizationHelp</tabstop>
<tabstop>camerastabilizationResetToDefaults</tabstop>
<tabstop>camerastabilizationSaveRAM</tabstop>
<tabstop>camerastabilizationSaveSD</tabstop>
<tabstop>scrollArea</tabstop>
</tabstops>
<resources>
<include location="../coreplugin/core.qrc"/>
</resources>
<connections/>
</ui>

View File

@ -43,7 +43,7 @@ ConfigProHWWidget::ConfigProHWWidget(QWidget *parent) : ConfigTaskWidget(parent)
addUAVObjectToWidgetRelation("HwSettings","TelemetrySpeed",m_telemetry->telemetrySpeed);
enableControls(false);
populateWidgets();
refreshWidgetsValues();
refreshWidgetsValues(NULL);
}
ConfigProHWWidget::~ConfigProHWWidget()

View File

@ -53,8 +53,6 @@ ConfigOutputWidget::ConfigOutputWidget(QWidget *parent) : ConfigTaskWidget(paren
m_config->setupUi(this);
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
addApplySaveButtons(m_config->saveRCOutputToRAM,m_config->saveRCOutputToSD);
addUAVObject("ActuatorSettings");
UAVSettingsImportExportFactory * importexportplugin = pm->getObject<UAVSettingsImportExportFactory>();
connect(importexportplugin,SIGNAL(importAboutToBegin()),this,SLOT(stopTests()));
@ -73,25 +71,37 @@ ConfigOutputWidget::ConfigOutputWidget(QWidget *parent) : ConfigTaskWidget(paren
connect(m_config->channelOutTest, SIGNAL(toggled(bool)), this, SLOT(runChannelTests(bool)));
refreshWidgetsValues();
firstUpdate = true;
connect(m_config->spinningArmed, SIGNAL(toggled(bool)), this, SLOT(setSpinningArmed(bool)));
// Configure the task widget
// Connect the help button
connect(m_config->outputHelp, SIGNAL(clicked()), this, SLOT(openHelp()));
// Add custom handling of displaying things
connect(this,SIGNAL(refreshWidgetsValuesRequested()), this, SLOT(refreshOutputWidgetsValues()));
addApplySaveButtons(m_config->saveRCOutputToRAM,m_config->saveRCOutputToSD);
// Track the ActuatorSettings object
addUAVObject("ActuatorSettings");
// Associate the buttons with their UAVO fields
addWidget(m_config->cb_outputRate4);
addWidget(m_config->cb_outputRate3);
addWidget(m_config->cb_outputRate2);
addWidget(m_config->cb_outputRate1);
addWidget(m_config->spinningArmed);
disconnect(this, SLOT(refreshWidgetsValues(UAVObject*)));
UAVObjectManager *objManager = pm->getObject<UAVObjectManager>();
UAVObject* obj = objManager->getObject(QString("ActuatorCommand"));
if(UAVObject::GetGcsTelemetryUpdateMode(obj->getMetadata()) == UAVObject::UPDATEMODE_ONCHANGE)
this->setEnabled(false);
connect(obj,SIGNAL(objectUpdated(UAVObject*)),this,SLOT(disableIfNotMe(UAVObject*)));
refreshWidgetsValues();
}
void ConfigOutputWidget::enableControls(bool enable)
{
@ -196,24 +206,6 @@ void ConfigOutputWidget::assignOutputChannel(UAVDataObject *obj, QString str)
outputChannelForm->setAssignment(str);
}
/**
* Set the "Spin motors at neutral when armed" flag in ActuatorSettings
*/
void ConfigOutputWidget::setSpinningArmed(bool val)
{
ActuatorSettings *actuatorSettings = ActuatorSettings::GetInstance(getObjectManager());
Q_ASSERT(actuatorSettings);
ActuatorSettings::DataFields actuatorSettingsData = actuatorSettings->getData();
if(val)
actuatorSettingsData.MotorsSpinWhileArmed = ActuatorSettings::MOTORSSPINWHILEARMED_TRUE;
else
actuatorSettingsData.MotorsSpinWhileArmed = ActuatorSettings::MOTORSSPINWHILEARMED_FALSE;
// Apply settings
actuatorSettings->setData(actuatorSettingsData);
}
/**
Sends the channel value to the UAV to move the servo.
Returns immediately if we are not in testing mode
@ -328,7 +320,16 @@ void ConfigOutputWidget::refreshWidgetsValues(UAVObject * obj)
}
}
setDirty(dirty);
// Get Channel ranges:
foreach(OutputChannelForm *outputChannelForm, outputChannelForms)
{
int minValue = actuatorSettingsData.ChannelMin[outputChannelForm->index()];
int maxValue = actuatorSettingsData.ChannelMax[outputChannelForm->index()];
outputChannelForm->minmax(minValue, maxValue);
int neutral = actuatorSettingsData.ChannelNeutral[outputChannelForm->index()];
outputChannelForm->neutral(neutral);
}
}
/**
@ -336,26 +337,36 @@ void ConfigOutputWidget::refreshWidgetsValues(UAVObject * obj)
*/
void ConfigOutputWidget::updateObjectsFromWidgets()
{
emit updateObjectsFromWidgetsRequested();
ActuatorSettings *actuatorSettings = ActuatorSettings::GetInstance(getObjectManager());
Q_ASSERT(actuatorSettings);
ActuatorSettings::DataFields actuatorSettingsData = actuatorSettings->getData();
if(actuatorSettings) {
ActuatorSettings::DataFields actuatorSettingsData = actuatorSettings->getData();
// Set channel ranges
QList<OutputChannelForm*> outputChannelForms = findChildren<OutputChannelForm*>();
foreach(OutputChannelForm *outputChannelForm, outputChannelForms)
{
actuatorSettingsData.ChannelMax[outputChannelForm->index()] = outputChannelForm->max();
actuatorSettingsData.ChannelMin[outputChannelForm->index()] = outputChannelForm->min();
actuatorSettingsData.ChannelNeutral[outputChannelForm->index()] = outputChannelForm->neutral();
// Set channel ranges
QList<OutputChannelForm*> outputChannelForms = findChildren<OutputChannelForm*>();
foreach(OutputChannelForm *outputChannelForm, outputChannelForms)
{
actuatorSettingsData.ChannelMax[outputChannelForm->index()] = outputChannelForm->max();
actuatorSettingsData.ChannelMin[outputChannelForm->index()] = outputChannelForm->min();
actuatorSettingsData.ChannelNeutral[outputChannelForm->index()] = outputChannelForm->neutral();
}
// Set update rates
actuatorSettingsData.ChannelUpdateFreq[0] = m_config->cb_outputRate1->currentText().toUInt();
actuatorSettingsData.ChannelUpdateFreq[1] = m_config->cb_outputRate2->currentText().toUInt();
actuatorSettingsData.ChannelUpdateFreq[2] = m_config->cb_outputRate3->currentText().toUInt();
actuatorSettingsData.ChannelUpdateFreq[3] = m_config->cb_outputRate4->currentText().toUInt();
if(m_config->spinningArmed->isChecked() == true)
actuatorSettingsData.MotorsSpinWhileArmed = ActuatorSettings::MOTORSSPINWHILEARMED_TRUE;
else
actuatorSettingsData.MotorsSpinWhileArmed = ActuatorSettings::MOTORSSPINWHILEARMED_FALSE;
// Apply settings
actuatorSettings->setData(actuatorSettingsData);
}
// Set update rates
actuatorSettingsData.ChannelUpdateFreq[0] = m_config->cb_outputRate1->currentText().toUInt();
actuatorSettingsData.ChannelUpdateFreq[1] = m_config->cb_outputRate2->currentText().toUInt();
actuatorSettingsData.ChannelUpdateFreq[2] = m_config->cb_outputRate3->currentText().toUInt();
actuatorSettingsData.ChannelUpdateFreq[3] = m_config->cb_outputRate4->currentText().toUInt();
// Apply settings
actuatorSettings->setData(actuatorSettingsData);
}
void ConfigOutputWidget::openHelp()

View File

@ -73,7 +73,6 @@ private slots:
void updateObjectsFromWidgets();
void runChannelTests(bool state);
void sendChannelTest(int index, int value);
void setSpinningArmed(bool val);
void openHelp();
protected:
void enableControls(bool enable);

View File

@ -89,9 +89,17 @@ ConfigPipXtremeWidget::ConfigPipXtremeWidget(QWidget *parent) : ConfigTaskWidget
timeOut = new QTimer(this);
connect(timeOut, SIGNAL(timeout()),this,SLOT(disconnected()));
//Add scroll bar when necessary
QScrollArea *scroll = new QScrollArea;
scroll->setWidget(m_pipx->frame_3);
m_pipx->verticalLayout_3->addWidget(scroll);
// Request and update of the setting object.
settingsUpdated = false;
pipxSettingsObj->requestUpdate();
disableMouseWheelEvents();
}
ConfigPipXtremeWidget::~ConfigPipXtremeWidget()

View File

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

View File

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

View File

@ -2,6 +2,7 @@
#include "ui_inputchannelform.h"
#include "manualcontrolsettings.h"
#include "gcsreceiver.h"
inputChannelForm::inputChannelForm(QWidget *parent,bool showlegend) :
ConfigTaskWidget(parent),
@ -115,7 +116,7 @@ void inputChannelForm::groupUpdated()
count = 18;
break;
case ManualControlSettings::CHANNELGROUPS_GCS:
count = 5;
count = GCSReceiver::CHANNEL_NUMELEM;
break;
case ManualControlSettings::CHANNELGROUPS_NONE:
count = 0;

View File

@ -7,7 +7,7 @@
<x>0</x>
<y>0</y>
<width>840</width>
<height>724</height>
<height>834</height>
</rect>
</property>
<property name="windowTitle">
@ -23,6 +23,96 @@
<enum>QFrame::Raised</enum>
</property>
<layout class="QGridLayout" name="gridLayout">
<item row="1" column="0" colspan="2">
<layout class="QHBoxLayout" name="horizontalLayout_12">
<item>
<widget class="QGraphicsView" name="graphicsView_Spectrum">
<property name="backgroundBrush">
<brush brushstyle="NoBrush">
<color alpha="255">
<red>0</red>
<green>0</green>
<blue>0</blue>
</color>
</brush>
</property>
<property name="foregroundBrush">
<brush brushstyle="NoBrush">
<color alpha="255">
<red>0</red>
<green>0</green>
<blue>0</blue>
</color>
</brush>
</property>
<property name="interactive">
<bool>true</bool>
</property>
</widget>
</item>
</layout>
</item>
<item row="2" column="0" colspan="2">
<layout class="QVBoxLayout" name="verticalLayout">
<item>
<widget class="QLabel" name="message">
<property name="text">
<string/>
</property>
</widget>
</item>
<item>
<layout class="QHBoxLayout" name="submitButtons">
<item>
<widget class="QFrame" name="frame">
<property name="frameShape">
<enum>QFrame::StyledPanel</enum>
</property>
<property name="frameShadow">
<enum>QFrame::Raised</enum>
</property>
</widget>
</item>
<item>
<spacer name="horizontalSpacer">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item>
<widget class="QPushButton" name="Apply">
<property name="toolTip">
<string>Send settings to the board but do not save to the non-volatile memory</string>
</property>
<property name="text">
<string>Apply</string>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="Save">
<property name="toolTip">
<string>Send settings to the board and save to the non-volatile memory</string>
</property>
<property name="text">
<string>Save</string>
</property>
<property name="checked">
<bool>false</bool>
</property>
</widget>
</item>
</layout>
</item>
</layout>
</item>
<item row="0" column="0">
<widget class="QFrame" name="frame_2">
<property name="frameShape">
@ -165,6 +255,12 @@
</item>
<item>
<widget class="QGroupBox" name="groupBox_3">
<property name="minimumSize">
<size>
<width>400</width>
<height>0</height>
</size>
</property>
<property name="font">
<font>
<weight>75</weight>
@ -374,7 +470,7 @@
<item row="6" column="0">
<widget class="QLabel" name="label_12">
<property name="text">
<string>Frequency Step Size</string>
<string>Freq. Step Size</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
@ -779,7 +875,7 @@
<item row="0" column="0">
<widget class="QLabel" name="TelemPortConfigLabel">
<property name="text">
<string>Telemetry Port Configuration</string>
<string>Telemetry Port Config.</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
@ -1105,13 +1201,13 @@
<bool>true</bool>
</property>
<property name="minimum">
<double>0</double>
<number>0</number>
</property>
<property name="maximum">
<double>1000000000</double>
<number>1000000000</number>
</property>
<property name="singleStep">
<double>100000</double>
<number>100000</number>
</property>
</widget>
</item>
@ -1213,98 +1309,51 @@
</layout>
</widget>
</item>
<item>
<layout class="QHBoxLayout" name="horizontalLayout_12">
<item>
<widget class="QGraphicsView" name="graphicsView_Spectrum">
<property name="backgroundBrush">
<brush brushstyle="NoBrush">
<color alpha="255">
<red>0</red>
<green>0</green>
<blue>0</blue>
</color>
</brush>
</property>
<property name="foregroundBrush">
<brush brushstyle="NoBrush">
<color alpha="255">
<red>0</red>
<green>0</green>
<blue>0</blue>
</color>
</brush>
</property>
<property name="interactive">
<bool>true</bool>
</property>
</widget>
</item>
</layout>
</item>
<item>
<layout class="QVBoxLayout" name="verticalLayout">
<item>
<widget class="QLabel" name="message">
<property name="text">
<string/>
</property>
</widget>
</item>
<item>
<layout class="QHBoxLayout" name="submitButtons">
<item>
<widget class="QFrame" name="frame">
<property name="frameShape">
<enum>QFrame::StyledPanel</enum>
</property>
<property name="frameShadow">
<enum>QFrame::Raised</enum>
</property>
</widget>
</item>
<item>
<spacer name="horizontalSpacer">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item>
<widget class="QPushButton" name="Apply">
<property name="toolTip">
<string>Send settings to the board but do not save to the non-volatile memory</string>
</property>
<property name="text">
<string>Apply</string>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="Save">
<property name="toolTip">
<string>Send settings to the board and save to the non-volatile memory</string>
</property>
<property name="text">
<string>Save</string>
</property>
<property name="checked">
<bool>false</bool>
</property>
</widget>
</item>
</layout>
</item>
</layout>
</item>
</layout>
</widget>
<tabstops>
<tabstop>PairSelect1</tabstop>
<tabstop>PairID1</tabstop>
<tabstop>PairSelect2</tabstop>
<tabstop>PairID2</tabstop>
<tabstop>PairSelect3</tabstop>
<tabstop>PairID3</tabstop>
<tabstop>PairSelect4</tabstop>
<tabstop>PairID4</tabstop>
<tabstop>FirmwareVersion</tabstop>
<tabstop>SerialNumber</tabstop>
<tabstop>DeviceID</tabstop>
<tabstop>MinFrequency</tabstop>
<tabstop>MaxFrequency</tabstop>
<tabstop>FrequencyStepSize</tabstop>
<tabstop>LinkState</tabstop>
<tabstop>RxAFC</tabstop>
<tabstop>Retries</tabstop>
<tabstop>Errors</tabstop>
<tabstop>UAVTalkErrors</tabstop>
<tabstop>Resets</tabstop>
<tabstop>TXRate</tabstop>
<tabstop>RXRate</tabstop>
<tabstop>TelemPortConfig</tabstop>
<tabstop>TelemPortSpeed</tabstop>
<tabstop>FlexiPortConfig</tabstop>
<tabstop>FlexiPortSpeed</tabstop>
<tabstop>VCPConfig</tabstop>
<tabstop>VCPSpeed</tabstop>
<tabstop>MaxRFDatarate</tabstop>
<tabstop>MaxRFTxPower</tabstop>
<tabstop>SendTimeout</tabstop>
<tabstop>MinPacketSize</tabstop>
<tabstop>FrequencyCalibration</tabstop>
<tabstop>Frequency</tabstop>
<tabstop>ScanSpectrum</tabstop>
<tabstop>AESKey</tabstop>
<tabstop>AESKeyRandom</tabstop>
<tabstop>AESEnable</tabstop>
<tabstop>graphicsView_Spectrum</tabstop>
<tabstop>Apply</tabstop>
<tabstop>Save</tabstop>
</tabstops>
<resources/>
<connections/>
</ui>

View File

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

View File

@ -1,647 +1,620 @@
<?xml version="1.0" encoding="UTF-8"?>
<ui version="4.0">
<class>TxPIDWidget</class>
<widget class="QWidget" name="TxPIDWidget">
<property name="geometry">
<rect>
<x>0</x>
<y>0</y>
<width>720</width>
<height>567</height>
</rect>
</property>
<property name="windowTitle">
<string>Form</string>
</property>
<layout class="QVBoxLayout" name="verticalLayout_3">
<item>
<widget class="QScrollArea" name="scrollArea">
<property name="frameShape">
<enum>QFrame::NoFrame</enum>
</property>
<property name="widgetResizable">
<bool>true</bool>
</property>
<widget class="QWidget" name="scrollAreaWidgetContents_2">
<property name="geometry">
<rect>
<x>0</x>
<y>0</y>
<width>702</width>
<height>489</height>
</rect>
</property>
<layout class="QVBoxLayout" name="verticalLayout_2">
<item>
<widget class="QCheckBox" name="TxPIDEnable">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>This module will periodically update values of stabilization PID settings
depending on configured input control channels. New values of stabilization
settings are not saved to flash, but updated in RAM. It is expected that the
module will be enabled only for tuning. When desired values are found, they
can be read via GCS and saved permanently. Then this module should be
disabled again.
Up to 3 separate PID options (or option pairs) can be selected and updated.</string>
</property>
<property name="text">
<string>Enable TxPID module</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="label_7">
<property name="text">
<string>After enabling the module, you must power cycle before using and configuring.</string>
</property>
</widget>
</item>
<item>
<widget class="Line" name="line">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
</widget>
</item>
<item>
<spacer name="verticalSpacer_2">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Preferred</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>10</height>
</size>
</property>
</spacer>
</item>
<item>
<widget class="QGroupBox" name="groupBox_6">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Minimum">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>100</height>
</size>
</property>
<property name="styleSheet">
<string notr="true">#groupBox_6{
background-color: qlineargradient(spread:pad, x1:0.507, y1:0.869318, x2:0.507, y2:0.0965909, stop:0 rgba(243, 243, 243, 255), stop:1 rgba(250, 250, 250, 255));
border: 1px outset #999;
border-radius: 3;
font:bold;
}
QGroupBox::title {
subcontrol-origin: margin;
subcontrol-position: top center; /* position at the top center */
padding: 0 3px;
background-color: qlineargradient(x1: 0, y1: 0, x2: 0, y2: 1,
stop: 0 #FFOECE, stop: 1 #FFFFFF);
top: 5px;
}</string>
</property>
<property name="title">
<string>Module Settings</string>
</property>
<layout class="QGridLayout" name="gridLayout">
<item row="1" column="1">
<widget class="QLabel" name="label_51">
<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 option</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="1" column="2">
<widget class="QLabel" name="label_50">
<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>Control Source</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="1" column="3">
<widget class="QLabel" name="label_49">
<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>Min</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="1" column="4">
<widget class="QLabel" name="label">
<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>Max</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="2" column="0">
<widget class="QLabel" name="label_47">
<property name="text">
<string>Instance 1</string>
</property>
</widget>
</item>
<item row="2" column="1">
<widget class="QComboBox" name="PID1">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Select PID option or option pair to update.
Set to Disabled if not used.</string>
</property>
</widget>
</item>
<item row="2" column="2">
<widget class="QComboBox" name="Input1">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Select input used as a control source for this instance.
It can be one of Accessory channels or Throttle channel.
If Accessory channel is chosen then its range [0..1] will be mapped
to PID range [Min..Max] defined for this instance.
If Throttle channel is chosen then Throttle range [Min..Max] will
be mapped to PID range [Min..Max] defined for this instance. If
Throttle is out of bounds then PID Min and Max values will be used
accordingly.
Note that it is possible to set PID Min &gt; Max. In that case increasing
control input value will decrease the PID option value. This can be
used, for instance, to decrease PID value when increasing Throttle.</string>
</property>
</widget>
</item>
<item row="2" column="3">
<widget class="QDoubleSpinBox" name="MinPID1">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Minimum PID value mapped to Accessory channel = 0 or
Throttle channel lesser or equal to Throttle Min value.</string>
</property>
<property name="decimals">
<number>6</number>
</property>
<property name="singleStep">
<double>0.000100000000000</double>
</property>
</widget>
</item>
<item row="2" column="4">
<widget class="QDoubleSpinBox" name="MaxPID1">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Maximum PID value mapped to Accessory channel = 1 or
Throttle channel greater or equal to Throttle Max value.</string>
</property>
<property name="decimals">
<number>6</number>
</property>
<property name="singleStep">
<double>0.000100000000000</double>
</property>
</widget>
</item>
<item row="3" column="0">
<widget class="QLabel" name="label_48">
<property name="text">
<string>Instance 2</string>
</property>
</widget>
</item>
<item row="3" column="1">
<widget class="QComboBox" name="PID2">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Select PID option or option pair to update.
Set to Disabled if not used.</string>
</property>
</widget>
</item>
<item row="3" column="2">
<widget class="QComboBox" name="Input2">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Select input used as a control source for this instance.
It can be one of Accessory channels or Throttle channel.
If Accessory channel is chosen then its range [0..1] will be mapped
to PID range [Min..Max] defined for this instance.
If Throttle channel is chosen then Throttle range [Min..Max] will
be mapped to PID range [Min..Max] defined for this instance. If
Throttle is out of bounds then PID Min and Max values will be used
accordingly.
Note that it is possible to set PID Min &gt; Max. In that case increasing
control input value will decrease the PID option value. This can be
used, for instance, to decrease PID value when increasing Throttle.</string>
</property>
</widget>
</item>
<item row="3" column="3">
<widget class="QDoubleSpinBox" name="MinPID2">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Minimum PID value mapped to Accessory channel = 0 or
Throttle channel lesser or equal to Throttle Min value.</string>
</property>
<property name="decimals">
<number>6</number>
</property>
<property name="singleStep">
<double>0.000100000000000</double>
</property>
</widget>
</item>
<item row="3" column="4">
<widget class="QDoubleSpinBox" name="MaxPID2">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Maximum PID value mapped to Accessory channel = 1 or
Throttle channel greater or equal to Throttle Max value.</string>
</property>
<property name="decimals">
<number>6</number>
</property>
<property name="singleStep">
<double>0.000100000000000</double>
</property>
</widget>
</item>
<item row="4" column="0">
<widget class="QLabel" name="label_52">
<property name="text">
<string>Instance 3</string>
</property>
</widget>
</item>
<item row="4" column="1">
<widget class="QComboBox" name="PID3">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Select PID option or option pair to update.
Set to Disabled if not used.</string>
</property>
</widget>
</item>
<item row="4" column="2">
<widget class="QComboBox" name="Input3">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Select input used as a control source for this instance.
It can be one of Accessory channels or Throttle channel.
If Accessory channel is chosen then its range [0..1] will be mapped
to PID range [Min..Max] defined for this instance.
If Throttle channel is chosen then Throttle range [Min..Max] will
be mapped to PID range [Min..Max] defined for this instance. If
Throttle is out of bounds then PID Min and Max values will be used
accordingly.
Note that it is possible to set PID Min &gt; Max. In that case increasing
control input value will decrease the PID option value. This can be
used, for instance, to decrease PID value when increasing Throttle.</string>
</property>
</widget>
</item>
<item row="4" column="3">
<widget class="QDoubleSpinBox" name="MinPID3">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Minimum PID value mapped to Accessory channel = 0 or
Throttle channel lesser or equal to Throttle Min value.</string>
</property>
<property name="decimals">
<number>6</number>
</property>
<property name="singleStep">
<double>0.000100000000000</double>
</property>
</widget>
</item>
<item row="4" column="4">
<widget class="QDoubleSpinBox" name="MaxPID3">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Maximum PID value mapped to Accessory channel = 1 or
Throttle channel greater or equal to Throttle Max value.</string>
</property>
<property name="decimals">
<number>6</number>
</property>
<property name="singleStep">
<double>0.000100000000000</double>
</property>
</widget>
</item>
<item row="8" column="0">
<widget class="QLabel" name="label_2">
<property name="text">
<string>Update Mode</string>
</property>
</widget>
</item>
<item row="8" column="1">
<widget class="QComboBox" name="UpdateMode">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>PID values update mode which can be set to:
- Never: this disables PID updates (but module still will be run if enabled),
- When Armed: PID updated only when system is armed,
- Always: PID updated always regardless of arm state.
Since the GCS updates GUI PID values in real time on change, could be
tricky to change other PID values from the GUI if the module is enabled
and constantly updates stabilization settings object. As a workaround,
this option can be used to temporarily disable updates or enable them
only when system is armed without disabling the module.</string>
</property>
</widget>
</item>
<item row="7" column="0">
<widget class="QLabel" name="label_3">
<property name="text">
<string>Throttle Range</string>
</property>
</widget>
</item>
<item row="7" column="1">
<widget class="QDoubleSpinBox" name="ThrottleMin">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Throttle channel lower bound mapped to PID Min value</string>
</property>
<property name="maximum">
<double>1.000000000000000</double>
</property>
<property name="singleStep">
<double>0.010000000000000</double>
</property>
</widget>
</item>
<item row="7" column="2">
<widget class="QDoubleSpinBox" name="ThrottleMax">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Throttle channel upper bound mapped to PID Max value</string>
</property>
<property name="maximum">
<double>1.000000000000000</double>
</property>
<property name="singleStep">
<double>0.010000000000000</double>
</property>
</widget>
</item>
<item row="6" column="1">
<widget class="QLabel" name="label_4">
<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>Min</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="6" column="2">
<widget class="QLabel" name="label_5">
<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>Max</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="0" column="2">
<spacer name="verticalSpacer_4">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item row="5" column="1">
<spacer name="verticalSpacer_3">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Preferred</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
</layout>
</widget>
</item>
<item>
<spacer name="verticalSpacer">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>40</height>
</size>
</property>
</spacer>
</item>
</layout>
</widget>
</widget>
</item>
<item>
<layout class="QVBoxLayout" name="verticalLayout">
<item>
<widget class="QLabel" name="message">
<property name="text">
<string/>
</property>
</widget>
</item>
<item>
<layout class="QHBoxLayout" name="submitButtons">
<item>
<widget class="QFrame" name="frame">
<property name="frameShape">
<enum>QFrame::StyledPanel</enum>
</property>
<property name="frameShadow">
<enum>QFrame::Raised</enum>
</property>
</widget>
</item>
<item>
<spacer name="horizontalSpacer">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item>
<widget class="QPushButton" name="Apply">
<property name="toolTip">
<string>Send settings to the board but do not save to the non-volatile memory</string>
</property>
<property name="text">
<string>Apply</string>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="Save">
<property name="toolTip">
<string>Send settings to the board and save to the non-volatile memory</string>
</property>
<property name="text">
<string>Save</string>
</property>
<property name="checked">
<bool>false</bool>
</property>
</widget>
</item>
</layout>
</item>
</layout>
</item>
</layout>
</widget>
<tabstops>
<tabstop>TxPIDEnable</tabstop>
<tabstop>Apply</tabstop>
<tabstop>Save</tabstop>
<tabstop>scrollArea</tabstop>
<tabstop>PID1</tabstop>
<tabstop>Input1</tabstop>
<tabstop>MinPID1</tabstop>
<tabstop>MaxPID1</tabstop>
<tabstop>PID2</tabstop>
<tabstop>Input2</tabstop>
<tabstop>MinPID2</tabstop>
<tabstop>MaxPID2</tabstop>
<tabstop>PID3</tabstop>
<tabstop>Input3</tabstop>
<tabstop>MinPID3</tabstop>
<tabstop>MaxPID3</tabstop>
<tabstop>ThrottleMin</tabstop>
<tabstop>ThrottleMax</tabstop>
<tabstop>UpdateMode</tabstop>
</tabstops>
<resources/>
<connections/>
</ui>
<?xml version="1.0" encoding="UTF-8"?>
<ui version="4.0">
<class>TxPIDWidget</class>
<widget class="QWidget" name="TxPIDWidget">
<property name="geometry">
<rect>
<x>0</x>
<y>0</y>
<width>720</width>
<height>567</height>
</rect>
</property>
<property name="windowTitle">
<string>Form</string>
</property>
<layout class="QVBoxLayout" name="verticalLayout_3">
<item>
<widget class="QScrollArea" name="scrollArea">
<property name="frameShape">
<enum>QFrame::NoFrame</enum>
</property>
<property name="widgetResizable">
<bool>true</bool>
</property>
<widget class="QWidget" name="scrollAreaWidgetContents_2">
<property name="geometry">
<rect>
<x>0</x>
<y>0</y>
<width>696</width>
<height>475</height>
</rect>
</property>
<layout class="QVBoxLayout" name="verticalLayout_2">
<item>
<widget class="QCheckBox" name="TxPIDEnable">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>This module will periodically update values of stabilization PID settings
depending on configured input control channels. New values of stabilization
settings are not saved to flash, but updated in RAM. It is expected that the
module will be enabled only for tuning. When desired values are found, they
can be read via GCS and saved permanently. Then this module should be
disabled again.
Up to 3 separate PID options (or option pairs) can be selected and updated.</string>
</property>
<property name="text">
<string>Enable TxPID module</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="label_7">
<property name="text">
<string>After enabling the module, you must power cycle before using and configuring.</string>
</property>
</widget>
</item>
<item>
<widget class="Line" name="line">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
</widget>
</item>
<item>
<spacer name="verticalSpacer_2">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Preferred</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>10</height>
</size>
</property>
</spacer>
</item>
<item>
<widget class="QGroupBox" name="groupBox_6">
<property name="enabled">
<bool>true</bool>
</property>
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Minimum">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>100</height>
</size>
</property>
<property name="title">
<string>Module Settings</string>
</property>
<layout class="QGridLayout" name="gridLayout">
<item row="1" column="1">
<widget class="QLabel" name="label_51">
<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 option</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="1" column="2">
<widget class="QLabel" name="label_50">
<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>Control Source</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="1" column="3">
<widget class="QLabel" name="label_49">
<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>Min</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="1" column="4">
<widget class="QLabel" name="label">
<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>Max</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="2" column="0">
<widget class="QLabel" name="label_47">
<property name="text">
<string>Instance 1</string>
</property>
</widget>
</item>
<item row="2" column="1">
<widget class="QComboBox" name="PID1">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Select PID option or option pair to update.
Set to Disabled if not used.</string>
</property>
</widget>
</item>
<item row="2" column="2">
<widget class="QComboBox" name="Input1">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Select input used as a control source for this instance.
It can be one of Accessory channels or Throttle channel.
If Accessory channel is chosen then its range [0..1] will be mapped
to PID range [Min..Max] defined for this instance.
If Throttle channel is chosen then Throttle range [Min..Max] will
be mapped to PID range [Min..Max] defined for this instance. If
Throttle is out of bounds then PID Min and Max values will be used
accordingly.
Note that it is possible to set PID Min &gt; Max. In that case increasing
control input value will decrease the PID option value. This can be
used, for instance, to decrease PID value when increasing Throttle.</string>
</property>
</widget>
</item>
<item row="2" column="3">
<widget class="QDoubleSpinBox" name="MinPID1">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Minimum PID value mapped to Accessory channel = 0 or
Throttle channel lesser or equal to Throttle Min value.</string>
</property>
<property name="decimals">
<number>6</number>
</property>
<property name="singleStep">
<double>0.000100000000000</double>
</property>
</widget>
</item>
<item row="2" column="4">
<widget class="QDoubleSpinBox" name="MaxPID1">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Maximum PID value mapped to Accessory channel = 1 or
Throttle channel greater or equal to Throttle Max value.</string>
</property>
<property name="decimals">
<number>6</number>
</property>
<property name="singleStep">
<double>0.000100000000000</double>
</property>
</widget>
</item>
<item row="3" column="0">
<widget class="QLabel" name="label_48">
<property name="text">
<string>Instance 2</string>
</property>
</widget>
</item>
<item row="3" column="1">
<widget class="QComboBox" name="PID2">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Select PID option or option pair to update.
Set to Disabled if not used.</string>
</property>
</widget>
</item>
<item row="3" column="2">
<widget class="QComboBox" name="Input2">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Select input used as a control source for this instance.
It can be one of Accessory channels or Throttle channel.
If Accessory channel is chosen then its range [0..1] will be mapped
to PID range [Min..Max] defined for this instance.
If Throttle channel is chosen then Throttle range [Min..Max] will
be mapped to PID range [Min..Max] defined for this instance. If
Throttle is out of bounds then PID Min and Max values will be used
accordingly.
Note that it is possible to set PID Min &gt; Max. In that case increasing
control input value will decrease the PID option value. This can be
used, for instance, to decrease PID value when increasing Throttle.</string>
</property>
</widget>
</item>
<item row="3" column="3">
<widget class="QDoubleSpinBox" name="MinPID2">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Minimum PID value mapped to Accessory channel = 0 or
Throttle channel lesser or equal to Throttle Min value.</string>
</property>
<property name="decimals">
<number>6</number>
</property>
<property name="singleStep">
<double>0.000100000000000</double>
</property>
</widget>
</item>
<item row="3" column="4">
<widget class="QDoubleSpinBox" name="MaxPID2">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Maximum PID value mapped to Accessory channel = 1 or
Throttle channel greater or equal to Throttle Max value.</string>
</property>
<property name="decimals">
<number>6</number>
</property>
<property name="singleStep">
<double>0.000100000000000</double>
</property>
</widget>
</item>
<item row="4" column="0">
<widget class="QLabel" name="label_52">
<property name="text">
<string>Instance 3</string>
</property>
</widget>
</item>
<item row="4" column="1">
<widget class="QComboBox" name="PID3">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Select PID option or option pair to update.
Set to Disabled if not used.</string>
</property>
</widget>
</item>
<item row="4" column="2">
<widget class="QComboBox" name="Input3">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Select input used as a control source for this instance.
It can be one of Accessory channels or Throttle channel.
If Accessory channel is chosen then its range [0..1] will be mapped
to PID range [Min..Max] defined for this instance.
If Throttle channel is chosen then Throttle range [Min..Max] will
be mapped to PID range [Min..Max] defined for this instance. If
Throttle is out of bounds then PID Min and Max values will be used
accordingly.
Note that it is possible to set PID Min &gt; Max. In that case increasing
control input value will decrease the PID option value. This can be
used, for instance, to decrease PID value when increasing Throttle.</string>
</property>
</widget>
</item>
<item row="4" column="3">
<widget class="QDoubleSpinBox" name="MinPID3">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Minimum PID value mapped to Accessory channel = 0 or
Throttle channel lesser or equal to Throttle Min value.</string>
</property>
<property name="decimals">
<number>6</number>
</property>
<property name="singleStep">
<double>0.000100000000000</double>
</property>
</widget>
</item>
<item row="4" column="4">
<widget class="QDoubleSpinBox" name="MaxPID3">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Maximum PID value mapped to Accessory channel = 1 or
Throttle channel greater or equal to Throttle Max value.</string>
</property>
<property name="decimals">
<number>6</number>
</property>
<property name="singleStep">
<double>0.000100000000000</double>
</property>
</widget>
</item>
<item row="8" column="0">
<widget class="QLabel" name="label_2">
<property name="text">
<string>Update Mode</string>
</property>
</widget>
</item>
<item row="8" column="1">
<widget class="QComboBox" name="UpdateMode">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>PID values update mode which can be set to:
- Never: this disables PID updates (but module still will be run if enabled),
- When Armed: PID updated only when system is armed,
- Always: PID updated always regardless of arm state.
Since the GCS updates GUI PID values in real time on change, could be
tricky to change other PID values from the GUI if the module is enabled
and constantly updates stabilization settings object. As a workaround,
this option can be used to temporarily disable updates or enable them
only when system is armed without disabling the module.</string>
</property>
</widget>
</item>
<item row="7" column="0">
<widget class="QLabel" name="label_3">
<property name="text">
<string>Throttle Range</string>
</property>
</widget>
</item>
<item row="7" column="1">
<widget class="QDoubleSpinBox" name="ThrottleMin">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Throttle channel lower bound mapped to PID Min value</string>
</property>
<property name="maximum">
<double>1.000000000000000</double>
</property>
<property name="singleStep">
<double>0.010000000000000</double>
</property>
</widget>
</item>
<item row="7" column="2">
<widget class="QDoubleSpinBox" name="ThrottleMax">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Throttle channel upper bound mapped to PID Max value</string>
</property>
<property name="maximum">
<double>1.000000000000000</double>
</property>
<property name="singleStep">
<double>0.010000000000000</double>
</property>
</widget>
</item>
<item row="6" column="1">
<widget class="QLabel" name="label_4">
<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>Min</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="6" column="2">
<widget class="QLabel" name="label_5">
<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>Max</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="5" column="1">
<spacer name="verticalSpacer_3">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Preferred</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
</layout>
</widget>
</item>
<item>
<spacer name="verticalSpacer">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
</layout>
</widget>
</widget>
</item>
<item>
<layout class="QVBoxLayout" name="verticalLayout">
<item>
<widget class="QLabel" name="message">
<property name="text">
<string/>
</property>
</widget>
</item>
<item>
<layout class="QHBoxLayout" name="submitButtons">
<item>
<widget class="QFrame" name="frame">
<property name="frameShape">
<enum>QFrame::StyledPanel</enum>
</property>
<property name="frameShadow">
<enum>QFrame::Raised</enum>
</property>
</widget>
</item>
<item>
<spacer name="horizontalSpacer">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item>
<widget class="QPushButton" name="Apply">
<property name="toolTip">
<string>Send settings to the board but do not save to the non-volatile memory</string>
</property>
<property name="text">
<string>Apply</string>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="Save">
<property name="toolTip">
<string>Send settings to the board and save to the non-volatile memory</string>
</property>
<property name="text">
<string>Save</string>
</property>
<property name="checked">
<bool>false</bool>
</property>
</widget>
</item>
</layout>
</item>
</layout>
</item>
</layout>
</widget>
<tabstops>
<tabstop>TxPIDEnable</tabstop>
<tabstop>Apply</tabstop>
<tabstop>Save</tabstop>
<tabstop>scrollArea</tabstop>
<tabstop>PID1</tabstop>
<tabstop>Input1</tabstop>
<tabstop>MinPID1</tabstop>
<tabstop>MaxPID1</tabstop>
<tabstop>PID2</tabstop>
<tabstop>Input2</tabstop>
<tabstop>MinPID2</tabstop>
<tabstop>MaxPID2</tabstop>
<tabstop>PID3</tabstop>
<tabstop>Input3</tabstop>
<tabstop>MinPID3</tabstop>
<tabstop>MaxPID3</tabstop>
<tabstop>ThrottleMin</tabstop>
<tabstop>ThrottleMax</tabstop>
<tabstop>UpdateMode</tabstop>
</tabstops>
<resources/>
<connections/>
</ui>

View File

@ -124,6 +124,17 @@ void ModeManager::activateMode(const QString &id)
m_modeStack->setCurrentIndex(index);
}
void ModeManager::activateModeByWorkspaceName(const QString &id)
{
for (int i = 0; i < m_modes.count(); ++i) {
if (m_modes.at(i)->name() == id)
{
m_modeStack->setCurrentIndex(i);
return;
}
}
}
void ModeManager::objectAdded(QObject *obj)
{
IMode *mode = Aggregation::query<IMode>(obj);

View File

@ -80,6 +80,7 @@ signals:
public slots:
void activateMode(const QString &id);
void activateModeByWorkspaceName(const QString &id);
void setFocusToCurrentMode();
private slots:

View File

@ -308,13 +308,7 @@ void FGSimulator::processUpdate(const QByteArray& inp)
double ECEF[3];
double RNE[9];
Utils::CoordinateConversions().RneFromLLA(LLA,(double (*)[3])RNE);
for (int t=0;t<9;t++) {
homeData.RNE[t]=RNE[t];
}
Utils::CoordinateConversions().LLA2ECEF(LLA,ECEF);
homeData.ECEF[0]=ECEF[0]*100;
homeData.ECEF[1]=ECEF[1]*100;
homeData.ECEF[2]=ECEF[2]*100;
homeData.Be[0]=0;
homeData.Be[1]=0;
homeData.Be[2]=0;
@ -335,7 +329,7 @@ void FGSimulator::processUpdate(const QByteArray& inp)
memset(&positionActualData, 0, sizeof(PositionActual::DataFields));
positionActualData.North = 0; //Currently hardcoded as there is no way of setting up a reference point to calculate distance
positionActualData.East = 0; //Currently hardcoded as there is no way of setting up a reference point to calculate distance
positionActualData.Down = (altitude * 100); //Multiply by 100 because positionActual expects input in Centimeters.
positionActualData.Down = altitude ; //Multiply by 1 because positionActual expects input in meters.
posActual->setData(positionActualData);
// Update AltitudeActual object
@ -371,26 +365,39 @@ void FGSimulator::processUpdate(const QByteArray& inp)
gpsPos->setData(gpsData);
float NED[3];
double LLA[3] = {(double) gpsData.Latitude / 1e7, (double) gpsData.Longitude / 1e7, (double) (gpsData.GeoidSeparation + gpsData.Altitude)};
// convert from cm back to meters
double ECEF[3] = {(double) (homeData.ECEF[0] / 100), (double) (homeData.ECEF[1] / 100), (double) (homeData.ECEF[2] / 100)};
Utils::CoordinateConversions().LLA2Base(LLA, ECEF, (float (*)[3]) homeData.RNE, NED);
positionActualData.North = NED[0]*100; //Currently hardcoded as there is no way of setting up a reference point to calculate distance
positionActualData.East = NED[1]*100; //Currently hardcoded as there is no way of setting up a reference point to calculate distance
positionActualData.Down = NED[2]*100; //Multiply by 100 because positionActual expects input in Centimeters.
double hLLA[3] = {(double) homeData.Latitude / 1e7, (double) homeData.Longitude / 1e7, (double) (homeData.Altitude)};
double ECEF[3];
double RNE[9];
Utils::CoordinateConversions().RneFromLLA(hLLA,(double (*)[3])RNE);
Utils::CoordinateConversions().LLA2ECEF(hLLA,ECEF);
Utils::CoordinateConversions().LLA2Base(hLLA, ECEF, (float (*)[3]) RNE, NED);
positionActualData.North = NED[0]; //Currently hardcoded as there is no way of setting up a reference point to calculate distance
positionActualData.East = NED[1]; //Currently hardcoded as there is no way of setting up a reference point to calculate distance
positionActualData.Down = NED[2]; //Multiply by 1 because positionActual expects input in meters.
posActual->setData(positionActualData);
// Update AttitudeRaw object (filtered gyros only for now)
AttitudeRaw::DataFields rawData;
memset(&rawData, 0, sizeof(AttitudeRaw::DataFields));
rawData = attRaw->getData();
rawData.gyros[0] = rollRate;
//AttitudeRaw::DataFields rawData;
//AttitudeRaw::DataFields rawData;
Gyros::DataFields gyroData;
Accels::DataFields accelData;
memset(&gyroData, 0, sizeof(Gyros::DataFields));
memset(&accelData, 0, sizeof(Accels::DataFields));
gyroData = gyros->getData();
accelData = accels->getData();
//rawData.gyros[0] = rollRate;
//rawData.gyros[1] = cos(DEG2RAD * roll) * pitchRate + sin(DEG2RAD * roll) * yawRate;
//rawData.gyros[2] = cos(DEG2RAD * roll) * yawRate - sin(DEG2RAD * roll) * pitchRate;
rawData.gyros[1] = pitchRate;
rawData.gyros[2] = yawRate;
attRaw->setData(rawData);
//rawData.gyros[1] = pitchRate;
//rawData.gyros[2] = yawRate;
gyroData.x = rollRate;
gyroData.y = pitchRate;
gyroData.z = yawRate;
// TODO: Accels are still missing!!!!
gyros->setData(gyroData);
// attRaw->updated();
}

View File

@ -263,35 +263,45 @@ void IL2Simulator::processUpdate(const QByteArray& inp)
// Update positionActual objects
PositionActual::DataFields posData;
memset(&posData, 0, sizeof(PositionActual::DataFields));
posData.North = current.Y*100;
posData.East = current.X*100;
posData.Down = current.Z*-100;
posData.North = current.Y;
posData.East = current.X;
posData.Down = current.Z*-1.;
// Update velocityActual objects
VelocityActual::DataFields velData;
memset(&velData, 0, sizeof(VelocityActual::DataFields));
velData.North = current.dY*100;
velData.East = current.dX*100;
velData.Down = current.dZ*-100;
velData.North = current.dY;
velData.East = current.dX;
velData.Down = current.dZ*-1.;
// Update AttitudeRaw object (filtered gyros and accels only for now)
AttitudeRaw::DataFields rawData;
memset(&rawData, 0, sizeof(AttitudeRaw::DataFields));
rawData = attRaw->getData();
//AttitudeRaw::DataFields rawData;
//memset(&rawData, 0, sizeof(AttitudeRaw::DataFields));
//rawData = attRaw->getData();
Gyros::DataFields gyroData;
Accels::DataFields accelData;
memset(&gyroData, 0, sizeof(Gyros::DataFields));
memset(&accelData, 0, sizeof(Accels::DataFields));
gyroData = gyros->getData();
accelData = accels->getData();
// rotate turn rates and accelerations into body frame
// (note: rotation deltas are NOT in NED frame but in RPY - manual conversion!)
rawData.gyros[0] = current.dRoll;
rawData.gyros[1] = cos(DEG2RAD * current.roll) * current.dPitch + sin(DEG2RAD * current.roll) * current.dAzimuth;
rawData.gyros[2] = cos(DEG2RAD * current.roll) * current.dAzimuth - sin(DEG2RAD * current.roll) * current.dPitch;
gyroData.x = current.dRoll;
gyroData.y = cos(DEG2RAD * current.roll) * current.dPitch + sin(DEG2RAD * current.roll) * current.dAzimuth;
gyroData.z = cos(DEG2RAD * current.roll) * current.dAzimuth - sin(DEG2RAD * current.roll) * current.dPitch;
// accels are in NED and can be converted using standard ned->local rotation matrix
float Rbe[3][3];
Utils::CoordinateConversions().Quaternion2R(quat,Rbe);
for (int t=0;t<3;t++) {
rawData.accels[t]=current.ddX*Rbe[t][0]
+current.ddY*Rbe[t][1]
+(current.ddZ+GEE)*Rbe[t][2];
}
rawData.accels[2]=-rawData.accels[2];
accelData.x = current.ddX*Rbe[0][0]
+current.ddY*Rbe[0][1]
+(current.ddZ+GEE)*Rbe[0][2];
accelData.y = current.ddX*Rbe[1][0]
+current.ddY*Rbe[1][1]
+(current.ddZ+GEE)*Rbe[1][2];
accelData.z = - (current.ddX*Rbe[2][0]
+current.ddY*Rbe[2][1]
+(current.ddZ+GEE)*Rbe[2][2]);
// Update homelocation
HomeLocation::DataFields homeData;
@ -307,13 +317,7 @@ void IL2Simulator::processUpdate(const QByteArray& inp)
double ECEF[3];
double RNE[9];
Utils::CoordinateConversions().RneFromLLA(LLA,(double (*)[3])RNE);
for (int t=0;t<9;t++) {
homeData.RNE[t]=RNE[t];
}
Utils::CoordinateConversions().LLA2ECEF(LLA,ECEF);
homeData.ECEF[0]=ECEF[0]*100;
homeData.ECEF[1]=ECEF[1]*100;
homeData.ECEF[2]=ECEF[2]*100;
homeData.Be[0]=0;
homeData.Be[1]=0;
homeData.Be[2]=0;
@ -339,7 +343,9 @@ void IL2Simulator::processUpdate(const QByteArray& inp)
// update every time (50ms)
attActual->setData(attActualData);
//attActual->updated();
attRaw->setData(rawData);
//attRaw->setData(rawData);
gyros->setData(gyroData);
accels->setData(accelData);
//attRaw->updated();
velActual->setData(velData);
//velActual->updated();

View File

@ -49,7 +49,7 @@ Simulator::Simulator(const SimulatorSettings& params) :
outSocket(NULL),
settings(params),
updatePeriod(50),
simTimeout(2000),
simTimeout(8000),
autopilotConnectionStatus(false),
simConnectionStatus(false),
txTimer(NULL),
@ -131,7 +131,8 @@ void Simulator::onStart()
posActual = PositionActual::GetInstance(objManager);
altActual = BaroAltitude::GetInstance(objManager);
attActual = AttitudeActual::GetInstance(objManager);
attRaw = AttitudeRaw::GetInstance(objManager);
accels = Accels::GetInstance(objManager);
gyros = Gyros::GetInstance(objManager);
gpsPos = GPSPosition::GetInstance(objManager);
telStats = GCSTelemetryStats::GetInstance(objManager);
@ -225,7 +226,8 @@ void Simulator::setupObjects()
setupOutputObject(posActual, 250);
setupOutputObject(velActual, 250);
setupOutputObject(posHome, 1000);
setupOutputObject(attRaw, 10);
setupOutputObject(accels, 10);
setupOutputObject(gyros, 10);
//setupOutputObject(attRaw, 100);

View File

@ -44,7 +44,8 @@
#include "attitudeactual.h"
#include "gpsposition.h"
#include "homelocation.h"
#include "attituderaw.h"
#include "accels.h"
#include "gyros.h"
#include "gcstelemetrystats.h"
#include "flightstatus.h"
@ -177,7 +178,8 @@ protected:
VelocityActual* velActual;
PositionActual* posActual;
HomeLocation* posHome;
AttitudeRaw* attRaw;
Accels* accels;
Gyros* gyros;
GPSPosition* gpsPos;
GCSTelemetryStats* telStats;

View File

@ -306,13 +306,7 @@ void XplaneSimulator::processUpdate(const QByteArray& dataBuf)
double ECEF[3];
double RNE[9];
Utils::CoordinateConversions().RneFromLLA(LLA,(double (*)[3])RNE);
for (int t=0;t<9;t++) {
homeData.RNE[t]=RNE[t];
}
Utils::CoordinateConversions().LLA2ECEF(LLA,ECEF);
homeData.ECEF[0]=ECEF[0]*100;
homeData.ECEF[1]=ECEF[1]*100;
homeData.ECEF[2]=ECEF[2]*100;
homeData.Be[0]=0;
homeData.Be[1]=0;
homeData.Be[2]=0;
@ -368,33 +362,45 @@ void XplaneSimulator::processUpdate(const QByteArray& dataBuf)
// Update VelocityActual.{Nort,East,Down}
VelocityActual::DataFields velocityActualData;
memset(&velocityActualData, 0, sizeof(VelocityActual::DataFields));
velocityActualData.North = velY*100;
velocityActualData.East = velX*100;
velocityActualData.Down = -velZ*100;
velocityActualData.North = velY;
velocityActualData.East = velX;
velocityActualData.Down = -velZ;
velActual->setData(velocityActualData);
// Update PositionActual.{Nort,East,Down}
PositionActual::DataFields positionActualData;
memset(&positionActualData, 0, sizeof(PositionActual::DataFields));
positionActualData.North = (dstY-initY)*100;
positionActualData.East = (dstX-initX)*100;
positionActualData.Down = -(dstZ-initZ)*100;
positionActualData.North = (dstY-initY);
positionActualData.East = (dstX-initX);
positionActualData.Down = -(dstZ-initZ);
posActual->setData(positionActualData);
// Update AttitudeRaw object (filtered gyros only for now)
AttitudeRaw::DataFields rawData;
memset(&rawData, 0, sizeof(AttitudeRaw::DataFields));
rawData = attRaw->getData();
rawData.gyros[0] = rollRate;
//AttitudeRaw::DataFields rawData;
//memset(&rawData, 0, sizeof(AttitudeRaw::DataFields));
//rawData = attRaw->getData();
//rawData.gyros[0] = rollRate;
//rawData.gyros_filtered[1] = cos(DEG2RAD * roll) * pitchRate + sin(DEG2RAD * roll) * yawRate;
//rawData.gyros_filtered[2] = cos(DEG2RAD * roll) * yawRate - sin(DEG2RAD * roll) * pitchRate;
rawData.gyros[1] = pitchRate;
rawData.gyros[2] = yawRate;
rawData.accels[0] = accX;
rawData.accels[1] = accY;
rawData.accels[2] = -accZ;
attRaw->setData(rawData);
//rawData.gyros[1] = pitchRate;
//rawData.gyros[2] = yawRate;
//rawData.accels[0] = accX;
//rawData.accels[1] = accY;
//rawData.accels[2] = -accZ;
//attRaw->setData(rawData);
Gyros::DataFields gyroData;
memset(&gyroData, 0, sizeof(Gyros::DataFields));
gyroData.x = rollRate;
gyroData.y = pitchRate;
gyroData.z = yawRate;
gyros->setData(gyroData);
Accels::DataFields accelData;
memset(&accelData, 0, sizeof(Accels::DataFields));
accelData.x = accX;
accelData.y = accY;
accelData.z = -accZ;
accels->setData(accelData);
}
// issue manual update

View File

@ -0,0 +1,468 @@
#include "aerosimrc.h"
#include <extensionsystem/pluginmanager.h>
#include <coreplugin/icore.h>
#include <coreplugin/threadmanager.h>
AeroSimRCSimulator::AeroSimRCSimulator(const SimulatorSettings &params)
: Simulator(params)
{
udpCounterASrecv = 0;
}
AeroSimRCSimulator::~AeroSimRCSimulator()
{
}
bool AeroSimRCSimulator::setupProcess()
{
QMutexLocker locker(&lock);
return true;
}
void AeroSimRCSimulator::setupUdpPorts(const QString &host, int inPort, int outPort)
{
Q_UNUSED(outPort)
if (inSocket->bind(QHostAddress(host), inPort))
emit processOutput("Successfully bound to address " + host + ", port " + QString::number(inPort) + "\n");
else
emit processOutput("Cannot bind to address " + host + ", port " + QString::number(inPort) + "\n");
}
void AeroSimRCSimulator::transmitUpdate()
{
// read actuator output
ActuatorCommand::DataFields actCmdData;
actCmdData = actCommand->getData();
float channels[10];
for (int i = 0; i < 10; ++i) {
qint16 ch = actCmdData.Channel[i];
float out = -1.0;
if (ch >= 1000 && ch <= 2000) {
ch -= 1000;
out = ((float)ch / 500.0) - 1.0;
}
channels[i] = out;
}
// read flight status
FlightStatus::DataFields flightData;
flightData = flightStatus->getData();
quint8 armed;
quint8 mode;
armed = flightData.Armed;
mode = flightData.FlightMode;
QByteArray data;
// 50 - current size of values, 4(quint32) + 10*4(float) + 2(quint8) + 4(quint32)
data.resize(50);
QDataStream stream(&data, QIODevice::WriteOnly);
stream.setFloatingPointPrecision(QDataStream::SinglePrecision);
stream << quint32(0x52434D44); // magic header, "RCMD"
for (int i = 0; i < 10; ++i)
stream << channels[i]; // channels
stream << armed << mode; // flight status
stream << udpCounterASrecv; // packet counter
if (outSocket->writeDatagram(data, QHostAddress(settings.remoteAddress), settings.outPort) == -1) {
qDebug() << "write failed: " << outSocket->errorString();
}
#ifdef DBG_TIMERS
static int cntTX = 0;
if (cntTX >= 100) {
qDebug() << "TX=" << 1000.0 * 100 / timeTX.restart();
cntTX = 0;
} else {
++cntTX;
}
#endif
}
void AeroSimRCSimulator::processUpdate(const QByteArray &data)
{
// check size
if (data.size() > 188) {
qDebug() << "!!! big datagram: " << data.size();
return;
}
QByteArray buf = data;
QDataStream stream(&buf, QIODevice::ReadOnly);
stream.setFloatingPointPrecision(QDataStream::SinglePrecision);
// check magic header
quint32 magic;
stream >> magic;
if (magic != 0x4153494D) { // "AERO"
qDebug() << "wrong magic: " << magic << ", correct: " << quint32(0x4153494D);
return;
}
float timeStep,
homeX, homeY, homeZ,
WpHX, WpHY, WpLat, WpLon,
posX, posY, posZ, // world
velX, velY, velZ, // world
angX, angY, angZ, // model
accX, accY, accZ, // model
lat, lon, agl, // world
yaw, pitch, roll, // model
volt, curr,
rx, ry, rz, fx, fy, fz, ux, uy, uz, // matrix
ch[8];
stream >> timeStep;
stream >> homeX >> homeY >> homeZ;
stream >> WpHX >> WpHY >> WpLat >> WpLon;
stream >> posX >> posY >> posZ;
stream >> velX >> velY >> velZ;
stream >> angX >> angY >> angZ;
stream >> accX >> accY >> accZ;
stream >> lat >> lon >> agl;
stream >> yaw >> pitch >> roll;
stream >> volt >> curr;
stream >> rx >> ry >> rz >> fx >> fy >> fz >> ux >> uy >> uz;
stream >> ch[0] >> ch[1] >> ch[2] >> ch[3] >> ch[4] >> ch[5] >> ch[6] >> ch[7];
stream >> udpCounterASrecv;
/**********************************************************************************************/
QTime currentTime = QTime::currentTime();
/**********************************************************************************************/
static bool firstRun = true;
if (settings.homeLocation) {
if (firstRun) {
HomeLocation::DataFields homeData;
homeData = posHome->getData();
homeData.Latitude = WpLat * 10e6;
homeData.Longitude = WpLon * 10e6;
homeData.Altitude = homeZ;
homeData.Set = HomeLocation::SET_TRUE;
posHome->setData(homeData);
firstRun = false;
}
if (settings.homeLocRate > 0) {
static QTime homeLocTime = currentTime;
if (homeLocTime.secsTo(currentTime) >= settings.homeLocRate) {
firstRun = true;
homeLocTime = currentTime;
}
}
}
/**********************************************************************************************/
if (settings.attRaw || settings.attActual) {
QMatrix4x4 mat;
mat = QMatrix4x4( fy, fx, -fz, 0.0, // model matrix
ry, rx, -rz, 0.0, // (X,Y,Z) -> (+Y,+X,-Z)
-uy, -ux, uz, 0.0,
0.0, 0.0, 0.0, 1.0);
mat.optimize();
QQuaternion quat; // model quat
asMatrix2Quat(mat, quat);
// rotate gravity
QVector3D acc = QVector3D(accY, accX, -accZ); // accel (X,Y,Z) -> (+Y,+X,-Z)
QVector3D gee = QVector3D(0.0, 0.0, -GEE);
QQuaternion qWorld = quat.conjugate();
gee = qWorld.rotatedVector(gee);
acc += gee;
/*************************************************************************************/
if (settings.attRaw) {
Accels::DataFields accelsData;
accelsData = accels->getData();
Gyros::DataFields gyrosData;
gyrosData = gyros->getData();
gyrosData.x = angY * RAD2DEG; // gyros (X,Y,Z) -> (+Y,+X,-Z)
gyrosData.y = angX * RAD2DEG;
gyrosData.z = angZ * -RAD2DEG;
accelsData.x = acc.x();
accelsData.y = acc.y();
accelsData.z = acc.z();
accels->setData(accelsData);
gyros->setData(gyrosData);
}
/*************************************************************************************/
if (settings.attActHW) {
// do nothing
/*****************************************/
} else if (settings.attActSim) {
// take all data from simulator
AttitudeActual::DataFields attActData;
attActData = attActual->getData();
QVector3D rpy; // model roll, pitch, yaw
asMatrix2RPY(mat, rpy);
attActData.Roll = rpy.x();
attActData.Pitch = rpy.y();
attActData.Yaw = rpy.z();
attActData.q1 = quat.scalar();
attActData.q2 = quat.x();
attActData.q3 = quat.y();
attActData.q4 = quat.z();
attActual->setData(attActData);
/*****************************************/
} else if (settings.attActCalc) {
// calculate RPY with code from Attitude module
AttitudeActual::DataFields attActData;
attActData = attActual->getData();
static float q[4] = {1, 0, 0, 0};
static float gyro_correct_int2 = 0;
float dT = timeStep;
AttitudeSettings::DataFields attSettData = attSettings->getData();
float accelKp = attSettData.AccelKp * 0.1666666666666667;
float accelKi = attSettData.AccelKp * 0.1666666666666667;
float yawBiasRate = attSettData.YawBiasRate;
// calibrate sensors on arming
if (flightStatus->getData().Armed == FlightStatus::ARMED_ARMING) {
accelKp = 2.0;
accelKi = 0.9;
}
float gyro[3] = {angY * RAD2DEG, angX * RAD2DEG, angZ * -RAD2DEG};
float attRawAcc[3] = {acc.x(), acc.y(), acc.z()};
// code from Attitude module begin ///////////////////////////////
float *accels = attRawAcc;
float grot[3];
float accel_err[3];
// Rotate gravity to body frame and cross with accels
grot[0] = -(2 * (q[1] * q[3] - q[0] * q[2]));
grot[1] = -(2 * (q[2] * q[3] + q[0] * q[1]));
grot[2] = -(q[0] * q[0] - q[1]*q[1] - q[2]*q[2] + q[3]*q[3]);
// CrossProduct
{
accel_err[0] = accels[1]*grot[2] - grot[1]*accels[2];
accel_err[1] = grot[0]*accels[2] - accels[0]*grot[2];
accel_err[2] = accels[0]*grot[1] - grot[0]*accels[1];
}
// Account for accel magnitude
float accel_mag = sqrt(accels[0] * accels[0] + accels[1] * accels[1] + accels[2] * accels[2]);
accel_err[0] /= accel_mag;
accel_err[1] /= accel_mag;
accel_err[2] /= accel_mag;
// Accumulate integral of error. Scale here so that units are (deg/s) but Ki has units of s
gyro_correct_int2 += -gyro[2] * yawBiasRate;
// Correct rates based on error, integral component dealt with in updateSensors
gyro[0] += accel_err[0] * accelKp / dT;
gyro[1] += accel_err[1] * accelKp / dT;
gyro[2] += accel_err[2] * accelKp / dT + gyro_correct_int2;
// Work out time derivative from INSAlgo writeup
// Also accounts for the fact that gyros are in deg/s
float qdot[4];
qdot[0] = (-q[1] * gyro[0] - q[2] * gyro[1] - q[3] * gyro[2]) * dT * M_PI / 180 / 2;
qdot[1] = (+q[0] * gyro[0] - q[3] * gyro[1] + q[2] * gyro[2]) * dT * M_PI / 180 / 2;
qdot[2] = (+q[3] * gyro[0] + q[0] * gyro[1] - q[1] * gyro[2]) * dT * M_PI / 180 / 2;
qdot[3] = (-q[2] * gyro[0] + q[1] * gyro[1] + q[0] * gyro[2]) * dT * M_PI / 180 / 2;
// Take a time step
q[0] += qdot[0];
q[1] += qdot[1];
q[2] += qdot[2];
q[3] += qdot[3];
if(q[0] < 0) {
q[0] = -q[0];
q[1] = -q[1];
q[2] = -q[2];
q[3] = -q[3];
}
// Renomalize
float qmag = sqrt((q[0] * q[0]) + (q[1] * q[1]) + (q[2] * q[2]) + (q[3] * q[3]));
q[0] /= qmag;
q[1] /= qmag;
q[2] /= qmag;
q[3] /= qmag;
// If quaternion has become inappropriately short or is nan reinit.
// THIS SHOULD NEVER ACTUALLY HAPPEN
if((fabs(qmag) < 1e-3) || (qmag != qmag)) {
q[0] = 1;
q[1] = 0;
q[2] = 0;
q[3] = 0;
}
float rpy2[3];
// Quaternion2RPY
{
float q0s, q1s, q2s, q3s;
q0s = q[0] * q[0];
q1s = q[1] * q[1];
q2s = q[2] * q[2];
q3s = q[3] * q[3];
float R13, R11, R12, R23, R33;
R13 = 2 * (q[1] * q[3] - q[0] * q[2]);
R11 = q0s + q1s - q2s - q3s;
R12 = 2 * (q[1] * q[2] + q[0] * q[3]);
R23 = 2 * (q[2] * q[3] + q[0] * q[1]);
R33 = q0s - q1s - q2s + q3s;
rpy2[1] = RAD2DEG * asinf(-R13); // pitch always between -pi/2 to pi/2
rpy2[2] = RAD2DEG * atan2f(R12, R11);
rpy2[0] = RAD2DEG * atan2f(R23, R33);
}
attActData.Roll = rpy2[0];
attActData.Pitch = rpy2[1];
attActData.Yaw = rpy2[2];
attActData.q1 = q[0];
attActData.q2 = q[1];
attActData.q3 = q[2];
attActData.q4 = q[3];
attActual->setData(attActData);
/*****************************************/
}
}
/**********************************************************************************************/
if (settings.gcsReciever) {
static QTime gcsRcvrTime = currentTime;
if (!settings.manualOutput || gcsRcvrTime.msecsTo(currentTime) >= settings.outputRate) {
GCSReceiver::DataFields gcsRcvrData;
gcsRcvrData = gcsReceiver->getData();
for (int i = 0; i < 8; ++i)
gcsRcvrData.Channel[i] = 1500 + (ch[i] * 500);
gcsReceiver->setData(gcsRcvrData);
if (settings.manualOutput)
gcsRcvrTime = currentTime;
}
} else if (settings.manualControl) {
// not implemented yet
}
/**********************************************************************************************/
if (settings.gpsPosition) {
static QTime gpsPosTime = currentTime;
if (gpsPosTime.msecsTo(currentTime) >= settings.gpsPosRate) {
GPSPosition::DataFields gpsPosData;
gpsPosData = gpsPosition->getData();
gpsPosData.Altitude = posZ;
gpsPosData.Heading = yaw * RAD2DEG;
gpsPosData.Latitude = lat * 10e6;
gpsPosData.Longitude = lon * 10e6;
gpsPosData.Groundspeed = qSqrt(velX * velX + velY * velY);
gpsPosData.GeoidSeparation = 0.0;
gpsPosData.Satellites = 8;
gpsPosData.PDOP = 3.0;
gpsPosData.Status = GPSPosition::STATUS_FIX3D;
gpsPosition->setData(gpsPosData);
gpsPosTime = currentTime;
}
}
/**********************************************************************************************/
if (settings.sonarAltitude) {
static QTime sonarAltTime = currentTime;
if (sonarAltTime.msecsTo(currentTime) >= settings.sonarAltRate) {
SonarAltitude::DataFields sonarAltData;
sonarAltData = sonarAlt->getData();
float sAlt = settings.sonarMaxAlt;
// 0.35 rad ~= 20 degree
if ((agl < (sAlt * 2.0)) && (roll < 0.35) && (pitch < 0.35)) {
float x = agl * qTan(roll);
float y = agl * qTan(pitch);
float h = qSqrt(x*x + y*y + agl*agl);
sAlt = qMin(h, sAlt);
}
sonarAltData.Altitude = sAlt;
sonarAlt->setData(sonarAltData);
sonarAltTime = currentTime;
}
}
/**********************************************************************************************/
/*
BaroAltitude::DataFields altActData;
altActData = altActual->getData();
altActData.Altitude = posZ;
altActual->setData(altActData);
PositionActual::DataFields posActData;
posActData = posActual->getData();
posActData.North = posY * 100;
posActData.East = posX * 100;
posActData.Down = posZ * -100;
posActual->setData(posActData);
VelocityActual::DataFields velActData;
velActData = velActual->getData();
velActData.North = velY * 100;
velActData.East = velX * 100;
velActData.Down = velZ * 100;
velActual->setData(velActData);
*/
#ifdef DBG_TIMERS
static int cntRX = 0;
if (cntRX >= 100) {
qDebug() << "RX=" << 1000.0 * 100 / timeRX.restart();
cntRX = 0;
} else {
++cntRX;
}
#endif
}
// transfomations
void AeroSimRCSimulator::asMatrix2Quat(const QMatrix4x4 &m, QQuaternion &q)
{
qreal w, x, y, z;
// w always >= 0
w = qSqrt(qMax(0.0, 1.0 + m(0, 0) + m(1, 1) + m(2, 2))) / 2.0;
x = qSqrt(qMax(0.0, 1.0 + m(0, 0) - m(1, 1) - m(2, 2))) / 2.0;
y = qSqrt(qMax(0.0, 1.0 - m(0, 0) + m(1, 1) - m(2, 2))) / 2.0;
z = qSqrt(qMax(0.0, 1.0 - m(0, 0) - m(1, 1) + m(2, 2))) / 2.0;
x = copysign(x, (m(1, 2) - m(2, 1)));
y = copysign(y, (m(2, 0) - m(0, 2)));
z = copysign(z, (m(0, 1) - m(1, 0)));
q.setScalar(w);
q.setX(x);
q.setY(y);
q.setZ(z);
}
void AeroSimRCSimulator::asMatrix2RPY(const QMatrix4x4 &m, QVector3D &rpy)
{
qreal roll, pitch, yaw;
if (qFabs(m(0, 2)) > 0.998) {
// ~86.3°, gimbal lock
roll = 0.0;
pitch = copysign(M_PI_2, -m(0, 2));
yaw = qAtan2(-m(1, 0), m(1, 1));
} else {
roll = qAtan2(m(1, 2), m(2, 2));
pitch = qAsin(-m(0, 2));
yaw = qAtan2(m(0, 1), m(0, 0));
}
rpy.setX(roll * RAD2DEG);
rpy.setY(pitch * RAD2DEG);
rpy.setZ(yaw * RAD2DEG);
}

View File

@ -0,0 +1,46 @@
#ifndef AEROSIMRC_H
#define AEROSIMRC_H
#include <QObject>
#include <QVector3D>
#include <QQuaternion>
#include <QMatrix4x4>
#include "simulatorv2.h"
class AeroSimRCSimulator: public Simulator
{
Q_OBJECT
public:
AeroSimRCSimulator(const SimulatorSettings &params);
~AeroSimRCSimulator();
bool setupProcess();
void setupUdpPorts(const QString& host, int inPort, int outPort);
private slots:
void transmitUpdate();
private:
quint32 udpCounterASrecv; //keeps track of udp packets received by ASim
void processUpdate(const QByteArray &data);
void asMatrix2Quat(const QMatrix4x4 &m, QQuaternion &q);
void asMatrix2RPY(const QMatrix4x4 &m, QVector3D &rpy);
};
class AeroSimRCSimulatorCreator : public SimulatorCreator
{
public:
AeroSimRCSimulatorCreator(const QString &classId, const QString &description)
: SimulatorCreator (classId, description)
{}
Simulator* createSimulator(const SimulatorSettings &params)
{
return new AeroSimRCSimulator(params);
}
};
#endif // AEROSIMRC_H

View File

@ -0,0 +1,12 @@
<plugin name="HITLv2" version="1.0.0" compatVersion="1.0.0">
<vendor>The OpenPilot Project</vendor>
<copyright>(C) 2011 OpenPilot Project</copyright>
<license>The GNU Public License (GPL) Version 3</license>
<description>Hardware In The Loop Simulation (v2)</description>
<url>http://www.openpilot.org</url>
<dependencyList>
<dependency name="Core" version="1.0.0"/>
<dependency name="UAVObjects" version="1.0.0"/>
<dependency name="UAVTalk" version="1.0.0"/>
</dependencyList>
</plugin>

View File

@ -0,0 +1,27 @@
TEMPLATE = lib
TARGET = HITLV2
QT += network
include(../../openpilotgcsplugin.pri)
include(hitlv2_dependencies.pri)
HEADERS += \
aerosimrc.h \
hitlv2configuration.h \
hitlv2factory.h \
hitlv2gadget.h \
hitlv2optionspage.h \
hitlv2plugin.h \
hitlv2widget.h \
simulatorv2.h
SOURCES += \
aerosimrc.cpp \
hitlv2configuration.cpp \
hitlv2factory.cpp \
hitlv2gadget.cpp \
hitlv2optionspage.cpp \
hitlv2plugin.cpp \
hitlv2widget.cpp \
simulatorv2.cpp
OTHER_FILES += hitlv2.pluginspec
FORMS += \
hitlv2optionspage.ui \
hitlv2widget.ui

View File

@ -0,0 +1,4 @@
include(../../plugins/uavobjects/uavobjects.pri)
include(../../plugins/uavtalk/uavtalk.pri)
#include(../../plugins/coreplugin/coreplugin.pri)
#include(../../libs/utils/utils.pri)

View File

@ -0,0 +1,178 @@
/**
******************************************************************************
*
* @file hitlconfiguration.cpp
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @addtogroup GCSPlugins GCS Plugins
* @{
* @addtogroup HITLPlugin HITL Plugin
* @{
* @brief The Hardware In The Loop plugin
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#include "hitlv2configuration.h"
HITLConfiguration::HITLConfiguration(QString classId,
QSettings* qSettings,
QObject *parent)
: IUAVGadgetConfiguration(classId, parent)
{
// qDebug() << "HITLV2Configuration";
// default values
QString simulatorId = "";
QString hostAddress = "127.0.0.1";
int inPort = 40100;
QString remoteAddress = "127.0.0.1";
int outPort = 40200;
QString binPath = "";
QString dataPath = "";
bool homeLocation = true;
quint16 homeLocRate = 0;
bool attRaw = true;
quint8 attRawRate = 20;
bool attActual = true;
bool attActHW = false;
bool attActSim = true;
bool attActCalc = false;
bool sonarAltitude = false;
float sonarMaxAlt = 5.0;
quint16 sonarAltRate = 50;
bool gpsPosition = true;
quint16 gpsPosRate = 200;
bool inputCommand = true;
bool gcsReciever = true;
bool manualControl = false;
bool manualOutput = false;
quint8 outputRate = 20;
// if a saved configuration exists load it
if (qSettings != 0) {
settings.simulatorId = qSettings->value("simulatorId", simulatorId).toString();
settings.hostAddress = qSettings->value("hostAddress", hostAddress).toString();
settings.inPort = qSettings->value("inPort", inPort).toInt();
settings.remoteAddress = qSettings->value("remoteAddress", remoteAddress).toString();
settings.outPort = qSettings->value("outPort", outPort).toInt();
settings.binPath = qSettings->value("binPath", binPath).toString();
settings.dataPath = qSettings->value("dataPath", dataPath).toString();
settings.homeLocation = qSettings->value("homeLocation", homeLocation).toBool();
settings.homeLocRate = qSettings->value("homeLocRate", homeLocRate).toInt();
settings.attRaw = qSettings->value("attRaw", attRaw).toBool();
settings.attRawRate = qSettings->value("attRawRate", attRawRate).toInt();
settings.attActual = qSettings->value("attActual", attActual).toBool();
settings.attActHW = qSettings->value("attActHW", attActHW).toBool();
settings.attActSim = qSettings->value("attActSim", attActSim).toBool();
settings.attActCalc = qSettings->value("attActCalc", attActCalc).toBool();
settings.sonarAltitude = qSettings->value("sonarAltitude", sonarAltitude).toBool();
settings.sonarMaxAlt = qSettings->value("sonarMaxAlt", sonarMaxAlt).toFloat();
settings.sonarAltRate = qSettings->value("sonarAltRate", sonarAltRate).toInt();
settings.gpsPosition = qSettings->value("gpsPosition", gpsPosition).toBool();
settings.gpsPosRate = qSettings->value("gpsPosRate", gpsPosRate).toInt();
settings.inputCommand = qSettings->value("inputCommand", inputCommand).toBool();
settings.gcsReciever = qSettings->value("gcsReciever", gcsReciever).toBool();
settings.manualControl = qSettings->value("manualControl", manualControl).toBool();
settings.manualOutput = qSettings->value("manualOutput", manualOutput).toBool();
settings.outputRate = qSettings->value("outputRate", outputRate).toInt();
} else {
settings.simulatorId = simulatorId;
settings.hostAddress = hostAddress;
settings.inPort = inPort;
settings.remoteAddress = remoteAddress;
settings.outPort = outPort;
settings.binPath = binPath;
settings.dataPath = dataPath;
settings.homeLocation = homeLocation;
settings.homeLocRate = homeLocRate;
settings.attRaw = attRaw;
settings.attRawRate = attRawRate;
settings.attActual = attActual;
settings.attActHW = attActHW;
settings.attActSim = attActSim;
settings.attActCalc = attActCalc;
settings.sonarAltitude = sonarAltitude;
settings.sonarMaxAlt = sonarMaxAlt;
settings.sonarAltRate = sonarAltRate;
settings.gpsPosition = gpsPosition;
settings.gpsPosRate = gpsPosRate;
settings.inputCommand = inputCommand;
settings.gcsReciever = gcsReciever;
settings.manualControl = manualControl;
settings.manualOutput = manualOutput;
settings.outputRate = outputRate;
}
}
IUAVGadgetConfiguration *HITLConfiguration::clone()
{
HITLConfiguration *m = new HITLConfiguration(this->classId());
m->settings = settings;
return m;
}
void HITLConfiguration::saveConfig(QSettings* qSettings) const
{
qSettings->setValue("simulatorId", settings.simulatorId);
qSettings->setValue("hostAddress", settings.hostAddress);
qSettings->setValue("inPort", settings.inPort);
qSettings->setValue("remoteAddress", settings.remoteAddress);
qSettings->setValue("outPort", settings.outPort);
qSettings->setValue("binPath", settings.binPath);
qSettings->setValue("dataPath", settings.dataPath);
qSettings->setValue("homeLocation", settings.homeLocation);
qSettings->setValue("homeLocRate", settings.homeLocRate);
qSettings->setValue("attRaw", settings.attRaw);
qSettings->setValue("attRawRate", settings.attRawRate);
qSettings->setValue("attActual", settings.attActual);
qSettings->setValue("attActHW", settings.attActHW);
qSettings->setValue("attActSim", settings.attActSim);
qSettings->setValue("attActCalc", settings.attActCalc);
qSettings->setValue("sonarAltitude", settings.sonarAltitude);
qSettings->setValue("sonarMaxAlt", settings.sonarMaxAlt);
qSettings->setValue("sonarAltRate", settings.sonarAltRate);
qSettings->setValue("gpsPosition", settings.gpsPosition);
qSettings->setValue("gpsPosRate", settings.gpsPosRate);
qSettings->setValue("inputCommand", settings.inputCommand);
qSettings->setValue("gcsReciever", settings.gcsReciever);
qSettings->setValue("manualControl", settings.manualControl);
qSettings->setValue("manualOutput", settings.manualOutput);
qSettings->setValue("outputRate", settings.outputRate);
}

View File

@ -0,0 +1,61 @@
/**
******************************************************************************
*
* @file hitlconfiguration.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @addtogroup GCSPlugins GCS Plugins
* @{
* @addtogroup HITLPlugin HITL Plugin
* @{
* @brief The Hardware In The Loop plugin
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef HITLV2CONFIGURATION_H
#define HITLV2CONFIGURATION_H
#include <coreplugin/iuavgadgetconfiguration.h>
#include <QtGui/QColor>
#include <QString>
#include <simulatorv2.h>
using namespace Core;
class HITLConfiguration : public IUAVGadgetConfiguration
{
Q_OBJECT
Q_PROPERTY(SimulatorSettings settings READ Settings WRITE setSimulatorSettings)
public:
explicit HITLConfiguration(QString classId, QSettings* qSettings = 0, QObject *parent = 0);
void saveConfig(QSettings* settings) const;
IUAVGadgetConfiguration *clone();
SimulatorSettings Settings() const { return settings; }
public slots:
void setSimulatorSettings (const SimulatorSettings& params ) { settings = params; }
private:
SimulatorSettings settings;
};
#endif // HITLV2CONFIGURATION_H

View File

@ -0,0 +1,58 @@
/**
******************************************************************************
*
* @file hitlfactory.cpp
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @addtogroup GCSPlugins GCS Plugins
* @{
* @addtogroup HITLPlugin HITL Plugin
* @{
* @brief The Hardware In The Loop plugin
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#include "hitlv2factory.h"
#include "hitlv2widget.h"
#include "hitlv2gadget.h"
#include "hitlv2configuration.h"
#include "hitlv2optionspage.h"
#include <coreplugin/iuavgadget.h>
HITLFactory::HITLFactory(QObject *parent)
: IUAVGadgetFactory(QString("HITLv2"), tr("HITL Simulation (v2)"), parent)
{
}
HITLFactory::~HITLFactory()
{
}
Core::IUAVGadget* HITLFactory::createGadget(QWidget *parent)
{
HITLWidget* gadgetWidget = new HITLWidget(parent);
return new HITLGadget(QString("HITLv2"), gadgetWidget, parent);
}
IUAVGadgetConfiguration *HITLFactory::createConfiguration(QSettings* qSettings)
{
return new HITLConfiguration(QString("HITLv2"), qSettings);
}
IOptionsPage *HITLFactory::createOptionsPage(IUAVGadgetConfiguration *config)
{
return new HITLOptionsPage(qobject_cast<HITLConfiguration*>(config));
}

View File

@ -0,0 +1,52 @@
/**
******************************************************************************
*
* @file hitlfactory.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @addtogroup GCSPlugins GCS Plugins
* @{
* @addtogroup HITLPlugin HITL Plugin
* @{
* @brief The Hardware In The Loop plugin
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef HITLV2FACTORY_H
#define HITLV2FACTORY_H
#include <coreplugin/iuavgadgetfactory.h>
namespace Core {
class IUAVGadget;
class IUAVGadgetFactory;
}
using namespace Core;
class HITLFactory : public Core::IUAVGadgetFactory
{
Q_OBJECT
public:
HITLFactory(QObject *parent = 0);
~HITLFactory();
IUAVGadget *createGadget(QWidget *parent);
IUAVGadgetConfiguration *createConfiguration(QSettings* qSettings);
IOptionsPage *createOptionsPage(IUAVGadgetConfiguration *config);
};
#endif // HITLV2FACTORY_H

View File

@ -0,0 +1,49 @@
/**
******************************************************************************
*
* @file hitl.cpp
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @addtogroup GCSPlugins GCS Plugins
* @{
* @addtogroup HITLPlugin HITL Plugin
* @{
* @brief The Hardware In The Loop plugin
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#include "hitlv2gadget.h"
#include "hitlv2widget.h"
#include "hitlv2configuration.h"
#include "simulatorv2.h"
HITLGadget::HITLGadget(QString classId, HITLWidget *widget, QWidget *parent) :
IUAVGadget(classId, parent),
m_widget(widget)
{
connect(this, SIGNAL(changeConfiguration(void)), m_widget, SLOT(stopButtonClicked(void)));
}
HITLGadget::~HITLGadget()
{
delete m_widget;
}
void HITLGadget::loadConfiguration(IUAVGadgetConfiguration* config)
{
HITLConfiguration *m = qobject_cast<HITLConfiguration*>(config);
emit changeConfiguration();
m_widget->setSettingParameters(m->Settings());
}

View File

@ -0,0 +1,60 @@
/**
******************************************************************************
*
* @file hitl.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @addtogroup GCSPlugins GCS Plugins
* @{
* @addtogroup HITLPlugin HITL Plugin
* @{
* @brief The Hardware In The Loop plugin
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef HITLV2_H
#define HITLV2_H
#include <coreplugin/iuavgadget.h>
#include "hitlv2widget.h"
class IUAVGadget;
class QWidget;
class QString;
class Simulator;
using namespace Core;
class HITLGadget : public Core::IUAVGadget
{
Q_OBJECT
public:
HITLGadget(QString classId, HITLWidget *widget, QWidget *parent = 0);
~HITLGadget();
QWidget *widget() { return m_widget; }
void loadConfiguration(IUAVGadgetConfiguration* config);
signals:
void changeConfiguration();
private:
HITLWidget* m_widget;
Simulator* simulator;
};
#endif // HITLV2_H

View File

@ -0,0 +1,146 @@
/**
******************************************************************************
*
* @file hitloptionspage.cpp
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @addtogroup GCSPlugins GCS Plugins
* @{
* @addtogroup HITLPlugin HITL Plugin
* @{
* @brief The Hardware In The Loop plugin
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#include "hitlv2optionspage.h"
#include "hitlv2configuration.h"
#include "ui_hitlv2optionspage.h"
#include "hitlv2plugin.h"
#include <QFileDialog>
#include <QtAlgorithms>
#include <QStringList>
#include "simulatorv2.h"
HITLOptionsPage::HITLOptionsPage(HITLConfiguration *conf, QObject *parent) :
IOptionsPage(parent),
config(conf)
{
}
QWidget *HITLOptionsPage::createPage(QWidget *parent)
{
// qDebug() << "HITLOptionsPage::createPage";
// Create page
m_optionsPage = new Ui::HITLOptionsPage();
QWidget* optionsPageWidget = new QWidget;
m_optionsPage->setupUi(optionsPageWidget);
int index = 0;
foreach (SimulatorCreator* creator, HITLPlugin::typeSimulators)
m_optionsPage->chooseFlightSimulator->insertItem(index++, creator->Description(), creator->ClassId());
m_optionsPage->executablePath->setExpectedKind(Utils::PathChooser::File);
m_optionsPage->executablePath->setPromptDialogTitle(tr("Choose flight simulator executable"));
m_optionsPage->dataPath->setExpectedKind(Utils::PathChooser::Directory);
m_optionsPage->dataPath->setPromptDialogTitle(tr("Choose flight simulator data directory"));
// Restore the contents from the settings:
foreach (SimulatorCreator* creator, HITLPlugin::typeSimulators) {
QString id = config->Settings().simulatorId;
if (creator->ClassId() == id)
m_optionsPage->chooseFlightSimulator->setCurrentIndex(HITLPlugin::typeSimulators.indexOf(creator));
}
m_optionsPage->hostAddress->setText(config->Settings().hostAddress);
m_optionsPage->inputPort->setText(QString::number(config->Settings().inPort));
m_optionsPage->remoteAddress->setText(config->Settings().remoteAddress);
m_optionsPage->outputPort->setText(QString::number(config->Settings().outPort));
m_optionsPage->executablePath->setPath(config->Settings().binPath);
m_optionsPage->dataPath->setPath(config->Settings().dataPath);
m_optionsPage->homeLocation->setChecked(config->Settings().homeLocation);
m_optionsPage->homeLocRate->setValue(config->Settings().homeLocRate);
m_optionsPage->attRaw->setChecked(config->Settings().attRaw);
m_optionsPage->attRawRate->setValue(config->Settings().attRawRate);
m_optionsPage->attActual->setChecked(config->Settings().attActual);
m_optionsPage->attActHW->setChecked(config->Settings().attActHW);
m_optionsPage->attActSim->setChecked(config->Settings().attActSim);
m_optionsPage->attActCalc->setChecked(config->Settings().attActCalc);
m_optionsPage->sonarAltitude->setChecked(config->Settings().sonarAltitude);
m_optionsPage->sonarMaxAlt->setValue(config->Settings().sonarMaxAlt);
m_optionsPage->sonarAltRate->setValue(config->Settings().sonarAltRate);
m_optionsPage->gpsPosition->setChecked(config->Settings().gpsPosition);
m_optionsPage->gpsPosRate->setValue(config->Settings().gpsPosRate);
m_optionsPage->inputCommand->setChecked(config->Settings().inputCommand);
m_optionsPage->gcsReciever->setChecked(config->Settings().gcsReciever);
m_optionsPage->manualControl->setChecked(config->Settings().manualControl);
m_optionsPage->manualOutput->setChecked(config->Settings().manualOutput);
m_optionsPage->outputRate->setValue(config->Settings().outputRate);
return optionsPageWidget;
}
void HITLOptionsPage::apply()
{
SimulatorSettings settings;
int i = m_optionsPage->chooseFlightSimulator->currentIndex();
settings.simulatorId = m_optionsPage->chooseFlightSimulator->itemData(i).toString();
settings.hostAddress = m_optionsPage->hostAddress->text();
settings.inPort = m_optionsPage->inputPort->text().toInt();
settings.remoteAddress = m_optionsPage->remoteAddress->text();
settings.outPort = m_optionsPage->outputPort->text().toInt();
settings.binPath = m_optionsPage->executablePath->path();
settings.dataPath = m_optionsPage->dataPath->path();
settings.homeLocation = m_optionsPage->homeLocation->isChecked();
settings.homeLocRate = m_optionsPage->homeLocRate->value();
settings.attRaw = m_optionsPage->attRaw->isChecked();
settings.attRawRate = m_optionsPage->attRawRate->value();
settings.attActual = m_optionsPage->attActual->isChecked();
settings.attActHW = m_optionsPage->attActHW->isChecked();
settings.attActSim = m_optionsPage->attActSim->isChecked();
settings.attActCalc = m_optionsPage->attActCalc->isChecked();
settings.sonarAltitude = m_optionsPage->sonarAltitude->isChecked();
settings.sonarMaxAlt = m_optionsPage->sonarMaxAlt->value();
settings.sonarAltRate = m_optionsPage->sonarAltRate->value();
settings.gpsPosition = m_optionsPage->gpsPosition->isChecked();
settings.gpsPosRate = m_optionsPage->gpsPosRate->value();
settings.inputCommand = m_optionsPage->inputCommand->isChecked();
settings.gcsReciever = m_optionsPage->gcsReciever->isChecked();
settings.manualControl = m_optionsPage->manualControl->isChecked();
settings.manualOutput = m_optionsPage->manualOutput->isChecked();
settings.outputRate = m_optionsPage->outputRate->value();
config->setSimulatorSettings(settings);
}
void HITLOptionsPage::finish()
{
delete m_optionsPage;
}

View File

@ -0,0 +1,61 @@
/**
******************************************************************************
*
* @file hitloptionspage.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @addtogroup GCSPlugins GCS Plugins
* @{
* @addtogroup HITLPlugin HITL Plugin
* @{
* @brief The Hardware In The Loop plugin
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef HITLV2OPTIONSPAGE_H
#define HITLV2OPTIONSPAGE_H
#include <coreplugin/dialogs/ioptionspage.h>
namespace Core {
class IUAVGadgetConfiguration;
}
class HITLConfiguration;
using namespace Core;
namespace Ui {
class HITLOptionsPage;
}
class HITLOptionsPage : public IOptionsPage
{
Q_OBJECT
public:
explicit HITLOptionsPage(HITLConfiguration *conf, QObject *parent = 0);
QWidget *createPage(QWidget *parent);
void apply();
void finish();
bool isDecorated() const { return true; }
private:
HITLConfiguration* config;
Ui::HITLOptionsPage* m_optionsPage;
};
#endif // HITLV2OPTIONSPAGE_H

View File

@ -0,0 +1,639 @@
<?xml version="1.0" encoding="UTF-8"?>
<ui version="4.0">
<class>HITLOptionsPage</class>
<widget class="QWidget" name="HITLOptionsPage">
<property name="geometry">
<rect>
<x>0</x>
<y>0</y>
<width>403</width>
<height>400</height>
</rect>
</property>
<property name="windowTitle">
<string>Form</string>
</property>
<layout class="QVBoxLayout" name="verticalLayout">
<property name="spacing">
<number>3</number>
</property>
<property name="leftMargin">
<number>0</number>
</property>
<property name="topMargin">
<number>0</number>
</property>
<property name="rightMargin">
<number>0</number>
</property>
<property name="bottomMargin">
<number>3</number>
</property>
<item>
<layout class="QHBoxLayout" name="horizontalLayout">
<item>
<widget class="QLabel" name="label_3">
<property name="text">
<string>Choose flight simulator:</string>
</property>
</widget>
</item>
<item>
<widget class="QComboBox" name="chooseFlightSimulator"/>
</item>
</layout>
</item>
<item>
<layout class="QGridLayout" name="gridLayout">
<item row="0" column="0">
<widget class="QLabel" name="label_6">
<property name="text">
<string>Local interface (IP):</string>
</property>
</widget>
</item>
<item row="0" column="1">
<widget class="QLineEdit" name="hostAddress">
<property name="toolTip">
<string>For communication with sim computer via network. Should be the IP address of one of the interfaces of the GCS computer.</string>
</property>
</widget>
</item>
<item row="1" column="0">
<widget class="QLabel" name="label_9">
<property name="text">
<string>Remote interface (IP):</string>
</property>
</widget>
</item>
<item row="1" column="1">
<widget class="QLineEdit" name="remoteAddress">
<property name="toolTip">
<string>Only required if running simulator on remote machine. Should be the IP of the machine on which the simulator is running.</string>
</property>
</widget>
</item>
<item row="0" column="2">
<widget class="QLabel" name="label_5">
<property name="text">
<string>Input Port:</string>
</property>
</widget>
</item>
<item row="0" column="3">
<widget class="QLineEdit" name="inputPort">
<property name="toolTip">
<string>For receiving data from sim</string>
</property>
</widget>
</item>
<item row="1" column="2">
<widget class="QLabel" name="label_4">
<property name="text">
<string>Output Port:</string>
</property>
</widget>
</item>
<item row="1" column="3">
<widget class="QLineEdit" name="outputPort">
<property name="toolTip">
<string>For sending data to sim</string>
</property>
</widget>
</item>
</layout>
</item>
<item>
<layout class="QFormLayout" name="formLayout">
<property name="fieldGrowthPolicy">
<enum>QFormLayout::AllNonFixedFieldsGrow</enum>
</property>
<item row="0" column="0">
<widget class="QLabel" name="label">
<property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="text">
<string>Path executable:</string>
</property>
</widget>
</item>
<item row="0" column="1">
<widget class="Utils::PathChooser" name="executablePath" native="true"/>
</item>
<item row="1" column="0">
<widget class="QLabel" name="label_2">
<property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="text">
<string>Data directory:</string>
</property>
</widget>
</item>
<item row="1" column="1">
<widget class="Utils::PathChooser" name="dataPath" native="true"/>
</item>
</layout>
</item>
<item>
<layout class="QHBoxLayout" name="horizontalLayout_3">
<item>
<widget class="QGroupBox" name="groupBox">
<property name="title">
<string>Attitude data</string>
</property>
<layout class="QVBoxLayout" name="verticalLayout_2">
<property name="spacing">
<number>3</number>
</property>
<property name="leftMargin">
<number>3</number>
</property>
<property name="topMargin">
<number>3</number>
</property>
<property name="rightMargin">
<number>3</number>
</property>
<property name="bottomMargin">
<number>0</number>
</property>
<item>
<widget class="QGroupBox" name="attRaw">
<property name="title">
<string>AttitudeRaw (gyro, accels)</string>
</property>
<property name="flat">
<bool>true</bool>
</property>
<property name="checkable">
<bool>true</bool>
</property>
<property name="checked">
<bool>false</bool>
</property>
<layout class="QHBoxLayout" name="horizontalLayout_4">
<property name="spacing">
<number>3</number>
</property>
<property name="topMargin">
<number>3</number>
</property>
<property name="rightMargin">
<number>0</number>
</property>
<property name="bottomMargin">
<number>0</number>
</property>
<item>
<widget class="QLabel" name="label_8">
<property name="text">
<string>Refresh rate</string>
</property>
</widget>
</item>
<item>
<widget class="QSpinBox" name="attRawRate">
<property name="suffix">
<string>ms</string>
</property>
<property name="minimum">
<number>10</number>
</property>
<property name="maximum">
<number>100</number>
</property>
<property name="value">
<number>20</number>
</property>
</widget>
</item>
</layout>
</widget>
</item>
<item>
<widget class="QGroupBox" name="attActual">
<property name="title">
<string>AttitudeActual</string>
</property>
<property name="flat">
<bool>true</bool>
</property>
<property name="checkable">
<bool>true</bool>
</property>
<property name="checked">
<bool>false</bool>
</property>
<layout class="QVBoxLayout" name="verticalLayout_4">
<property name="spacing">
<number>3</number>
</property>
<property name="topMargin">
<number>3</number>
</property>
<property name="rightMargin">
<number>0</number>
</property>
<property name="bottomMargin">
<number>0</number>
</property>
<item>
<widget class="QRadioButton" name="attActHW">
<property name="text">
<string>send raw data to board</string>
</property>
</widget>
</item>
<item>
<widget class="QRadioButton" name="attActSim">
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="toolTip">
<string/>
</property>
<property name="text">
<string>use values from simulator</string>
</property>
<property name="checked">
<bool>true</bool>
</property>
</widget>
</item>
<item>
<widget class="QRadioButton" name="attActCalc">
<property name="toolTip">
<string/>
</property>
<property name="text">
<string>calculate from AttitudeRaw</string>
</property>
</widget>
</item>
<item>
<spacer name="verticalSpacer_2">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>40</height>
</size>
</property>
</spacer>
</item>
</layout>
</widget>
</item>
</layout>
</widget>
</item>
<item>
<widget class="QGroupBox" name="groupBox_2">
<property name="title">
<string>Other data</string>
</property>
<layout class="QVBoxLayout" name="verticalLayout_3">
<property name="spacing">
<number>3</number>
</property>
<property name="leftMargin">
<number>3</number>
</property>
<property name="topMargin">
<number>3</number>
</property>
<property name="rightMargin">
<number>3</number>
</property>
<property name="bottomMargin">
<number>0</number>
</property>
<item>
<widget class="QGroupBox" name="homeLocation">
<property name="title">
<string>HomeLocation</string>
</property>
<property name="flat">
<bool>true</bool>
</property>
<property name="checkable">
<bool>true</bool>
</property>
<property name="checked">
<bool>false</bool>
</property>
<layout class="QHBoxLayout" name="horizontalLayout_2">
<property name="spacing">
<number>3</number>
</property>
<property name="topMargin">
<number>3</number>
</property>
<property name="rightMargin">
<number>0</number>
</property>
<property name="bottomMargin">
<number>0</number>
</property>
<item>
<widget class="QLabel" name="label_7">
<property name="text">
<string>Refresh rate</string>
</property>
</widget>
</item>
<item>
<widget class="QSpinBox" name="homeLocRate">
<property name="toolTip">
<string>0 - update once, or every N seconds</string>
</property>
<property name="suffix">
<string>sec</string>
</property>
<property name="maximum">
<number>10</number>
</property>
</widget>
</item>
</layout>
</widget>
</item>
<item>
<widget class="QGroupBox" name="gpsPosition">
<property name="title">
<string>GPSPosition</string>
</property>
<property name="flat">
<bool>true</bool>
</property>
<property name="checkable">
<bool>true</bool>
</property>
<property name="checked">
<bool>false</bool>
</property>
<layout class="QHBoxLayout" name="horizontalLayout_5">
<property name="spacing">
<number>3</number>
</property>
<property name="topMargin">
<number>3</number>
</property>
<property name="rightMargin">
<number>0</number>
</property>
<property name="bottomMargin">
<number>0</number>
</property>
<item>
<widget class="QLabel" name="label_10">
<property name="text">
<string>Refresh rate</string>
</property>
</widget>
</item>
<item>
<widget class="QSpinBox" name="gpsPosRate">
<property name="suffix">
<string>ms</string>
</property>
<property name="minimum">
<number>100</number>
</property>
<property name="maximum">
<number>2000</number>
</property>
<property name="value">
<number>500</number>
</property>
</widget>
</item>
</layout>
</widget>
</item>
<item>
<widget class="QGroupBox" name="sonarAltitude">
<property name="title">
<string>SonarAltitude</string>
</property>
<property name="flat">
<bool>true</bool>
</property>
<property name="checkable">
<bool>true</bool>
</property>
<property name="checked">
<bool>false</bool>
</property>
<layout class="QVBoxLayout" name="verticalLayout_6">
<property name="spacing">
<number>3</number>
</property>
<property name="leftMargin">
<number>6</number>
</property>
<property name="topMargin">
<number>3</number>
</property>
<property name="rightMargin">
<number>0</number>
</property>
<property name="bottomMargin">
<number>0</number>
</property>
<item>
<layout class="QGridLayout" name="gridLayout_2">
<item row="0" column="0">
<widget class="QLabel" name="label_11">
<property name="text">
<string>Range detectioon</string>
</property>
</widget>
</item>
<item row="0" column="1">
<widget class="QSpinBox" name="sonarMaxAlt">
<property name="suffix">
<string>m</string>
</property>
<property name="minimum">
<number>1</number>
</property>
<property name="maximum">
<number>10</number>
</property>
<property name="value">
<number>5</number>
</property>
</widget>
</item>
<item row="1" column="0">
<widget class="QLabel" name="label_12">
<property name="text">
<string>Refresh rate</string>
</property>
</widget>
</item>
<item row="1" column="1">
<widget class="QSpinBox" name="sonarAltRate">
<property name="suffix">
<string>ms</string>
</property>
<property name="minimum">
<number>20</number>
</property>
<property name="maximum">
<number>2000</number>
</property>
<property name="singleStep">
<number>10</number>
</property>
<property name="value">
<number>50</number>
</property>
</widget>
</item>
</layout>
</item>
</layout>
</widget>
</item>
<item>
<widget class="QGroupBox" name="inputCommand">
<property name="title">
<string>Map command from simulator</string>
</property>
<property name="flat">
<bool>true</bool>
</property>
<property name="checkable">
<bool>true</bool>
</property>
<property name="checked">
<bool>false</bool>
</property>
<layout class="QVBoxLayout" name="verticalLayout_5">
<property name="spacing">
<number>3</number>
</property>
<property name="topMargin">
<number>3</number>
</property>
<property name="rightMargin">
<number>0</number>
</property>
<property name="bottomMargin">
<number>0</number>
</property>
<item>
<widget class="QRadioButton" name="gcsReciever">
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="text">
<string>to GCSReciver</string>
</property>
<property name="checked">
<bool>true</bool>
</property>
</widget>
</item>
<item>
<widget class="QRadioButton" name="manualControl">
<property name="enabled">
<bool>false</bool>
</property>
<property name="text">
<string>to ManualCtrll (not implemented)</string>
</property>
</widget>
</item>
</layout>
</widget>
</item>
<item>
<layout class="QHBoxLayout" name="horizontalLayout_6">
<property name="spacing">
<number>6</number>
</property>
<item>
<widget class="QCheckBox" name="manualOutput">
<property name="text">
<string>Maximum output rate</string>
</property>
</widget>
</item>
<item>
<widget class="QSpinBox" name="outputRate">
<property name="suffix">
<string>ms</string>
</property>
<property name="minimum">
<number>10</number>
</property>
<property name="maximum">
<number>100</number>
</property>
<property name="singleStep">
<number>5</number>
</property>
<property name="value">
<number>15</number>
</property>
</widget>
</item>
</layout>
</item>
<item>
<spacer name="verticalSpacer">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>40</height>
</size>
</property>
</spacer>
</item>
</layout>
</widget>
</item>
</layout>
</item>
</layout>
</widget>
<customwidgets>
<customwidget>
<class>Utils::PathChooser</class>
<extends>QWidget</extends>
<header>utils/pathchooser.h</header>
<container>1</container>
</customwidget>
</customwidgets>
<tabstops>
<tabstop>chooseFlightSimulator</tabstop>
<tabstop>hostAddress</tabstop>
<tabstop>inputPort</tabstop>
<tabstop>remoteAddress</tabstop>
<tabstop>outputPort</tabstop>
</tabstops>
<resources/>
<connections/>
</ui>

View File

@ -0,0 +1,70 @@
/**
******************************************************************************
*
* @file mapplugin.cpp
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @addtogroup GCSPlugins GCS Plugins
* @{
* @addtogroup HITLPlugin HITL Plugin
* @{
* @brief The Hardware In The Loop plugin
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#include "hitlv2plugin.h"
#include "hitlv2factory.h"
#include <QtPlugin>
#include <QStringList>
#include <extensionsystem/pluginmanager.h>
#include "aerosimrc.h"
QList<SimulatorCreator* > HITLPlugin::typeSimulators;
HITLPlugin::HITLPlugin()
{
// Do nothing
}
HITLPlugin::~HITLPlugin()
{
// Do nothing
}
bool HITLPlugin::initialize(const QStringList& args, QString *errMsg)
{
Q_UNUSED(args);
Q_UNUSED(errMsg);
mf = new HITLFactory(this);
addAutoReleasedObject(mf);
addSimulator(new AeroSimRCSimulatorCreator("ASimRC", "AeroSimRC"));
return true;
}
void HITLPlugin::extensionsInitialized()
{
// Do nothing
}
void HITLPlugin::shutdown()
{
// Do nothing
}
Q_EXPORT_PLUGIN(HITLPlugin)

View File

@ -0,0 +1,67 @@
/**
******************************************************************************
*
* @file browserplugin.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @addtogroup GCSPlugins GCS Plugins
* @{
* @addtogroup HITLPlugin HITL Plugin
* @{
* @brief The Hardware In The Loop plugin
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef HITLV2PLUGIN_H
#define HITLV2PLUGIN_H
#include <extensionsystem/iplugin.h>
#include <QStringList>
#include <simulatorv2.h>
class HITLFactory;
class HITLPlugin : public ExtensionSystem::IPlugin
{
public:
HITLPlugin();
~HITLPlugin();
void extensionsInitialized();
bool initialize(const QStringList & arguments, QString * errorString);
void shutdown();
static void addSimulator(SimulatorCreator* creator)
{
HITLPlugin::typeSimulators.append(creator);
}
static SimulatorCreator* getSimulatorCreator(const QString classId)
{
foreach(SimulatorCreator* creator, HITLPlugin::typeSimulators) {
if(classId == creator->ClassId())
return creator;
}
return 0;
}
static QList<SimulatorCreator* > typeSimulators;
private:
HITLFactory *mf;
};
#endif /* HITLV2PLUGIN_H */

View File

@ -0,0 +1,187 @@
/**
******************************************************************************
*
* @file hitlwidget.cpp
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @addtogroup GCSPlugins GCS Plugins
* @{
* @addtogroup HITLPlugin HITL Plugin
* @{
* @brief The Hardware In The Loop plugin
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#include "hitlv2widget.h"
#include "ui_hitlv2widget.h"
#include <QDebug>
#include <QFile>
#include <QDir>
#include <QDateTime>
#include <QThread>
#include "hitlv2plugin.h"
#include "simulatorv2.h"
#include "uavobjectmanager.h"
#include <coreplugin/icore.h>
#include <coreplugin/threadmanager.h>
QStringList Simulator::instances;
HITLWidget::HITLWidget(QWidget *parent)
: QWidget(parent),
simulator(0)
{
widget = new Ui_HITLWidget();
widget->setupUi(this);
widget->startButton->setEnabled(true);
widget->stopButton->setEnabled(false);
strAutopilotDisconnected = " AP OFF ";
strSimulatorDisconnected = " Sim OFF ";
strAutopilotConnected = " AP ON ";
// strSimulatorConnected = " Sim ON ";
strStyleEnable = "QFrame{background-color: green; color: white}";
strStyleDisable = "QFrame{background-color: red; color: grey}";
widget->apLabel->setText(strAutopilotDisconnected);
widget->simLabel->setText(strSimulatorDisconnected);
connect(widget->startButton, SIGNAL(clicked()), this, SLOT(startButtonClicked()));
connect(widget->stopButton, SIGNAL(clicked()), this, SLOT(stopButtonClicked()));
connect(widget->buttonClearLog, SIGNAL(clicked()), this, SLOT(buttonClearLogClicked()));
}
HITLWidget::~HITLWidget()
{
delete widget;
}
void HITLWidget::startButtonClicked()
{
// allow only one instance per simulator
if (Simulator::Instances().indexOf(settings.simulatorId) != -1) {
widget->textBrowser->append(settings.simulatorId + " alreary started!");
return;
}
if (!HITLPlugin::typeSimulators.size()) {
widget->textBrowser->append("There is no registered simulators, add through HITLPlugin::addSimulator");
return;
}
// Stop running process if one is active
if (simulator) {
QMetaObject::invokeMethod(simulator, "onDeleteSimulator", Qt::QueuedConnection);
simulator = NULL;
}
if (settings.hostAddress == "" || settings.inPort == 0) {
widget->textBrowser->append("Before start, set UDP parameters in options page!");
return;
}
SimulatorCreator* creator = HITLPlugin::getSimulatorCreator(settings.simulatorId);
simulator = creator->createSimulator(settings);
simulator->setName(creator->Description());
simulator->setSimulatorId(creator->ClassId());
connect(simulator, SIGNAL(processOutput(QString)), this, SLOT(onProcessOutput(QString)));
// Setup process
onProcessOutput(QString("[%1] Starting %2... ")
.arg(QTime::currentTime().toString("hh:mm:ss"))
.arg(creator->Description()));
// Start bridge
bool ret = QMetaObject::invokeMethod(simulator, "setupProcess", Qt::QueuedConnection);
if (ret) {
Simulator::setInstance(settings.simulatorId);
connect(this, SIGNAL(deleteSimulator()), simulator, SLOT(onDeleteSimulator()), Qt::QueuedConnection);
widget->startButton->setEnabled(false);
widget->stopButton->setEnabled(true);
connect(simulator, SIGNAL(autopilotConnected()), this, SLOT(onAutopilotConnect()), Qt::QueuedConnection);
connect(simulator, SIGNAL(autopilotDisconnected()), this, SLOT(onAutopilotDisconnect()), Qt::QueuedConnection);
connect(simulator, SIGNAL(simulatorConnected()), this, SLOT(onSimulatorConnect()), Qt::QueuedConnection);
connect(simulator, SIGNAL(simulatorDisconnected()), this, SLOT(onSimulatorDisconnect()), Qt::QueuedConnection);
// Initialize connection status
if (simulator->isAutopilotConnected())
onAutopilotConnect();
else
onAutopilotDisconnect();
if (simulator->isSimulatorConnected())
onSimulatorConnect();
else
onSimulatorDisconnect();
}
}
void HITLWidget::stopButtonClicked()
{
if (simulator)
widget->textBrowser->append(QString("[%1] Terminate %2 ")
.arg(QTime::currentTime().toString("hh:mm:ss"))
.arg(simulator->Name()));
widget->startButton->setEnabled(true);
widget->stopButton->setEnabled(false);
widget->apLabel->setStyleSheet(QString::fromUtf8("QFrame{background-color: transparent; color: white}"));
widget->simLabel->setStyleSheet(QString::fromUtf8("QFrame{background-color: transparent; color: white}"));
widget->apLabel->setText(strAutopilotDisconnected);
widget->simLabel->setText(strSimulatorDisconnected);
if (simulator) {
QMetaObject::invokeMethod(simulator, "onDeleteSimulator", Qt::QueuedConnection);
simulator = NULL;
}
}
void HITLWidget::buttonClearLogClicked()
{
widget->textBrowser->clear();
}
void HITLWidget::onProcessOutput(QString text)
{
widget->textBrowser->append(text);
}
void HITLWidget::onAutopilotConnect()
{
widget->apLabel->setStyleSheet(strStyleEnable);
widget->apLabel->setText(strAutopilotConnected);
}
void HITLWidget::onAutopilotDisconnect()
{
widget->apLabel->setStyleSheet(strStyleDisable);
widget->apLabel->setText(strAutopilotDisconnected);
}
void HITLWidget::onSimulatorConnect()
{
widget->simLabel->setStyleSheet(strStyleEnable);
widget->simLabel->setText(" " + simulator->Name() + " ON ");
}
void HITLWidget::onSimulatorDisconnect()
{
widget->simLabel->setStyleSheet(strStyleDisable);
widget->simLabel->setText(" " + simulator->Name() + " OFF ");
}

View File

@ -0,0 +1,72 @@
/**
******************************************************************************
*
* @file hitlwidget.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @addtogroup GCSPlugins GCS Plugins
* @{
* @addtogroup HITLPlugin HITL Plugin
* @{
* @brief The Hardware In The Loop plugin
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef HITLV2WIDGET_H
#define HITLV2WIDGET_H
#include <QtGui/QWidget>
#include <QProcess>
#include "simulatorv2.h"
class Ui_HITLWidget;
class HITLWidget : public QWidget
{
Q_OBJECT
public:
HITLWidget(QWidget *parent = 0);
~HITLWidget();
void setSettingParameters(const SimulatorSettings& params) { settings = params; }
signals:
void deleteSimulator();
private slots:
void startButtonClicked();
void stopButtonClicked();
void buttonClearLogClicked();
void onProcessOutput(QString text);
void onAutopilotConnect();
void onAutopilotDisconnect();
void onSimulatorConnect();
void onSimulatorDisconnect();
private:
Ui_HITLWidget* widget;
Simulator* simulator;
SimulatorSettings settings;
QString strAutopilotDisconnected;
QString strSimulatorDisconnected;
QString strAutopilotConnected;
// QString strSimulatorConnected;
QString strStyleEnable;
QString strStyleDisable;
};
#endif /* HITLV2WIDGET_H */

View File

@ -0,0 +1,314 @@
<?xml version="1.0" encoding="UTF-8"?>
<ui version="4.0">
<class>HITLWidget</class>
<widget class="QWidget" name="HITLWidget">
<property name="geometry">
<rect>
<x>0</x>
<y>0</y>
<width>477</width>
<height>300</height>
</rect>
</property>
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="windowTitle">
<string>Form</string>
</property>
<property name="styleSheet">
<string notr="true">
QScrollBar:vertical {
border: 1px solid grey;
background: grey;
margin: 22px 0 22px 0;
}
QScrollBar:vertical:disabled {
border: 1px solid grey;
background-color: grey;
margin: 22px 0 22px 0;
}
QScrollBar::handle:vertical {
background-color: qlineargradient(spread:pad, x1:0.5, y1:0, x2:0.5, y2:1, stop:0 rgba(120, 120, 255, 255), stop:1 rgba(80, 80, 160, 255));
min-height: 20px;
}
QScrollBar::handle:vertical:disabled{
background-color: grey;
min-height: 20px;
}
QScrollBar::handle:vertical:pressed {
background-color: rgb(85, 85, 255);
background-color: qlineargradient(spread:pad, x1:0.5, y1:0, x2:0.5, y2:1, stop:0 rgba(170, 170, 255, 255), stop:1 rgba(80, 80, 160, 255));
min-height: 20px;
}
QScrollBar::add-line:vertical {
border: 1px solid black;
background-color: qlineargradient(spread:pad, x1:0.5, y1:0, x2:0.5, y2:1, stop:0 rgba(48, 48, 48, 255), stop:1 rgba(120, 120, 120, 255));
height: 20px;
subcontrol-position: bottom;
subcontrol-origin: margin;
}
QScrollBar::add-line:vertical:disabled {
background-color: qlineargradient(spread:pad, x1:0.5, y1:0, x2:0.5, y2:1, stop:0 rgba(100, 100, 100, 255));
border: 1px solid grey;
}
QScrollBar::sub-line:vertical:disabled {
background-color: qlineargradient(spread:pad, x1:0.5, y1:0, x2:0.5, y2:1, stop:0 rgba(100, 100, 100, 255));
border: 1px solid grey;
}
QScrollBar::add-line:vertical:pressed {
background-color: qlineargradient(spread:pad, x1:0.5, y1:0, x2:0.5, y2:1, stop:0 rgba(255, 255, 255, 200), stop:1 rgba(180, 180, 180, 200));
}
QScrollBar::sub-line:vertical:pressed {
background-color: qlineargradient(spread:pad, x1:0.5, y1:0, x2:0.5, y2:1, stop:0 rgba(255, 255, 255, 200), stop:1 rgba(180, 180, 180, 200));
}
QScrollBar::sub-line:vertical {
border: 1px solid black;
background-color: qlineargradient(spread:pad, x1:0.5, y1:0, x2:0.5, y2:1, stop:0 rgba(48, 48, 48, 255), stop:1 rgba(120, 120, 120, 255));
height: 20px;
subcontrol-position: top;
subcontrol-origin: margin;
}
QScrollBar::down-arrow:vertical {
image: url(:/hitlnew/images/arrow-down2.png);
}
QScrollBar::up-arrow:vertical {
image: url(:/hitlnew/images/arrow-up2.png);
}
QScrollBar::add-page:vertical, QScrollBar::sub-page:vertical {
background: none;
}
QPushButton {
background-color: qlineargradient(spread:pad, x1:0.5, y1:0, x2:0.5, y2:1, stop:0 rgba(110, 110, 110, 255), stop:1 rgba(71, 71, 71, 255));
color: rgb(255, 255, 255);
border: 1px solid black;
width: 66px;
height: 20px;
}
QPushButton:disabled {
background-color: qlineargradient(spread:pad, x1:0.5, y1:0, x2:0.5, y2:1, stop:0 rgba(120, 120, 120, 255));
color: rgb(194, 194, 194);
border: 1px solid gray;
width: 66px;
height: 20px;
}
QPushButton:hover {
background-color: qlineargradient(spread:pad, x1:0.5, y1:0, x2:0.5, y2:1, stop:0 rgba(255, 255, 255, 200), stop:1 rgba(180, 180, 180, 200));
color: rgb(255, 255, 255);
border: 0px;
}
QPushButton:pressed {
background-color: qlineargradient(spread:pad, x1:0.5, y1:0, x2:0.5, y2:1, stop:0 rgba(48, 48, 48, 255), stop:1 rgba(120, 120, 120, 255));
color: rgb(255, 255, 255);
border: 0px;
}
QPushButton:checked {
background-color: qlineargradient(spread:pad, x1:0.5, y1:0, x2:0.5, y2:1, stop:0 rgba(48, 48, 48, 255), stop:1 rgba(120, 120, 120, 255));
color: rgb(255, 255, 255);
border: 0px;
}</string>
</property>
<layout class="QVBoxLayout" name="verticalLayout">
<property name="margin">
<number>0</number>
</property>
<item>
<widget class="QFrame" name="frame">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>0</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>16777215</height>
</size>
</property>
<property name="styleSheet">
<string notr="true">
QFrame{
background-color: qlineargradient(spread:pad, x1:0.5, y1:0, x2:0.5, y2:1, stop:0 rgba(110, 110, 110, 255), stop:1 rgba(71, 71, 71, 255));
color: rgba(0, 0, 0, 128);
}
</string>
</property>
<property name="frameShape">
<enum>QFrame::StyledPanel</enum>
</property>
<property name="frameShadow">
<enum>QFrame::Raised</enum>
</property>
<layout class="QVBoxLayout" name="verticalLayout_2">
<property name="sizeConstraint">
<enum>QLayout::SetMaximumSize</enum>
</property>
<item>
<layout class="QHBoxLayout" name="horizontalLayout">
<property name="sizeConstraint">
<enum>QLayout::SetDefaultConstraint</enum>
</property>
<item>
<widget class="QPushButton" name="startButton">
<property name="toolTip">
<string>Request update</string>
</property>
<property name="styleSheet">
<string notr="true"/>
</property>
<property name="text">
<string>Start</string>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="stopButton">
<property name="enabled">
<bool>false</bool>
</property>
<property name="toolTip">
<string>Send update</string>
</property>
<property name="text">
<string>Stop</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="apLabel">
<property name="minimumSize">
<size>
<width>0</width>
<height>22</height>
</size>
</property>
<property name="font">
<font>
<weight>50</weight>
<bold>false</bold>
</font>
</property>
<property name="layoutDirection">
<enum>Qt::LeftToRight</enum>
</property>
<property name="autoFillBackground">
<bool>false</bool>
</property>
<property name="styleSheet">
<string notr="true">color: rgb(255, 255, 255);</string>
</property>
<property name="text">
<string>AP OFF</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="simLabel">
<property name="minimumSize">
<size>
<width>0</width>
<height>22</height>
</size>
</property>
<property name="styleSheet">
<string notr="true">color: rgb(255, 255, 255);</string>
</property>
<property name="text">
<string>Sim OFF</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="buttonClearLog">
<property name="text">
<string>Clear Log</string>
</property>
</widget>
</item>
</layout>
</item>
<item>
<widget class="QTextEdit" name="textBrowser">
<property name="sizePolicy">
<sizepolicy hsizetype="Expanding" vsizetype="Expanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>0</height>
</size>
</property>
<property name="autoFillBackground">
<bool>false</bool>
</property>
<property name="styleSheet">
<string notr="true">QTextEdit {
background-color: white;
color: rgb(0, 0, 0);
}</string>
</property>
<property name="frameShape">
<enum>QFrame::NoFrame</enum>
</property>
<property name="frameShadow">
<enum>QFrame::Plain</enum>
</property>
<property name="verticalScrollBarPolicy">
<enum>Qt::ScrollBarAlwaysOn</enum>
</property>
</widget>
</item>
</layout>
</widget>
</item>
</layout>
</widget>
<resources/>
<connections/>
</ui>

View File

@ -0,0 +1,341 @@
/**
******************************************************************************
*
* @file simulator.cpp
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @addtogroup GCSPlugins GCS Plugins
* @{
* @addtogroup HITLPlugin HITL Plugin
* @{
* @brief The Hardware In The Loop plugin
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#include "simulatorv2.h"
#include <extensionsystem/pluginmanager.h>
#include <coreplugin/icore.h>
#include <coreplugin/threadmanager.h>
volatile bool Simulator::isStarted = false;
const float Simulator::GEE = 9.81;
const float Simulator::FT2M = 0.3048;
const float Simulator::KT2MPS = 0.514444444;
const float Simulator::INHG2KPA = 3.386;
const float Simulator::FPS2CMPS = 30.48;
const float Simulator::DEG2RAD = (M_PI/180.0);
const float Simulator::RAD2DEG = (180.0/M_PI);
Simulator::Simulator(const SimulatorSettings& params) :
inSocket(NULL),
outSocket(NULL),
settings(params),
updatePeriod(50),
simTimeout(2000),
autopilotConnectionStatus(false),
simConnectionStatus(false),
txTimer(NULL),
simTimer(NULL),
name("")
{
// move to thread
moveToThread(Core::ICore::instance()->threadManager()->getRealTimeThread());
connect(this, SIGNAL(myStart()), this, SLOT(onStart()), Qt::QueuedConnection);
emit myStart();
}
Simulator::~Simulator()
{
// qDebug() << "Simulator::~Simulator";
if (inSocket) {
delete inSocket;
inSocket = NULL;
}
if (outSocket) {
delete outSocket;
outSocket = NULL;
}
if (txTimer) {
delete txTimer;
txTimer = NULL;
}
if (simTimer) {
delete simTimer;
simTimer = NULL;
}
}
void Simulator::onDeleteSimulator(void)
{
// qDebug() << "Simulator::onDeleteSimulator";
resetAllObjects();
Simulator::setStarted(false);
Simulator::Instances().removeOne(simulatorId);
disconnect(this);
delete this;
}
void Simulator::onStart()
{
// qDebug() << "Simulator::onStart";
QMutexLocker locker(&lock);
// Get required UAVObjects
ExtensionSystem::PluginManager* pm = ExtensionSystem::PluginManager::instance();
UAVObjectManager* objManager = pm->getObject<UAVObjectManager>();
// actDesired = ActuatorDesired::GetInstance(objManager);
// manCtrlCommand = ManualControlCommand::GetInstance(objManager);
// velActual = VelocityActual::GetInstance(objManager);
// posActual = PositionActual::GetInstance(objManager);
// altActual = BaroAltitude::GetInstance(objManager);
// camDesired = CameraDesired::GetInstance(objManager);
// acsDesired = AccessoryDesired::GetInstance(objManager);
posHome = HomeLocation::GetInstance(objManager);
accels = Accels::GetInstance(objManager);
gyros = Gyros::GetInstance(objManager);
attActual = AttitudeActual::GetInstance(objManager);
gpsPosition = GPSPosition::GetInstance(objManager);
flightStatus = FlightStatus::GetInstance(objManager);
gcsReceiver = GCSReceiver::GetInstance(objManager);
actCommand = ActuatorCommand::GetInstance(objManager);
attSettings = AttitudeSettings::GetInstance(objManager);
sonarAlt = SonarAltitude::GetInstance(objManager);
telStats = GCSTelemetryStats::GetInstance(objManager);
// Listen to autopilot connection events
TelemetryManager* telMngr = pm->getObject<TelemetryManager>();
connect(telMngr, SIGNAL(connected()), this, SLOT(onAutopilotConnect()));
connect(telMngr, SIGNAL(disconnected()), this, SLOT(onAutopilotDisconnect()));
// If already connect setup autopilot
GCSTelemetryStats::DataFields stats = telStats->getData();
if (stats.Status == GCSTelemetryStats::STATUS_CONNECTED)
onAutopilotConnect();
emit processOutput("Local interface: " + settings.hostAddress + ":" + \
QString::number(settings.inPort) + "\n" + \
"Remote interface: " + settings.remoteAddress + ":" + \
QString::number(settings.outPort) + "\n");
inSocket = new QUdpSocket();
outSocket = new QUdpSocket();
setupUdpPorts(settings.hostAddress, settings.inPort, settings.outPort);
connect(inSocket, SIGNAL(readyRead()), this, SLOT(receiveUpdate())/*, Qt::DirectConnection*/);
// Setup transmit timer
if (settings.manualOutput) {
txTimer = new QTimer();
connect(txTimer, SIGNAL(timeout()), this, SLOT(transmitUpdate())/*, Qt::DirectConnection*/);
txTimer->setInterval(settings.outputRate);
txTimer->start();
}
// Setup simulator connection timer
simTimer = new QTimer();
connect(simTimer, SIGNAL(timeout()), this, SLOT(onSimulatorConnectionTimeout())/*, Qt::DirectConnection*/);
simTimer->setInterval(simTimeout);
simTimer->start();
#ifdef DBG_TIMERS
timeRX = QTime();
timeRX.start();
timeTX = QTime();
timeTX.start();
#endif
setupObjects();
}
void Simulator::receiveUpdate()
{
// Update connection timer and status
simTimer->start();
if (!simConnectionStatus) {
simConnectionStatus = true;
emit simulatorConnected();
}
// Process data
while (inSocket->hasPendingDatagrams()) {
// Receive datagram
QByteArray datagram;
datagram.resize(inSocket->pendingDatagramSize());
QHostAddress sender;
quint16 senderPort;
inSocket->readDatagram(datagram.data(), datagram.size(), &sender, &senderPort);
// Process incomming data
processUpdate(datagram);
}
if (!settings.manualOutput)
transmitUpdate();
}
void Simulator::setupObjects()
{
if (settings.gcsReciever) {
setupInputObject(actCommand, settings.outputRate);
setupOutputObject(gcsReceiver);
} else if (settings.manualControl) {
// setupInputObject(actDesired);
// setupInputObject(camDesired);
// setupInputObject(acsDesired);
// setupOutputObject(manCtrlCommand);
qDebug() << "ManualControlCommand not implemented yet";
}
if (settings.homeLocation)
setupOutputObject(posHome);
if (settings.sonarAltitude)
setupOutputObject(sonarAlt);
if (settings.gpsPosition)
setupOutputObject(gpsPosition);
if (settings.attRaw || settings.attActual) {
setupOutputObject(accels);
setupOutputObject(gyros);
}
if (settings.attActual && !settings.attActHW)
setupOutputObject(attActual);
else
setupWatchedObject(attActual);
}
void Simulator::resetAllObjects()
{
setupDefaultObject(posHome);
setupDefaultObject(accels);
setupDefaultObject(gyros);
setupDefaultObject(attActual);
setupDefaultObject(gpsPosition);
setupDefaultObject(gcsReceiver);
setupDefaultObject(actCommand);
setupDefaultObject(sonarAlt);
// setupDefaultObject(manCtrlCommand);
// setupDefaultObject(actDesired);
// setupDefaultObject(camDesired);
// setupDefaultObject(acsDesired);
// setupDefaultObject(altActual);
// setupDefaultObject(posActual);
// setupDefaultObject(velActual);
}
void Simulator::setupInputObject(UAVObject* obj, quint32 updateRate)
{
UAVObject::Metadata mdata;
mdata = obj->getDefaultMetadata();
UAVObject::SetGcsAccess(mdata, UAVObject::ACCESS_READONLY);
UAVObject::SetGcsTelemetryAcked(mdata, false);
UAVObject::SetGcsTelemetryUpdateMode(mdata, UAVObject::UPDATEMODE_MANUAL);
mdata.gcsTelemetryUpdatePeriod = 0;
UAVObject::SetFlightAccess(mdata, UAVObject::ACCESS_READWRITE);
UAVObject::SetFlightTelemetryAcked(mdata, false);
if (settings.manualOutput) {
UAVObject::SetFlightTelemetryUpdateMode(mdata, UAVObject::UPDATEMODE_PERIODIC);
mdata.flightTelemetryUpdatePeriod = updateRate;
} else {
UAVObject::SetFlightTelemetryUpdateMode(mdata, UAVObject::UPDATEMODE_ONCHANGE);
mdata.flightTelemetryUpdatePeriod = 0;
}
obj->setMetadata(mdata);
}
void Simulator::setupWatchedObject(UAVObject *obj)
{
UAVObject::Metadata mdata;
mdata = obj->getDefaultMetadata();
UAVObject::SetGcsAccess(mdata, UAVObject::ACCESS_READONLY);
UAVObject::SetGcsTelemetryAcked(mdata, false);
UAVObject::SetGcsTelemetryUpdateMode(mdata, UAVObject::UPDATEMODE_MANUAL);
mdata.gcsTelemetryUpdatePeriod = 0;
UAVObject::SetFlightAccess(mdata, UAVObject::ACCESS_READWRITE);
UAVObject::SetFlightTelemetryAcked(mdata, false);
UAVObject::SetFlightTelemetryUpdateMode(mdata, UAVObject::UPDATEMODE_PERIODIC);
mdata.flightTelemetryUpdatePeriod = 100;
obj->setMetadata(mdata);
}
void Simulator::setupOutputObject(UAVObject* obj)
{
UAVObject::Metadata mdata;
mdata = obj->getDefaultMetadata();
UAVObject::SetGcsAccess(mdata, UAVObject::ACCESS_READWRITE);
UAVObject::SetGcsTelemetryAcked(mdata, false);
UAVObject::SetGcsTelemetryUpdateMode(mdata, UAVObject::UPDATEMODE_ONCHANGE);
mdata.gcsTelemetryUpdatePeriod = 0;
UAVObject::SetFlightAccess(mdata, UAVObject::ACCESS_READONLY);
UAVObject::SetFlightTelemetryAcked(mdata, false);
UAVObject::SetFlightTelemetryUpdateMode(mdata, UAVObject::UPDATEMODE_MANUAL);
mdata.flightTelemetryUpdatePeriod = 0;
obj->setMetadata(mdata);
}
void Simulator::setupDefaultObject(UAVObject *obj)
{
UAVObject::Metadata mdata;
mdata = obj->getDefaultMetadata();
obj->setMetadata(mdata);
}
void Simulator::onAutopilotConnect()
{
autopilotConnectionStatus = true;
emit autopilotConnected();
}
void Simulator::onAutopilotDisconnect()
{
autopilotConnectionStatus = false;
emit autopilotDisconnected();
}
void Simulator::onSimulatorConnectionTimeout()
{
if (simConnectionStatus) {
simConnectionStatus = false;
emit simulatorDisconnected();
}
}
void Simulator::telStatsUpdated(UAVObject* obj)
{
GCSTelemetryStats::DataFields stats = telStats->getData();
if (!autopilotConnectionStatus && stats.Status == GCSTelemetryStats::STATUS_CONNECTED)
onAutopilotConnect();
else if (autopilotConnectionStatus && stats.Status != GCSTelemetryStats::STATUS_CONNECTED)
onAutopilotDisconnect();
}

View File

@ -0,0 +1,222 @@
/**
******************************************************************************
*
* @file simulator.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @addtogroup GCSPlugins GCS Plugins
* @{
* @addtogroup HITLPlugin HITL Plugin
* @{
* @brief The Hardware In The Loop plugin
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef ISIMULATORV2_H
#define ISIMULATORV2_H
#include <QObject>
#include <QUdpSocket>
#include <QTimer>
#include <QProcess>
#include <QScopedPointer>
#include <qmath.h>
#include "uavtalk/telemetrymanager.h"
#include "uavobjectmanager.h"
#include "homelocation.h"
#include "accels.h"
#include "gyros.h"
#include "attitudeactual.h"
#include "gpsposition.h"
#include "flightstatus.h"
#include "gcsreceiver.h"
#include "actuatorcommand.h"
#include "gcstelemetrystats.h"
#include "attitudesettings.h"
#include "sonaraltitude.h"
//#define DBG_TIMERS
#undef DBG_TIMERS
/**
* just imagine this was a class without methods and all public properties
*/
typedef struct _CONNECTION
{
QString simulatorId;
QString hostAddress;
int inPort;
QString remoteAddress;
int outPort;
QString binPath;
QString dataPath;
bool homeLocation;
quint16 homeLocRate;
bool attRaw;
quint8 attRawRate;
bool attActual;
bool attActHW;
bool attActSim;
bool attActCalc;
bool sonarAltitude;
float sonarMaxAlt;
quint16 sonarAltRate;
bool gpsPosition;
quint16 gpsPosRate;
bool inputCommand;
bool gcsReciever;
bool manualControl;
bool manualOutput;
quint8 outputRate;
} SimulatorSettings;
class Simulator : public QObject
{
Q_OBJECT
public:
Simulator(const SimulatorSettings& params);
virtual ~Simulator();
bool isAutopilotConnected() const { return autopilotConnectionStatus; }
bool isSimulatorConnected() const { return simConnectionStatus; }
QString Name() const { return name; }
void setName(QString str) { name = str; }
QString SimulatorId() const { return simulatorId; }
void setSimulatorId(QString str) { simulatorId = str; }
static bool IsStarted() { return isStarted; }
static void setStarted(bool val) { isStarted = val; }
static QStringList& Instances() { return Simulator::instances; }
static void setInstance(const QString& str) { Simulator::instances.append(str); }
virtual void stopProcess() {}
virtual void setupUdpPorts(const QString& host, int inPort, int outPort) { Q_UNUSED(host) Q_UNUSED(inPort) Q_UNUSED(outPort)}
signals:
void processOutput(QString str);
void autopilotConnected();
void autopilotDisconnected();
void simulatorConnected();
void simulatorDisconnected();
void myStart();
public slots:
Q_INVOKABLE virtual bool setupProcess() { return true; }
private slots:
void onStart();
void receiveUpdate();
void onAutopilotConnect();
void onAutopilotDisconnect();
void onSimulatorConnectionTimeout();
void telStatsUpdated(UAVObject* obj);
Q_INVOKABLE void onDeleteSimulator(void);
virtual void transmitUpdate() = 0;
virtual void processUpdate(const QByteArray& data) = 0;
protected:
static const float GEE;
static const float FT2M;
static const float KT2MPS;
static const float INHG2KPA;
static const float FPS2CMPS;
static const float DEG2RAD;
static const float RAD2DEG;
#ifdef DBG_TIMERS
QTime timeRX;
QTime timeTX;
#endif
QUdpSocket* inSocket;
QUdpSocket* outSocket;
// ActuatorDesired* actDesired;
// ManualControlCommand* manCtrlCommand;
// VelocityActual* velActual;
// PositionActual* posActual;
// BaroAltitude* altActual;
// CameraDesired *camDesired;
// AccessoryDesired *acsDesired;
Accels *accels;
Gyros *gyros;
AttitudeActual *attActual;
HomeLocation *posHome;
FlightStatus *flightStatus;
GPSPosition *gpsPosition;
GCSReceiver *gcsReceiver;
ActuatorCommand *actCommand;
AttitudeSettings *attSettings;
SonarAltitude *sonarAlt;
GCSTelemetryStats* telStats;
SimulatorSettings settings;
QMutex lock;
private:
int updatePeriod;
int simTimeout;
volatile bool autopilotConnectionStatus;
volatile bool simConnectionStatus;
QTimer* txTimer;
QTimer* simTimer;
QString name;
QString simulatorId;
volatile static bool isStarted;
static QStringList instances;
void setupObjects();
void resetAllObjects();
void setupInputObject(UAVObject* obj, quint32 updateRate);
void setupOutputObject(UAVObject* obj);
void setupWatchedObject(UAVObject *obj);
void setupDefaultObject(UAVObject *obj);
};
class SimulatorCreator
{
public:
SimulatorCreator(QString id, QString descr) :
classId(id),
description(descr)
{}
virtual ~SimulatorCreator() {}
QString ClassId() const { return classId; }
QString Description() const { return description; }
virtual Simulator* createSimulator(const SimulatorSettings& params) = 0;
private:
QString classId;
QString description;
};
#endif // ISIMULATORV2_H

View File

@ -256,7 +256,10 @@ void NotifyPluginOptionsPage::addDynamicField(UAVObjectField* objField)
_dynamicFieldCondition->removeItem(smaller);
_dynamicFieldCondition->removeItem(bigger);
}
_dynamicFieldCondition->setCurrentIndex(_dynamicFieldCondition->findText(NotifyPluginOptionsPage::conditionValues.at(_selectedNotification->getCondition())));
int cond=_selectedNotification->getCondition();
if(cond<0)
return;
_dynamicFieldCondition->setCurrentIndex(_dynamicFieldCondition->findText(NotifyPluginOptionsPage::conditionValues.at(cond)));
connect(_dynamicFieldCondition, SIGNAL(currentIndexChanged(QString)),
this, SLOT(on_changedIndex_rangeValue(QString)));
@ -434,8 +437,10 @@ void NotifyPluginOptionsPage::updateConfigView(NotificationItem* notification)
_optionsPage->SoundCollectionList->setCurrentIndex(_optionsPage->SoundCollectionList->findText("default"));
_optionsPage->Sound3->setCurrentIndex(_optionsPage->Sound3->findText(notification->getSound3()));
}
_dynamicFieldCondition->setCurrentIndex(_dynamicFieldCondition->findText(NotifyPluginOptionsPage::conditionValues.at(notification->getCondition())));
int cond=notification->getCondition();
if(cond<0)
return;
_dynamicFieldCondition->setCurrentIndex(_dynamicFieldCondition->findText(NotifyPluginOptionsPage::conditionValues.at(cond)));
_sayOrder->setCurrentIndex(notification->getSayOrder());

View File

@ -140,13 +140,19 @@ plugin_ipconnection.subdir = ipconnection
plugin_ipconnection.depends = plugin_coreplugin
SUBDIRS += plugin_ipconnection
# Disable until updated to the new sensor objects
#HITLNEW Simulation gadget
#plugin_hitlnew.subdir = hitlnew
#plugin_hitlnew.depends = plugin_coreplugin
#plugin_hitlnew.depends += plugin_uavobjects
#plugin_hitlnew.depends += plugin_uavtalk
#SUBDIRS += plugin_hitlnew
plugin_hitlnew.subdir = hitlnew
plugin_hitlnew.depends = plugin_coreplugin
plugin_hitlnew.depends += plugin_uavobjects
plugin_hitlnew.depends += plugin_uavtalk
SUBDIRS += plugin_hitlnew
#HITLNEW Simulation gadget v2
plugin_hitl_v2.subdir = hitlv2
plugin_hitl_v2.depends = plugin_coreplugin
plugin_hitl_v2.depends += plugin_uavobjects
plugin_hitl_v2.depends += plugin_uavtalk
SUBDIRS += plugin_hitl_v2
# Export and Import GCS Configuration
plugin_importexport.subdir = importexport

View File

@ -12,18 +12,23 @@ public:
int boardRevision;
static QString idToBoardName(int id)
{
switch (id | 0x0011) {
case 0x0111://MB
switch (id) {
case 0x0101://MB
return QString("OpenPilot MainBoard");
break;
case 0x0311://PipX
case 0x0201://INS
return QString("OpenPilot INS");
break;
case 0x0301://PipX
return QString("PipXtreame");
break;
case 0x0411://Coptercontrol
case 0x0401://Coptercontrol
return QString("CopterControl");
break;
case 0x0211://INS
return QString("OpenPilot INS");
case 0x0402://Coptercontrol
// It would be nice to say CC3D here but since currently we use string comparisons
// for firmware compatibility and the filename path that would break
return QString("CopterControl");
break;
default:
return QString("");

View File

@ -35,6 +35,7 @@
#include <QEventLoop>
#include <QTimer>
#include <objectpersistence.h>
#include <firmwareiapobj.h>
// ******************************
// constructor/destructor
@ -199,25 +200,63 @@ void UAVObjectUtilManager::objectPersistenceOperationFailed()
*/
void UAVObjectUtilManager::objectPersistenceUpdated(UAVObject * obj)
{
qDebug() << "objectPersistenceUpdated: " << obj->getField("Operation")->getValue().toString();
Q_ASSERT(obj->getName().compare("ObjectPersistence") == 0);
if(saveState == AWAITING_COMPLETED) {
failureTimer.stop();
// Check flight is saying it completed. This is the only thing flight should do to trigger an update.
Q_ASSERT( obj->getField("Operation")->getValue().toString().compare(QString("Completed")) == 0 );
Q_ASSERT(obj);
Q_ASSERT(obj->getObjID() == ObjectPersistence::OBJID);
ObjectPersistence::DataFields objectPersistence = ((ObjectPersistence *)obj)->getData();
if(saveState == AWAITING_COMPLETED && objectPersistence.Operation == ObjectPersistence::OPERATION_ERROR) {
failureTimer.stop();
objectPersistenceOperationFailed();
} else if (saveState == AWAITING_COMPLETED &&
objectPersistence.Operation == ObjectPersistence::OPERATION_COMPLETED) {
failureTimer.stop();
// Check right object saved
UAVObject* savingObj = queue.head();
Q_ASSERT( obj->getField("ObjectID")->getValue() == savingObj->getObjID() );
if(objectPersistence.ObjectID != savingObj->getObjID() ) {
objectPersistenceOperationFailed();
return;
}
obj->disconnect(this);
queue.dequeue(); // We can now remove the object, it's done.
saveState = IDLE;
emit saveCompleted(obj->getField("ObjectID")->getValue().toInt(), true);
emit saveCompleted(objectPersistence.ObjectID, true);
saveNextObject();
}
}
/**
* Helper function that makes sure FirmwareIAP is updated and then returns the data
*/
FirmwareIAPObj::DataFields UAVObjectUtilManager::getFirmwareIap()
{
FirmwareIAPObj::DataFields dummy;
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
Q_ASSERT(pm);
if (!pm)
return dummy;
UAVObjectManager *om = pm->getObject<UAVObjectManager>();
Q_ASSERT(om);
if (!om)
return dummy;
FirmwareIAPObj *firmwareIap = FirmwareIAPObj::GetInstance(om);
Q_ASSERT(firmwareIap);
if (!firmwareIap)
return dummy;
// The code below will ask for the object update and wait for the updated to be received,
// or the timeout of the timer, set to 1 second.
QEventLoop loop;
connect(firmwareIap, SIGNAL(objectUpdated(UAVObject*)), &loop, SLOT(quit()));
QTimer::singleShot(1000, &loop, SLOT(quit())); // Create a timeout
firmwareIap->requestUpdate();
loop.exec();
return firmwareIap->getData();
}
/**
* Get the UAV Board model, for anyone interested. Return format is:
@ -225,25 +264,8 @@ void UAVObjectUtilManager::objectPersistenceUpdated(UAVObject * obj)
*/
int UAVObjectUtilManager::getBoardModel()
{
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
if (!pm)
return 0;
UAVObjectManager *om = pm->getObject<UAVObjectManager>();
if (!om)
return 0;
UAVDataObject *obj = dynamic_cast<UAVDataObject *>(om->getObject(QString("FirmwareIAPObj")));
// The code below will ask for the object update and wait for the updated to be received,
// or the timeout of the timer, set to 1 second.
QEventLoop loop;
connect(obj, SIGNAL(objectUpdated(UAVObject*)), &loop, SLOT(quit()));
QTimer::singleShot(1000, &loop, SLOT(quit())); // Create a timeout
obj->requestUpdate();
loop.exec();
int boardType = (obj->getField("BoardType")->getValue().toInt()) << 8;
boardType += obj->getField("BoardRevision")->getValue().toInt();
return boardType;
FirmwareIAPObj::DataFields firmwareIapData = getFirmwareIap();
return (firmwareIapData.BoardType << 8) + firmwareIapData.BoardRevision;
}
/**
@ -252,54 +274,18 @@ int UAVObjectUtilManager::getBoardModel()
QByteArray UAVObjectUtilManager::getBoardCPUSerial()
{
QByteArray cpuSerial;
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
if (!pm)
return 0;
UAVObjectManager *om = pm->getObject<UAVObjectManager>();
if (!om)
return 0;
FirmwareIAPObj::DataFields firmwareIapData = getFirmwareIap();
UAVDataObject *obj = dynamic_cast<UAVDataObject *>(om->getObject(QString("FirmwareIAPObj")));
// The code below will ask for the object update and wait for the updated to be received,
// or the timeout of the timer, set to 1 second.
QEventLoop loop;
connect(obj, SIGNAL(objectUpdated(UAVObject*)), &loop, SLOT(quit()));
QTimer::singleShot(1000, &loop, SLOT(quit())); // Create a timeout
obj->requestUpdate();
loop.exec();
for (int i = 0; i < FirmwareIAPObj::CPUSERIAL_NUMELEM; i++)
cpuSerial.append(firmwareIapData.CPUSerial[i]);
UAVObjectField* cpuField = obj->getField("CPUSerial");
for (uint i = 0; i < cpuField->getNumElements(); ++i) {
cpuSerial.append(cpuField->getValue(i).toUInt());
}
return cpuSerial;
}
quint32 UAVObjectUtilManager::getFirmwareCRC()
{
quint32 fwCRC;
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
if (!pm)
return 0;
UAVObjectManager *om = pm->getObject<UAVObjectManager>();
if (!om)
return 0;
UAVDataObject *obj = dynamic_cast<UAVDataObject *>(om->getObject(QString("FirmwareIAPObj")));
obj->getField("crc")->setValue(0);
obj->updated();
// The code below will ask for the object update and wait for the updated to be received,
// or the timeout of the timer, set to 1 second.
QEventLoop loop;
connect(obj, SIGNAL(objectUpdated(UAVObject*)), &loop, SLOT(quit()));
QTimer::singleShot(1000, &loop, SLOT(quit())); // Create a timeout
obj->requestUpdate();
loop.exec();
UAVObjectField* fwCRCField = obj->getField("crc");
fwCRC=(quint32)fwCRCField->getValue().toLongLong();
return fwCRC;
FirmwareIAPObj::DataFields firmwareIapData = getFirmwareIap();
return firmwareIapData.crc;
}
/**
@ -308,27 +294,11 @@ quint32 UAVObjectUtilManager::getFirmwareCRC()
QByteArray UAVObjectUtilManager::getBoardDescription()
{
QByteArray ret;
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
if (!pm)
return 0;
UAVObjectManager *om = pm->getObject<UAVObjectManager>();
if (!om)
return 0;
FirmwareIAPObj::DataFields firmwareIapData = getFirmwareIap();
UAVDataObject *obj = dynamic_cast<UAVDataObject *>(om->getObject(QString("FirmwareIAPObj")));
// The code below will ask for the object update and wait for the updated to be received,
// or the timeout of the timer, set to 1 second.
QEventLoop loop;
connect(obj, SIGNAL(objectUpdated(UAVObject*)), &loop, SLOT(quit()));
QTimer::singleShot(1000, &loop, SLOT(quit())); // Create a timeout
obj->requestUpdate();
loop.exec();
for (int i = 0; i < FirmwareIAPObj::DESCRIPTION_NUMELEM; i++)
ret.append(firmwareIapData.Description[i]);
UAVObjectField* descriptionField = obj->getField("Description");
// Description starts with an offset of
for (uint i = 0; i < descriptionField->getNumElements(); ++i) {
ret.append(descriptionField->getValue(i).toInt());
}
return ret;
}

View File

@ -43,6 +43,8 @@
#include <QQueue>
#include <QComboBox>
#include <QDateTime>
#include <firmwareiapobj.h>
class UAVOBJECTUTIL_EXPORT UAVObjectUtilManager: public QObject
{
Q_OBJECT
@ -69,6 +71,8 @@ public:
static bool descriptionToStructure(QByteArray desc,deviceDescriptorStruct * struc);
UAVObjectManager* getObjectManager();
void saveObjectToSD(UAVObject *obj);
protected:
FirmwareIAPObj::DataFields getFirmwareIap();
signals:
void saveCompleted(int objectID, bool status);

View File

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

View File

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

View File

@ -78,27 +78,6 @@ void deviceWidget::setDfu(DFUObject *dfu)
m_dfu = dfu;
}
QString deviceWidget::idToBoardName(int id)
{
switch (id | 0x0011) {
case 0x0111://MB
return QString("OpenPilot MainBoard");
break;
case 0x0311://PipX
return QString("PipXtreme");
break;
case 0x0411://Coptercontrol
return QString("CopterControl");
break;
case 0x0211://INS
return QString("OpenPilot INS");
break;
default:
return QString("");
break;
}
}
/**
Fills the various fields for the device
*/
@ -125,6 +104,9 @@ void deviceWidget::populate()
case 0x0401:
devicePic->renderer()->load(QString(":/uploader/images/deviceID-0401.svg"));
break;
case 0x0402:
devicePic->renderer()->load(QString(":/uploader/images/deviceID-0402.svg"));
break;
case 0x0201:
devicePic->renderer()->load(QString(":/uploader/images/deviceID-0201.svg"));
break;
@ -200,7 +182,7 @@ bool deviceWidget::populateBoardStructuredDescription(QByteArray desc)
myDevice->lblCertified->setToolTip(tr("Untagged or custom firmware build"));
}
myDevice->lblBrdName->setText(idToBoardName(onBoardDescription.boardType<<8));
myDevice->lblBrdName->setText(deviceDescriptorStruct::idToBoardName(onBoardDescription.boardType << 8 | onBoardDescription.boardRevision));
return true;
}
@ -230,7 +212,7 @@ bool deviceWidget::populateLoadedStructuredDescription(QByteArray desc)
myDevice->lblCertifiedL->setPixmap(pix);
myDevice->lblCertifiedL->setToolTip(tr("Untagged or custom firmware build"));
}
myDevice->lblBrdNameL->setText(deviceDescriptorStruct::idToBoardName(LoadedDescription.boardType<<8));
myDevice->lblBrdNameL->setText(deviceDescriptorStruct::idToBoardName(LoadedDescription.boardType << 8 | LoadedDescription.boardRevision));
return true;
}

View File

@ -59,7 +59,6 @@ private:
deviceDescriptorStruct onBoardDescription;
deviceDescriptorStruct LoadedDescription;
QByteArray loadedFW;
QString idToBoardName(int id);
Ui_deviceWidget *myDevice;
int deviceID;
DFUObject *m_dfu;

View File

@ -0,0 +1,2389 @@
<?xml version="1.0" encoding="UTF-8" standalone="no"?>
<!-- Created with Inkscape (http://www.inkscape.org/) -->
<svg
xmlns:dc="http://purl.org/dc/elements/1.1/"
xmlns:cc="http://creativecommons.org/ns#"
xmlns:rdf="http://www.w3.org/1999/02/22-rdf-syntax-ns#"
xmlns:svg="http://www.w3.org/2000/svg"
xmlns="http://www.w3.org/2000/svg"
xmlns:sodipodi="http://sodipodi.sourceforge.net/DTD/sodipodi-0.dtd"
xmlns:inkscape="http://www.inkscape.org/namespaces/inkscape"
id="svg3578"
version="1.1"
inkscape:version="0.48.2 r9819"
width="217.16675"
height="212.0625"
xml:space="preserve"
sodipodi:docname="deviceID-0402.svg"><metadata
id="metadata3584"><rdf:RDF><cc:Work
rdf:about=""><dc:format>image/svg+xml</dc:format><dc:type
rdf:resource="http://purl.org/dc/dcmitype/StillImage" /><dc:title /></cc:Work></rdf:RDF></metadata><defs
id="defs3582"><clipPath
clipPathUnits="userSpaceOnUse"
id="clipPath3596"><path
d="M 0,0 662,0 662,675 0,675 0,0 z"
id="path3598"
inkscape:connector-curvature="0" /></clipPath></defs><sodipodi:namedview
pagecolor="#ffffff"
bordercolor="#666666"
borderopacity="1"
objecttolerance="10"
gridtolerance="10"
guidetolerance="10"
inkscape:pageopacity="0"
inkscape:pageshadow="2"
inkscape:window-width="1680"
inkscape:window-height="930"
id="namedview3580"
showgrid="false"
inkscape:zoom="1.4596704"
inkscape:cx="74.195835"
inkscape:cy="113.87434"
inkscape:window-x="0"
inkscape:window-y="0"
inkscape:window-maximized="1"
inkscape:current-layer="device"
fit-margin-top="0"
fit-margin-left="0"
fit-margin-right="0"
fit-margin-bottom="0" /><g
inkscape:groupmode="layer"
id="layer2"
inkscape:label="Rendering#1"
style="display:inline"
transform="translate(-40.177007,-31.1875)"><g
id="device"
inkscape:label="#g15334"><rect
rx="13.079585"
ry="10"
y="32.199471"
x="46.668976"
height="210.03767"
width="209.67079"
id="rect9798"
style="fill:#171717;fill-opacity:1;stroke:#000000;stroke-width:2;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><g
transform="translate(-311.74173,-199.45)"
id="g4318"
style="display:inline"><rect
y="365.75504"
x="422.11606"
height="5.0892859"
width="6.5178571"
id="rect4320"
style="fill:#312d29;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
id="rect4322"
width="3.5714285"
height="5.0892859"
x="428.58929"
y="365.75504" /><rect
y="365.75504"
x="418.58929"
height="5.0892859"
width="3.5714285"
id="rect4324"
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /></g><g
transform="matrix(0,-1,1,0,-158.96398,620.23853)"
id="g4406"
style="display:inline"><rect
y="365.75504"
x="422.11606"
height="5.0892859"
width="6.5178571"
id="rect4408"
style="fill:#312d29;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
id="rect4410"
width="3.5714285"
height="5.0892859"
x="428.58929"
y="365.75504" /><rect
y="365.75504"
x="418.58929"
height="5.0892859"
width="3.5714285"
id="rect4412"
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /></g><g
style="display:inline"
id="g10505"
transform="translate(-238.1085,-287.13166)"><rect
style="fill:#312d29;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
id="rect10507"
width="6.5178571"
height="5.0892859"
x="422.11606"
y="365.75504" /><rect
y="365.75504"
x="428.58929"
height="5.0892859"
width="3.5714285"
id="rect10509"
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
id="rect10511"
width="3.5714285"
height="5.0892859"
x="418.58929"
y="365.75504" /></g><g
transform="translate(-297.20885,-185.40155)"
id="g10513"
style="display:inline"><rect
y="365.75504"
x="422.11606"
height="5.0892859"
width="6.5178571"
id="rect10515"
style="fill:#312d29;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
id="rect10517"
width="3.5714285"
height="5.0892859"
x="428.58929"
y="365.75504" /><rect
y="365.75504"
x="418.58929"
height="5.0892859"
width="3.5714285"
id="rect10519"
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /></g><g
id="g4225"
style="display:inline"
transform="translate(-324.12933,-188.57649)"><rect
style="fill:#bc781e;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
id="rect4219"
width="6.5178571"
height="5.0892859"
x="422.11606"
y="365.75504" /><rect
y="365.75504"
x="428.58929"
height="5.0892859"
width="3.5714285"
id="rect4221"
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
id="rect4223"
width="3.5714285"
height="5.0892859"
x="418.58929"
y="365.75504" /></g><g
transform="translate(-229.42344,-179.37234)"
style="display:inline"
id="g10548"><rect
y="365.75504"
x="422.11606"
height="5.0892859"
width="6.5178571"
id="rect10550"
style="fill:#bc781e;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
id="rect10552"
width="3.5714285"
height="5.0892859"
x="428.58929"
y="365.75504" /><rect
y="365.75504"
x="418.58929"
height="5.0892859"
width="3.5714285"
id="rect10554"
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /></g><g
id="g10556"
style="display:inline"
transform="translate(-230.15008,-167.50383)"><rect
style="fill:#bc781e;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
id="rect10558"
width="6.5178571"
height="5.0892859"
x="422.11606"
y="365.75504" /><rect
y="365.75504"
x="428.58929"
height="5.0892859"
width="3.5714285"
id="rect10560"
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
id="rect10562"
width="3.5714285"
height="5.0892859"
x="418.58929"
y="365.75504" /></g><g
transform="translate(-235.23659,-253.7322)"
style="display:inline"
id="g10564"><rect
y="365.75504"
x="422.11606"
height="5.0892859"
width="6.5178571"
id="rect10566"
style="fill:#bc781e;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
id="rect10568"
width="3.5714285"
height="5.0892859"
x="428.58929"
y="365.75504" /><rect
y="365.75504"
x="418.58929"
height="5.0892859"
width="3.5714285"
id="rect10570"
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /></g><g
id="g10572"
style="display:inline"
transform="translate(-214.16393,-327.60763)"><rect
style="fill:#bc781e;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
id="rect10574"
width="6.5178571"
height="5.0892859"
x="422.11606"
y="365.75504" /><rect
y="365.75504"
x="428.58929"
height="5.0892859"
width="3.5714285"
id="rect10576"
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
id="rect10578"
width="3.5714285"
height="5.0892859"
x="418.58929"
y="365.75504" /></g><g
id="g4414"
transform="translate(-365.77251,-288.34483)"
style="display:inline"><rect
style="fill:#0052ff;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
id="rect4416"
width="6.5178571"
height="5.0892859"
x="422.11606"
y="365.75504" /><rect
y="365.75504"
x="428.58929"
height="5.0892859"
width="3.5714285"
id="rect4418"
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
id="rect4420"
width="3.5714285"
height="5.0892859"
x="418.58929"
y="365.75504" /></g><g
id="g10667"
style="display:inline"
transform="translate(-466.1013,-470.16522)"><rect
style="fill:#ff7900;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
id="rect4432"
width="6.5178571"
height="5.0892859"
x="522.11609"
y="559.755" /><rect
y="559.755"
x="528.58929"
height="5.0892859"
width="3.5714285"
id="rect4434"
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
id="rect4436"
width="3.5714285"
height="5.0892859"
x="518.58929"
y="559.755" /></g><g
transform="matrix(0,1,-1,0,476.81179,-372.57224)"
id="g4278"
style="display:inline"><rect
y="365.75504"
x="422.11606"
height="5.0892859"
width="6.5178571"
id="rect4280"
style="fill:#bc781e;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
id="rect4282"
width="3.5714285"
height="5.0892859"
x="428.58929"
y="365.75504" /><rect
y="365.75504"
x="418.58929"
height="5.0892859"
width="3.5714285"
id="rect4284"
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /></g><g
style="display:inline"
id="g10761"
transform="matrix(0,1,-1,0,476.81179,-340.57224)"><rect
style="fill:#bc781e;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
id="rect10763"
width="6.5178571"
height="5.0892859"
x="422.11606"
y="365.75504" /><rect
y="365.75504"
x="428.58929"
height="5.0892859"
width="3.5714285"
id="rect10765"
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
id="rect10767"
width="3.5714285"
height="5.0892859"
x="418.58929"
y="365.75504" /></g><g
style="display:inline"
id="g10777"
transform="matrix(0,1,-1,0,453.06093,-235.02206)"><rect
style="fill:#bc781e;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
id="rect10779"
width="6.5178571"
height="5.0892859"
x="422.11606"
y="365.75504" /><rect
y="365.75504"
x="428.58929"
height="5.0892859"
width="3.5714285"
id="rect10781"
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
id="rect10783"
width="3.5714285"
height="5.0892859"
x="418.58929"
y="365.75504" /></g><g
transform="matrix(0,1,-1,0,453.06093,-213.9494)"
id="g10785"
style="display:inline"><rect
y="365.75504"
x="422.11606"
height="5.0892859"
width="6.5178571"
id="rect10787"
style="fill:#bc781e;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
id="rect10789"
width="3.5714285"
height="5.0892859"
x="428.58929"
y="365.75504" /><rect
y="365.75504"
x="418.58929"
height="5.0892859"
width="3.5714285"
id="rect10791"
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /></g><g
style="display:inline"
id="g10793"
transform="matrix(0,1,-1,0,497.6284,-222.66912)"><rect
style="fill:#bc781e;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
id="rect10795"
width="6.5178571"
height="5.0892859"
x="422.11606"
y="365.75504" /><rect
y="365.75504"
x="428.58929"
height="5.0892859"
width="3.5714285"
id="rect10797"
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
id="rect10799"
width="3.5714285"
height="5.0892859"
x="418.58929"
y="365.75504" /></g><g
style="display:inline"
id="g10801"
transform="matrix(0,-1,1,0,-252.45879,579.30427)"><rect
style="fill:#312d29;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
id="rect10803"
width="6.5178571"
height="5.0892859"
x="422.11606"
y="365.75504" /><rect
y="365.75504"
x="428.58929"
height="5.0892859"
width="3.5714285"
id="rect10805"
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
id="rect10807"
width="3.5714285"
height="5.0892859"
x="418.58929"
y="365.75504" /></g><g
transform="matrix(0,-1,1,0,-263.11623,579.54648)"
id="g10809"
style="display:inline"><rect
y="365.75504"
x="422.11606"
height="5.0892859"
width="6.5178571"
id="rect10811"
style="fill:#312d29;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
id="rect10813"
width="3.5714285"
height="5.0892859"
x="428.58929"
y="365.75504" /><rect
y="365.75504"
x="418.58929"
height="5.0892859"
width="3.5714285"
id="rect10815"
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /></g><g
style="display:inline"
id="g10817"
transform="matrix(0,-1,1,0,-273.53145,580.27312)"><rect
style="fill:#312d29;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
id="rect10819"
width="6.5178571"
height="5.0892859"
x="422.11606"
y="365.75504" /><rect
y="365.75504"
x="428.58929"
height="5.0892859"
width="3.5714285"
id="rect10821"
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
id="rect10823"
width="3.5714285"
height="5.0892859"
x="418.58929"
y="365.75504" /></g><g
transform="matrix(0,-1,1,0,-272.56259,546.12087)"
id="g10825"
style="display:inline"><rect
y="365.75504"
x="422.11606"
height="5.0892859"
width="6.5178571"
id="rect10827"
style="fill:#312d29;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
id="rect10829"
width="3.5714285"
height="5.0892859"
x="428.58929"
y="365.75504" /><rect
y="365.75504"
x="418.58929"
height="5.0892859"
width="3.5714285"
id="rect10831"
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /></g><g
style="display:inline"
id="g10833"
transform="matrix(0,-1,1,0,-257.06086,546.36308)"><rect
style="fill:#312d29;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
id="rect10835"
width="6.5178571"
height="5.0892859"
x="422.11606"
y="365.75504" /><rect
y="365.75504"
x="428.58929"
height="5.0892859"
width="3.5714285"
id="rect10837"
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
id="rect10839"
width="3.5714285"
height="5.0892859"
x="418.58929"
y="365.75504" /></g><g
id="g10887"><path
sodipodi:type="arc"
style="fill:none;stroke:#f2edda;stroke-width:1.5;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
id="path4550"
sodipodi:cx="225.89285"
sodipodi:cy="542.54077"
sodipodi:rx="5.1785712"
sodipodi:ry="5.1785712"
d="m 231.07142,542.54077 c 0,2.86005 -2.31852,5.17857 -5.17857,5.17857 -2.86004,0 -5.17857,-2.31852 -5.17857,-5.17857 0,-2.86004 2.31853,-5.17857 5.17857,-5.17857 2.86005,0 5.17857,2.31853 5.17857,5.17857 z"
transform="translate(20.6651,-466.48541)" /><path
sodipodi:type="arc"
style="fill:none;stroke:#f2edda;stroke-width:1.5;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
id="path4554"
sodipodi:cx="225.89285"
sodipodi:cy="542.54077"
sodipodi:rx="5.1785712"
sodipodi:ry="5.1785712"
d="m 231.07142,542.54077 c 0,2.86005 -2.31852,5.17857 -5.17857,5.17857 -2.86004,0 -5.17857,-2.31852 -5.17857,-5.17857 0,-2.86004 2.31853,-5.17857 5.17857,-5.17857 2.86005,0 5.17857,2.31853 5.17857,5.17857 z"
transform="translate(4.6651,-466.48541)" /><rect
y="71.519623"
x="210.81711"
height="8.5714283"
width="9.6428576"
id="rect4556"
style="fill:none;stroke:#f2edda;stroke-width:1.5;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" /></g><g
transform="translate(0,14)"
id="g10892"><path
transform="translate(20.6651,-466.48541)"
d="m 231.07142,542.54077 c 0,2.86005 -2.31852,5.17857 -5.17857,5.17857 -2.86004,0 -5.17857,-2.31852 -5.17857,-5.17857 0,-2.86004 2.31853,-5.17857 5.17857,-5.17857 2.86005,0 5.17857,2.31853 5.17857,5.17857 z"
sodipodi:ry="5.1785712"
sodipodi:rx="5.1785712"
sodipodi:cy="542.54077"
sodipodi:cx="225.89285"
id="path10894"
style="fill:none;stroke:#f2edda;stroke-width:1.5;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
sodipodi:type="arc" /><path
transform="translate(4.6651,-466.48541)"
d="m 231.07142,542.54077 c 0,2.86005 -2.31852,5.17857 -5.17857,5.17857 -2.86004,0 -5.17857,-2.31852 -5.17857,-5.17857 0,-2.86004 2.31853,-5.17857 5.17857,-5.17857 2.86005,0 5.17857,2.31853 5.17857,5.17857 z"
sodipodi:ry="5.1785712"
sodipodi:rx="5.1785712"
sodipodi:cy="542.54077"
sodipodi:cx="225.89285"
id="path10896"
style="fill:none;stroke:#f2edda;stroke-width:1.5;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
sodipodi:type="arc" /><rect
style="fill:none;stroke:#f2edda;stroke-width:1.5;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
id="rect10898"
width="9.6428576"
height="8.5714283"
x="210.81711"
y="71.519623" /></g><g
id="g10900"
transform="translate(0,30)"><path
sodipodi:type="arc"
style="fill:none;stroke:#f2edda;stroke-width:1.5;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
id="path10902"
sodipodi:cx="225.89285"
sodipodi:cy="542.54077"
sodipodi:rx="5.1785712"
sodipodi:ry="5.1785712"
d="m 231.07142,542.54077 c 0,2.86005 -2.31852,5.17857 -5.17857,5.17857 -2.86004,0 -5.17857,-2.31852 -5.17857,-5.17857 0,-2.86004 2.31853,-5.17857 5.17857,-5.17857 2.86005,0 5.17857,2.31853 5.17857,5.17857 z"
transform="translate(20.6651,-466.48541)" /><path
sodipodi:type="arc"
style="fill:none;stroke:#f2edda;stroke-width:1.5;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
id="path10904"
sodipodi:cx="225.89285"
sodipodi:cy="542.54077"
sodipodi:rx="5.1785712"
sodipodi:ry="5.1785712"
d="m 231.07142,542.54077 c 0,2.86005 -2.31852,5.17857 -5.17857,5.17857 -2.86004,0 -5.17857,-2.31852 -5.17857,-5.17857 0,-2.86004 2.31853,-5.17857 5.17857,-5.17857 2.86005,0 5.17857,2.31853 5.17857,5.17857 z"
transform="translate(4.6651,-466.48541)" /><rect
y="71.519623"
x="210.81711"
height="8.5714283"
width="9.6428576"
id="rect10906"
style="fill:none;stroke:#f2edda;stroke-width:1.5;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" /></g><g
transform="translate(0,46)"
id="g10908"><path
transform="translate(20.6651,-466.48541)"
d="m 231.07142,542.54077 c 0,2.86005 -2.31852,5.17857 -5.17857,5.17857 -2.86004,0 -5.17857,-2.31852 -5.17857,-5.17857 0,-2.86004 2.31853,-5.17857 5.17857,-5.17857 2.86005,0 5.17857,2.31853 5.17857,5.17857 z"
sodipodi:ry="5.1785712"
sodipodi:rx="5.1785712"
sodipodi:cy="542.54077"
sodipodi:cx="225.89285"
id="path10910"
style="fill:none;stroke:#f2edda;stroke-width:1.5;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
sodipodi:type="arc" /><path
transform="translate(4.6651,-466.48541)"
d="m 231.07142,542.54077 c 0,2.86005 -2.31852,5.17857 -5.17857,5.17857 -2.86004,0 -5.17857,-2.31852 -5.17857,-5.17857 0,-2.86004 2.31853,-5.17857 5.17857,-5.17857 2.86005,0 5.17857,2.31853 5.17857,5.17857 z"
sodipodi:ry="5.1785712"
sodipodi:rx="5.1785712"
sodipodi:cy="542.54077"
sodipodi:cx="225.89285"
id="path10912"
style="fill:none;stroke:#f2edda;stroke-width:1.5;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
sodipodi:type="arc" /><rect
style="fill:none;stroke:#f2edda;stroke-width:1.5;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
id="rect10914"
width="9.6428576"
height="8.5714283"
x="210.81711"
y="71.519623" /></g><g
id="g10916"
transform="translate(0,62)"><path
sodipodi:type="arc"
style="fill:none;stroke:#f2edda;stroke-width:1.5;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
id="path10918"
sodipodi:cx="225.89285"
sodipodi:cy="542.54077"
sodipodi:rx="5.1785712"
sodipodi:ry="5.1785712"
d="m 231.07142,542.54077 c 0,2.86005 -2.31852,5.17857 -5.17857,5.17857 -2.86004,0 -5.17857,-2.31852 -5.17857,-5.17857 0,-2.86004 2.31853,-5.17857 5.17857,-5.17857 2.86005,0 5.17857,2.31853 5.17857,5.17857 z"
transform="translate(20.6651,-466.48541)" /><path
sodipodi:type="arc"
style="fill:none;stroke:#f2edda;stroke-width:1.5;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
id="path10920"
sodipodi:cx="225.89285"
sodipodi:cy="542.54077"
sodipodi:rx="5.1785712"
sodipodi:ry="5.1785712"
d="m 231.07142,542.54077 c 0,2.86005 -2.31852,5.17857 -5.17857,5.17857 -2.86004,0 -5.17857,-2.31852 -5.17857,-5.17857 0,-2.86004 2.31853,-5.17857 5.17857,-5.17857 2.86005,0 5.17857,2.31853 5.17857,5.17857 z"
transform="translate(4.6651,-466.48541)" /><rect
y="71.519623"
x="210.81711"
height="8.5714283"
width="9.6428576"
id="rect10922"
style="fill:none;stroke:#f2edda;stroke-width:1.5;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" /></g><g
transform="translate(0,76)"
id="g10924"><path
transform="translate(20.6651,-466.48541)"
d="m 231.07142,542.54077 c 0,2.86005 -2.31852,5.17857 -5.17857,5.17857 -2.86004,0 -5.17857,-2.31852 -5.17857,-5.17857 0,-2.86004 2.31853,-5.17857 5.17857,-5.17857 2.86005,0 5.17857,2.31853 5.17857,5.17857 z"
sodipodi:ry="5.1785712"
sodipodi:rx="5.1785712"
sodipodi:cy="542.54077"
sodipodi:cx="225.89285"
id="path10926"
style="fill:none;stroke:#f2edda;stroke-width:1.5;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
sodipodi:type="arc" /><path
transform="translate(4.6651,-466.48541)"
d="m 231.07142,542.54077 c 0,2.86005 -2.31852,5.17857 -5.17857,5.17857 -2.86004,0 -5.17857,-2.31852 -5.17857,-5.17857 0,-2.86004 2.31853,-5.17857 5.17857,-5.17857 2.86005,0 5.17857,2.31853 5.17857,5.17857 z"
sodipodi:ry="5.1785712"
sodipodi:rx="5.1785712"
sodipodi:cy="542.54077"
sodipodi:cx="225.89285"
id="path10928"
style="fill:none;stroke:#f2edda;stroke-width:1.5;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
sodipodi:type="arc" /><rect
style="fill:none;stroke:#f2edda;stroke-width:1.5;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
id="rect10930"
width="9.6428576"
height="8.5714283"
x="210.81711"
y="71.519623" /></g><g
style="display:inline"
transform="matrix(0,1.2406633,-1.7870765,0,753.06413,-443.20477)"
id="g4788"><rect
y="365.75504"
x="422.11606"
height="5.0892859"
width="6.5178571"
id="rect4790"
style="fill:#a9814d;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
id="rect4792"
width="3.5714285"
height="5.0892859"
x="428.58929"
y="365.75504" /><rect
y="365.75504"
x="418.58929"
height="5.0892859"
width="3.5714285"
id="rect4794"
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /></g><g
id="g12054"
transform="matrix(0,1.2406633,-1.7870765,0,753.06413,-475.20477)"
style="display:inline"><rect
style="fill:#a9814d;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
id="rect12056"
width="6.5178571"
height="5.0892859"
x="422.11606"
y="365.75504" /><rect
y="365.75504"
x="428.58929"
height="5.0892859"
width="3.5714285"
id="rect12058"
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
id="rect12060"
width="3.5714285"
height="5.0892859"
x="418.58929"
y="365.75504" /></g><g
style="display:inline"
transform="matrix(1.2406633,0,0,1.7870765,-460.86273,-457.63731)"
id="g12062"><rect
y="365.75504"
x="422.11606"
height="5.0892859"
width="6.5178571"
id="rect12064"
style="fill:#a9814d;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
id="rect12066"
width="3.5714285"
height="5.0892859"
x="428.58929"
y="365.75504" /><rect
y="365.75504"
x="418.58929"
height="5.0892859"
width="3.5714285"
id="rect12068"
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /></g><g
id="g12070"
transform="matrix(1.2406633,0,0,1.7870765,-426.86273,-457.63731)"
style="display:inline"><rect
style="fill:#a9814d;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
id="rect12072"
width="6.5178571"
height="5.0892859"
x="422.11606"
y="365.75504" /><rect
y="365.75504"
x="428.58929"
height="5.0892859"
width="3.5714285"
id="rect12074"
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
id="rect12076"
width="3.5714285"
height="5.0892859"
x="418.58929"
y="365.75504" /></g><g
id="g12796"
transform="matrix(1.2994908,0,0,1,-24.942522,8.9061202)"><g
transform="translate(-0.3633218,-0.12110727)"
id="g12766"><path
d="m 133.77917,39.752694 0,-2.686385"
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
id="path5376"
inkscape:connector-curvature="0" /><path
d="m 130.94256,39.752694 0,-2.686385"
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
id="path5378"
inkscape:connector-curvature="0" /><path
d="m 145.57351,39.752694 0,-2.686385"
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
id="path5386"
inkscape:connector-curvature="0" /><path
d="m 142.58758,39.752694 0,-2.686385"
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
id="path5388"
inkscape:connector-curvature="0" /><path
d="m 139.75097,39.752694 0,-2.686385"
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
id="path5390"
inkscape:connector-curvature="0" /><path
d="m 130.94256,69.7503 0,-2.686344"
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
id="path5454"
inkscape:connector-curvature="0" /><path
d="m 133.77917,69.7503 0,-2.686344"
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
id="path5456"
inkscape:connector-curvature="0" /><path
d="m 139.75097,69.7503 0,-2.686344"
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
id="path5466"
inkscape:connector-curvature="0" /><path
d="m 142.58758,69.7503 0,-2.686344"
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
id="path5468"
inkscape:connector-curvature="0" /><path
d="m 145.57351,69.7503 0,-2.686344"
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
id="path5470"
inkscape:connector-curvature="0" /><path
d="m 124.82147,57.810942 2.6873,0"
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
id="path5612"
inkscape:connector-curvature="0" /><path
d="m 124.82147,60.64656 2.6873,0"
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
id="path5614"
inkscape:connector-curvature="0" /><path
d="m 124.82147,63.63141 2.6873,0"
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
id="path5616"
inkscape:connector-curvature="0" /><path
d="m 149.0073,63.63141 2.53802,0"
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
id="path5618"
inkscape:connector-curvature="0" /><path
d="m 149.0073,60.64656 2.53802,0"
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
id="path5620"
inkscape:connector-curvature="0" /><path
d="m 149.0073,57.810942 2.53802,0"
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
id="path5622"
inkscape:connector-curvature="0" /><path
d="m 124.82147,46.020858 2.6873,0"
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
id="path5624"
inkscape:connector-curvature="0" /><path
d="m 124.82147,49.005667 2.6873,0"
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
id="path5626"
inkscape:connector-curvature="0" /><path
d="m 124.82147,51.841284 2.6873,0"
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
id="path5628"
inkscape:connector-curvature="0" /><path
d="m 149.0073,51.841284 2.53802,0"
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
id="path5630"
inkscape:connector-curvature="0" /><path
d="m 149.0073,49.005667 2.53802,0"
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
id="path5632"
inkscape:connector-curvature="0" /><path
d="m 149.0073,46.020858 2.53802,0"
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
id="path5634"
inkscape:connector-curvature="0" /><path
d="m 136.76509,39.752694 0,-2.686385"
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
id="path5636"
inkscape:connector-curvature="0" /><path
d="m 124.82147,54.826134 2.6873,0"
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
id="path5726"
inkscape:connector-curvature="0" /><path
d="m 136.76509,69.7503 0,-2.686344"
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
id="path5728"
inkscape:connector-curvature="0" /><path
d="m 149.0073,54.826134 2.53802,0"
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
id="path5730"
inkscape:connector-curvature="0" /><path
d="m 124.82147,43.036008 2.6873,0"
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
id="path5738"
inkscape:connector-curvature="0" /><path
d="m 149.0073,43.036008 2.53802,0"
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
id="path5740"
inkscape:connector-curvature="0" /></g><rect
style="fill:#6a6a6a;fill-opacity:1;stroke:#000000;stroke-width:0.69999999;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
id="rect4974"
width="24.34742"
height="31.192205"
x="125.66183"
y="37.711323" /></g><g
id="g12952"
style="display:inline"
transform="matrix(0.55313316,0,0,0.55313316,202.151,-66.0335)"><rect
style="fill:#6a6a6a;fill-opacity:1;stroke:#000000;stroke-width:3.61576581;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
id="rect3773"
width="76.428574"
height="76.785713"
x="-104.28571"
y="358.43362"
ry="2.5" /><g
id="g3875"
transform="translate(-520,-37.142857)"><g
transform="matrix(1.4970318,0,0,1,-211.28069,0.21205357)"
id="g3781"><path
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
d="m 423.9087,394.32647 0,-7.85715"
id="path3777"
inkscape:connector-curvature="0" /><path
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
d="m 423.84066,392.00721 0.13607,0"
id="path3779"
inkscape:connector-curvature="0"
sodipodi:nodetypes="cc" /></g><g
id="g3785"
transform="matrix(1.4970318,0,0,1,-207.28069,0.21205357)"><path
inkscape:connector-curvature="0"
id="path3787"
d="m 423.9087,394.32647 0,-7.85715"
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
sodipodi:nodetypes="cc"
inkscape:connector-curvature="0"
id="path3789"
d="m 423.84066,392.00721 0.13607,0"
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
transform="matrix(1.4970318,0,0,1,-203.28069,0.21205357)"
id="g3791"><path
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
d="m 423.9087,394.32647 0,-7.85715"
id="path3793"
inkscape:connector-curvature="0" /><path
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
d="m 423.84066,392.00721 0.13607,0"
id="path3795"
inkscape:connector-curvature="0"
sodipodi:nodetypes="cc" /></g><g
id="g3797"
transform="matrix(1.4970318,0,0,1,-199.28069,0.21205357)"><path
inkscape:connector-curvature="0"
id="path3799"
d="m 423.9087,394.32647 0,-7.85715"
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
sodipodi:nodetypes="cc"
inkscape:connector-curvature="0"
id="path3801"
d="m 423.84066,392.00721 0.13607,0"
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
transform="matrix(1.4970318,0,0,1,-195.28069,0.21205357)"
id="g3803"><path
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
d="m 423.9087,394.32647 0,-7.85715"
id="path3805"
inkscape:connector-curvature="0" /><path
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
d="m 423.84066,392.00721 0.13607,0"
id="path3807"
inkscape:connector-curvature="0"
sodipodi:nodetypes="cc" /></g><g
id="g3809"
transform="matrix(1.4970318,0,0,1,-191.28069,0.21205357)"><path
inkscape:connector-curvature="0"
id="path3811"
d="m 423.9087,394.32647 0,-7.85715"
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
sodipodi:nodetypes="cc"
inkscape:connector-curvature="0"
id="path3813"
d="m 423.84066,392.00721 0.13607,0"
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
transform="matrix(1.4970318,0,0,1,-187.28069,0.21205357)"
id="g3815"><path
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
d="m 423.9087,394.32647 0,-7.85715"
id="path3817"
inkscape:connector-curvature="0" /><path
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
d="m 423.84066,392.00721 0.13607,0"
id="path3819"
inkscape:connector-curvature="0"
sodipodi:nodetypes="cc" /></g><g
id="g3821"
transform="matrix(1.4970318,0,0,1,-183.28069,0.21205357)"><path
inkscape:connector-curvature="0"
id="path3823"
d="m 423.9087,394.32647 0,-7.85715"
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
sodipodi:nodetypes="cc"
inkscape:connector-curvature="0"
id="path3825"
d="m 423.84066,392.00721 0.13607,0"
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
transform="matrix(1.4970318,0,0,1,-179.28069,0.21205357)"
id="g3827"><path
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
d="m 423.9087,394.32647 0,-7.85715"
id="path3829"
inkscape:connector-curvature="0" /><path
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
d="m 423.84066,392.00721 0.13607,0"
id="path3831"
inkscape:connector-curvature="0"
sodipodi:nodetypes="cc" /></g><g
id="g3833"
transform="matrix(1.4970318,0,0,1,-175.28069,0.21205357)"><path
inkscape:connector-curvature="0"
id="path3835"
d="m 423.9087,394.32647 0,-7.85715"
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
sodipodi:nodetypes="cc"
inkscape:connector-curvature="0"
id="path3837"
d="m 423.84066,392.00721 0.13607,0"
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
transform="matrix(1.4970318,0,0,1,-171.28069,0.21205357)"
id="g3839"><path
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
d="m 423.9087,394.32647 0,-7.85715"
id="path3841"
inkscape:connector-curvature="0" /><path
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
d="m 423.84066,392.00721 0.13607,0"
id="path3843"
inkscape:connector-curvature="0"
sodipodi:nodetypes="cc" /></g><g
id="g3845"
transform="matrix(1.4970318,0,0,1,-167.28069,0.21205357)"><path
inkscape:connector-curvature="0"
id="path3847"
d="m 423.9087,394.32647 0,-7.85715"
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
sodipodi:nodetypes="cc"
inkscape:connector-curvature="0"
id="path3849"
d="m 423.84066,392.00721 0.13607,0"
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
transform="matrix(1.4970318,0,0,1,-163.28069,0.21205357)"
id="g3851"><path
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
d="m 423.9087,394.32647 0,-7.85715"
id="path3853"
inkscape:connector-curvature="0" /><path
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
d="m 423.84066,392.00721 0.13607,0"
id="path3855"
inkscape:connector-curvature="0"
sodipodi:nodetypes="cc" /></g><g
id="g3857"
transform="matrix(1.4970318,0,0,1,-159.28069,0.21205357)"><path
inkscape:connector-curvature="0"
id="path3859"
d="m 423.9087,394.32647 0,-7.85715"
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
sodipodi:nodetypes="cc"
inkscape:connector-curvature="0"
id="path3861"
d="m 423.84066,392.00721 0.13607,0"
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
transform="matrix(1.4970318,0,0,1,-155.28069,0.21205357)"
id="g3863"><path
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
d="m 423.9087,394.32647 0,-7.85715"
id="path3865"
inkscape:connector-curvature="0" /><path
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
d="m 423.84066,392.00721 0.13607,0"
id="path3867"
inkscape:connector-curvature="0"
sodipodi:nodetypes="cc" /></g><g
id="g3869"
transform="matrix(1.4970318,0,0,1,-151.28069,0.21205357)"><path
inkscape:connector-curvature="0"
id="path3871"
d="m 423.9087,394.32647 0,-7.85715"
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
sodipodi:nodetypes="cc"
inkscape:connector-curvature="0"
id="path3873"
d="m 423.84066,392.00721 0.13607,0"
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g></g><g
id="g3925"
transform="matrix(0,1,-1,0,367.93406,-54.993437)"><g
id="g3927"
transform="matrix(1.4970318,0,0,1,-211.28069,0.21205357)"><path
inkscape:connector-curvature="0"
id="path3929"
d="m 423.9087,394.32647 0,-7.85715"
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
sodipodi:nodetypes="cc"
inkscape:connector-curvature="0"
id="path3931"
d="m 423.84066,392.00721 0.13607,0"
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
transform="matrix(1.4970318,0,0,1,-207.28069,0.21205357)"
id="g3933"><path
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
d="m 423.9087,394.32647 0,-7.85715"
id="path3935"
inkscape:connector-curvature="0" /><path
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
d="m 423.84066,392.00721 0.13607,0"
id="path3937"
inkscape:connector-curvature="0"
sodipodi:nodetypes="cc" /></g><g
id="g3939"
transform="matrix(1.4970318,0,0,1,-203.28069,0.21205357)"><path
inkscape:connector-curvature="0"
id="path3941"
d="m 423.9087,394.32647 0,-7.85715"
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
sodipodi:nodetypes="cc"
inkscape:connector-curvature="0"
id="path3943"
d="m 423.84066,392.00721 0.13607,0"
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
transform="matrix(1.4970318,0,0,1,-199.28069,0.21205357)"
id="g3945"><path
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
d="m 423.9087,394.32647 0,-7.85715"
id="path3947"
inkscape:connector-curvature="0" /><path
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
d="m 423.84066,392.00721 0.13607,0"
id="path3949"
inkscape:connector-curvature="0"
sodipodi:nodetypes="cc" /></g><g
id="g3951"
transform="matrix(1.4970318,0,0,1,-195.28069,0.21205357)"><path
inkscape:connector-curvature="0"
id="path3953"
d="m 423.9087,394.32647 0,-7.85715"
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
sodipodi:nodetypes="cc"
inkscape:connector-curvature="0"
id="path3955"
d="m 423.84066,392.00721 0.13607,0"
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
transform="matrix(1.4970318,0,0,1,-191.28069,0.21205357)"
id="g3957"><path
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
d="m 423.9087,394.32647 0,-7.85715"
id="path3959"
inkscape:connector-curvature="0" /><path
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
d="m 423.84066,392.00721 0.13607,0"
id="path3961"
inkscape:connector-curvature="0"
sodipodi:nodetypes="cc" /></g><g
id="g3963"
transform="matrix(1.4970318,0,0,1,-187.28069,0.21205357)"><path
inkscape:connector-curvature="0"
id="path3965"
d="m 423.9087,394.32647 0,-7.85715"
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
sodipodi:nodetypes="cc"
inkscape:connector-curvature="0"
id="path3967"
d="m 423.84066,392.00721 0.13607,0"
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
transform="matrix(1.4970318,0,0,1,-183.28069,0.21205357)"
id="g3969"><path
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
d="m 423.9087,394.32647 0,-7.85715"
id="path3971"
inkscape:connector-curvature="0" /><path
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
d="m 423.84066,392.00721 0.13607,0"
id="path3973"
inkscape:connector-curvature="0"
sodipodi:nodetypes="cc" /></g><g
id="g3975"
transform="matrix(1.4970318,0,0,1,-179.28069,0.21205357)"><path
inkscape:connector-curvature="0"
id="path3977"
d="m 423.9087,394.32647 0,-7.85715"
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
sodipodi:nodetypes="cc"
inkscape:connector-curvature="0"
id="path3979"
d="m 423.84066,392.00721 0.13607,0"
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
transform="matrix(1.4970318,0,0,1,-175.28069,0.21205357)"
id="g3981"><path
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
d="m 423.9087,394.32647 0,-7.85715"
id="path3983"
inkscape:connector-curvature="0" /><path
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
d="m 423.84066,392.00721 0.13607,0"
id="path3985"
inkscape:connector-curvature="0"
sodipodi:nodetypes="cc" /></g><g
id="g3987"
transform="matrix(1.4970318,0,0,1,-171.28069,0.21205357)"><path
inkscape:connector-curvature="0"
id="path3989"
d="m 423.9087,394.32647 0,-7.85715"
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
sodipodi:nodetypes="cc"
inkscape:connector-curvature="0"
id="path3991"
d="m 423.84066,392.00721 0.13607,0"
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
transform="matrix(1.4970318,0,0,1,-167.28069,0.21205357)"
id="g3993"><path
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
d="m 423.9087,394.32647 0,-7.85715"
id="path3995"
inkscape:connector-curvature="0" /><path
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
d="m 423.84066,392.00721 0.13607,0"
id="path3997"
inkscape:connector-curvature="0"
sodipodi:nodetypes="cc" /></g><g
id="g3999"
transform="matrix(1.4970318,0,0,1,-163.28069,0.21205357)"><path
inkscape:connector-curvature="0"
id="path4001"
d="m 423.9087,394.32647 0,-7.85715"
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
sodipodi:nodetypes="cc"
inkscape:connector-curvature="0"
id="path4003"
d="m 423.84066,392.00721 0.13607,0"
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
transform="matrix(1.4970318,0,0,1,-159.28069,0.21205357)"
id="g4005"><path
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
d="m 423.9087,394.32647 0,-7.85715"
id="path4007"
inkscape:connector-curvature="0" /><path
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
d="m 423.84066,392.00721 0.13607,0"
id="path4009"
inkscape:connector-curvature="0"
sodipodi:nodetypes="cc" /></g><g
id="g4011"
transform="matrix(1.4970318,0,0,1,-155.28069,0.21205357)"><path
inkscape:connector-curvature="0"
id="path4013"
d="m 423.9087,394.32647 0,-7.85715"
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
sodipodi:nodetypes="cc"
inkscape:connector-curvature="0"
id="path4015"
d="m 423.84066,392.00721 0.13607,0"
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
transform="matrix(1.4970318,0,0,1,-151.28069,0.21205357)"
id="g4017"><path
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
d="m 423.9087,394.32647 0,-7.85715"
id="path4019"
inkscape:connector-curvature="0" /><path
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
d="m 423.84066,392.00721 0.13607,0"
id="path4021"
inkscape:connector-curvature="0"
sodipodi:nodetypes="cc" /></g></g><g
transform="matrix(0,1,1,0,-500.02315,-54.993437)"
id="g4023"><g
transform="matrix(1.4970318,0,0,1,-211.28069,0.21205357)"
id="g4025"><path
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
d="m 423.9087,394.32647 0,-7.85715"
id="path4027"
inkscape:connector-curvature="0" /><path
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
d="m 423.84066,392.00721 0.13607,0"
id="path4029"
inkscape:connector-curvature="0"
sodipodi:nodetypes="cc" /></g><g
id="g4031"
transform="matrix(1.4970318,0,0,1,-207.28069,0.21205357)"><path
inkscape:connector-curvature="0"
id="path4033"
d="m 423.9087,394.32647 0,-7.85715"
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
sodipodi:nodetypes="cc"
inkscape:connector-curvature="0"
id="path4035"
d="m 423.84066,392.00721 0.13607,0"
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
transform="matrix(1.4970318,0,0,1,-203.28069,0.21205357)"
id="g4037"><path
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
d="m 423.9087,394.32647 0,-7.85715"
id="path4039"
inkscape:connector-curvature="0" /><path
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
d="m 423.84066,392.00721 0.13607,0"
id="path4041"
inkscape:connector-curvature="0"
sodipodi:nodetypes="cc" /></g><g
id="g4043"
transform="matrix(1.4970318,0,0,1,-199.28069,0.21205357)"><path
inkscape:connector-curvature="0"
id="path4045"
d="m 423.9087,394.32647 0,-7.85715"
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
sodipodi:nodetypes="cc"
inkscape:connector-curvature="0"
id="path4047"
d="m 423.84066,392.00721 0.13607,0"
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
transform="matrix(1.4970318,0,0,1,-195.28069,0.21205357)"
id="g4049"><path
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
d="m 423.9087,394.32647 0,-7.85715"
id="path4051"
inkscape:connector-curvature="0" /><path
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
d="m 423.84066,392.00721 0.13607,0"
id="path4053"
inkscape:connector-curvature="0"
sodipodi:nodetypes="cc" /></g><g
id="g4055"
transform="matrix(1.4970318,0,0,1,-191.28069,0.21205357)"><path
inkscape:connector-curvature="0"
id="path4057"
d="m 423.9087,394.32647 0,-7.85715"
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
sodipodi:nodetypes="cc"
inkscape:connector-curvature="0"
id="path4059"
d="m 423.84066,392.00721 0.13607,0"
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
transform="matrix(1.4970318,0,0,1,-187.28069,0.21205357)"
id="g4061"><path
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
d="m 423.9087,394.32647 0,-7.85715"
id="path4063"
inkscape:connector-curvature="0" /><path
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
d="m 423.84066,392.00721 0.13607,0"
id="path4065"
inkscape:connector-curvature="0"
sodipodi:nodetypes="cc" /></g><g
id="g4067"
transform="matrix(1.4970318,0,0,1,-183.28069,0.21205357)"><path
inkscape:connector-curvature="0"
id="path4069"
d="m 423.9087,394.32647 0,-7.85715"
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
sodipodi:nodetypes="cc"
inkscape:connector-curvature="0"
id="path4071"
d="m 423.84066,392.00721 0.13607,0"
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
transform="matrix(1.4970318,0,0,1,-179.28069,0.21205357)"
id="g4073"><path
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
d="m 423.9087,394.32647 0,-7.85715"
id="path4075"
inkscape:connector-curvature="0" /><path
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
d="m 423.84066,392.00721 0.13607,0"
id="path4077"
inkscape:connector-curvature="0"
sodipodi:nodetypes="cc" /></g><g
id="g4079"
transform="matrix(1.4970318,0,0,1,-175.28069,0.21205357)"><path
inkscape:connector-curvature="0"
id="path4081"
d="m 423.9087,394.32647 0,-7.85715"
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
sodipodi:nodetypes="cc"
inkscape:connector-curvature="0"
id="path4083"
d="m 423.84066,392.00721 0.13607,0"
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
transform="matrix(1.4970318,0,0,1,-171.28069,0.21205357)"
id="g4085"><path
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
d="m 423.9087,394.32647 0,-7.85715"
id="path4087"
inkscape:connector-curvature="0" /><path
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
d="m 423.84066,392.00721 0.13607,0"
id="path4089"
inkscape:connector-curvature="0"
sodipodi:nodetypes="cc" /></g><g
id="g4091"
transform="matrix(1.4970318,0,0,1,-167.28069,0.21205357)"><path
inkscape:connector-curvature="0"
id="path4093"
d="m 423.9087,394.32647 0,-7.85715"
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
sodipodi:nodetypes="cc"
inkscape:connector-curvature="0"
id="path4095"
d="m 423.84066,392.00721 0.13607,0"
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
transform="matrix(1.4970318,0,0,1,-163.28069,0.21205357)"
id="g4097"><path
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
d="m 423.9087,394.32647 0,-7.85715"
id="path4099"
inkscape:connector-curvature="0" /><path
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
d="m 423.84066,392.00721 0.13607,0"
id="path4101"
inkscape:connector-curvature="0"
sodipodi:nodetypes="cc" /></g><g
id="g4103"
transform="matrix(1.4970318,0,0,1,-159.28069,0.21205357)"><path
inkscape:connector-curvature="0"
id="path4105"
d="m 423.9087,394.32647 0,-7.85715"
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
sodipodi:nodetypes="cc"
inkscape:connector-curvature="0"
id="path4107"
d="m 423.84066,392.00721 0.13607,0"
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
transform="matrix(1.4970318,0,0,1,-155.28069,0.21205357)"
id="g4109"><path
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
d="m 423.9087,394.32647 0,-7.85715"
id="path4111"
inkscape:connector-curvature="0" /><path
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
d="m 423.84066,392.00721 0.13607,0"
id="path4113"
inkscape:connector-curvature="0"
sodipodi:nodetypes="cc" /></g><g
id="g4115"
transform="matrix(1.4970318,0,0,1,-151.28069,0.21205357)"><path
inkscape:connector-curvature="0"
id="path4117"
d="m 423.9087,394.32647 0,-7.85715"
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
sodipodi:nodetypes="cc"
inkscape:connector-curvature="0"
id="path4119"
d="m 423.84066,392.00721 0.13607,0"
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g></g><g
id="g4121"
transform="matrix(1,0,0,-1,-520,830.07704)"><g
id="g4123"
transform="matrix(1.4970318,0,0,1,-211.28069,0.21205357)"><path
inkscape:connector-curvature="0"
id="path4125"
d="m 423.9087,394.32647 0,-7.85715"
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
sodipodi:nodetypes="cc"
inkscape:connector-curvature="0"
id="path4127"
d="m 423.84066,392.00721 0.13607,0"
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
transform="matrix(1.4970318,0,0,1,-207.28069,0.21205357)"
id="g4129"><path
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
d="m 423.9087,394.32647 0,-7.85715"
id="path4131"
inkscape:connector-curvature="0" /><path
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
d="m 423.84066,392.00721 0.13607,0"
id="path4133"
inkscape:connector-curvature="0"
sodipodi:nodetypes="cc" /></g><g
id="g4135"
transform="matrix(1.4970318,0,0,1,-203.28069,0.21205357)"><path
inkscape:connector-curvature="0"
id="path4137"
d="m 423.9087,394.32647 0,-7.85715"
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
sodipodi:nodetypes="cc"
inkscape:connector-curvature="0"
id="path4139"
d="m 423.84066,392.00721 0.13607,0"
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
transform="matrix(1.4970318,0,0,1,-199.28069,0.21205357)"
id="g4141"><path
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
d="m 423.9087,394.32647 0,-7.85715"
id="path4143"
inkscape:connector-curvature="0" /><path
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
d="m 423.84066,392.00721 0.13607,0"
id="path4145"
inkscape:connector-curvature="0"
sodipodi:nodetypes="cc" /></g><g
id="g4147"
transform="matrix(1.4970318,0,0,1,-195.28069,0.21205357)"><path
inkscape:connector-curvature="0"
id="path4149"
d="m 423.9087,394.32647 0,-7.85715"
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
sodipodi:nodetypes="cc"
inkscape:connector-curvature="0"
id="path4151"
d="m 423.84066,392.00721 0.13607,0"
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
transform="matrix(1.4970318,0,0,1,-191.28069,0.21205357)"
id="g4153"><path
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
d="m 423.9087,394.32647 0,-7.85715"
id="path4155"
inkscape:connector-curvature="0" /><path
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
d="m 423.84066,392.00721 0.13607,0"
id="path4157"
inkscape:connector-curvature="0"
sodipodi:nodetypes="cc" /></g><g
id="g4159"
transform="matrix(1.4970318,0,0,1,-187.28069,0.21205357)"><path
inkscape:connector-curvature="0"
id="path4161"
d="m 423.9087,394.32647 0,-7.85715"
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
sodipodi:nodetypes="cc"
inkscape:connector-curvature="0"
id="path4163"
d="m 423.84066,392.00721 0.13607,0"
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
transform="matrix(1.4970318,0,0,1,-183.28069,0.21205357)"
id="g4165"><path
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
d="m 423.9087,394.32647 0,-7.85715"
id="path4167"
inkscape:connector-curvature="0" /><path
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
d="m 423.84066,392.00721 0.13607,0"
id="path4169"
inkscape:connector-curvature="0"
sodipodi:nodetypes="cc" /></g><g
id="g4171"
transform="matrix(1.4970318,0,0,1,-179.28069,0.21205357)"><path
inkscape:connector-curvature="0"
id="path4173"
d="m 423.9087,394.32647 0,-7.85715"
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
sodipodi:nodetypes="cc"
inkscape:connector-curvature="0"
id="path4175"
d="m 423.84066,392.00721 0.13607,0"
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
transform="matrix(1.4970318,0,0,1,-175.28069,0.21205357)"
id="g4177"><path
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
d="m 423.9087,394.32647 0,-7.85715"
id="path4179"
inkscape:connector-curvature="0" /><path
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
d="m 423.84066,392.00721 0.13607,0"
id="path4181"
inkscape:connector-curvature="0"
sodipodi:nodetypes="cc" /></g><g
id="g4183"
transform="matrix(1.4970318,0,0,1,-171.28069,0.21205357)"><path
inkscape:connector-curvature="0"
id="path4185"
d="m 423.9087,394.32647 0,-7.85715"
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
sodipodi:nodetypes="cc"
inkscape:connector-curvature="0"
id="path4187"
d="m 423.84066,392.00721 0.13607,0"
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
transform="matrix(1.4970318,0,0,1,-167.28069,0.21205357)"
id="g4189"><path
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
d="m 423.9087,394.32647 0,-7.85715"
id="path4191"
inkscape:connector-curvature="0" /><path
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
d="m 423.84066,392.00721 0.13607,0"
id="path4193"
inkscape:connector-curvature="0"
sodipodi:nodetypes="cc" /></g><g
id="g4195"
transform="matrix(1.4970318,0,0,1,-163.28069,0.21205357)"><path
inkscape:connector-curvature="0"
id="path4197"
d="m 423.9087,394.32647 0,-7.85715"
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
sodipodi:nodetypes="cc"
inkscape:connector-curvature="0"
id="path4199"
d="m 423.84066,392.00721 0.13607,0"
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
transform="matrix(1.4970318,0,0,1,-159.28069,0.21205357)"
id="g4201"><path
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
d="m 423.9087,394.32647 0,-7.85715"
id="path4203"
inkscape:connector-curvature="0" /><path
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
d="m 423.84066,392.00721 0.13607,0"
id="path4205"
inkscape:connector-curvature="0"
sodipodi:nodetypes="cc" /></g><g
id="g4207"
transform="matrix(1.4970318,0,0,1,-155.28069,0.21205357)"><path
inkscape:connector-curvature="0"
id="path4209"
d="m 423.9087,394.32647 0,-7.85715"
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
sodipodi:nodetypes="cc"
inkscape:connector-curvature="0"
id="path4211"
d="m 423.84066,392.00721 0.13607,0"
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
transform="matrix(1.4970318,0,0,1,-151.28069,0.21205357)"
id="g4213"><path
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
d="m 423.9087,394.32647 0,-7.85715"
id="path4215"
inkscape:connector-curvature="0" /><path
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
d="m 423.84066,392.00721 0.13607,0"
id="path4217"
inkscape:connector-curvature="0"
sodipodi:nodetypes="cc" /></g></g></g><g
style="display:inline"
id="g4920"
transform="matrix(0.41419929,0,0,0.41419929,-10.368172,-50.871127)"><g
transform="matrix(0,1.4970318,-1,0,849.26635,-33.0226)"
id="g4871"
style="display:inline"><rect
style="fill:#e9dcdc;fill-opacity:1;stroke:none"
id="rect4867"
width="10.985409"
height="4.0486217"
x="-386.60983"
y="417.41403"
transform="matrix(0,-1,1,0,0,0)" /><rect
transform="matrix(0,-1,1,0,0,0)"
y="417.41403"
x="-383.45309"
height="4.0486217"
width="2.5253813"
id="rect4869"
style="fill:#8c8989;fill-opacity:1;stroke:none" /></g><g
id="g4875"
transform="matrix(0,1.4970318,-1,0,849.26635,-23.0226)"
style="display:inline"><rect
transform="matrix(0,-1,1,0,0,0)"
y="417.41403"
x="-386.60983"
height="4.0486217"
width="10.985409"
id="rect4877"
style="fill:#e9dcdc;fill-opacity:1;stroke:none" /><rect
style="fill:#8c8989;fill-opacity:1;stroke:none"
id="rect4879"
width="2.5253813"
height="4.0486217"
x="-383.45309"
y="417.41403"
transform="matrix(0,-1,1,0,0,0)" /></g><g
transform="matrix(0,1.4970318,-1,0,849.26635,-13.0226)"
id="g4881"
style="display:inline"><rect
style="fill:#e9dcdc;fill-opacity:1;stroke:none"
id="rect4883"
width="10.985409"
height="4.0486217"
x="-386.60983"
y="417.41403"
transform="matrix(0,-1,1,0,0,0)" /><rect
transform="matrix(0,-1,1,0,0,0)"
y="417.41403"
x="-383.45309"
height="4.0486217"
width="2.5253813"
id="rect4885"
style="fill:#8c8989;fill-opacity:1;stroke:none" /></g><g
id="g4887"
transform="matrix(0,1.4970318,1,0,55.91598,-13.0226)"
style="display:inline"><rect
transform="matrix(0,-1,1,0,0,0)"
y="417.41403"
x="-386.60983"
height="4.0486217"
width="10.985409"
id="rect4889"
style="fill:#e9dcdc;fill-opacity:1;stroke:none" /><rect
style="fill:#8c8989;fill-opacity:1;stroke:none"
id="rect4891"
width="2.5253813"
height="4.0486217"
x="-383.45309"
y="417.41403"
transform="matrix(0,-1,1,0,0,0)" /></g><g
transform="matrix(0,1.4970318,1,0,55.91598,-33.0226)"
id="g4899"
style="display:inline"><rect
style="fill:#e9dcdc;fill-opacity:1;stroke:none"
id="rect4901"
width="10.985409"
height="4.0486217"
x="-386.60983"
y="417.41403"
transform="matrix(0,-1,1,0,0,0)" /><rect
transform="matrix(0,-1,1,0,0,0)"
y="417.41403"
x="-383.45309"
height="4.0486217"
width="2.5253813"
id="rect4903"
style="fill:#8c8989;fill-opacity:1;stroke:none" /></g><rect
ry="1.5"
y="590.15265"
x="443.12988"
height="31.819805"
width="18.687822"
id="rect4841"
style="fill:#6a6a6a;fill-opacity:1;stroke:#000000;stroke-width:2.41429687;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /></g><g
transform="matrix(0,0.41419929,-0.41419929,0,462.12545,-133.30339)"
id="g13877"
style="display:inline"><g
style="display:inline"
id="g13879"
transform="matrix(0,1.4970318,-1,0,849.26635,-33.0226)"><rect
transform="matrix(0,-1,1,0,0,0)"
y="417.41403"
x="-386.60983"
height="4.0486217"
width="10.985409"
id="rect13881"
style="fill:#e9dcdc;fill-opacity:1;stroke:none" /><rect
style="fill:#8c8989;fill-opacity:1;stroke:none"
id="rect13883"
width="2.5253813"
height="4.0486217"
x="-383.45309"
y="417.41403"
transform="matrix(0,-1,1,0,0,0)" /></g><g
style="display:inline"
transform="matrix(0,1.4970318,-1,0,849.26635,-23.0226)"
id="g13885"><rect
style="fill:#e9dcdc;fill-opacity:1;stroke:none"
id="rect13887"
width="10.985409"
height="4.0486217"
x="-386.60983"
y="417.41403"
transform="matrix(0,-1,1,0,0,0)" /><rect
transform="matrix(0,-1,1,0,0,0)"
y="417.41403"
x="-383.45309"
height="4.0486217"
width="2.5253813"
id="rect13889"
style="fill:#8c8989;fill-opacity:1;stroke:none" /></g><g
style="display:inline"
id="g13891"
transform="matrix(0,1.4970318,-1,0,849.26635,-13.0226)"><rect
transform="matrix(0,-1,1,0,0,0)"
y="417.41403"
x="-386.60983"
height="4.0486217"
width="10.985409"
id="rect13893"
style="fill:#e9dcdc;fill-opacity:1;stroke:none" /><rect
style="fill:#8c8989;fill-opacity:1;stroke:none"
id="rect13895"
width="2.5253813"
height="4.0486217"
x="-383.45309"
y="417.41403"
transform="matrix(0,-1,1,0,0,0)" /></g><g
style="display:inline"
transform="matrix(0,1.4970318,1,0,55.91598,-13.0226)"
id="g13897"><rect
style="fill:#e9dcdc;fill-opacity:1;stroke:none"
id="rect13899"
width="10.985409"
height="4.0486217"
x="-386.60983"
y="417.41403"
transform="matrix(0,-1,1,0,0,0)" /><rect
transform="matrix(0,-1,1,0,0,0)"
y="417.41403"
x="-383.45309"
height="4.0486217"
width="2.5253813"
id="rect13901"
style="fill:#8c8989;fill-opacity:1;stroke:none" /></g><g
style="display:inline"
id="g13903"
transform="matrix(0,1.4970318,1,0,55.91598,-33.0226)"><rect
transform="matrix(0,-1,1,0,0,0)"
y="417.41403"
x="-386.60983"
height="4.0486217"
width="10.985409"
id="rect13905"
style="fill:#e9dcdc;fill-opacity:1;stroke:none" /><rect
style="fill:#8c8989;fill-opacity:1;stroke:none"
id="rect13907"
width="2.5253813"
height="4.0486217"
x="-383.45309"
y="417.41403"
transform="matrix(0,-1,1,0,0,0)" /></g><rect
style="fill:#6a6a6a;fill-opacity:1;stroke:#000000;stroke-width:2.41429687;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
id="rect13909"
width="18.687822"
height="31.819805"
x="443.12988"
y="590.15265"
ry="1.5" /></g><g
id="g13760"
style="display:inline"
transform="matrix(0,0.61819183,-0.61819183,0,444.94676,-97.125819)"><rect
transform="translate(188.57143,331.57648)"
y="269.42856"
x="140.71428"
height="52.142857"
width="89.285713"
id="rect5020"
style="fill:#fffcfc;fill-opacity:1;stroke:#828282;stroke-width:3.23524165;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" /><g
transform="matrix(-1.4970318,0,0,1,971.39158,213.03078)"
id="g4964-3"
style="display:inline"><rect
style="fill:#e9dcdc;fill-opacity:1;stroke:none"
id="rect4966-2"
width="10.985409"
height="4.0486217"
x="-386.60983"
y="417.41403"
transform="matrix(0,-1,1,0,0,0)" /><rect
transform="matrix(0,-1,1,0,0,0)"
y="417.41403"
x="-383.45309"
height="4.0486217"
width="2.5253813"
id="rect4968-1"
style="fill:#8c8989;fill-opacity:1;stroke:none" /></g><g
style="display:inline"
id="g5046"
transform="matrix(-1.4970318,0,0,1,981.39158,213.03078)"><rect
transform="matrix(0,-1,1,0,0,0)"
y="417.41403"
x="-386.60983"
height="4.0486217"
width="10.985409"
id="rect5048"
style="fill:#e9dcdc;fill-opacity:1;stroke:none" /><rect
style="fill:#8c8989;fill-opacity:1;stroke:none"
id="rect5050"
width="2.5253813"
height="4.0486217"
x="-383.45309"
y="417.41403"
transform="matrix(0,-1,1,0,0,0)" /></g><g
transform="matrix(-1.4970318,0,0,1,991.39158,213.03078)"
id="g5052"
style="display:inline"><rect
style="fill:#e9dcdc;fill-opacity:1;stroke:none"
id="rect5054"
width="10.985409"
height="4.0486217"
x="-386.60983"
y="417.41403"
transform="matrix(0,-1,1,0,0,0)" /><rect
transform="matrix(0,-1,1,0,0,0)"
y="417.41403"
x="-383.45309"
height="4.0486217"
width="2.5253813"
id="rect5056"
style="fill:#8c8989;fill-opacity:1;stroke:none" /></g><g
style="display:inline"
id="g5058"
transform="matrix(-1.4970318,0,0,1,1001.3916,213.03078)"><rect
transform="matrix(0,-1,1,0,0,0)"
y="417.41403"
x="-386.60983"
height="4.0486217"
width="10.985409"
id="rect5060"
style="fill:#e9dcdc;fill-opacity:1;stroke:none" /><rect
style="fill:#8c8989;fill-opacity:1;stroke:none"
id="rect5062"
width="2.5253813"
height="4.0486217"
x="-383.45309"
y="417.41403"
transform="matrix(0,-1,1,0,0,0)" /></g><g
transform="matrix(-1.4970318,0,0,1,1011.3916,213.03078)"
id="g5064"
style="display:inline"><rect
style="fill:#e9dcdc;fill-opacity:1;stroke:none"
id="rect5066"
width="10.985409"
height="4.0486217"
x="-386.60983"
y="417.41403"
transform="matrix(0,-1,1,0,0,0)" /><rect
transform="matrix(0,-1,1,0,0,0)"
y="417.41403"
x="-383.45309"
height="4.0486217"
width="2.5253813"
id="rect5068"
style="fill:#8c8989;fill-opacity:1;stroke:none" /></g><g
style="display:inline"
id="g5070"
transform="matrix(-1.4970318,0,0,1,1021.3916,213.03078)"><rect
transform="matrix(0,-1,1,0,0,0)"
y="417.41403"
x="-386.60983"
height="4.0486217"
width="10.985409"
id="rect5072"
style="fill:#e9dcdc;fill-opacity:1;stroke:none" /><rect
style="fill:#8c8989;fill-opacity:1;stroke:none"
id="rect5074"
width="2.5253813"
height="4.0486217"
x="-383.45309"
y="417.41403"
transform="matrix(0,-1,1,0,0,0)" /></g><g
style="display:inline"
id="g13998"
transform="matrix(-1.4970318,0,0,1,1031.0972,213.03078)"><rect
transform="matrix(0,-1,1,0,0,0)"
y="417.41403"
x="-386.60983"
height="4.0486217"
width="10.985409"
id="rect14000"
style="fill:#e9dcdc;fill-opacity:1;stroke:none" /><rect
style="fill:#8c8989;fill-opacity:1;stroke:none"
id="rect14002"
width="2.5253813"
height="4.0486217"
x="-383.45309"
y="417.41403"
transform="matrix(0,-1,1,0,0,0)" /></g><g
transform="matrix(-1.4970318,0,0,1,1040.8028,213.03078)"
id="g14004"
style="display:inline"><rect
style="fill:#e9dcdc;fill-opacity:1;stroke:none"
id="rect14006"
width="10.985409"
height="4.0486217"
x="-386.60983"
y="417.41403"
transform="matrix(0,-1,1,0,0,0)" /><rect
transform="matrix(0,-1,1,0,0,0)"
y="417.41403"
x="-383.45309"
height="4.0486217"
width="2.5253813"
id="rect14008"
style="fill:#8c8989;fill-opacity:1;stroke:none" /></g></g><g
style="display:inline"
id="g4920-2"
transform="matrix(-0.48222043,0,0,-0.59728256,285.82656,546.58597)"><g
transform="matrix(0,1.4970318,-1,0,849.26635,-33.0226)"
id="g4871-7"
style="display:inline"><rect
style="fill:#e9dcdc;fill-opacity:1;stroke:none"
id="rect4867-0"
width="10.985409"
height="4.0486217"
x="-386.60983"
y="417.41403"
transform="matrix(0,-1,1,0,0,0)" /><rect
transform="matrix(0,-1,1,0,0,0)"
y="417.41403"
x="-383.45309"
height="4.0486217"
width="2.5253813"
id="rect4869-4"
style="fill:#8c8989;fill-opacity:1;stroke:none" /></g><g
id="g4875-1"
transform="matrix(0,1.4970318,-1,0,849.26635,-23.0226)"
style="display:inline"><rect
transform="matrix(0,-1,1,0,0,0)"
y="417.41403"
x="-386.60983"
height="4.0486217"
width="10.985409"
id="rect4877-3"
style="fill:#e9dcdc;fill-opacity:1;stroke:none" /><rect
style="fill:#8c8989;fill-opacity:1;stroke:none"
id="rect4879-4"
width="2.5253813"
height="4.0486217"
x="-383.45309"
y="417.41403"
transform="matrix(0,-1,1,0,0,0)" /></g><g
transform="matrix(0,1.4970318,-1,0,849.26635,-13.0226)"
id="g4881-9"
style="display:inline"><rect
style="fill:#e9dcdc;fill-opacity:1;stroke:none"
id="rect4883-6"
width="10.985409"
height="4.0486217"
x="-386.60983"
y="417.41403"
transform="matrix(0,-1,1,0,0,0)" /><rect
transform="matrix(0,-1,1,0,0,0)"
y="417.41403"
x="-383.45309"
height="4.0486217"
width="2.5253813"
id="rect4885-2"
style="fill:#8c8989;fill-opacity:1;stroke:none" /></g><g
id="g4887-8"
transform="matrix(0,1.4970318,1,0,55.91598,-13.0226)"
style="display:inline"><rect
transform="matrix(0,-1,1,0,0,0)"
y="417.41403"
x="-386.60983"
height="4.0486217"
width="10.985409"
id="rect4889-3"
style="fill:#e9dcdc;fill-opacity:1;stroke:none" /><rect
style="fill:#8c8989;fill-opacity:1;stroke:none"
id="rect4891-3"
width="2.5253813"
height="4.0486217"
x="-383.45309"
y="417.41403"
transform="matrix(0,-1,1,0,0,0)" /></g><g
transform="matrix(0,1.4970318,1,0,55.91598,-33.0226)"
id="g4899-7"
style="display:inline"><rect
style="fill:#e9dcdc;fill-opacity:1;stroke:none"
id="rect4901-7"
width="10.985409"
height="4.0486217"
x="-386.60983"
y="417.41403"
transform="matrix(0,-1,1,0,0,0)" /><rect
transform="matrix(0,-1,1,0,0,0)"
y="417.41403"
x="-383.45309"
height="4.0486217"
width="2.5253813"
id="rect4903-8"
style="fill:#8c8989;fill-opacity:1;stroke:none" /></g><rect
ry="1.5"
y="590.15265"
x="443.12988"
height="31.819805"
width="18.687822"
id="rect4841-1"
style="fill:#6a6a6a;fill-opacity:1;stroke:#000000;stroke-width:1.86331928;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /></g><g
style="display:inline"
id="g14076"
transform="matrix(0,-1,1,0,-150.96398,652.23853)"><rect
y="365.75504"
x="426.58929"
height="5.0892859"
width="3.5714285"
id="rect14080"
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
id="rect14082"
width="3.5714285"
height="5.0892859"
x="418.58929"
y="365.75504" /></g><g
transform="matrix(0.61819183,0,0,0.48347584,-108.7519,-76.23362)"
style="display:inline"
id="g14084"><rect
style="fill:#fffcfc;fill-opacity:1;stroke:#828282;stroke-width:3.65831399;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
id="rect14086"
width="53.268898"
height="52.142857"
x="329.28571"
y="601.00507" /><g
style="display:inline"
id="g14088"
transform="matrix(-1.4970318,0,0,1,971.39158,213.03078)"><rect
transform="matrix(0,-1,1,0,0,0)"
y="417.41403"
x="-386.60983"
height="4.0486217"
width="10.985409"
id="rect14090"
style="fill:#e9dcdc;fill-opacity:1;stroke:none" /><rect
style="fill:#8c8989;fill-opacity:1;stroke:none"
id="rect14092"
width="2.5253813"
height="4.0486217"
x="-383.45309"
y="417.41403"
transform="matrix(0,-1,1,0,0,0)" /></g><g
transform="matrix(-1.4970318,0,0,1,981.39158,213.03078)"
id="g14094"
style="display:inline"><rect
style="fill:#e9dcdc;fill-opacity:1;stroke:none"
id="rect14096"
width="10.985409"
height="4.0486217"
x="-386.60983"
y="417.41403"
transform="matrix(0,-1,1,0,0,0)" /><rect
transform="matrix(0,-1,1,0,0,0)"
y="417.41403"
x="-383.45309"
height="4.0486217"
width="2.5253813"
id="rect14098"
style="fill:#8c8989;fill-opacity:1;stroke:none" /></g><g
style="display:inline"
id="g14100"
transform="matrix(-1.4970318,0,0,1,991.39158,213.03078)"><rect
transform="matrix(0,-1,1,0,0,0)"
y="417.41403"
x="-386.60983"
height="4.0486217"
width="10.985409"
id="rect14102"
style="fill:#e9dcdc;fill-opacity:1;stroke:none" /><rect
style="fill:#8c8989;fill-opacity:1;stroke:none"
id="rect14104"
width="2.5253813"
height="4.0486217"
x="-383.45309"
y="417.41403"
transform="matrix(0,-1,1,0,0,0)" /></g><g
transform="matrix(-1.4970318,0,0,1,1001.3916,213.03078)"
id="g14106"
style="display:inline"><rect
style="fill:#e9dcdc;fill-opacity:1;stroke:none"
id="rect14108"
width="10.985409"
height="4.0486217"
x="-386.60983"
y="417.41403"
transform="matrix(0,-1,1,0,0,0)" /><rect
transform="matrix(0,-1,1,0,0,0)"
y="417.41403"
x="-383.45309"
height="4.0486217"
width="2.5253813"
id="rect14110"
style="fill:#8c8989;fill-opacity:1;stroke:none" /></g></g><g
id="g14136"
style="display:inline"
transform="matrix(0.61819183,0,0,0.48347584,-30.7519,-76.23362)"><rect
y="601.00507"
x="329.28571"
height="52.142857"
width="53.268898"
id="rect14138"
style="fill:#fffcfc;fill-opacity:1;stroke:#828282;stroke-width:3.65831399;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" /><g
transform="matrix(-1.4970318,0,0,1,971.39158,213.03078)"
id="g14140"
style="display:inline"><rect
style="fill:#e9dcdc;fill-opacity:1;stroke:none"
id="rect14142"
width="10.985409"
height="4.0486217"
x="-386.60983"
y="417.41403"
transform="matrix(0,-1,1,0,0,0)" /><rect
transform="matrix(0,-1,1,0,0,0)"
y="417.41403"
x="-383.45309"
height="4.0486217"
width="2.5253813"
id="rect14144"
style="fill:#8c8989;fill-opacity:1;stroke:none" /></g><g
style="display:inline"
id="g14146"
transform="matrix(-1.4970318,0,0,1,981.39158,213.03078)"><rect
transform="matrix(0,-1,1,0,0,0)"
y="417.41403"
x="-386.60983"
height="4.0486217"
width="10.985409"
id="rect14148"
style="fill:#e9dcdc;fill-opacity:1;stroke:none" /><rect
style="fill:#8c8989;fill-opacity:1;stroke:none"
id="rect14150"
width="2.5253813"
height="4.0486217"
x="-383.45309"
y="417.41403"
transform="matrix(0,-1,1,0,0,0)" /></g><g
transform="matrix(-1.4970318,0,0,1,991.39158,213.03078)"
id="g14152"
style="display:inline"><rect
style="fill:#e9dcdc;fill-opacity:1;stroke:none"
id="rect14154"
width="10.985409"
height="4.0486217"
x="-386.60983"
y="417.41403"
transform="matrix(0,-1,1,0,0,0)" /><rect
transform="matrix(0,-1,1,0,0,0)"
y="417.41403"
x="-383.45309"
height="4.0486217"
width="2.5253813"
id="rect14156"
style="fill:#8c8989;fill-opacity:1;stroke:none" /></g><g
style="display:inline"
id="g14158"
transform="matrix(-1.4970318,0,0,1,1001.3916,213.03078)"><rect
transform="matrix(0,-1,1,0,0,0)"
y="417.41403"
x="-386.60983"
height="4.0486217"
width="10.985409"
id="rect14160"
style="fill:#e9dcdc;fill-opacity:1;stroke:none" /><rect
style="fill:#8c8989;fill-opacity:1;stroke:none"
id="rect14162"
width="2.5253813"
height="4.0486217"
x="-383.45309"
y="417.41403"
transform="matrix(0,-1,1,0,0,0)" /></g></g><g
style="display:inline"
transform="matrix(2.4017041,0,0,3.9408912,-788.51882,-1271.7817)"
id="g14164"><rect
y="365.75504"
x="422.11606"
height="5.0892859"
width="6.5178571"
id="rect14166"
style="fill:#00440d;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
id="rect14168"
width="3.5714285"
height="5.0892859"
x="428.58929"
y="365.75504" /><rect
y="365.75504"
x="418.58929"
height="5.0892859"
width="3.5714285"
id="rect14170"
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /></g><g
style="display:inline"
id="g14192"
transform="translate(-342.57061,-300.15766)"><rect
style="fill:#312d29;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
id="rect14194"
width="6.5178571"
height="5.0892859"
x="422.11606"
y="365.75504" /><rect
y="365.75504"
x="428.58929"
height="5.0892859"
width="3.5714285"
id="rect14196"
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
id="rect14198"
width="3.5714285"
height="5.0892859"
x="418.58929"
y="365.75504" /></g><g
style="display:inline"
id="g14200"
transform="matrix(0,0.63857044,-0.6183842,0,527.83252,-72.180508)"><g
transform="matrix(0,1.4970318,-1,0,852.39835,-33.0226)"
id="g14202"
style="display:inline"><rect
style="fill:#e9dcdc;fill-opacity:1;stroke:none"
id="rect14204"
width="10.985409"
height="4.0486217"
x="-386.60983"
y="417.41403"
transform="matrix(0,-1,1,0,0,0)" /><rect
transform="matrix(0,-1,1,0,0,0)"
y="417.41403"
x="-383.45309"
height="4.0486217"
width="2.5253813"
id="rect14206"
style="fill:#8c8989;fill-opacity:1;stroke:none" /></g><g
id="g14208"
transform="matrix(0,1.4970318,-1,0,852.39835,-23.0226)"
style="display:inline"><rect
transform="matrix(0,-1,1,0,0,0)"
y="417.41403"
x="-386.60983"
height="4.0486217"
width="10.985409"
id="rect14210"
style="fill:#e9dcdc;fill-opacity:1;stroke:none" /><rect
style="fill:#8c8989;fill-opacity:1;stroke:none"
id="rect14212"
width="2.5253813"
height="4.0486217"
x="-383.45309"
y="417.41403"
transform="matrix(0,-1,1,0,0,0)" /></g><g
transform="matrix(0,1.4970318,-1,0,852.39835,-13.0226)"
id="g14214"
style="display:inline"><rect
style="fill:#e9dcdc;fill-opacity:1;stroke:none"
id="rect14216"
width="10.985409"
height="4.0486217"
x="-386.60983"
y="417.41403"
transform="matrix(0,-1,1,0,0,0)" /><rect
transform="matrix(0,-1,1,0,0,0)"
y="417.41403"
x="-383.45309"
height="4.0486217"
width="2.5253813"
id="rect14218"
style="fill:#8c8989;fill-opacity:1;stroke:none" /></g><g
id="g14220"
transform="matrix(0,1.4970318,1,0,46.519992,-13.0226)"
style="display:inline"><rect
transform="matrix(0,-1,1,0,0,0)"
y="417.41403"
x="-386.60983"
height="4.0486217"
width="10.985409"
id="rect14222"
style="fill:#e9dcdc;fill-opacity:1;stroke:none" /><rect
style="fill:#8c8989;fill-opacity:1;stroke:none"
id="rect14224"
width="2.5253813"
height="4.0486217"
x="-383.45309"
y="417.41403"
transform="matrix(0,-1,1,0,0,0)" /></g><g
transform="matrix(0,1.4970318,1,0,46.519992,-33.0226)"
id="g14226"
style="display:inline"><rect
style="fill:#e9dcdc;fill-opacity:1;stroke:none"
id="rect14228"
width="10.985409"
height="4.0486217"
x="-386.60983"
y="417.41403"
transform="matrix(0,-1,1,0,0,0)" /><rect
transform="matrix(0,-1,1,0,0,0)"
y="417.41403"
x="-383.45309"
height="4.0486217"
width="2.5253813"
id="rect14230"
style="fill:#8c8989;fill-opacity:1;stroke:none" /></g><g
style="display:inline"
transform="matrix(0,1.4970318,1,0,46.519992,-22.679788)"
id="g14240"><rect
style="fill:#e9dcdc;fill-opacity:1;stroke:none"
id="rect14242"
width="10.985409"
height="4.0486217"
x="-386.60983"
y="417.41403"
transform="matrix(0,-1,1,0,0,0)" /><rect
transform="matrix(0,-1,1,0,0,0)"
y="417.41403"
x="-383.45309"
height="4.0486217"
width="2.5253813"
id="rect14244"
style="fill:#8c8989;fill-opacity:1;stroke:none" /></g><g
style="display:inline"
transform="matrix(0,1.4970318,1,0,46.519992,-3.365413)"
id="g14246"><rect
style="fill:#e9dcdc;fill-opacity:1;stroke:none"
id="rect14248"
width="10.985409"
height="4.0486217"
x="-386.60983"
y="417.41403"
transform="matrix(0,-1,1,0,0,0)" /><rect
transform="matrix(0,-1,1,0,0,0)"
y="417.41403"
x="-383.45309"
height="4.0486217"
width="2.5253813"
id="rect14250"
style="fill:#8c8989;fill-opacity:1;stroke:none" /></g><g
style="display:inline"
id="g14252"
transform="matrix(0,1.4970318,-1,0,852.39835,-3.365413)"><rect
transform="matrix(0,-1,1,0,0,0)"
y="417.41403"
x="-386.60983"
height="4.0486217"
width="10.985409"
id="rect14254"
style="fill:#e9dcdc;fill-opacity:1;stroke:none" /><rect
style="fill:#8c8989;fill-opacity:1;stroke:none"
id="rect14256"
width="2.5253813"
height="4.0486217"
x="-383.45309"
y="417.41403"
transform="matrix(0,-1,1,0,0,0)" /></g><rect
ry="1.9272836"
y="590.15265"
x="432.12994"
height="40.883862"
width="34.998043"
id="rect14232"
style="fill:#6a6a6a;fill-opacity:1;stroke:#000000;stroke-width:1.59135258;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /></g><text
xml:space="preserve"
style="font-size:18px;font-style:normal;font-variant:normal;font-weight:bold;font-stretch:normal;text-align:start;line-height:125%;letter-spacing:0px;word-spacing:0px;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;font-family:Arial;-inkscape-font-specification:Sans Bold"
x="123.07243"
y="109.6582"
id="text3548"
sodipodi:linespacing="125%"><tspan
sodipodi:role="line"
id="tspan3550"
x="123.07243"
y="109.6582"
style="font-size:20px;fill:#ffffff">CC3D</tspan></text>
</g></g></svg>

After

Width:  |  Height:  |  Size: 120 KiB

View File

@ -12,5 +12,6 @@
<file>images/application-certificate.svg</file>
<file>images/warning.svg</file>
<file>images/error.svg</file>
<file>images/deviceID-0402.svg</file>
</qresource>
</RCC>

View File

@ -51,37 +51,37 @@ Rectangle {
WelcomePageButton {
baseIconName: "flightdata"
label: "Flight Data"
onClicked: welcomePlugin.openPage("Mode1")
onClicked: welcomePlugin.openPage("Flight data")
}
WelcomePageButton {
baseIconName: "config"
label: "Configuration"
onClicked: welcomePlugin.openPage("Mode2")
onClicked: welcomePlugin.openPage("Configuration")
}
WelcomePageButton {
baseIconName: "planner"
label: "Flight Planner"
onClicked: welcomePlugin.openPage("Mode3")
onClicked: welcomePlugin.openPage("Flight Planner")
}
WelcomePageButton {
baseIconName: "scopes"
label: "Scopes"
onClicked: welcomePlugin.openPage("Mode4")
onClicked: welcomePlugin.openPage("Scopes")
}
WelcomePageButton {
baseIconName: "hitl"
label: "HIL"
onClicked: welcomePlugin.openPage("Mode5")
label: "HITL"
onClicked: welcomePlugin.openPage("HITL")
}
WelcomePageButton {
baseIconName: "firmware"
label: "Firmware"
onClicked: welcomePlugin.openPage("Mode6")
onClicked: welcomePlugin.openPage("Firmware")
}
} //icons grid
} // images row

View File

@ -124,7 +124,7 @@ void WelcomeMode::openUrl(const QString &url)
void WelcomeMode::openPage(const QString &page)
{
Core::ModeManager::instance()->activateMode(page);
Core::ModeManager::instance()->activateModeByWorkspaceName(page);
}
} // namespace Welcome

2
overo

@ -1 +1 @@
Subproject commit 8381aa124feafbb268c4d87d569a8185765f4297
Subproject commit 335a3486dd41e48345209d0a65d49a8cc8b442a1

View File

@ -1,8 +1,8 @@
<xml>
<object name="GCSReceiver" singleinstance="true" settings="false">
<description>A receiver channel group carried over the telemetry link.</description>
<field name="Channel" units="us" type="uint16" elements="6"/>
<access gcs="readwrite" flight="readwrite"/>
<field name="Channel" units="us" type="uint16" elements="8"/>
<access gcs="readwrite" flight="readonly"/>
<telemetrygcs acked="false" updatemode="onchange" period="0"/>
<telemetryflight acked="false" updatemode="onchange" period="0"/>
<logging updatemode="manual" period="0"/>

View File

@ -18,9 +18,9 @@
<field name="Arming" units="" type="enum" elements="1" options="Always Disarmed,Always Armed,Roll Left,Roll Right,Pitch Forward,Pitch Aft,Yaw Left,Yaw Right" defaultvalue="Always Disarmed"/>
<!-- Note these options should be identical to those in StabilizationDesired.StabilizationMode -->
<field name="Stabilization1Settings" units="" type="enum" elementnames="Roll,Pitch,Yaw" options="None,Rate,Attitude,AxisLock,WeakLeveling" defaultvalue="Attitude,Attitude,Rate"/>
<field name="Stabilization2Settings" units="" type="enum" elementnames="Roll,Pitch,Yaw" options="None,Rate,Attitude,AxisLock,WeakLeveling" defaultvalue="Attitude,Attitude,Rate"/>
<field name="Stabilization3Settings" units="" type="enum" elementnames="Roll,Pitch,Yaw" options="None,Rate,Attitude,AxisLock,WeakLeveling" defaultvalue="Attitude,Attitude,Rate"/>
<field name="Stabilization1Settings" units="" type="enum" elementnames="Roll,Pitch,Yaw" options="None,Rate,Attitude,AxisLock,WeakLeveling,VirtualBar" defaultvalue="Attitude,Attitude,Rate"/>
<field name="Stabilization2Settings" units="" type="enum" elementnames="Roll,Pitch,Yaw" options="None,Rate,Attitude,AxisLock,WeakLeveling,VirtualBar" defaultvalue="Attitude,Attitude,Rate"/>
<field name="Stabilization3Settings" units="" type="enum" elementnames="Roll,Pitch,Yaw" options="None,Rate,Attitude,AxisLock,WeakLeveling,VirtualBar" defaultvalue="Attitude,Attitude,Rate"/>
<!-- Note these options values should be identical to those defined in FlightMode -->
<field name="FlightModePosition" units="" type="enum" elements="3" options="Manual,Stabilized1,Stabilized2,Stabilized3,AltitudeHold,VelocityControl,PositionHold" defaultvalue="Manual,Stabilized1,Stabilized2"/>

View File

@ -1,7 +1,7 @@
<xml>
<object name="ObjectPersistence" singleinstance="true" settings="false">
<description>Someone who knows please enter this</description>
<field name="Operation" units="" type="enum" elements="1" options="NOP,Load,Save,Delete,FullErase,Completed"/>
<field name="Operation" units="" type="enum" elements="1" options="NOP,Load,Save,Delete,FullErase,Completed,Error"/>
<field name="Selection" units="" type="enum" elements="1" options="SingleObject,AllSettings,AllMetaObjects,AllObjects"/>
<field name="ObjectID" units="" type="uint32" elements="1"/>
<field name="InstanceID" units="" type="uint32" elements="1"/>

View File

@ -6,7 +6,7 @@
<field name="Yaw" units="degrees" type="float" elements="1"/>
<field name="Throttle" units="%" type="float" elements="1"/>
<!-- These values should match those in ManualControlCommand.Stabilization{1,2,3}Settings -->
<field name="StabilizationMode" units="" type="enum" elementnames="Roll,Pitch,Yaw" options="None,Rate,Attitude,AxisLock,WeakLeveling"/>
<field name="StabilizationMode" units="" type="enum" elementnames="Roll,Pitch,Yaw" options="None,Rate,Attitude,AxisLock,WeakLeveling,VirtualBar"/>
<access gcs="readwrite" flight="readwrite"/>
<telemetrygcs acked="false" updatemode="manual" period="0"/>
<telemetryflight acked="false" updatemode="periodic" period="1000"/>

View File

@ -13,6 +13,15 @@
<field name="RollPI" units="" type="float" elementnames="Kp,Ki,ILimit" defaultvalue="2,0,50" limits="%BE:0:10,%BE:0:10,"/>
<field name="PitchPI" units="" type="float" elementnames="Kp,Ki,ILimit" defaultvalue="2,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,"/>
<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"/>
<field name="VbarPitchPI" units="1/(deg/s)" type="float" elementnames="Kp,Ki" defaultvalue="0.005,0.002"/>
<field name="VbarYawPI" units="1/(deg/s)" type="float" elementnames="Kp,Ki" defaultvalue="0.005,0.002"/>
<field name="VbarTau" units="sec" type="float" elements="1" defaultvalue="0.5"/>
<field name="VbarGyroSuppress" units="%" type="int8" elements="1" defaultvalue="30"/>
<field name="VbarPiroComp" units="" type="enum" elements="1" options="FALSE,TRUE" defaultvalue="FALSE"/>
<field name="VbarMaxAngle" units="deg" type="uint8" elements="1" defaultvalue="10"/>
<field name="GyroTau" units="" type="float" elements="1" defaultvalue="0.005"/>

View File

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