1
0
mirror of https://bitbucket.org/librepilot/librepilot.git synced 2025-01-18 03:52:11 +01:00

Merge remote-tracking branch 'origin/next' into amorale/OP-1302_updated_led_behaviour

This commit is contained in:
Alessio Morale 2014-05-08 22:27:08 +02:00
commit e5d6726bb6
111 changed files with 5170 additions and 10697 deletions

View File

@ -67,6 +67,7 @@ void INSSetAccelVar(float accel_var[3]);
void INSSetGyroVar(float gyro_var[3]);
void INSSetGyroBiasVar(float gyro_bias_var[3]);
void INSSetMagNorth(float B[3]);
void INSSetG(float g_e);
void INSSetMagVar(float scaled_mag_var[3]);
void INSSetBaroVar(float baro_var);
void INSPosVelReset(float pos[3], float vel[3]);

View File

@ -91,6 +91,8 @@ static struct EKFData {
float H[NUMV][NUMX];
// local magnetic unit vector in NED frame
float Be[3];
// local gravity vector
float g_e;
// covariance matrix and state vector
float P[NUMX][NUMX];
float X[NUMX];
@ -286,6 +288,11 @@ void INSSetMagNorth(float B[3])
ekf.Be[2] = B[2] / mag;
}
void INSSetG(float g_e)
{
ekf.g_e = g_e;
}
void INSStatePrediction(float gyro_data[3], float accel_data[3], float dT)
{
float U[6];
@ -641,7 +648,7 @@ void StateEq(float X[NUMX], float U[NUMU], float Xdot[NUMX])
az;
Xdot[5] =
2.0f * (q1 * q3 - q0 * q2) * ax + 2 * (q2 * q3 + q0 * q1) * ay +
(q0 * q0 - q1 * q1 - q2 * q2 + q3 * q3) * az + 9.81f;
(q0 * q0 - q1 * q1 - q2 * q2 + q3 * q3) * az + ekf.g_e;
// qdot = Q*w
Xdot[6] = (-q1 * wx - q2 * wy - q3 * wz) / 2.0f;

View File

@ -1,9 +1,13 @@
/**
******************************************************************************
* @addtogroup OpenPilot Math Utilities
* @{
* @addtogroup Reuseable math functions
* @{
*
* @file examplemodperiodic.c
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @brief Example module to be used as a template for actual modules.
* @file mathmisc.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
* @brief Reuseable math functions
*
* @see The GNU Public License (GPL) Version 3
*
@ -23,9 +27,6 @@
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef EXAMPLEMODPERIODIC_H
#define EXAMPLEMODPERIODIC_H
int32_t ExampleModPeriodicInitialize();
int32_t GuidanceInitialize(void);
#endif // EXAMPLEMODPERIODIC_H
// space deliberately left empty, any non inline misc math functions can go here

View File

@ -0,0 +1,55 @@
/**
******************************************************************************
* @addtogroup OpenPilot Math Utilities
* @{
* @addtogroup Reuseable math functions
* @{
*
* @file mathmisc.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
* @brief Reuseable math functions
*
* @see The GNU Public License (GPL) Version 3
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef MATHMISC_H
#define MATHMISC_H
// returns min(boundary1,boundary2) if val<min(boundary1,boundary2)
// returns max(boundary1,boundary2) if val>max(boundary1,boundary2)
// returns val if min(boundary1,boundary2)<=val<=max(boundary1,boundary2)
static inline float boundf(float val, float boundary1, float boundary2)
{
if (boundary1 > boundary2) {
if (!(val >= boundary2)) {
return boundary2;
} else if (!(val <= boundary1)) {
return boundary1;
}
} else {
if (!(val >= boundary1)) {
return boundary1;
} else if (!(val <= boundary2)) {
return boundary2;
}
}
return val;
}
#endif /* MATHMISC_H */

View File

@ -30,11 +30,9 @@
#include "openpilot.h"
#include "pid.h"
#include <mathmisc.h>
#include <pios_math.h>
// ! Private method
static float bound(float val, float range);
// ! Store the shared time constant for the derivative cutoff.
static float deriv_tau = 7.9577e-3f;
@ -52,7 +50,7 @@ float pid_apply(struct pid *pid, const float err, float dT)
{
// Scale up accumulator by 1000 while computing to avoid losing precision
pid->iAccumulator += err * (pid->i * dT * 1000.0f);
pid->iAccumulator = bound(pid->iAccumulator, pid->iLim * 1000.0f);
pid->iAccumulator = boundf(pid->iAccumulator, pid->iLim * -1000.0f, pid->iLim * 1000.0f);
// Calculate DT1 term
float diff = (err - pid->lastErr);
@ -84,7 +82,7 @@ float pid_apply_setpoint(struct pid *pid, const float factor, const float setpoi
// Scale up accumulator by 1000 while computing to avoid losing precision
pid->iAccumulator += err * (factor * pid->i * dT * 1000.0f);
pid->iAccumulator = bound(pid->iAccumulator, pid->iLim * 1000.0f);
pid->iAccumulator = boundf(pid->iAccumulator, pid->iLim * -1000.0f, pid->iLim * 1000.0f);
// Calculate DT1 term,
float dterm = 0;
@ -142,16 +140,3 @@ void pid_configure(struct pid *pid, float p, float i, float d, float iLim)
pid->d = d;
pid->iLim = iLim;
}
/**
* Bound input value between limits
*/
static float bound(float val, float range)
{
if (val < -range) {
val = -range;
} else if (val > range) {
val = range;
}
return val;
}

View File

@ -46,7 +46,7 @@
****************************/
// ! Check a stabilization mode switch position for safety
static int32_t check_stabilization_settings(int index, bool multirotor);
static int32_t check_stabilization_settings(int index, bool multirotor, bool coptercontrol);
/**
* Run a preflight check over the hardware configuration
@ -98,34 +98,28 @@ int32_t configuration_check()
}
break;
case FLIGHTMODESETTINGS_FLIGHTMODEPOSITION_STABILIZED1:
severity = (severity == SYSTEMALARMS_ALARM_OK) ? check_stabilization_settings(1, multirotor) : severity;
severity = (severity == SYSTEMALARMS_ALARM_OK) ? check_stabilization_settings(1, multirotor, coptercontrol) : severity;
break;
case FLIGHTMODESETTINGS_FLIGHTMODEPOSITION_STABILIZED2:
severity = (severity == SYSTEMALARMS_ALARM_OK) ? check_stabilization_settings(2, multirotor) : severity;
severity = (severity == SYSTEMALARMS_ALARM_OK) ? check_stabilization_settings(2, multirotor, coptercontrol) : severity;
break;
case FLIGHTMODESETTINGS_FLIGHTMODEPOSITION_STABILIZED3:
severity = (severity == SYSTEMALARMS_ALARM_OK) ? check_stabilization_settings(3, multirotor) : severity;
severity = (severity == SYSTEMALARMS_ALARM_OK) ? check_stabilization_settings(3, multirotor, coptercontrol) : severity;
break;
case FLIGHTMODESETTINGS_FLIGHTMODEPOSITION_STABILIZED4:
severity = (severity == SYSTEMALARMS_ALARM_OK) ? check_stabilization_settings(4, multirotor, coptercontrol) : severity;
break;
case FLIGHTMODESETTINGS_FLIGHTMODEPOSITION_STABILIZED5:
severity = (severity == SYSTEMALARMS_ALARM_OK) ? check_stabilization_settings(5, multirotor, coptercontrol) : severity;
break;
case FLIGHTMODESETTINGS_FLIGHTMODEPOSITION_STABILIZED6:
severity = (severity == SYSTEMALARMS_ALARM_OK) ? check_stabilization_settings(6, multirotor, coptercontrol) : severity;
break;
case FLIGHTMODESETTINGS_FLIGHTMODEPOSITION_AUTOTUNE:
if (!PIOS_TASK_MONITOR_IsRunning(TASKINFO_RUNNING_AUTOTUNE)) {
severity = SYSTEMALARMS_ALARM_ERROR;
}
break;
case FLIGHTMODESETTINGS_FLIGHTMODEPOSITION_ALTITUDEHOLD:
case FLIGHTMODESETTINGS_FLIGHTMODEPOSITION_ALTITUDEVARIO:
if (coptercontrol) {
severity = SYSTEMALARMS_ALARM_ERROR;
}
// TODO: put check equivalent to TASK_MONITOR_IsRunning
// here as soon as available for delayed callbacks
break;
case FLIGHTMODESETTINGS_FLIGHTMODEPOSITION_VELOCITYCONTROL:
if (coptercontrol) {
severity = SYSTEMALARMS_ALARM_ERROR;
} else if (!PIOS_TASK_MONITOR_IsRunning(TASKINFO_RUNNING_PATHFOLLOWER)) { // Revo supports altitude hold
severity = SYSTEMALARMS_ALARM_ERROR;
}
break;
case FLIGHTMODESETTINGS_FLIGHTMODEPOSITION_POSITIONHOLD:
if (coptercontrol) {
severity = SYSTEMALARMS_ALARM_ERROR;
@ -199,14 +193,8 @@ int32_t configuration_check()
* @param[in] index Which stabilization mode to check
* @returns SYSTEMALARMS_ALARM_OK or SYSTEMALARMS_ALARM_ERROR
*/
static int32_t check_stabilization_settings(int index, bool multirotor)
static int32_t check_stabilization_settings(int index, bool multirotor, bool coptercontrol)
{
// Make sure the modes have identical sizes
if (FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_NUMELEM != FLIGHTMODESETTINGS_STABILIZATION2SETTINGS_NUMELEM ||
FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_NUMELEM != FLIGHTMODESETTINGS_STABILIZATION3SETTINGS_NUMELEM) {
return SYSTEMALARMS_ALARM_ERROR;
}
uint8_t modes[FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_NUMELEM];
// Get the different axis modes for this switch position
@ -220,22 +208,58 @@ static int32_t check_stabilization_settings(int index, bool multirotor)
case 3:
FlightModeSettingsStabilization3SettingsArrayGet(modes);
break;
case 4:
FlightModeSettingsStabilization4SettingsArrayGet(modes);
break;
case 5:
FlightModeSettingsStabilization5SettingsArrayGet(modes);
break;
case 6:
FlightModeSettingsStabilization6SettingsArrayGet(modes);
break;
default:
return SYSTEMALARMS_ALARM_ERROR;
}
// For multirotors verify that nothing is set to "none"
// For multirotors verify that roll/pitch/yaw are not set to "none"
// (why not? might be fun to test ones reactions ;) if you dare, set your frame to "custom"!
if (multirotor) {
for (uint32_t i = 0; i < NELEMENTS(modes); i++) {
if (modes[i] == FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_NONE) {
for (uint32_t i = 0; i < FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_THRUST; i++) {
if (modes[i] == FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_MANUAL) {
return SYSTEMALARMS_ALARM_ERROR;
}
}
}
// coptercontrol cannot do altitude holding
if (coptercontrol) {
if (modes[FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_THRUST] == FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_ALTITUDEHOLD
|| modes[FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_THRUST] == FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_VERTICALVELOCITY
) {
return SYSTEMALARMS_ALARM_ERROR;
}
}
// check that thrust modes are only set to thrust axis
for (uint32_t i = 0; i < FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_THRUST; i++) {
if (modes[i] == FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_ALTITUDEHOLD
|| modes[i] == FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_VERTICALVELOCITY
) {
return SYSTEMALARMS_ALARM_ERROR;
}
}
if (!(modes[FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_THRUST] == FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_MANUAL
|| modes[FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_THRUST] == FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_ALTITUDEHOLD
|| modes[FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_THRUST] == FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_VERTICALVELOCITY
|| modes[FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_THRUST] == FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_CRUISECONTROL
)) {
return SYSTEMALARMS_ALARM_ERROR;
}
// Warning: This assumes that certain conditions in the XML file are met. That
// FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_NONE has the same numeric value for each channel
// and is the same for STABILIZATIONDESIRED_STABILIZATIONMODE_NONE
// FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_MANUAL has the same numeric value for each channel
// and is the same for STABILIZATIONDESIRED_STABILIZATIONMODE_MANUAL
// (this is checked at compile time by static constraint manualcontrol.h)
return SYSTEMALARMS_ALARM_OK;
}

View File

@ -49,7 +49,7 @@
// Private constants
#define STACK_SIZE_BYTES 500
#define STACK_SIZE_BYTES 650
#define TASK_PRIORITY (tskIDLE_PRIORITY + 1)
@ -147,6 +147,7 @@ static void airspeedTask(__attribute__((unused)) void *parameters)
airspeedData.SensorConnected = AIRSPEEDSENSOR_SENSORCONNECTED_FALSE;
// Main task loop
portTickType lastSysTime = xTaskGetTickCount();
while (1) {
@ -155,18 +156,9 @@ static void airspeedTask(__attribute__((unused)) void *parameters)
// Update the airspeed object
AirspeedSensorGet(&airspeedData);
// if sensor type changed and the last sensor was
// either Eagletree or PixHawk, reset Airspeed alarm
// if sensor type changed reset Airspeed alarm
if (airspeedSettings.AirspeedSensorType != lastAirspeedSensorType) {
switch (lastAirspeedSensorType) {
// Eagletree or PixHawk => Reset Airspeed alams
case AIRSPEEDSETTINGS_AIRSPEEDSENSORTYPE_EAGLETREEAIRSPEEDV3:
case AIRSPEEDSETTINGS_AIRSPEEDSENSORTYPE_PIXHAWKAIRSPEEDMS4525DO:
AlarmsDefault(SYSTEMALARMS_ALARM_AIRSPEED);
break;
// else do not reset Airspeed alarm
default: break;
}
AlarmsSet(SYSTEMALARMS_ALARM_AIRSPEED, SYSTEMALARMS_ALARM_DEFAULT);
lastAirspeedSensorType = airspeedSettings.AirspeedSensorType;
}
@ -196,6 +188,7 @@ static void airspeedTask(__attribute__((unused)) void *parameters)
case AIRSPEEDSETTINGS_AIRSPEEDSENSORTYPE_NONE:
default:
airspeedData.SensorConnected = AIRSPEEDSENSOR_SENSORCONNECTED_FALSE;
break;
}
// Set the UAVO

View File

@ -64,11 +64,13 @@ void baro_airspeedGetETASV3(AirspeedSensorData *airspeedSensor, AirspeedSettings
if (airspeedSensor->SensorValue == (uint16_t)-1) {
airspeedSensor->SensorConnected = AIRSPEEDSENSOR_SENSORCONNECTED_FALSE;
airspeedSensor->CalibratedAirspeed = 0;
AlarmsSet(SYSTEMALARMS_ALARM_AIRSPEED, SYSTEMALARMS_ALARM_ERROR);
return;
}
// only calibrate if no stored calibration is available
if (!airspeedSettings->ZeroPoint) {
AlarmsSet(SYSTEMALARMS_ALARM_AIRSPEED, SYSTEMALARMS_ALARM_WARNING);
// Calibrate sensor by averaging zero point value
if (calibrationCount <= CALIBRATION_IDLE_MS / airspeedSettings->SamplePeriod) {
calibrationCount++;
@ -93,6 +95,7 @@ void baro_airspeedGetETASV3(AirspeedSensorData *airspeedSensor, AirspeedSettings
// Compute airspeed
airspeedSensor->CalibratedAirspeed = airspeedSettings->Scale * sqrtf((float)abs(airspeedSensor->SensorValue - airspeedSettings->ZeroPoint));
airspeedSensor->SensorConnected = AIRSPEEDSENSOR_SENSORCONNECTED_TRUE;
AlarmsSet(SYSTEMALARMS_ALARM_AIRSPEED, SYSTEMALARMS_ALARM_OK);
}

View File

@ -63,7 +63,7 @@ void baro_airspeedGetMPXV(AirspeedSensorData *airspeedSensor, AirspeedSettingsDa
// Ensure that the ADC pin is properly configured
if (airspeedADCPin < 0) {
airspeedSensor->SensorConnected = AIRSPEEDSENSOR_SENSORCONNECTED_FALSE;
AlarmsSet(SYSTEMALARMS_ALARM_AIRSPEED, SYSTEMALARMS_ALARM_ERROR);
return;
}
if (sensor.type == PIOS_MPXV_UNKNOWN) {
@ -76,6 +76,7 @@ void baro_airspeedGetMPXV(AirspeedSensorData *airspeedSensor, AirspeedSettingsDa
break;
default:
airspeedSensor->SensorConnected = AIRSPEEDSENSOR_SENSORCONNECTED_FALSE;
AlarmsSet(SYSTEMALARMS_ALARM_AIRSPEED, SYSTEMALARMS_ALARM_ERROR);
return;
}
}
@ -83,6 +84,7 @@ void baro_airspeedGetMPXV(AirspeedSensorData *airspeedSensor, AirspeedSettingsDa
airspeedSensor->SensorValue = PIOS_MPXV_Measure(&sensor);
if (!airspeedSettings->ZeroPoint) {
AlarmsSet(SYSTEMALARMS_ALARM_AIRSPEED, SYSTEMALARMS_ALARM_WARNING);
// Calibrate sensor by averaging zero point value
if (calibrationCount < CALIBRATION_IDLE_MS / airspeedSettings->SamplePeriod) { // First let sensor warm up and stabilize.
calibrationCount++;
@ -107,6 +109,7 @@ void baro_airspeedGetMPXV(AirspeedSensorData *airspeedSensor, AirspeedSettingsDa
airspeedSensor->CalibratedAirspeed = PIOS_MPXV_CalcAirspeed(&sensor, airspeedSensor->SensorValue) * (alpha) + airspeedSensor->CalibratedAirspeed * (1.0f - alpha);
airspeedSensor->SensorConnected = AIRSPEEDSENSOR_SENSORCONNECTED_TRUE;
AlarmsSet(SYSTEMALARMS_ALARM_AIRSPEED, SYSTEMALARMS_ALARM_OK);
}
#endif /* if defined(PIOS_INCLUDE_MPXV) */

View File

@ -53,13 +53,9 @@
#define CASFACTOR 760.8802669f // sqrt(5) * speed of sound at standard
#define TASFACTOR 0.05891022589f // 1/sqrt(T0)
#define max(x, y) ((x) >= (y) ? (x) : (y))
// Private types
// Private functions definitions
static int8_t baro_airspeedReadMS4525DO(AirspeedSensorData *airspeedSensor, AirspeedSettingsData *airspeedSettings);
// Private variables
static uint16_t calibrationCount = 0;
@ -67,63 +63,32 @@ static uint32_t filter_reg = 0; // Barry Dorr filter register
void baro_airspeedGetMS4525DO(AirspeedSensorData *airspeedSensor, AirspeedSettingsData *airspeedSettings)
{
// request measurement first
int8_t retVal = PIOS_MS4525DO_Request();
if (retVal != 0) {
AlarmsSet(SYSTEMALARMS_ALARM_AIRSPEED, SYSTEMALARMS_ALARM_ERROR);
return;
}
// Datasheet of MS4525DO: conversion needs 0.5 ms + 20% more when status bit used
// delay by one Tick or at least 2 ms
const portTickType xDelay = max(2 / portTICK_RATE_MS, 1);
vTaskDelay(xDelay);
// read the sensor
retVal = baro_airspeedReadMS4525DO(airspeedSensor, airspeedSettings);
switch (retVal) {
case 0: AlarmsClear(SYSTEMALARMS_ALARM_AIRSPEED);
break;
case -4:
case -5:
case -7: AlarmsSet(SYSTEMALARMS_ALARM_AIRSPEED, SYSTEMALARMS_ALARM_WARNING);
break;
case -1:
case -2:
case -3:
case -6:
default: AlarmsSet(SYSTEMALARMS_ALARM_AIRSPEED, SYSTEMALARMS_ALARM_ERROR);
}
}
// Private functions
static int8_t baro_airspeedReadMS4525DO(AirspeedSensorData *airspeedSensor, AirspeedSettingsData *airspeedSettings)
{
// Check to see if airspeed sensor is returning airspeedSensor
uint16_t values[2];
// Read sensor
int8_t retVal = PIOS_MS4525DO_Read(values);
if (retVal == 0) {
airspeedSensor->SensorValue = values[0];
airspeedSensor->SensorValueTemperature = values[1];
} else {
// check for errors
if (retVal != 0) {
airspeedSensor->SensorValue = -1;
airspeedSensor->SensorValueTemperature = -1;
airspeedSensor->SensorConnected = AIRSPEEDSENSOR_SENSORCONNECTED_FALSE;
airspeedSensor->CalibratedAirspeed = 0;
return retVal;
AlarmsSet(SYSTEMALARMS_ALARM_AIRSPEED, SYSTEMALARMS_ALARM_ERROR);
return;
}
airspeedSensor->SensorValue = values[0];
airspeedSensor->SensorValueTemperature = values[1];
// only calibrate if no stored calibration is available
if (!airspeedSettings->ZeroPoint) {
// Calibrate sensor by averaging zero point value
if (calibrationCount <= CALIBRATION_IDLE_MS / airspeedSettings->SamplePeriod) {
calibrationCount++;
filter_reg = (airspeedSensor->SensorValue << FILTER_SHIFT);
return -7;
AlarmsSet(SYSTEMALARMS_ALARM_AIRSPEED, SYSTEMALARMS_ALARM_WARNING);
return;
} else if (calibrationCount <= (CALIBRATION_IDLE_MS + CALIBRATION_COUNT_MS) / airspeedSettings->SamplePeriod) {
calibrationCount++;
// update filter register
@ -136,7 +101,8 @@ static int8_t baro_airspeedReadMS4525DO(AirspeedSensorData *airspeedSensor, Airs
AirspeedSettingsZeroPointSet(&airspeedSettings->ZeroPoint);
calibrationCount = 0;
}
return -7;
AlarmsSet(SYSTEMALARMS_ALARM_AIRSPEED, SYSTEMALARMS_ALARM_WARNING);
return;
}
}
@ -161,11 +127,10 @@ static int8_t baro_airspeedReadMS4525DO(AirspeedSensorData *airspeedSensor, Airs
airspeedSensor->CalibratedAirspeed = airspeedSettings->Scale * CASFACTOR * sqrtf(powf(fabsf(dP) / P0 + 1.0f, CCEXPONENT) - 1.0f);
airspeedSensor->TrueAirspeed = airspeedSensor->CalibratedAirspeed * TASFACTOR * sqrtf(T);
airspeedSensor->SensorConnected = AIRSPEEDSENSOR_SENSORCONNECTED_TRUE;
return retVal;
// everything is fine so set ALARM_OK
AlarmsSet(SYSTEMALARMS_ALARM_AIRSPEED, SYSTEMALARMS_ALARM_OK);
}
#endif /* if defined(PIOS_INCLUDE_MS4525DO) */
/**

View File

@ -45,6 +45,7 @@
#define GPS_AIRSPEED_BIAS_KI 0.1f // Needs to be settable in a UAVO
#define SAMPLING_DELAY_MS_GPS 100 // Needs to be settable in a UAVO
#define GPS_AIRSPEED_TIME_CONSTANT_MS 500.0f // Needs to be settable in a UAVO
#define COSINE_OF_5_DEG 0.9961947f
// Private types
struct GPSGlobals {
@ -59,6 +60,12 @@ struct GPSGlobals {
static struct GPSGlobals *gps;
// Private functions
// a simple square inline function based on multiplication faster than powf(x,2.0f)
static inline float Sq(float x)
{
return x * x;
}
/*
* Initialize function loads first data sets, and allocates memory for structure.
@ -102,6 +109,11 @@ void gps_airspeedInitialize()
* where "f" is the fuselage vector in earth coordinates.
* We then solve for |V| = |V_gps_2-V_gps_1|/ |f_2 - f1|.
*/
/* Remark regarding "IMU Wind Estimation": The approach includes errors when |V| is
* not constant, i.e. when the change in V_gps does not solely come from a reorientation
* this error depends strongly on the time scale considered. Is the time between t1 and t2 too
* small, "spikes" absorving unconsidred acceleration will arise
*/
void gps_airspeedGet(AirspeedSensorData *airspeedData, AirspeedSettingsData *airspeedSettings)
{
float Rbe[3][3];
@ -120,32 +132,39 @@ void gps_airspeedGet(AirspeedSensorData *airspeedData, AirspeedSettingsData *air
float cosDiff = (Rbe[0][0] * gps->RbeCol1_old[0]) + (Rbe[0][1] * gps->RbeCol1_old[1]) + (Rbe[0][2] * gps->RbeCol1_old[2]);
// If there's more than a 5 degree difference between two fuselage measurements, then we have sufficient delta to continue.
if (fabsf(cosDiff) < cosf(DEG2RAD(5.0f))) {
if (fabsf(cosDiff) < COSINE_OF_5_DEG) {
VelocityStateData gpsVelData;
VelocityStateGet(&gpsVelData);
if (gpsVelData.North * gpsVelData.North + gpsVelData.East * gpsVelData.East + gpsVelData.Down * gpsVelData.Down < 1.0f) {
airspeedData->CalibratedAirspeed = 0;
airspeedData->SensorConnected = AIRSPEEDSENSOR_SENSORCONNECTED_FALSE;
AlarmsSet(SYSTEMALARMS_ALARM_AIRSPEED, SYSTEMALARMS_ALARM_WARNING);
return; // do not calculate if gps velocity is insufficient...
}
// Calculate the norm^2 of the difference between the two GPS vectors
float normDiffGPS2 = powf(gpsVelData.North - gps->gpsVelOld_N, 2.0f) + powf(gpsVelData.East - gps->gpsVelOld_E, 2.0f) + powf(gpsVelData.Down - gps->gpsVelOld_D, 2.0f);
float normDiffGPS2 = Sq(gpsVelData.North - gps->gpsVelOld_N) + Sq(gpsVelData.East - gps->gpsVelOld_E) + Sq(gpsVelData.Down - gps->gpsVelOld_D);
// Calculate the norm^2 of the difference between the two fuselage vectors
float normDiffAttitude2 = powf(Rbe[0][0] - gps->RbeCol1_old[0], 2.0f) + powf(Rbe[0][1] - gps->RbeCol1_old[1], 2.0f) + powf(Rbe[0][2] - gps->RbeCol1_old[2], 2.0f);
float normDiffAttitude2 = Sq(Rbe[0][0] - gps->RbeCol1_old[0]) + Sq(Rbe[0][1] - gps->RbeCol1_old[1]) + Sq(Rbe[0][2] - gps->RbeCol1_old[2]);
// Airspeed magnitude is the ratio between the two difference norms
float airspeed = sqrtf(normDiffGPS2 / normDiffAttitude2);
if (!IS_REAL(airspeedData->CalibratedAirspeed)) {
airspeedData->CalibratedAirspeed = 0;
airspeedData->SensorConnected = AIRSPEEDSENSOR_SENSORCONNECTED_FALSE;
AlarmsSet(SYSTEMALARMS_ALARM_AIRSPEED, SYSTEMALARMS_ALARM_ERROR);
} else if (!IS_REAL(airspeed)) {
airspeedData->CalibratedAirspeed = 0;
airspeedData->SensorConnected = AIRSPEEDSENSOR_SENSORCONNECTED_FALSE;
AlarmsSet(SYSTEMALARMS_ALARM_AIRSPEED, SYSTEMALARMS_ALARM_WARNING);
} else {
// need a low pass filter to filter out spikes in non coordinated maneuvers
airspeedData->CalibratedAirspeed = (1.0f - airspeedSettings->GroundSpeedBasedEstimationLowPassAlpha) * gps->oldAirspeed + airspeedSettings->GroundSpeedBasedEstimationLowPassAlpha * airspeed;
gps->oldAirspeed = airspeedData->CalibratedAirspeed;
airspeedData->SensorConnected = AIRSPEEDSENSOR_SENSORCONNECTED_TRUE;
AlarmsSet(SYSTEMALARMS_ALARM_AIRSPEED, SYSTEMALARMS_ALARM_OK);
}
// Save old variables for next pass

View File

@ -278,7 +278,7 @@ static void AttitudeTask(__attribute__((unused)) void *parameters)
case REVOSETTINGS_FUSIONALGORITHM_COMPLEMENTARY:
ret_val = updateAttitudeComplementary(first_run);
break;
case REVOSETTINGS_FUSIONALGORITHM_INS13OUTDOOR:
case REVOSETTINGS_FUSIONALGORITHM_INS13GPSOUTDOOR:
ret_val = updateAttitudeINSGPS(first_run, true);
break;
case REVOSETTINGS_FUSIONALGORITHM_INS13INDOOR:
@ -1072,13 +1072,22 @@ static int32_t updateAttitudeINSGPS(bool first_run, bool outdoor_mode)
vel[2] = gpsVelData.Down;
}
// Copy the position into the UAVO
PositionStateData positionState;
PositionStateGet(&positionState);
positionState.North = Nav.Pos[0];
positionState.East = Nav.Pos[1];
positionState.Down = Nav.Pos[2];
PositionStateSet(&positionState);
// airspeed correction needs current positionState
if (airspeed_updated) {
// we have airspeed available
AirspeedStateData airspeed;
AirspeedStateGet(&airspeed);
airspeed.CalibratedAirspeed = airspeedData.CalibratedAirspeed;
airspeed.TrueAirspeed = (airspeedSensor.TrueAirspeed < 0.f) ? airspeed.CalibratedAirspeed *IAS2TAS(homeLocation.Altitude - positionState.Down) : airspeedSensor.TrueAirspeed;
airspeed.TrueAirspeed = (airspeedData.TrueAirspeed < 0.f) ? airspeed.CalibratedAirspeed *IAS2TAS(homeLocation.Altitude - positionState.Down) : airspeedData.TrueAirspeed;
AirspeedStateSet(&airspeed);
@ -1108,14 +1117,7 @@ static int32_t updateAttitudeINSGPS(bool first_run, bool outdoor_mode)
INSCorrection(&magData.x, NED, vel, (baroData.Altitude + baroOffset), sensors);
}
// Copy the position and velocity into the UAVO
PositionStateData positionState;
PositionStateGet(&positionState);
positionState.North = Nav.Pos[0];
positionState.East = Nav.Pos[1];
positionState.Down = Nav.Pos[2];
PositionStateSet(&positionState);
// Copy the velocity into the UAVO
VelocityStateData velocityState;
VelocityStateGet(&velocityState);
velocityState.North = Nav.Vel[0];

View File

@ -183,6 +183,7 @@ static void AutotuneTask(__attribute__((unused)) void *parameters)
stabDesired.StabilizationMode[STABILIZATIONDESIRED_STABILIZATIONMODE_YAW] = STABILIZATIONDESIRED_STABILIZATIONMODE_RATE;
stabDesired.Yaw = manualControl.Yaw * stabSettings.ManualRate[STABILIZATIONSETTINGS_MANUALRATE_YAW];
stabDesired.StabilizationMode[STABILIZATIONDESIRED_STABILIZATIONMODE_THRUST] = STABILIZATIONDESIRED_STABILIZATIONMODE_MANUAL;
stabDesired.Thrust = manualControl.Thrust;
switch (state) {

View File

@ -47,6 +47,7 @@
#include "openpilot.h"
#include "flightstatus.h"
#include "flightbatterystate.h"
#include "flightbatterysettings.h"
#include "hwsettings.h"
@ -69,6 +70,7 @@ static int8_t currentADCPin = -1; // ADC pin for current
// Private functions
static void onTimer(UAVObjEvent *ev);
static int8_t GetNbCells(const FlightBatterySettingsData *batterySettings, FlightBatteryStateData *flightBatteryData);
/**
* Initialise the module, called on startup
@ -113,6 +115,8 @@ int32_t BatteryInitialize(void)
FlightBatteryStateInitialize();
FlightBatterySettingsInitialize();
// FlightBatterySettingsConnectCallback(FlightBatterySettingsUpdatedCb);
static UAVObjEvent ev;
memset(&ev, 0, sizeof(UAVObjEvent));
@ -125,10 +129,11 @@ int32_t BatteryInitialize(void)
MODULE_INITCALL(BatteryInitialize, 0);
static void onTimer(__attribute__((unused)) UAVObjEvent *ev)
{
static FlightBatteryStateData flightBatteryData;
static FlightBatterySettingsData batterySettings;
static FlightBatteryStateData flightBatteryData;
FlightBatterySettingsGet(&batterySettings);
FlightBatteryStateGet(&flightBatteryData);
const float dT = SAMPLE_PERIOD_MS / 1000.0f;
float energyRemaining;
@ -140,7 +145,11 @@ static void onTimer(__attribute__((unused)) UAVObjEvent *ev)
flightBatteryData.Voltage = 0; // Dummy placeholder value. This is in case we get another source of battery current which is not from the ADC
}
if (currentADCPin >= 0) {
// voltage available: get the number of cells if possible, desired and not armed
GetNbCells(&batterySettings, &flightBatteryData);
// ad a plausibility check: zero voltage => zero current
if (currentADCPin >= 0 && flightBatteryData.Voltage > 0.f) {
flightBatteryData.Current = (PIOS_ADC_PinGetVolt(currentADCPin) - batterySettings.SensorCalibrations.CurrentZero) * batterySettings.SensorCalibrations.CurrentFactor; // in Amps
if (flightBatteryData.Current > flightBatteryData.PeakCurrent) {
flightBatteryData.PeakCurrent = flightBatteryData.Current; // in Amps
@ -149,7 +158,11 @@ static void onTimer(__attribute__((unused)) UAVObjEvent *ev)
flightBatteryData.Current = -0; // Dummy placeholder value. This is in case we get another source of battery current which is not from the ADC
}
// For safety reasons consider only positive currents in energy comsumption, i.e. no charging up.
// necesary when sensor are not perfectly calibrated
if (flightBatteryData.Current > 0) {
flightBatteryData.ConsumedEnergy += (flightBatteryData.Current * dT * 1000.0f / 3600.0f); // in mAh
}
// Apply a 2 second rise time low-pass filter to average the current
float alpha = 1.0f - dT / (dT + 2.0f);
@ -184,9 +197,9 @@ static void onTimer(__attribute__((unused)) UAVObjEvent *ev)
// FIXME: should make the battery voltage detection dependent on battery type.
/*Not so sure. Some users will want to run their batteries harder than others, so it should be the user's choice. [KDS]*/
if (flightBatteryData.Voltage < batterySettings.CellVoltageThresholds.Alarm * batterySettings.NbCells) {
if (flightBatteryData.Voltage < batterySettings.CellVoltageThresholds.Alarm * flightBatteryData.NbCells) {
AlarmsSet(SYSTEMALARMS_ALARM_BATTERY, SYSTEMALARMS_ALARM_CRITICAL);
} else if (flightBatteryData.Voltage < batterySettings.CellVoltageThresholds.Warning * batterySettings.NbCells) {
} else if (flightBatteryData.Voltage < batterySettings.CellVoltageThresholds.Warning * flightBatteryData.NbCells) {
AlarmsSet(SYSTEMALARMS_ALARM_BATTERY, SYSTEMALARMS_ALARM_WARNING);
} else {
AlarmsClear(SYSTEMALARMS_ALARM_BATTERY);
@ -196,6 +209,71 @@ static void onTimer(__attribute__((unused)) UAVObjEvent *ev)
FlightBatteryStateSet(&flightBatteryData);
}
static int8_t GetNbCells(const FlightBatterySettingsData *batterySettings, FlightBatteryStateData *flightBatteryData)
{
// get flight status to check for armed
uint8_t armed = 0;
FlightStatusArmedGet(&armed);
// check only if not armed
if (armed == FLIGHTSTATUS_ARMED_ARMED) {
return -2;
}
// prescribed number of cells?
if (batterySettings->NbCells != 0) {
flightBatteryData->NbCells = batterySettings->NbCells;
flightBatteryData->NbCellsAutodetected = 0;
return -3;
}
// plausibility check
if (flightBatteryData->Voltage <= 0.5f) {
// cannot detect number of cells
flightBatteryData->NbCellsAutodetected = 0;
return -1;
}
float voltageMin = 0.f, voltageMax = 0.f;
// Cell type specific values
// TODO: could be implemented as constant arrays indexed by cellType
// or could be part of the UAVObject definition
switch (batterySettings->Type) {
case FLIGHTBATTERYSETTINGS_TYPE_LIPO:
case FLIGHTBATTERYSETTINGS_TYPE_LICO:
voltageMin = 3.6f;
voltageMax = 4.2f;
break;
case FLIGHTBATTERYSETTINGS_TYPE_A123:
voltageMin = 2.01f;
voltageMax = 3.59f;
break;
case FLIGHTBATTERYSETTINGS_TYPE_LIFESO4:
default:
flightBatteryData->NbCellsAutodetected = 0;
return -1;
}
// uniquely measurable under any condition iff n * voltageMax < (n+1) * voltageMin
// or n < voltageMin / (voltageMax-voltageMin)
// weaken condition by setting n <= voltageMin / (voltageMax-voltageMin) and
// checking for v <= voltageMin * voltageMax / (voltageMax-voltageMin)
if (flightBatteryData->Voltage > voltageMin * voltageMax / (voltageMax - voltageMin)) {
flightBatteryData->NbCellsAutodetected = 0;
return -1;
}
flightBatteryData->NbCells = (int8_t)(flightBatteryData->Voltage / voltageMin);
flightBatteryData->NbCellsAutodetected = 1;
return flightBatteryData->NbCells;
}
/**
* @}
*/

View File

@ -79,7 +79,6 @@ static struct CameraStab_data {
// Private functions
static void attitudeUpdated(UAVObjEvent *ev);
static float bound(float val, float limit);
#ifdef USE_GIMBAL_FF
static void applyFeedForward(uint8_t index, float dT, float *attitude, CameraStabSettingsData *cameraStab);
@ -186,7 +185,8 @@ static void attitudeUpdated(UAVObjEvent *ev)
input_rate = accessory.AccessoryVal *
cast_struct_to_array(cameraStab.InputRate, cameraStab.InputRate.Roll)[i];
if (fabsf(input_rate) > cameraStab.MaxAxisLockRate) {
csd->inputs[i] = bound(csd->inputs[i] + input_rate * 0.001f * dT_millis,
csd->inputs[i] = boundf(csd->inputs[i] + input_rate * 0.001f * dT_millis,
-cast_struct_to_array(cameraStab.InputRange, cameraStab.InputRange.Roll)[i],
cast_struct_to_array(cameraStab.InputRange, cameraStab.InputRange.Roll)[i]);
}
break;
@ -229,7 +229,7 @@ static void attitudeUpdated(UAVObjEvent *ev)
// bounding for elevon mixing occurs on the unmixed output
// to limit the range of the mixed output you must limit the range
// of both the unmixed pitch and unmixed roll
float output = bound((attitude + csd->inputs[i]) / cast_struct_to_array(cameraStab.OutputRange, cameraStab.OutputRange.Roll)[i], 1.0f);
float output = boundf((attitude + csd->inputs[i]) / cast_struct_to_array(cameraStab.OutputRange, cameraStab.OutputRange.Roll)[i], -1.0f, 1.0f);
// set output channels
switch (i) {
@ -282,13 +282,6 @@ static void attitudeUpdated(UAVObjEvent *ev)
}
}
float bound(float val, float limit)
{
return (val > limit) ? limit :
(val < -limit) ? -limit :
val;
}
#ifdef USE_GIMBAL_FF
void applyFeedForward(uint8_t index, float dT_millis, float *attitude, CameraStabSettingsData *cameraStab)
{

View File

@ -85,7 +85,6 @@ static void updatePathVelocity();
static uint8_t updateFixedDesiredAttitude();
static void updateFixedAttitude();
static void airspeedStateUpdatedCb(UAVObjEvent *ev);
static float bound(float val, float min, float max);
/**
* Initialise the module, called on startup
@ -277,9 +276,9 @@ static void updatePathVelocity()
case PATHDESIRED_MODE_DRIVEVECTOR:
default:
groundspeed = pathDesired.StartingVelocity + (pathDesired.EndingVelocity - pathDesired.StartingVelocity) *
bound(progress.fractional_progress, 0, 1);
boundf(progress.fractional_progress, 0, 1);
altitudeSetpoint = pathDesired.Start.Down + (pathDesired.End.Down - pathDesired.Start.Down) *
bound(progress.fractional_progress, 0, 1);
boundf(progress.fractional_progress, 0, 1);
break;
}
// make sure groundspeed is not zero
@ -359,6 +358,7 @@ static void updateFixedAttitude(float *attitude)
stabDesired.StabilizationMode.Roll = STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE;
stabDesired.StabilizationMode.Pitch = STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE;
stabDesired.StabilizationMode.Yaw = STABILIZATIONDESIRED_STABILIZATIONMODE_RATE;
stabDesired.StabilizationMode.Thrust = STABILIZATIONDESIRED_STABILIZATIONMODE_MANUAL;
StabilizationDesiredSet(&stabDesired);
}
@ -427,7 +427,7 @@ static uint8_t updateFixedDesiredAttitude()
// Desired ground speed
groundspeedDesired = sqrtf(velocityDesired.North * velocityDesired.North + velocityDesired.East * velocityDesired.East);
indicatedAirspeedDesired = bound(groundspeedDesired + indicatedAirspeedStateBias,
indicatedAirspeedDesired = boundf(groundspeedDesired + indicatedAirspeedStateBias,
fixedwingpathfollowerSettings.HorizontalVelMin,
fixedwingpathfollowerSettings.HorizontalVelMax);
@ -435,7 +435,7 @@ static uint8_t updateFixedDesiredAttitude()
airspeedError = indicatedAirspeedDesired - indicatedAirspeedState;
// Vertical speed error
descentspeedDesired = bound(
descentspeedDesired = boundf(
velocityDesired.Down,
-fixedwingpathfollowerSettings.VerticalVelMax,
fixedwingpathfollowerSettings.VerticalVelMax);
@ -473,14 +473,14 @@ static uint8_t updateFixedDesiredAttitude()
*/
// compute saturated integral error thrust response. Make integral leaky for better performance. Approximately 30s time constant.
if (fixedwingpathfollowerSettings.PowerPI.Ki > 0) {
powerIntegral = bound(powerIntegral + -descentspeedError * dT,
powerIntegral = boundf(powerIntegral + -descentspeedError * dT,
-fixedwingpathfollowerSettings.PowerPI.ILimit / fixedwingpathfollowerSettings.PowerPI.Ki,
fixedwingpathfollowerSettings.PowerPI.ILimit / fixedwingpathfollowerSettings.PowerPI.Ki
) * (1.0f - 1.0f / (1.0f + 30.0f / dT));
} else { powerIntegral = 0; }
// Compute the cross feed from vertical speed to pitch, with saturation
float speedErrorToPowerCommandComponent = bound(
float speedErrorToPowerCommandComponent = boundf(
(airspeedError / fixedwingpathfollowerSettings.HorizontalVelMin) * fixedwingpathfollowerSettings.AirspeedToPowerCrossFeed.Kp,
-fixedwingpathfollowerSettings.AirspeedToPowerCrossFeed.Max,
fixedwingpathfollowerSettings.AirspeedToPowerCrossFeed.Max
@ -497,7 +497,7 @@ static uint8_t updateFixedDesiredAttitude()
fixedwingpathfollowerStatus.Command.Power = powerCommand;
// set thrust
stabDesired.Thrust = bound(fixedwingpathfollowerSettings.ThrustLimit.Neutral + powerCommand,
stabDesired.Thrust = boundf(fixedwingpathfollowerSettings.ThrustLimit.Neutral + powerCommand,
fixedwingpathfollowerSettings.ThrustLimit.Min,
fixedwingpathfollowerSettings.ThrustLimit.Max);
@ -529,13 +529,13 @@ static uint8_t updateFixedDesiredAttitude()
if (fixedwingpathfollowerSettings.SpeedPI.Ki > 0) {
// Integrate with saturation
airspeedErrorInt = bound(airspeedErrorInt + airspeedError * dT,
airspeedErrorInt = boundf(airspeedErrorInt + airspeedError * dT,
-fixedwingpathfollowerSettings.SpeedPI.ILimit / fixedwingpathfollowerSettings.SpeedPI.Ki,
fixedwingpathfollowerSettings.SpeedPI.ILimit / fixedwingpathfollowerSettings.SpeedPI.Ki);
}
// Compute the cross feed from vertical speed to pitch, with saturation
float verticalSpeedToPitchCommandComponent = bound(-descentspeedError * fixedwingpathfollowerSettings.VerticalToPitchCrossFeed.Kp,
float verticalSpeedToPitchCommandComponent = boundf(-descentspeedError * fixedwingpathfollowerSettings.VerticalToPitchCrossFeed.Kp,
-fixedwingpathfollowerSettings.VerticalToPitchCrossFeed.Max,
fixedwingpathfollowerSettings.VerticalToPitchCrossFeed.Max
);
@ -549,7 +549,7 @@ static uint8_t updateFixedDesiredAttitude()
fixedwingpathfollowerStatus.ErrorInt.Speed = airspeedErrorInt;
fixedwingpathfollowerStatus.Command.Speed = pitchCommand;
stabDesired.Pitch = bound(fixedwingpathfollowerSettings.PitchLimit.Neutral + pitchCommand,
stabDesired.Pitch = boundf(fixedwingpathfollowerSettings.PitchLimit.Neutral + pitchCommand,
fixedwingpathfollowerSettings.PitchLimit.Min,
fixedwingpathfollowerSettings.PitchLimit.Max);
@ -606,7 +606,7 @@ static uint8_t updateFixedDesiredAttitude()
courseError -= 360.0f;
}
courseIntegral = bound(courseIntegral + courseError * dT * fixedwingpathfollowerSettings.CoursePI.Ki,
courseIntegral = boundf(courseIntegral + courseError * dT * fixedwingpathfollowerSettings.CoursePI.Ki,
-fixedwingpathfollowerSettings.CoursePI.ILimit,
fixedwingpathfollowerSettings.CoursePI.ILimit);
courseCommand = (courseError * fixedwingpathfollowerSettings.CoursePI.Kp +
@ -616,7 +616,7 @@ static uint8_t updateFixedDesiredAttitude()
fixedwingpathfollowerStatus.ErrorInt.Course = courseIntegral;
fixedwingpathfollowerStatus.Command.Course = courseCommand;
stabDesired.Roll = bound(fixedwingpathfollowerSettings.RollLimit.Neutral +
stabDesired.Roll = boundf(fixedwingpathfollowerSettings.RollLimit.Neutral +
courseCommand,
fixedwingpathfollowerSettings.RollLimit.Min,
fixedwingpathfollowerSettings.RollLimit.Max);
@ -633,7 +633,8 @@ static uint8_t updateFixedDesiredAttitude()
stabDesired.StabilizationMode.Roll = STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE;
stabDesired.StabilizationMode.Pitch = STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE;
stabDesired.StabilizationMode.Yaw = STABILIZATIONDESIRED_STABILIZATIONMODE_NONE;
stabDesired.StabilizationMode.Yaw = STABILIZATIONDESIRED_STABILIZATIONMODE_MANUAL;
stabDesired.StabilizationMode.Thrust = STABILIZATIONDESIRED_STABILIZATIONMODE_MANUAL;
StabilizationDesiredSet(&stabDesired);
@ -642,20 +643,6 @@ static uint8_t updateFixedDesiredAttitude()
return result;
}
/**
* Bound input value between limits
*/
static float bound(float val, float min, float max)
{
if (val < min) {
val = min;
} else if (val > max) {
val = max;
}
return val;
}
static void SettingsUpdatedCb(__attribute__((unused)) UAVObjEvent *ev)
{
FixedWingPathFollowerSettingsGet(&fixedwingpathfollowerSettings);

View File

@ -254,10 +254,9 @@ void parse_ubx_nav_velned(struct UBX_NAV_VELNED *velned, GPSPositionSensorData *
#if !defined(PIOS_GPS_MINIMAL)
void parse_ubx_nav_timeutc(struct UBX_NAV_TIMEUTC *timeutc)
{
if (!(timeutc->valid & TIMEUTC_VALIDUTC)) {
return;
}
// Test if time is valid
if ((timeutc->valid & TIMEUTC_VALIDTOW) && (timeutc->valid & TIMEUTC_VALIDWKN)) {
// Time is valid, set GpsTime
GPSTimeData GpsTime;
GpsTime.Year = timeutc->year;
@ -268,8 +267,12 @@ void parse_ubx_nav_timeutc(struct UBX_NAV_TIMEUTC *timeutc)
GpsTime.Second = timeutc->sec;
GPSTimeSet(&GpsTime);
} else {
// Time is not valid, nothing to do
return;
}
#endif
}
#endif /* if !defined(PIOS_GPS_MINIMAL) */
#if !defined(PIOS_GPS_MINIMAL)
void parse_ubx_nav_svinfo(struct UBX_NAV_SVINFO *svinfo)

View File

@ -1,133 +0,0 @@
/**
******************************************************************************
* @addtogroup OpenPilotModules OpenPilot Modules
* @{
* @addtogroup ManualControl
* @brief Interpretes the control input in ManualControlCommand
* @{
*
* @file altitudehandler.c
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2014.
*
* @see The GNU Public License (GPL) Version 3
*
******************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#include "inc/manualcontrol.h"
#include <manualcontrolcommand.h>
#include <stabilizationbank.h>
#include <altitudeholddesired.h>
#include <altitudeholdsettings.h>
#include <positionstate.h>
#if defined(REVOLUTION)
// Private constants
// Private types
// Private functions
/**
* @brief Handler to control deprecated flight modes controlled by AltitudeHold module
* @input: ManualControlCommand
* @output: AltitudeHoldDesired
*/
void altitudeHandler(bool newinit)
{
const float DEADBAND = 0.20f;
const float DEADBAND_HIGH = 1.0f / 2 + DEADBAND / 2;
const float DEADBAND_LOW = 1.0f / 2 - DEADBAND / 2;
if (newinit) {
StabilizationBankInitialize();
AltitudeHoldDesiredInitialize();
AltitudeHoldSettingsInitialize();
PositionStateInitialize();
}
// this is the max speed in m/s at the extents of thrust
float thrustRate;
uint8_t thrustExp;
static uint8_t flightMode;
static bool newaltitude = true;
ManualControlCommandData cmd;
ManualControlCommandGet(&cmd);
FlightStatusFlightModeGet(&flightMode);
AltitudeHoldDesiredData altitudeHoldDesiredData;
AltitudeHoldDesiredGet(&altitudeHoldDesiredData);
AltitudeHoldSettingsThrustExpGet(&thrustExp);
AltitudeHoldSettingsThrustRateGet(&thrustRate);
StabilizationBankData stabSettings;
StabilizationBankGet(&stabSettings);
PositionStateData posState;
PositionStateGet(&posState);
altitudeHoldDesiredData.Roll = cmd.Roll * stabSettings.RollMax;
altitudeHoldDesiredData.Pitch = cmd.Pitch * stabSettings.PitchMax;
altitudeHoldDesiredData.Yaw = cmd.Yaw * stabSettings.ManualRate.Yaw;
if (newinit) {
newaltitude = true;
}
uint8_t cutOff;
AltitudeHoldSettingsCutThrustWhenZeroGet(&cutOff);
if (cutOff && cmd.Thrust < 0) {
// Cut thrust if desired
altitudeHoldDesiredData.SetPoint = cmd.Thrust;
altitudeHoldDesiredData.ControlMode = ALTITUDEHOLDDESIRED_CONTROLMODE_THRUST;
newaltitude = true;
} else if (flightMode == FLIGHTSTATUS_FLIGHTMODE_ALTITUDEVARIO && cmd.Thrust > DEADBAND_HIGH) {
// being the two band symmetrical I can divide by DEADBAND_LOW to scale it to a value betweeon 0 and 1
// then apply an "exp" f(x,k) = (k*x*x*x + (255-k)*x) / 255
altitudeHoldDesiredData.SetPoint = -((thrustExp * powf((cmd.Thrust - DEADBAND_HIGH) / (DEADBAND_LOW), 3) + (255 - thrustExp) * (cmd.Thrust - DEADBAND_HIGH) / DEADBAND_LOW) / 255 * thrustRate);
altitudeHoldDesiredData.ControlMode = ALTITUDEHOLDDESIRED_CONTROLMODE_VELOCITY;
newaltitude = true;
} else if (flightMode == FLIGHTSTATUS_FLIGHTMODE_ALTITUDEVARIO && cmd.Thrust < DEADBAND_LOW) {
altitudeHoldDesiredData.SetPoint = -(-(thrustExp * powf((DEADBAND_LOW - (cmd.Thrust < 0 ? 0 : cmd.Thrust)) / DEADBAND_LOW, 3) + (255 - thrustExp) * (DEADBAND_LOW - cmd.Thrust) / DEADBAND_LOW) / 255 * thrustRate);
altitudeHoldDesiredData.ControlMode = ALTITUDEHOLDDESIRED_CONTROLMODE_VELOCITY;
newaltitude = true;
} else if (newaltitude == true) {
altitudeHoldDesiredData.SetPoint = posState.Down;
altitudeHoldDesiredData.ControlMode = ALTITUDEHOLDDESIRED_CONTROLMODE_ALTITUDE;
newaltitude = false;
}
AltitudeHoldDesiredSet(&altitudeHoldDesiredData);
}
#else /* if defined(REVOLUTION) */
void altitudeHandler(__attribute__((unused)) bool newinit)
{
AlarmsSet(SYSTEMALARMS_ALARM_MANUALCONTROL, SYSTEMALARMS_ALARM_CRITICAL); // should not be called
}
#endif // REVOLUTION
/**
* @}
* @}
*/

View File

@ -61,13 +61,6 @@ void manualHandler(bool newinit);
*/
void stabilizedHandler(bool newinit);
/**
* @brief Handler to control deprecated flight modes controlled by AltitudeHold module
* @input: ManualControlCommand
* @output: AltitudeHoldDesired
*/
void altitudeHandler(bool newinit);
/**
* @brief Handler to control Guided flightmodes. FlightControl is governed by PathFollower, control via PathDesired
* @input: NONE: fully automated mode -- TODO recursively call handler for advanced stick commands
@ -88,29 +81,114 @@ void pathPlannerHandler(bool newinit);
*/
#define assumptions1 \
( \
((int)FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_NONE == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_NONE) && \
((int)FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_MANUAL == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_MANUAL) && \
((int)FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_RATE == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_RATE) && \
((int)FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_ATTITUDE == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE) && \
((int)FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_AXISLOCK == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_AXISLOCK) && \
((int)FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_WEAKLEVELING == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_WEAKLEVELING) && \
((int)FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_ATTITUDE == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE) \
((int)FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_VIRTUALBAR == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_VIRTUALBAR) && \
((int)FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_RATTITUDE == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_RATTITUDE) && \
((int)FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_RELAYRATE == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_RELAYRATE) && \
((int)FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_RELAYATTITUDE == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_RELAYATTITUDE) && \
((int)FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_ALTITUDEHOLD == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_ALTITUDEHOLD) && \
((int)FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_VERTICALVELOCITY == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_VERTICALVELOCITY) && \
((int)FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_CRUISECONTROL == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_CRUISECONTROL) && \
1 \
)
#define assumptions2 \
( \
((int)FLIGHTMODESETTINGS_STABILIZATION2SETTINGS_MANUAL == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_MANUAL) && \
((int)FLIGHTMODESETTINGS_STABILIZATION2SETTINGS_RATE == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_RATE) && \
((int)FLIGHTMODESETTINGS_STABILIZATION2SETTINGS_ATTITUDE == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE) && \
((int)FLIGHTMODESETTINGS_STABILIZATION2SETTINGS_AXISLOCK == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_AXISLOCK) && \
((int)FLIGHTMODESETTINGS_STABILIZATION2SETTINGS_WEAKLEVELING == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_WEAKLEVELING) && \
((int)FLIGHTMODESETTINGS_STABILIZATION2SETTINGS_VIRTUALBAR == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_VIRTUALBAR) && \
((int)FLIGHTMODESETTINGS_STABILIZATION2SETTINGS_RATTITUDE == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_RATTITUDE) && \
((int)FLIGHTMODESETTINGS_STABILIZATION2SETTINGS_RELAYRATE == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_RELAYRATE) && \
((int)FLIGHTMODESETTINGS_STABILIZATION2SETTINGS_RELAYATTITUDE == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_RELAYATTITUDE) && \
((int)FLIGHTMODESETTINGS_STABILIZATION2SETTINGS_ALTITUDEHOLD == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_ALTITUDEHOLD) && \
((int)FLIGHTMODESETTINGS_STABILIZATION2SETTINGS_VERTICALVELOCITY == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_VERTICALVELOCITY) && \
((int)FLIGHTMODESETTINGS_STABILIZATION2SETTINGS_CRUISECONTROL == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_CRUISECONTROL) && \
1 \
)
#define assumptions3 \
( \
((int)FLIGHTMODESETTINGS_STABILIZATION2SETTINGS_NONE == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_NONE) && \
((int)FLIGHTMODESETTINGS_STABILIZATION2SETTINGS_RATE == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_RATE) && \
((int)FLIGHTMODESETTINGS_STABILIZATION2SETTINGS_AXISLOCK == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_AXISLOCK) && \
((int)FLIGHTMODESETTINGS_STABILIZATION2SETTINGS_WEAKLEVELING == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_WEAKLEVELING) && \
((int)FLIGHTMODESETTINGS_STABILIZATION2SETTINGS_ATTITUDE == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE) \
((int)FLIGHTMODESETTINGS_STABILIZATION3SETTINGS_MANUAL == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_MANUAL) && \
((int)FLIGHTMODESETTINGS_STABILIZATION3SETTINGS_RATE == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_RATE) && \
((int)FLIGHTMODESETTINGS_STABILIZATION3SETTINGS_ATTITUDE == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE) && \
((int)FLIGHTMODESETTINGS_STABILIZATION3SETTINGS_AXISLOCK == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_AXISLOCK) && \
((int)FLIGHTMODESETTINGS_STABILIZATION3SETTINGS_WEAKLEVELING == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_WEAKLEVELING) && \
((int)FLIGHTMODESETTINGS_STABILIZATION3SETTINGS_VIRTUALBAR == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_VIRTUALBAR) && \
((int)FLIGHTMODESETTINGS_STABILIZATION3SETTINGS_RATTITUDE == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_RATTITUDE) && \
((int)FLIGHTMODESETTINGS_STABILIZATION3SETTINGS_RELAYRATE == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_RELAYRATE) && \
((int)FLIGHTMODESETTINGS_STABILIZATION3SETTINGS_RELAYATTITUDE == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_RELAYATTITUDE) && \
((int)FLIGHTMODESETTINGS_STABILIZATION3SETTINGS_ALTITUDEHOLD == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_ALTITUDEHOLD) && \
((int)FLIGHTMODESETTINGS_STABILIZATION3SETTINGS_VERTICALVELOCITY == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_VERTICALVELOCITY) && \
((int)FLIGHTMODESETTINGS_STABILIZATION3SETTINGS_CRUISECONTROL == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_CRUISECONTROL) && \
1 \
)
#define assumptions4 \
( \
((int)FLIGHTMODESETTINGS_STABILIZATION4SETTINGS_MANUAL == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_MANUAL) && \
((int)FLIGHTMODESETTINGS_STABILIZATION4SETTINGS_RATE == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_RATE) && \
((int)FLIGHTMODESETTINGS_STABILIZATION4SETTINGS_ATTITUDE == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE) && \
((int)FLIGHTMODESETTINGS_STABILIZATION4SETTINGS_AXISLOCK == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_AXISLOCK) && \
((int)FLIGHTMODESETTINGS_STABILIZATION4SETTINGS_WEAKLEVELING == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_WEAKLEVELING) && \
((int)FLIGHTMODESETTINGS_STABILIZATION4SETTINGS_VIRTUALBAR == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_VIRTUALBAR) && \
((int)FLIGHTMODESETTINGS_STABILIZATION4SETTINGS_RATTITUDE == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_RATTITUDE) && \
((int)FLIGHTMODESETTINGS_STABILIZATION4SETTINGS_RELAYRATE == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_RELAYRATE) && \
((int)FLIGHTMODESETTINGS_STABILIZATION4SETTINGS_RELAYATTITUDE == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_RELAYATTITUDE) && \
((int)FLIGHTMODESETTINGS_STABILIZATION4SETTINGS_ALTITUDEHOLD == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_ALTITUDEHOLD) && \
((int)FLIGHTMODESETTINGS_STABILIZATION4SETTINGS_VERTICALVELOCITY == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_VERTICALVELOCITY) && \
((int)FLIGHTMODESETTINGS_STABILIZATION4SETTINGS_CRUISECONTROL == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_CRUISECONTROL) && \
1 \
)
#define assumptions5 \
( \
((int)FLIGHTMODESETTINGS_STABILIZATION3SETTINGS_NONE == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_NONE) && \
((int)FLIGHTMODESETTINGS_STABILIZATION3SETTINGS_RATE == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_RATE) && \
((int)FLIGHTMODESETTINGS_STABILIZATION3SETTINGS_AXISLOCK == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_AXISLOCK) && \
((int)FLIGHTMODESETTINGS_STABILIZATION3SETTINGS_WEAKLEVELING == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_WEAKLEVELING) && \
((int)FLIGHTMODESETTINGS_STABILIZATION3SETTINGS_ATTITUDE == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE) \
((int)FLIGHTMODESETTINGS_STABILIZATION5SETTINGS_MANUAL == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_MANUAL) && \
((int)FLIGHTMODESETTINGS_STABILIZATION5SETTINGS_RATE == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_RATE) && \
((int)FLIGHTMODESETTINGS_STABILIZATION5SETTINGS_ATTITUDE == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE) && \
((int)FLIGHTMODESETTINGS_STABILIZATION5SETTINGS_AXISLOCK == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_AXISLOCK) && \
((int)FLIGHTMODESETTINGS_STABILIZATION5SETTINGS_WEAKLEVELING == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_WEAKLEVELING) && \
((int)FLIGHTMODESETTINGS_STABILIZATION5SETTINGS_VIRTUALBAR == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_VIRTUALBAR) && \
((int)FLIGHTMODESETTINGS_STABILIZATION5SETTINGS_RATTITUDE == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_RATTITUDE) && \
((int)FLIGHTMODESETTINGS_STABILIZATION5SETTINGS_RELAYRATE == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_RELAYRATE) && \
((int)FLIGHTMODESETTINGS_STABILIZATION5SETTINGS_RELAYATTITUDE == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_RELAYATTITUDE) && \
((int)FLIGHTMODESETTINGS_STABILIZATION5SETTINGS_ALTITUDEHOLD == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_ALTITUDEHOLD) && \
((int)FLIGHTMODESETTINGS_STABILIZATION5SETTINGS_VERTICALVELOCITY == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_VERTICALVELOCITY) && \
((int)FLIGHTMODESETTINGS_STABILIZATION5SETTINGS_CRUISECONTROL == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_CRUISECONTROL) && \
1 \
)
#define assumptions6 \
( \
((int)FLIGHTMODESETTINGS_STABILIZATION6SETTINGS_MANUAL == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_MANUAL) && \
((int)FLIGHTMODESETTINGS_STABILIZATION6SETTINGS_RATE == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_RATE) && \
((int)FLIGHTMODESETTINGS_STABILIZATION6SETTINGS_ATTITUDE == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE) && \
((int)FLIGHTMODESETTINGS_STABILIZATION6SETTINGS_AXISLOCK == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_AXISLOCK) && \
((int)FLIGHTMODESETTINGS_STABILIZATION6SETTINGS_WEAKLEVELING == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_WEAKLEVELING) && \
((int)FLIGHTMODESETTINGS_STABILIZATION6SETTINGS_VIRTUALBAR == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_VIRTUALBAR) && \
((int)FLIGHTMODESETTINGS_STABILIZATION6SETTINGS_RATTITUDE == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_RATTITUDE) && \
((int)FLIGHTMODESETTINGS_STABILIZATION6SETTINGS_RELAYRATE == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_RELAYRATE) && \
((int)FLIGHTMODESETTINGS_STABILIZATION6SETTINGS_RELAYATTITUDE == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_RELAYATTITUDE) && \
((int)FLIGHTMODESETTINGS_STABILIZATION6SETTINGS_ALTITUDEHOLD == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_ALTITUDEHOLD) && \
((int)FLIGHTMODESETTINGS_STABILIZATION6SETTINGS_VERTICALVELOCITY == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_VERTICALVELOCITY) && \
((int)FLIGHTMODESETTINGS_STABILIZATION6SETTINGS_CRUISECONTROL == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_CRUISECONTROL) && \
1 \
)
#define assumptions7 \
( \
((int)FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_NUMELEM == (int)FLIGHTMODESETTINGS_STABILIZATION2SETTINGS_NUMELEM) && \
((int)FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_NUMELEM == (int)FLIGHTMODESETTINGS_STABILIZATION3SETTINGS_NUMELEM) && \
((int)FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_NUMELEM == (int)FLIGHTMODESETTINGS_STABILIZATION4SETTINGS_NUMELEM) && \
((int)FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_NUMELEM == (int)FLIGHTMODESETTINGS_STABILIZATION5SETTINGS_NUMELEM) && \
((int)FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_NUMELEM == (int)FLIGHTMODESETTINGS_STABILIZATION6SETTINGS_NUMELEM) && \
1 \
)
#define assumptions_flightmode \
@ -119,15 +197,16 @@ void pathPlannerHandler(bool newinit);
((int)FLIGHTMODESETTINGS_FLIGHTMODEPOSITION_STABILIZED1 == (int)FLIGHTSTATUS_FLIGHTMODE_STABILIZED1) && \
((int)FLIGHTMODESETTINGS_FLIGHTMODEPOSITION_STABILIZED2 == (int)FLIGHTSTATUS_FLIGHTMODE_STABILIZED2) && \
((int)FLIGHTMODESETTINGS_FLIGHTMODEPOSITION_STABILIZED3 == (int)FLIGHTSTATUS_FLIGHTMODE_STABILIZED3) && \
((int)FLIGHTMODESETTINGS_FLIGHTMODEPOSITION_ALTITUDEHOLD == (int)FLIGHTSTATUS_FLIGHTMODE_ALTITUDEHOLD) && \
((int)FLIGHTMODESETTINGS_FLIGHTMODEPOSITION_ALTITUDEVARIO == (int)FLIGHTSTATUS_FLIGHTMODE_ALTITUDEVARIO) && \
((int)FLIGHTMODESETTINGS_FLIGHTMODEPOSITION_VELOCITYCONTROL == (int)FLIGHTSTATUS_FLIGHTMODE_VELOCITYCONTROL) && \
((int)FLIGHTMODESETTINGS_FLIGHTMODEPOSITION_STABILIZED4 == (int)FLIGHTSTATUS_FLIGHTMODE_STABILIZED4) && \
((int)FLIGHTMODESETTINGS_FLIGHTMODEPOSITION_STABILIZED5 == (int)FLIGHTSTATUS_FLIGHTMODE_STABILIZED5) && \
((int)FLIGHTMODESETTINGS_FLIGHTMODEPOSITION_STABILIZED6 == (int)FLIGHTSTATUS_FLIGHTMODE_STABILIZED6) && \
((int)FLIGHTMODESETTINGS_FLIGHTMODEPOSITION_AUTOTUNE == (int)FLIGHTSTATUS_FLIGHTMODE_AUTOTUNE) && \
((int)FLIGHTMODESETTINGS_FLIGHTMODEPOSITION_POSITIONHOLD == (int)FLIGHTSTATUS_FLIGHTMODE_POSITIONHOLD) && \
((int)FLIGHTMODESETTINGS_FLIGHTMODEPOSITION_PATHPLANNER == (int)FLIGHTSTATUS_FLIGHTMODE_PATHPLANNER) && \
((int)FLIGHTMODESETTINGS_FLIGHTMODEPOSITION_RETURNTOBASE == (int)FLIGHTSTATUS_FLIGHTMODE_RETURNTOBASE) && \
((int)FLIGHTMODESETTINGS_FLIGHTMODEPOSITION_LAND == (int)FLIGHTSTATUS_FLIGHTMODE_LAND) && \
((int)FLIGHTMODESETTINGS_FLIGHTMODEPOSITION_AUTOTUNE == (int)FLIGHTSTATUS_FLIGHTMODE_AUTOTUNE) && \
((int)FLIGHTMODESETTINGS_FLIGHTMODEPOSITION_POI == (int)FLIGHTSTATUS_FLIGHTMODE_POI) \
((int)FLIGHTMODESETTINGS_FLIGHTMODEPOSITION_PATHPLANNER == (int)FLIGHTSTATUS_FLIGHTMODE_PATHPLANNER) && \
((int)FLIGHTMODESETTINGS_FLIGHTMODEPOSITION_POI == (int)FLIGHTSTATUS_FLIGHTMODE_POI) && \
1 \
)
#endif // MANUALCONTROL_H

View File

@ -57,7 +57,7 @@
// defined handlers
static controlHandler handler_MANUAL = {
static const controlHandler handler_MANUAL = {
.controlChain = {
.Stabilization = false,
.PathFollower = false,
@ -65,7 +65,7 @@ static controlHandler handler_MANUAL = {
},
.handler = &manualHandler,
};
static controlHandler handler_STABILIZED = {
static const controlHandler handler_STABILIZED = {
.controlChain = {
.Stabilization = true,
.PathFollower = false,
@ -74,16 +74,8 @@ static controlHandler handler_STABILIZED = {
.handler = &stabilizedHandler,
};
// TODO: move the altitude handling into stabi
static controlHandler handler_ALTITUDE = {
.controlChain = {
.Stabilization = true,
.PathFollower = false,
.PathPlanner = false,
},
.handler = &altitudeHandler,
};
static controlHandler handler_AUTOTUNE = {
static const controlHandler handler_AUTOTUNE = {
.controlChain = {
.Stabilization = false,
.PathFollower = false,
@ -92,7 +84,8 @@ static controlHandler handler_AUTOTUNE = {
.handler = NULL,
};
static controlHandler handler_PATHFOLLOWER = {
#ifndef PIOS_EXCLUDE_ADVANCED_FEATURES
static const controlHandler handler_PATHFOLLOWER = {
.controlChain = {
.Stabilization = true,
.PathFollower = true,
@ -101,7 +94,7 @@ static controlHandler handler_PATHFOLLOWER = {
.handler = &pathFollowerHandler,
};
static controlHandler handler_PATHPLANNER = {
static const controlHandler handler_PATHPLANNER = {
.controlChain = {
.Stabilization = true,
.PathFollower = true,
@ -110,7 +103,7 @@ static controlHandler handler_PATHPLANNER = {
.handler = &pathPlannerHandler,
};
#endif /* ifndef PIOS_EXCLUDE_ADVANCED_FEATURES */
// Private variables
static DelayedCallbackInfo *callbackHandle;
@ -120,7 +113,7 @@ static void commandUpdatedCb(UAVObjEvent *ev);
static void manualControlTask(void);
#define assumptions (assumptions1 && assumptions3 && assumptions5 && assumptions_flightmode)
#define assumptions (assumptions1 && assumptions2 && assumptions3 && assumptions4 && assumptions5 && assumptions6 && assumptions7 && assumptions_flightmode)
/**
* Module starting
@ -192,7 +185,7 @@ static void manualControlTask(void)
}
// Depending on the mode update the Stabilization or Actuator objects
controlHandler *handler = &handler_MANUAL;
const controlHandler *handler = &handler_MANUAL;
switch (newMode) {
case FLIGHTSTATUS_FLIGHTMODE_MANUAL:
handler = &handler_MANUAL;
@ -200,9 +193,12 @@ static void manualControlTask(void)
case FLIGHTSTATUS_FLIGHTMODE_STABILIZED1:
case FLIGHTSTATUS_FLIGHTMODE_STABILIZED2:
case FLIGHTSTATUS_FLIGHTMODE_STABILIZED3:
case FLIGHTSTATUS_FLIGHTMODE_STABILIZED4:
case FLIGHTSTATUS_FLIGHTMODE_STABILIZED5:
case FLIGHTSTATUS_FLIGHTMODE_STABILIZED6:
handler = &handler_STABILIZED;
break;
case FLIGHTSTATUS_FLIGHTMODE_VELOCITYCONTROL:
#ifndef PIOS_EXCLUDE_ADVANCED_FEATURES
case FLIGHTSTATUS_FLIGHTMODE_POSITIONHOLD:
case FLIGHTSTATUS_FLIGHTMODE_RETURNTOBASE:
case FLIGHTSTATUS_FLIGHTMODE_LAND:
@ -212,10 +208,7 @@ static void manualControlTask(void)
case FLIGHTSTATUS_FLIGHTMODE_PATHPLANNER:
handler = &handler_PATHPLANNER;
break;
case FLIGHTSTATUS_FLIGHTMODE_ALTITUDEHOLD:
case FLIGHTSTATUS_FLIGHTMODE_ALTITUDEVARIO:
handler = &handler_ALTITUDE;
break;
#endif
case FLIGHTSTATUS_FLIGHTMODE_AUTOTUNE:
handler = &handler_AUTOTUNE;
break;

View File

@ -78,6 +78,15 @@ void stabilizedHandler(bool newinit)
case FLIGHTSTATUS_FLIGHTMODE_STABILIZED3:
stab_settings = cast_struct_to_array(settings.Stabilization3Settings, settings.Stabilization3Settings.Roll);
break;
case FLIGHTSTATUS_FLIGHTMODE_STABILIZED4:
stab_settings = cast_struct_to_array(settings.Stabilization4Settings, settings.Stabilization4Settings.Roll);
break;
case FLIGHTSTATUS_FLIGHTMODE_STABILIZED5:
stab_settings = cast_struct_to_array(settings.Stabilization5Settings, settings.Stabilization5Settings.Roll);
break;
case FLIGHTSTATUS_FLIGHTMODE_STABILIZED6:
stab_settings = cast_struct_to_array(settings.Stabilization6Settings, settings.Stabilization6Settings.Roll);
break;
default:
// Major error, this should not occur because only enter this block when one of these is true
AlarmsSet(SYSTEMALARMS_ALARM_MANUALCONTROL, SYSTEMALARMS_ALARM_CRITICAL);
@ -86,25 +95,25 @@ void stabilizedHandler(bool newinit)
}
stabilization.Roll =
(stab_settings[0] == STABILIZATIONDESIRED_STABILIZATIONMODE_NONE) ? cmd.Roll :
(stab_settings[0] == STABILIZATIONDESIRED_STABILIZATIONMODE_MANUAL) ? cmd.Roll :
(stab_settings[0] == STABILIZATIONDESIRED_STABILIZATIONMODE_RATE) ? cmd.Roll * stabSettings.ManualRate.Roll :
(stab_settings[0] == STABILIZATIONDESIRED_STABILIZATIONMODE_WEAKLEVELING) ? cmd.Roll * stabSettings.ManualRate.Roll :
(stab_settings[0] == STABILIZATIONDESIRED_STABILIZATIONMODE_WEAKLEVELING) ? cmd.Roll * stabSettings.RollMax :
(stab_settings[0] == STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE) ? cmd.Roll * stabSettings.RollMax :
(stab_settings[0] == STABILIZATIONDESIRED_STABILIZATIONMODE_AXISLOCK) ? cmd.Roll * stabSettings.ManualRate.Roll :
(stab_settings[0] == STABILIZATIONDESIRED_STABILIZATIONMODE_VIRTUALBAR) ? cmd.Roll :
(stab_settings[0] == STABILIZATIONDESIRED_STABILIZATIONMODE_RATTITUDE) ? cmd.Roll :
(stab_settings[0] == STABILIZATIONDESIRED_STABILIZATIONMODE_RATTITUDE) ? cmd.Roll * stabSettings.RollMax :
(stab_settings[0] == STABILIZATIONDESIRED_STABILIZATIONMODE_RELAYRATE) ? cmd.Roll * stabSettings.ManualRate.Roll :
(stab_settings[0] == STABILIZATIONDESIRED_STABILIZATIONMODE_RELAYATTITUDE) ? cmd.Roll * stabSettings.RollMax :
0; // this is an invalid mode
stabilization.Pitch =
(stab_settings[1] == STABILIZATIONDESIRED_STABILIZATIONMODE_NONE) ? cmd.Pitch :
(stab_settings[1] == STABILIZATIONDESIRED_STABILIZATIONMODE_MANUAL) ? cmd.Pitch :
(stab_settings[1] == STABILIZATIONDESIRED_STABILIZATIONMODE_RATE) ? cmd.Pitch * stabSettings.ManualRate.Pitch :
(stab_settings[1] == STABILIZATIONDESIRED_STABILIZATIONMODE_WEAKLEVELING) ? cmd.Pitch * stabSettings.ManualRate.Pitch :
(stab_settings[1] == STABILIZATIONDESIRED_STABILIZATIONMODE_WEAKLEVELING) ? cmd.Pitch * stabSettings.PitchMax :
(stab_settings[1] == STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE) ? cmd.Pitch * stabSettings.PitchMax :
(stab_settings[1] == STABILIZATIONDESIRED_STABILIZATIONMODE_AXISLOCK) ? cmd.Pitch * stabSettings.ManualRate.Pitch :
(stab_settings[1] == STABILIZATIONDESIRED_STABILIZATIONMODE_VIRTUALBAR) ? cmd.Pitch :
(stab_settings[1] == STABILIZATIONDESIRED_STABILIZATIONMODE_RATTITUDE) ? cmd.Pitch :
(stab_settings[1] == STABILIZATIONDESIRED_STABILIZATIONMODE_RATTITUDE) ? cmd.Pitch * stabSettings.PitchMax :
(stab_settings[1] == STABILIZATIONDESIRED_STABILIZATIONMODE_RELAYRATE) ? cmd.Pitch * stabSettings.ManualRate.Pitch :
(stab_settings[1] == STABILIZATIONDESIRED_STABILIZATIONMODE_RELAYATTITUDE) ? cmd.Pitch * stabSettings.PitchMax :
0; // this is an invalid mode
@ -120,19 +129,20 @@ void stabilizedHandler(bool newinit)
} else {
stabilization.StabilizationMode.Yaw = stab_settings[2];
stabilization.Yaw =
(stab_settings[2] == STABILIZATIONDESIRED_STABILIZATIONMODE_NONE) ? cmd.Yaw :
(stab_settings[2] == STABILIZATIONDESIRED_STABILIZATIONMODE_MANUAL) ? cmd.Yaw :
(stab_settings[2] == STABILIZATIONDESIRED_STABILIZATIONMODE_RATE) ? cmd.Yaw * stabSettings.ManualRate.Yaw :
(stab_settings[2] == STABILIZATIONDESIRED_STABILIZATIONMODE_WEAKLEVELING) ? cmd.Yaw * stabSettings.ManualRate.Yaw :
(stab_settings[2] == STABILIZATIONDESIRED_STABILIZATIONMODE_WEAKLEVELING) ? cmd.Yaw * stabSettings.YawMax :
(stab_settings[2] == STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE) ? cmd.Yaw * stabSettings.YawMax :
(stab_settings[2] == STABILIZATIONDESIRED_STABILIZATIONMODE_AXISLOCK) ? cmd.Yaw * stabSettings.ManualRate.Yaw :
(stab_settings[2] == STABILIZATIONDESIRED_STABILIZATIONMODE_VIRTUALBAR) ? cmd.Yaw :
(stab_settings[2] == STABILIZATIONDESIRED_STABILIZATIONMODE_RATTITUDE) ? cmd.Yaw :
(stab_settings[2] == STABILIZATIONDESIRED_STABILIZATIONMODE_RATTITUDE) ? cmd.Yaw * stabSettings.YawMax :
(stab_settings[2] == STABILIZATIONDESIRED_STABILIZATIONMODE_RELAYRATE) ? cmd.Yaw * stabSettings.ManualRate.Yaw :
(stab_settings[2] == STABILIZATIONDESIRED_STABILIZATIONMODE_RELAYATTITUDE) ? cmd.Yaw * stabSettings.YawMax :
0; // this is an invalid mode
}
stabilization.Thrust = cmd.Thrust;
stabilization.StabilizationMode.Thrust = stab_settings[3];
StabilizationDesiredSet(&stabilization);
}

View File

@ -1,8 +1,8 @@
/**
******************************************************************************
*
* @file guidance.c
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @file altitudeloop.c
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2014.
* @brief This module compared @ref PositionActuatl to @ref ActiveWaypoint
* and sets @ref AttitudeDesired. It only does this when the FlightMode field
* of @ref ManualControlCommand is Auto.
@ -26,89 +26,122 @@
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
/**
* Input object: ActiveWaypoint
* Input object: PositionState
* Input object: ManualControlCommand
* Output object: AttitudeDesired
*
* This module will periodically update the value of the AttitudeDesired object.
*
* The module executes in its own thread in this example.
*
* Modules have no API, all communication to other modules is done through UAVObjects.
* However modules may use the API exposed by shared libraries.
* See the OpenPilot wiki for more details.
* http://www.openpilot.org/OpenPilot_Application_Architecture
*
*/
#include <openpilot.h>
#include <callbackinfo.h>
#include <math.h>
#include <pid.h>
#include <altitudeloop.h>
#include <CoordinateConversions.h>
#include <altitudeholdsettings.h>
#include <altitudeholddesired.h> // object that will be updated by the module
#include <altitudeholdstatus.h>
#include <flightstatus.h>
#include <stabilizationdesired.h>
#include <accelstate.h>
#include <pios_constants.h>
#include <velocitystate.h>
#include <positionstate.h>
// Private constants
#ifdef REVOLUTION
#define UPDATE_EXPECTED (1.0f / 666.0f)
#define UPDATE_MIN 1.0e-6f
#define UPDATE_MAX 1.0f
#define UPDATE_ALPHA 1.0e-2f
#define CALLBACK_PRIORITY CALLBACK_PRIORITY_LOW
#define CBTASK_PRIORITY CALLBACK_TASK_FLIGHTCONTROL
#define STACK_SIZE_BYTES 1024
#define DESIRED_UPDATE_RATE_MS 100 // milliseconds
#define STACK_SIZE_BYTES 512
// Private types
// Private variables
static DelayedCallbackInfo *altitudeHoldCBInfo;
static AltitudeHoldSettingsData altitudeHoldSettings;
static struct pid pid0, pid1;
static ThrustModeType thrustMode;
static PiOSDeltatimeConfig timeval;
static float thrustSetpoint = 0.0f;
static float thrustDemand = 0.0f;
static float startThrust = 0.5f;
// Private functions
static void altitudeHoldTask(void);
static void SettingsUpdatedCb(UAVObjEvent *ev);
static void VelocityStateUpdatedCb(UAVObjEvent *ev);
/**
* Initialise the module, called on startup
* \returns 0 on success or -1 if initialisation failed
* Setup mode and setpoint
*/
int32_t AltitudeHoldStart()
float stabilizationAltitudeHold(float setpoint, ThrustModeType mode, bool reinit)
{
// Start main task
SettingsUpdatedCb(NULL);
PIOS_CALLBACKSCHEDULER_Dispatch(altitudeHoldCBInfo);
static bool newaltitude = true;
return 0;
if (reinit) {
startThrust = setpoint;
pid_zero(&pid0);
pid_zero(&pid1);
newaltitude = true;
}
const float DEADBAND = 0.20f;
const float DEADBAND_HIGH = 1.0f / 2 + DEADBAND / 2;
const float DEADBAND_LOW = 1.0f / 2 - DEADBAND / 2;
// this is the max speed in m/s at the extents of thrust
float thrustRate;
uint8_t thrustExp;
AltitudeHoldSettingsThrustExpGet(&thrustExp);
AltitudeHoldSettingsThrustRateGet(&thrustRate);
PositionStateData posState;
PositionStateGet(&posState);
if (altitudeHoldSettings.CutThrustWhenZero && setpoint <= 0) {
// Cut thrust if desired
thrustSetpoint = 0.0f;
thrustDemand = 0.0f;
thrustMode = DIRECT;
newaltitude = true;
} else if (mode == ALTITUDEVARIO && setpoint > DEADBAND_HIGH) {
// being the two band symmetrical I can divide by DEADBAND_LOW to scale it to a value betweeon 0 and 1
// then apply an "exp" f(x,k) = (k*x*x*x + (255-k)*x) / 255
thrustSetpoint = -((thrustExp * powf((setpoint - DEADBAND_HIGH) / (DEADBAND_LOW), 3) + (255 - thrustExp) * (setpoint - DEADBAND_HIGH) / DEADBAND_LOW) / 255 * thrustRate);
thrustMode = ALTITUDEVARIO;
newaltitude = true;
} else if (mode == ALTITUDEVARIO && setpoint < DEADBAND_LOW) {
thrustSetpoint = -(-(thrustExp * powf((DEADBAND_LOW - (setpoint < 0 ? 0 : setpoint)) / DEADBAND_LOW, 3) + (255 - thrustExp) * (DEADBAND_LOW - setpoint) / DEADBAND_LOW) / 255 * thrustRate);
thrustMode = ALTITUDEVARIO;
newaltitude = true;
} else if (newaltitude == true) {
thrustSetpoint = posState.Down;
thrustMode = ALTITUDEHOLD;
newaltitude = false;
}
return thrustDemand;
}
/**
* Initialise the module, called on startup
* \returns 0 on success or -1 if initialisation failed
*/
int32_t AltitudeHoldInitialize()
void stabilizationAltitudeloopInit()
{
AltitudeHoldSettingsInitialize();
AltitudeHoldDesiredInitialize();
AltitudeHoldStatusInitialize();
PositionStateInitialize();
VelocityStateInitialize();
PIOS_DELTATIME_Init(&timeval, UPDATE_EXPECTED, UPDATE_MIN, UPDATE_MAX, UPDATE_ALPHA);
// Create object queue
altitudeHoldCBInfo = PIOS_CALLBACKSCHEDULER_Create(&altitudeHoldTask, CALLBACK_PRIORITY, CBTASK_PRIORITY, CALLBACKINFO_RUNNING_ALTITUDEHOLD, STACK_SIZE_BYTES);
AltitudeHoldSettingsConnectCallback(&SettingsUpdatedCb);
VelocityStateConnectCallback(&VelocityStateUpdatedCb);
return 0;
// Start main task
SettingsUpdatedCb(NULL);
}
MODULE_INITCALL(AltitudeHoldInitialize, AltitudeHoldStart);
/**
@ -116,44 +149,25 @@ MODULE_INITCALL(AltitudeHoldInitialize, AltitudeHoldStart);
*/
static void altitudeHoldTask(void)
{
static float startThrust = 0.5f;
// make sure we run only when we are supposed to run
FlightStatusData flightStatus;
FlightStatusGet(&flightStatus);
switch (flightStatus.FlightMode) {
case FLIGHTSTATUS_FLIGHTMODE_ALTITUDEHOLD:
case FLIGHTSTATUS_FLIGHTMODE_ALTITUDEVARIO:
break;
default:
pid_zero(&pid0);
pid_zero(&pid1);
StabilizationDesiredThrustGet(&startThrust);
PIOS_CALLBACKSCHEDULER_Schedule(altitudeHoldCBInfo, DESIRED_UPDATE_RATE_MS, CALLBACK_UPDATEMODE_SOONER);
return;
break;
}
AltitudeHoldStatusData altitudeHoldStatus;
AltitudeHoldStatusGet(&altitudeHoldStatus);
// do the actual control loop(s)
AltitudeHoldDesiredData altitudeHoldDesired;
AltitudeHoldDesiredGet(&altitudeHoldDesired);
float positionStateDown;
PositionStateDownGet(&positionStateDown);
float velocityStateDown;
VelocityStateDownGet(&velocityStateDown);
switch (altitudeHoldDesired.ControlMode) {
case ALTITUDEHOLDDESIRED_CONTROLMODE_ALTITUDE:
float dT;
dT = PIOS_DELTATIME_GetAverageSeconds(&timeval);
switch (thrustMode) {
case ALTITUDEHOLD:
// altitude control loop
altitudeHoldStatus.VelocityDesired = pid_apply_setpoint(&pid0, 1.0f, altitudeHoldDesired.SetPoint, positionStateDown, 1000.0f / DESIRED_UPDATE_RATE_MS);
altitudeHoldStatus.VelocityDesired = pid_apply_setpoint(&pid0, 1.0f, thrustSetpoint, positionStateDown, dT);
break;
case ALTITUDEHOLDDESIRED_CONTROLMODE_VELOCITY:
altitudeHoldStatus.VelocityDesired = altitudeHoldDesired.SetPoint;
case ALTITUDEVARIO:
altitudeHoldStatus.VelocityDesired = thrustSetpoint;
break;
default:
altitudeHoldStatus.VelocityDesired = 0;
@ -162,37 +176,16 @@ static void altitudeHoldTask(void)
AltitudeHoldStatusSet(&altitudeHoldStatus);
float thrust;
switch (altitudeHoldDesired.ControlMode) {
case ALTITUDEHOLDDESIRED_CONTROLMODE_THRUST:
thrust = altitudeHoldDesired.SetPoint;
switch (thrustMode) {
case DIRECT:
thrustDemand = thrustSetpoint;
break;
default:
// velocity control loop
thrust = startThrust - pid_apply_setpoint(&pid1, 1.0f, altitudeHoldStatus.VelocityDesired, velocityStateDown, 1000.0f / DESIRED_UPDATE_RATE_MS);
thrustDemand = startThrust - pid_apply_setpoint(&pid1, 1.0f, altitudeHoldStatus.VelocityDesired, velocityStateDown, dT);
if (thrust >= 1.0f) {
thrust = 1.0f;
}
if (thrust <= 0.0f) {
thrust = 0.0f;
}
break;
}
StabilizationDesiredData stab;
StabilizationDesiredGet(&stab);
stab.Roll = altitudeHoldDesired.Roll;
stab.Pitch = altitudeHoldDesired.Pitch;
stab.Yaw = altitudeHoldDesired.Yaw;
stab.Thrust = thrust;
stab.StabilizationMode.Roll = STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE;
stab.StabilizationMode.Pitch = STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE;
stab.StabilizationMode.Yaw = STABILIZATIONDESIRED_STABILIZATIONMODE_AXISLOCK;
StabilizationDesiredSet(&stab);
PIOS_CALLBACKSCHEDULER_Schedule(altitudeHoldCBInfo, DESIRED_UPDATE_RATE_MS, CALLBACK_UPDATEMODE_SOONER);
}
static void SettingsUpdatedCb(__attribute__((unused)) UAVObjEvent *ev)
@ -203,3 +196,11 @@ static void SettingsUpdatedCb(__attribute__((unused)) UAVObjEvent *ev)
pid_configure(&pid1, altitudeHoldSettings.VelocityPI.Kp, altitudeHoldSettings.VelocityPI.Ki, 0, altitudeHoldSettings.VelocityPI.Ilimit);
pid_zero(&pid1);
}
static void VelocityStateUpdatedCb(__attribute__((unused)) UAVObjEvent *ev)
{
PIOS_CALLBACKSCHEDULER_Dispatch(altitudeHoldCBInfo);
}
#endif /* ifdef REVOLUTION */

View File

@ -0,0 +1,293 @@
/**
******************************************************************************
* @addtogroup OpenPilotModules OpenPilot Modules
* @{
* @addtogroup StabilizationModule Stabilization Module
* @brief cruisecontrol mode
* @note This file implements the logic for a cruisecontrol
* @{
*
* @file cruisecontrol.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2014.
* @brief Attitude stabilization module.
*
* @see The GNU Public License (GPL) Version 3
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#include <openpilot.h>
#include <stabilization.h>
#include <attitudestate.h>
#include <sin_lookup.h>
static float cruisecontrol_factor = 1.0f;
static inline float CruiseControlLimitThrust(float thrust)
{
// limit to user specified absolute max thrust
return boundf(thrust, stabSettings.cruiseControl.min_thrust, stabSettings.cruiseControl.max_thrust);
}
// assumes 1.0 <= factor <= 100.0
// a factor of less than 1.0 could make it return a value less than stabSettings.cruiseControl.min_thrust
// CP helis need to have min_thrust=-1
//
// multicopters need to have min_thrust=0.05 or so
// values below that will not be subject to max / min limiting
// that means thrust can be less than min
// that means multicopter motors stop spinning at low stick
static inline float CruiseControlFactorToThrust(float factor, float thrust)
{
// don't touch thrust if it's less than min_thrust
// without that test, quadcopter props will spin up
// to min thrust even at zero throttle stick
// if Cruise Control is enabled on this flight switch position
if (thrust > stabSettings.cruiseControl.min_thrust) {
return CruiseControlLimitThrust(thrust * factor);
}
return thrust;
}
static float CruiseControlAngleToFactor(float angle)
{
float factor;
// avoid singularity
if (angle > 89.999f && angle < 90.001f) {
factor = stabSettings.settings.CruiseControlMaxPowerFactor;
} else {
// the simple bank angle boost calculation that Cruise Control revolves around
factor = 1.0f / fabsf(cos_lookup_deg(angle));
// factor in the power trim, no effect at 1.0, linear effect increases with factor
factor = (factor - 1.0f) * stabSettings.cruiseControl.power_trim + 1.0f;
// limit to user specified max power multiplier
if (factor > stabSettings.settings.CruiseControlMaxPowerFactor) {
factor = stabSettings.settings.CruiseControlMaxPowerFactor;
}
}
return factor;
}
void cruisecontrol_compute_factor(AttitudeStateData *attitude, float thrustDemand)
{
static float previous_angle;
static uint32_t previous_time = 0;
static bool previous_time_valid = false;
// For multiple, speedy flips this mainly strives to address the
// fact that (due to thrust delay) thrust didn't average straight
// down, but at an angle. For less speedy flips it acts like it
// used to. It can be turned off by setting power delay to 0.
// It takes significant time for the motors of a multi-copter to
// spin up. It takes significant time for the collective servo of
// a CP heli to move from one end to the other. Both of those are
// modeled here as linear, i.e. twice as much change takes twice
// as long. Given a correctly configured maximum delay time this
// code calculates how far in advance to start the control
// transition so that half way through the physical transition it
// is just crossing the transition angle.
// Example: Rotation rate = 360. Full stroke delay = 0.2
// Transition angle 90 degrees. Start the transition 0.1 second
// before 90 degrees (36 degrees at 360 deg/sec) and it will be
// complete 0.1 seconds after 90 degrees.
// Note that this code only handles the transition to/from inverted
// thrust. It doesn't handle the case where thrust is changed a
// lot in a small angle range when that range is close to 90 degrees.
// It doesn't handle the small constant "system delay" caused by the
// delay between reading sensors and actuators beginning to respond.
// It also assumes that the pilot is holding the throttle constant;
// when the pilot does change the throttle, the compensation is
// simply recalculated.
// This implementation of future thrust isn't perfect. That would
// probably require an iterative procedure for solving a
// transcendental equation of the form linear(x) = 1/cos(x). It's
// shortcomings generally don't hurt anything and work better than
// without it. It is designed to work perfectly if the pilot is
// using full thrust during flips and it is only activated if 70% or
// greater thrust is used.
uint32_t time = PIOS_DELAY_GetuS();
// Get roll and pitch angles, calculate combined angle, and begin
// the general algorithm.
// Example: 45 degrees roll plus 45 degrees pitch = 60 degrees
// Do it every 8th iteration to save CPU.
if (time != previous_time || previous_time_valid == false) {
float angle, angle_unmodified;
// spherical right triangle
// 0.0 <= angle <= 180.0
angle_unmodified = angle = RAD2DEG(acosf(cos_lookup_deg(attitude->Roll)
* cos_lookup_deg(attitude->Pitch)));
// Calculate rate as a combined (roll and pitch) bank angle
// change; in degrees per second. Rate is calculated over the
// most recent 8 loops through stabilization. We could have
// asked the gyros. This is probably cheaper.
if (previous_time_valid) {
float rate;
// rate can be negative.
rate = (angle - previous_angle) / ((float)(time - previous_time) / 1000000.0f);
// Define "within range" to be those transitions that should
// be executing now. Recall that each impulse transition is
// spread out over a range of time / angle.
// There is only one transition and the high power level for
// it is either:
// 1/fabsf(cos(angle)) * current thrust
// or max power factor * current thrust
// or full thrust
// You can cross the transition with angle either increasing
// or decreasing (rate positive or negative).
// Thrust is never boosted for negative values of
// thrustDemand (negative stick values)
//
// When the aircraft is upright, thrust is always boosted
// . for positive values of thrustDemand
// When the aircraft is inverted, thrust is sometimes
// . boosted or reversed (or combinations thereof) or zeroed
// . for positive values of thrustDemand
// It depends on the inverted power settings.
// Of course, you can set MaxPowerFactor to 1.0 to
// . effectively disable boost.
if (thrustDemand > 0.0f) {
// to enable the future thrust calculations, make sure
// there is a large enough transition that the result
// will be roughly on vs. off; without that, it can
// exaggerate the length of time the inverted to upright
// transition holds full throttle and reduce the length
// of time for full throttle when going upright to inverted.
if (thrustDemand > 0.7f) {
float thrust;
thrust = CruiseControlFactorToThrust(CruiseControlAngleToFactor((float)stabSettings.settings.CruiseControlMaxAngle), thrustDemand);
// determine if we are in range of the transition
// given the thrust at max_angle and thrustDemand
// (typically close to 1.0), change variable 'thrust' to
// be the proportion of the largest thrust change possible
// that occurs when going into inverted mode.
// Example: 'thrust' is 0.8 A quad has min_thrust set
// to 0.05 The difference is 0.75. The largest possible
// difference with this setup is 0.9 - 0.05 = 0.85, so
// the proportion is 0.75/0.85
// That is nearly a full throttle stroke.
// the 'thrust' variable is non-negative here
switch (stabSettings.settings.CruiseControlInvertedPowerOutput) {
case STABILIZATIONSETTINGS_CRUISECONTROLINVERTEDPOWEROUTPUT_ZERO:
// normal multi-copter case, stroke is max to zero
// technically max to constant min_thrust
// can be used by CP
thrust = (thrust - CruiseControlLimitThrust(0.0f)) / stabSettings.cruiseControl.thrust_difference;
break;
case STABILIZATIONSETTINGS_CRUISECONTROLINVERTEDPOWEROUTPUT_NORMAL:
// reversed but not boosted
// : CP heli case, stroke is max to -stick
// : thrust = (thrust - CruiseControlLimitThrust(-thrustDemand)) / stabSettings.cruiseControl.thrust_difference;
// else it is both unreversed and unboosted
// : simply turn off boost, stroke is max to +stick
// : thrust = (thrust - CruiseControlLimitThrust(thrustDemand)) / stabSettings.cruiseControl.thrust_difference;
thrust = (thrust - CruiseControlLimitThrust(
(stabSettings.settings.CruiseControlInvertedThrustReversing
== STABILIZATIONSETTINGS_CRUISECONTROLINVERTEDTHRUSTREVERSING_REVERSED)
? -thrustDemand
: thrustDemand)) / stabSettings.cruiseControl.thrust_difference;
break;
case STABILIZATIONSETTINGS_CRUISECONTROLINVERTEDPOWEROUTPUT_BOOSTED:
// if boosted and reversed
if (stabSettings.settings.CruiseControlInvertedThrustReversing
== STABILIZATIONSETTINGS_CRUISECONTROLINVERTEDTHRUSTREVERSING_REVERSED) {
// CP heli case, stroke is max to min
thrust = (thrust - CruiseControlFactorToThrust(-CruiseControlAngleToFactor((float)stabSettings.settings.CruiseControlMaxAngle), thrustDemand)) / stabSettings.cruiseControl.thrust_difference;
}
// else it is boosted and unreversed so the throttle doesn't change
else {
// CP heli case, no transition, so stroke is zero
thrust = 0.0f;
}
break;
}
// 'thrust' is now the proportion of max stroke
// multiply this proportion of max stroke,
// times the max stroke time, to get this stroke time
// we only want half of this time before the transition
// (and half after the transition)
thrust *= stabSettings.cruiseControl.half_power_delay;
// 'thrust' is now the length of time for this stroke
// multiply that times angular rate to get the lead angle
thrust *= fabsf(rate);
// if the transition is within range we use it,
// else we just use the current calculated thrust
if ((float)stabSettings.settings.CruiseControlMaxAngle - thrust <= angle
&& angle <= (float)stabSettings.settings.CruiseControlMaxAngle + thrust) {
// default to a little above max angle
angle = (float)stabSettings.settings.CruiseControlMaxAngle + 0.01f;
// if roll direction is downward
// then thrust value is taken from below max angle
// by the code that knows about the transition angle
if (rate < 0.0f) {
angle -= 0.02f;
}
}
} // if thrust > 0.7; else just use the angle we already calculated
cruisecontrol_factor = CruiseControlAngleToFactor(angle);
} else { // if thrust > 0 set factor from angle; else
cruisecontrol_factor = 1.0f;
}
if (angle >= (float)stabSettings.settings.CruiseControlMaxAngle) {
switch (stabSettings.settings.CruiseControlInvertedPowerOutput) {
case STABILIZATIONSETTINGS_CRUISECONTROLINVERTEDPOWEROUTPUT_ZERO:
cruisecontrol_factor = 0.0f;
break;
case STABILIZATIONSETTINGS_CRUISECONTROLINVERTEDPOWEROUTPUT_NORMAL:
cruisecontrol_factor = 1.0f;
break;
case STABILIZATIONSETTINGS_CRUISECONTROLINVERTEDPOWEROUTPUT_BOOSTED:
// no change, leave factor >= 1.0 alone
break;
}
if (stabSettings.settings.CruiseControlInvertedThrustReversing
== STABILIZATIONSETTINGS_CRUISECONTROLINVERTEDTHRUSTREVERSING_REVERSED) {
cruisecontrol_factor = -cruisecontrol_factor;
}
}
} // if previous_time_valid i.e. we've got a rate; else leave (angle and) factor alone
previous_time = time;
previous_time_valid = true;
previous_angle = angle_unmodified;
} // every 8th time
}
float cruisecontrol_apply_factor(float raw)
{
if (stabSettings.settings.CruiseControlMaxPowerFactor > 0.0001f) {
raw = CruiseControlFactorToThrust(cruisecontrol_factor, raw);
}
return raw;
}

View File

@ -0,0 +1,41 @@
/**
******************************************************************************
* @addtogroup OpenPilotModules OpenPilot Modules
* @{
* @addtogroup StabilizationModule Stabilization Module
* @brief altitudeloop mode
* @note This file implements the logic for a altitudeloop
* @{
*
* @file altitudeloop.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2014.
* @brief Attitude stabilization module.
*
* @see The GNU Public License (GPL) Version 3
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef ALTITUDELOOP_H
#define ALTITUDELOOP_H
typedef enum { ALTITUDEHOLD = 0, ALTITUDEVARIO = 1, DIRECT = 2 } ThrustModeType;
void stabilizationAltitudeloopInit();
float stabilizationAltitudeHold(float setpoint, ThrustModeType mode, bool reinit);
#endif /* ALTITUDELOOP_H */

View File

@ -0,0 +1,42 @@
/**
******************************************************************************
* @addtogroup OpenPilotModules OpenPilot Modules
* @{
* @addtogroup StabilizationModule Stabilization Module
* @brief cruisecontrol mode
* @note This file implements the logic for a cruisecontrol
* @{
*
* @file cruisecontrol.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2014.
* @brief Attitude stabilization module.
*
* @see The GNU Public License (GPL) Version 3
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef CRUISECONTROL_H
#define CRUISECONTROL_H
#include <openpilot.h>
#include <attitudestate.h>
void cruisecontrol_compute_factor(AttitudeStateData *attitude, float thrustDemand);
float cruisecontrol_apply_factor(float raw);
#endif /* CRUISECONTROL_H */

View File

@ -0,0 +1,38 @@
/**
******************************************************************************
* @addtogroup OpenPilotModules OpenPilot Modules
* @{
* @addtogroup StabilizationModule Stabilization Module
* @brief innerloop mode
* @note This file implements the logic for a innerloop
* @{
*
* @file innerloop.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2014.
* @brief Attitude stabilization module.
*
* @see The GNU Public License (GPL) Version 3
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef INNERLOOP_H
#define INNERLOOP_H
void stabilizationInnerloopInit();
#endif /* INNERLOOP_H */

View File

@ -0,0 +1,38 @@
/**
******************************************************************************
* @addtogroup OpenPilotModules OpenPilot Modules
* @{
* @addtogroup StabilizationModule Stabilization Module
* @brief outerloop mode
* @note This file implements the logic for a outerloop
* @{
*
* @file outerloop.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2014.
* @brief Attitude stabilization module.
*
* @see The GNU Public License (GPL) Version 3
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef OUTERLOOP_H
#define OUTERLOOP_H
void stabilizationOuterloopInit();
#endif /* OUTERLOOP_H */

View File

@ -33,10 +33,52 @@
#ifndef STABILIZATION_H
#define STABILIZATION_H
enum { ROLL, PITCH, YAW, MAX_AXES };
#include <openpilot.h>
#include <pid.h>
#include <stabilizationsettings.h>
#include <stabilizationbank.h>
int32_t StabilizationInitialize();
typedef struct {
StabilizationSettingsData settings;
StabilizationBankData stabBank;
float gyro_alpha;
struct {
float min_thrust;
float max_thrust;
float thrust_difference;
float power_trim;
float half_power_delay;
float max_power_factor_angle;
} cruiseControl;
struct {
int8_t gyroupdates;
int8_t rateupdates;
} monitor;
float rattitude_mode_transition_stick_position;
struct pid innerPids[3], outerPids[3];
} StabilizationData;
extern StabilizationData stabSettings;
#define AXES 4
#define FAILSAFE_TIMEOUT_MS 30
#ifndef PIOS_STABILIZATION_STACK_SIZE
#define STACK_SIZE_BYTES 800
#else
#define STACK_SIZE_BYTES PIOS_STABILIZATION_STACK_SIZE
#endif
// must be same as eventdispatcher to avoid needing additional mutexes
#define CBTASK_PRIORITY CALLBACK_TASK_FLIGHTCONTROL
// outer loop only executes every 4th uavobject update to safe CPU
#define OUTERLOOP_SKIPCOUNT 4
#endif // STABILIZATION_H
/**

View File

@ -0,0 +1,289 @@
/**
******************************************************************************
* @addtogroup OpenPilotModules OpenPilot Modules
* @{
* @addtogroup StabilizationModule Stabilization Module
* @brief Stabilization PID loops in an airframe type independent manner
* @note This object updates the @ref ActuatorDesired "Actuator Desired" based on the
* PID loops on the @ref AttitudeDesired "Attitude Desired" and @ref AttitudeState "Attitude State"
* @{
*
* @file innerloop.c
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2014.
* @brief Attitude stabilization module.
*
* @see The GNU Public License (GPL) Version 3
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#include <openpilot.h>
#include <pios_struct_helper.h>
#include <pid.h>
#include <callbackinfo.h>
#include <ratedesired.h>
#include <actuatordesired.h>
#include <gyrostate.h>
#include <airspeedstate.h>
#include <stabilizationstatus.h>
#include <flightstatus.h>
#include <manualcontrolcommand.h>
#include <stabilizationbank.h>
#include <stabilization.h>
#include <relay_tuning.h>
#include <virtualflybar.h>
#include <cruisecontrol.h>
// Private constants
#define CALLBACK_PRIORITY CALLBACK_PRIORITY_CRITICAL
#define UPDATE_EXPECTED (1.0f / 666.0f)
#define UPDATE_MIN 1.0e-6f
#define UPDATE_MAX 1.0f
#define UPDATE_ALPHA 1.0e-2f
// Private variables
static DelayedCallbackInfo *callbackHandle;
static float gyro_filtered[3] = { 0, 0, 0 };
static float axis_lock_accum[3] = { 0, 0, 0 };
static uint8_t previous_mode[AXES] = { 255, 255, 255, 255 };
static PiOSDeltatimeConfig timeval;
static float speedScaleFactor = 1.0f;
// Private functions
static void stabilizationInnerloopTask();
static void GyroStateUpdatedCb(__attribute__((unused)) UAVObjEvent *ev);
#ifdef REVOLUTION
static void AirSpeedUpdatedCb(__attribute__((unused)) UAVObjEvent *ev);
#endif
void stabilizationInnerloopInit()
{
RateDesiredInitialize();
ActuatorDesiredInitialize();
GyroStateInitialize();
StabilizationStatusInitialize();
FlightStatusInitialize();
ManualControlCommandInitialize();
#ifdef REVOLUTION
AirspeedStateInitialize();
AirspeedStateConnectCallback(AirSpeedUpdatedCb);
#endif
PIOS_DELTATIME_Init(&timeval, UPDATE_EXPECTED, UPDATE_MIN, UPDATE_MAX, UPDATE_ALPHA);
callbackHandle = PIOS_CALLBACKSCHEDULER_Create(&stabilizationInnerloopTask, CALLBACK_PRIORITY, CBTASK_PRIORITY, CALLBACKINFO_RUNNING_STABILIZATION1, STACK_SIZE_BYTES);
GyroStateConnectCallback(GyroStateUpdatedCb);
// schedule dead calls every FAILSAFE_TIMEOUT_MS to have the watchdog cleared
PIOS_CALLBACKSCHEDULER_Schedule(callbackHandle, FAILSAFE_TIMEOUT_MS, CALLBACK_UPDATEMODE_LATER);
}
/**
* WARNING! This callback executes with critical flight control priority every
* time a gyroscope update happens do NOT put any time consuming calculations
* in this loop unless they really have to execute with every gyro update
*/
static void stabilizationInnerloopTask()
{
// watchdog and error handling
{
#ifdef PIOS_INCLUDE_WDG
PIOS_WDG_UpdateFlag(PIOS_WDG_STABILIZATION);
#endif
bool warn = false;
bool error = false;
bool crit = false;
// check if outer loop keeps executing
if (stabSettings.monitor.rateupdates > -64) {
stabSettings.monitor.rateupdates--;
}
if (stabSettings.monitor.rateupdates < -(2 * OUTERLOOP_SKIPCOUNT)) {
// warning if rate loop skipped more than 2 execution
warn = true;
}
if (stabSettings.monitor.rateupdates < -(4 * OUTERLOOP_SKIPCOUNT)) {
// error if rate loop skipped more than 4 executions
error = true;
}
// check if gyro keeps updating
if (stabSettings.monitor.gyroupdates < 1) {
// critical if gyro didn't update at all!
crit = true;
}
if (stabSettings.monitor.gyroupdates > 1) {
// warning if we missed a gyro update
warn = true;
}
if (stabSettings.monitor.gyroupdates > 3) {
// error if we missed 3 gyro updates
error = true;
}
stabSettings.monitor.gyroupdates = 0;
if (crit) {
AlarmsSet(SYSTEMALARMS_ALARM_STABILIZATION, SYSTEMALARMS_ALARM_CRITICAL);
} else if (error) {
AlarmsSet(SYSTEMALARMS_ALARM_STABILIZATION, SYSTEMALARMS_ALARM_ERROR);
} else if (warn) {
AlarmsSet(SYSTEMALARMS_ALARM_STABILIZATION, SYSTEMALARMS_ALARM_WARNING);
} else {
AlarmsClear(SYSTEMALARMS_ALARM_STABILIZATION);
}
}
RateDesiredData rateDesired;
ActuatorDesiredData actuator;
StabilizationStatusInnerLoopData enabled;
FlightStatusControlChainData cchain;
RateDesiredGet(&rateDesired);
ActuatorDesiredGet(&actuator);
StabilizationStatusInnerLoopGet(&enabled);
FlightStatusControlChainGet(&cchain);
float *rate = &rateDesired.Roll;
float *actuatorDesiredAxis = &actuator.Roll;
int t;
float dT;
dT = PIOS_DELTATIME_GetAverageSeconds(&timeval);
for (t = 0; t < AXES; t++) {
bool reinit = (cast_struct_to_array(enabled, enabled.Roll)[t] != previous_mode[t]);
previous_mode[t] = cast_struct_to_array(enabled, enabled.Roll)[t];
if (t < STABILIZATIONSTATUS_INNERLOOP_THRUST) {
if (reinit) {
stabSettings.innerPids[t].iAccumulator = 0;
}
switch (cast_struct_to_array(enabled, enabled.Roll)[t]) {
case STABILIZATIONSTATUS_INNERLOOP_VIRTUALFLYBAR:
stabilization_virtual_flybar(gyro_filtered[t], rate[t], &actuatorDesiredAxis[t], dT, reinit, t, &stabSettings.settings);
break;
case STABILIZATIONSTATUS_INNERLOOP_RELAYTUNING:
rate[t] = boundf(rate[t],
-cast_struct_to_array(stabSettings.stabBank.MaximumRate, stabSettings.stabBank.MaximumRate.Roll)[t],
cast_struct_to_array(stabSettings.stabBank.MaximumRate, stabSettings.stabBank.MaximumRate.Roll)[t]
);
stabilization_relay_rate(rate[t] - gyro_filtered[t], &actuatorDesiredAxis[t], t, reinit);
break;
case STABILIZATIONSTATUS_INNERLOOP_AXISLOCK:
if (fabsf(rate[t]) > stabSettings.settings.MaxAxisLockRate) {
// While getting strong commands act like rate mode
axis_lock_accum[t] = 0;
} else {
// For weaker commands or no command simply attitude lock (almost) on no gyro change
axis_lock_accum[t] += (rate[t] - gyro_filtered[t]) * dT;
axis_lock_accum[t] = boundf(axis_lock_accum[t], -stabSettings.settings.MaxAxisLock, stabSettings.settings.MaxAxisLock);
rate[t] = axis_lock_accum[t] * stabSettings.settings.AxisLockKp;
}
// IMPORTANT: deliberately no "break;" here, execution continues with regular RATE control loop to avoid code duplication!
// keep order as it is, RATE must follow!
case STABILIZATIONSTATUS_INNERLOOP_RATE:
// limit rate to maximum configured limits (once here instead of 5 times in outer loop)
rate[t] = boundf(rate[t],
-cast_struct_to_array(stabSettings.stabBank.MaximumRate, stabSettings.stabBank.MaximumRate.Roll)[t],
cast_struct_to_array(stabSettings.stabBank.MaximumRate, stabSettings.stabBank.MaximumRate.Roll)[t]
);
actuatorDesiredAxis[t] = pid_apply_setpoint(&stabSettings.innerPids[t], speedScaleFactor, rate[t], gyro_filtered[t], dT);
break;
case STABILIZATIONSTATUS_INNERLOOP_DIRECT:
default:
actuatorDesiredAxis[t] = rate[t];
break;
}
} else {
switch (cast_struct_to_array(enabled, enabled.Roll)[t]) {
case STABILIZATIONSTATUS_INNERLOOP_CRUISECONTROL:
actuatorDesiredAxis[t] = cruisecontrol_apply_factor(rate[t]);
break;
case STABILIZATIONSTATUS_INNERLOOP_DIRECT:
default:
actuatorDesiredAxis[t] = rate[t];
break;
}
}
actuatorDesiredAxis[t] = boundf(actuatorDesiredAxis[t], -1.0f, 1.0f);
}
actuator.UpdateTime = dT * 1000;
if (cchain.Stabilization == FLIGHTSTATUS_CONTROLCHAIN_TRUE) {
ActuatorDesiredSet(&actuator);
} else {
// Force all axes to reinitialize when engaged
for (t = 0; t < AXES; t++) {
previous_mode[t] = 255;
}
}
{
uint8_t armed;
FlightStatusArmedGet(&armed);
float throttleDesired;
ManualControlCommandThrottleGet(&throttleDesired);
if (armed != FLIGHTSTATUS_ARMED_ARMED ||
((stabSettings.settings.LowThrottleZeroIntegral == STABILIZATIONSETTINGS_LOWTHROTTLEZEROINTEGRAL_TRUE) && throttleDesired < 0)) {
// Force all axes to reinitialize when engaged
for (t = 0; t < AXES; t++) {
previous_mode[t] = 255;
}
}
}
PIOS_CALLBACKSCHEDULER_Schedule(callbackHandle, FAILSAFE_TIMEOUT_MS, CALLBACK_UPDATEMODE_LATER);
}
static void GyroStateUpdatedCb(__attribute__((unused)) UAVObjEvent *ev)
{
GyroStateData gyroState;
GyroStateGet(&gyroState);
gyro_filtered[0] = gyro_filtered[0] * stabSettings.gyro_alpha + gyroState.x * (1 - stabSettings.gyro_alpha);
gyro_filtered[1] = gyro_filtered[1] * stabSettings.gyro_alpha + gyroState.y * (1 - stabSettings.gyro_alpha);
gyro_filtered[2] = gyro_filtered[2] * stabSettings.gyro_alpha + gyroState.z * (1 - stabSettings.gyro_alpha);
PIOS_CALLBACKSCHEDULER_Dispatch(callbackHandle);
stabSettings.monitor.gyroupdates++;
}
#ifdef REVOLUTION
static void AirSpeedUpdatedCb(__attribute__((unused)) UAVObjEvent *ev)
{
// Scale PID coefficients based on current airspeed estimation - needed for fixed wing planes
AirspeedStateData airspeedState;
AirspeedStateGet(&airspeedState);
if (stabSettings.settings.ScaleToAirspeed < 0.1f || airspeedState.CalibratedAirspeed < 0.1f) {
// feature has been turned off
speedScaleFactor = 1.0f;
} else {
// scale the factor to be 1.0 at the specified airspeed (for example 10m/s) but scaled by 1/speed^2
speedScaleFactor = boundf((stabSettings.settings.ScaleToAirspeed * stabSettings.settings.ScaleToAirspeed) / (airspeedState.CalibratedAirspeed * airspeedState.CalibratedAirspeed),
stabSettings.settings.ScaleToAirspeedLimits.Min,
stabSettings.settings.ScaleToAirspeedLimits.Max);
}
}
#endif
/**
* @}
* @}
*/

View File

@ -0,0 +1,288 @@
/**
******************************************************************************
* @addtogroup OpenPilotModules OpenPilot Modules
* @{
* @addtogroup StabilizationModule Stabilization Module
* @brief Stabilization PID loops in an airframe type independent manner
* @note This object updates the @ref ActuatorDesired "Actuator Desired" based on the
* PID loops on the @ref AttitudeDesired "Attitude Desired" and @ref AttitudeState "Attitude State"
* @{
*
* @file outerloop.c
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2014.
* @brief Attitude stabilization module.
*
* @see The GNU Public License (GPL) Version 3
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#include <openpilot.h>
#include <pios_struct_helper.h>
#include <pid.h>
#include <callbackinfo.h>
#include <ratedesired.h>
#include <stabilizationdesired.h>
#include <attitudestate.h>
#include <stabilizationstatus.h>
#include <flightstatus.h>
#include <manualcontrolcommand.h>
#include <stabilizationbank.h>
#include <stabilization.h>
#include <cruisecontrol.h>
#include <altitudeloop.h>
#include <CoordinateConversions.h>
// Private constants
#define CALLBACK_PRIORITY CALLBACK_PRIORITY_REGULAR
#define UPDATE_EXPECTED (1.0f / 666.0f)
#define UPDATE_MIN 1.0e-6f
#define UPDATE_MAX 1.0f
#define UPDATE_ALPHA 1.0e-2f
// Private variables
static DelayedCallbackInfo *callbackHandle;
static AttitudeStateData attitude;
static uint8_t previous_mode[AXES] = { 255, 255, 255, 255 };
static PiOSDeltatimeConfig timeval;
// Private functions
static void stabilizationOuterloopTask();
static void AttitudeStateUpdatedCb(__attribute__((unused)) UAVObjEvent *ev);
void stabilizationOuterloopInit()
{
RateDesiredInitialize();
StabilizationDesiredInitialize();
AttitudeStateInitialize();
StabilizationStatusInitialize();
FlightStatusInitialize();
ManualControlCommandInitialize();
PIOS_DELTATIME_Init(&timeval, UPDATE_EXPECTED, UPDATE_MIN, UPDATE_MAX, UPDATE_ALPHA);
callbackHandle = PIOS_CALLBACKSCHEDULER_Create(&stabilizationOuterloopTask, CALLBACK_PRIORITY, CBTASK_PRIORITY, CALLBACKINFO_RUNNING_STABILIZATION0, STACK_SIZE_BYTES);
AttitudeStateConnectCallback(AttitudeStateUpdatedCb);
}
/**
* WARNING! This callback executes with critical flight control priority every
* time a gyroscope update happens do NOT put any time consuming calculations
* in this loop unless they really have to execute with every gyro update
*/
static void stabilizationOuterloopTask()
{
AttitudeStateData attitudeState;
RateDesiredData rateDesired;
StabilizationDesiredData stabilizationDesired;
StabilizationStatusOuterLoopData enabled;
AttitudeStateGet(&attitudeState);
StabilizationDesiredGet(&stabilizationDesired);
RateDesiredGet(&rateDesired);
StabilizationStatusOuterLoopGet(&enabled);
float *stabilizationDesiredAxis = &stabilizationDesired.Roll;
float *rateDesiredAxis = &rateDesired.Roll;
int t;
float dT = PIOS_DELTATIME_GetAverageSeconds(&timeval);
float local_error[3];
{
#if defined(PIOS_QUATERNION_STABILIZATION)
// Quaternion calculation of error in each axis. Uses more memory.
float rpy_desired[3];
float q_desired[4];
float q_error[4];
rpy_desired[0] = stabilizationDesiredAxis[0];
rpy_desired[1] = stabilizationDesiredAxis[1];
rpy_desired[2] = stabilizationDesiredAxis[2];
RPY2Quaternion(rpy_desired, q_desired);
quat_inverse(q_desired);
quat_mult(q_desired, &attitudeState.q1, q_error);
quat_inverse(q_error);
Quaternion2RPY(q_error, local_error);
#else /* if defined(PIOS_QUATERNION_STABILIZATION) */
// Simpler algorithm for CC, less memory
local_error[0] = stabilizationDesiredAxis[0] - attitudeState.Roll;
local_error[1] = stabilizationDesiredAxis[1] - attitudeState.Pitch;
local_error[2] = stabilizationDesiredAxis[2] - attitudeState.Yaw;
// find shortest way
float modulo = fmodf(local_error[2] + 180.0f, 360.0f);
if (modulo < 0) {
local_error[2] = modulo + 180.0f;
} else {
local_error[2] = modulo - 180.0f;
}
#endif /* if defined(PIOS_QUATERNION_STABILIZATION) */
}
for (t = 0; t < AXES; t++) {
bool reinit = (cast_struct_to_array(enabled, enabled.Roll)[t] != previous_mode[t]);
previous_mode[t] = cast_struct_to_array(enabled, enabled.Roll)[t];
if (t < STABILIZATIONSTATUS_OUTERLOOP_THRUST) {
if (reinit) {
stabSettings.outerPids[t].iAccumulator = 0;
}
switch (cast_struct_to_array(enabled, enabled.Roll)[t]) {
case STABILIZATIONSTATUS_OUTERLOOP_ATTITUDE:
rateDesiredAxis[t] = pid_apply(&stabSettings.outerPids[t], local_error[t], dT);
break;
case STABILIZATIONSTATUS_OUTERLOOP_RATTITUDE:
{
float stickinput[3];
stickinput[0] = boundf(stabilizationDesiredAxis[0] / stabSettings.stabBank.RollMax, -1.0f, 1.0f);
stickinput[1] = boundf(stabilizationDesiredAxis[1] / stabSettings.stabBank.PitchMax, -1.0f, 1.0f);
stickinput[2] = boundf(stabilizationDesiredAxis[2] / stabSettings.stabBank.YawMax, -1.0f, 1.0f);
float rateDesiredAxisRate = stickinput[t] * cast_struct_to_array(stabSettings.stabBank.ManualRate, stabSettings.stabBank.ManualRate.Roll)[t];
// limit corrective rate to maximum rates to not give it overly large impact over manual rate when joined together
rateDesiredAxis[t] = boundf(pid_apply(&stabSettings.outerPids[t], local_error[t], dT),
-cast_struct_to_array(stabSettings.stabBank.ManualRate, stabSettings.stabBank.ManualRate.Roll)[t],
cast_struct_to_array(stabSettings.stabBank.ManualRate, stabSettings.stabBank.ManualRate.Roll)[t]
);
// Compute the weighted average rate desired
// Using max() rather than sqrt() for cpu speed;
// - this makes the stick region into a square;
// - this is a feature!
// - hold a roll angle and add just pitch without the stick sensitivity changing
float magnitude = fabsf(stickinput[t]);
if (t < 2) {
magnitude = fmaxf(fabsf(stickinput[0]), fabsf(stickinput[1]));
}
// modify magnitude to move the Att to Rate transition to the place
// specified by the user
// we are looking for where the stick angle == transition angle
// and the Att rate equals the Rate rate
// that's where Rate x (1-StickAngle) [Attitude pulling down max X Ratt proportion]
// == Rate x StickAngle [Rate pulling up according to stick angle]
// * StickAngle [X Ratt proportion]
// so 1-x == x*x or x*x+x-1=0 where xE(0,1)
// (-1+-sqrt(1+4))/2 = (-1+sqrt(5))/2
// and quadratic formula says that is 0.618033989f
// I tested 14.01 and came up with .61 without even remembering this number
// I thought that moving the P,I, and maxangle terms around would change this value
// and that I would have to take these into account, but varying
// all P's and I's by factors of 1/2 to 2 didn't change it noticeably
// and varying maxangle from 4 to 120 didn't either.
// so for now I'm not taking these into account
// while working with this, it occurred to me that Attitude mode,
// set up with maxangle=190 would be similar to Ratt, and it is.
#define STICK_VALUE_AT_MODE_TRANSITION 0.618033989f
// the following assumes the transition would otherwise be at 0.618033989f
// and THAT assumes that Att ramps up to max roll rate
// when a small number of degrees off of where it should be
// if below the transition angle (still in attitude mode)
// '<=' instead of '<' keeps rattitude_mode_transition_stick_position==1.0 from causing DZ
if (magnitude <= stabSettings.rattitude_mode_transition_stick_position) {
magnitude *= STICK_VALUE_AT_MODE_TRANSITION / stabSettings.rattitude_mode_transition_stick_position;
} else {
magnitude = (magnitude - stabSettings.rattitude_mode_transition_stick_position)
* (1.0f - STICK_VALUE_AT_MODE_TRANSITION)
/ (1.0f - stabSettings.rattitude_mode_transition_stick_position)
+ STICK_VALUE_AT_MODE_TRANSITION;
}
rateDesiredAxis[t] = (1.0f - magnitude) * rateDesiredAxis[t] + magnitude * rateDesiredAxisRate;
}
break;
case STABILIZATIONSTATUS_OUTERLOOP_WEAKLEVELING:
// FIXME: local_error[] is rate - attitude for Weak Leveling
// The only ramifications are:
// Weak Leveling Kp is off by a factor of 3 to 12 and may need a different default in GCS
// Changing Rate mode max rate currently requires a change to Kp
// That would be changed to Attitude mode max angle affecting Kp
// Also does not take dT into account
{
float rate_input = cast_struct_to_array(stabSettings.stabBank.ManualRate, stabSettings.stabBank.ManualRate.Roll)[t] * stabilizationDesiredAxis[t] / cast_struct_to_array(stabSettings.stabBank, stabSettings.stabBank.RollMax)[t];
float weak_leveling = local_error[t] * stabSettings.settings.WeakLevelingKp;
weak_leveling = boundf(weak_leveling, -stabSettings.settings.MaxWeakLevelingRate, stabSettings.settings.MaxWeakLevelingRate);
// Compute desired rate as input biased towards leveling
rateDesiredAxis[t] = rate_input + weak_leveling;
}
break;
case STABILIZATIONSTATUS_OUTERLOOP_DIRECT:
default:
rateDesiredAxis[t] = stabilizationDesiredAxis[t];
break;
}
} else {
switch (cast_struct_to_array(enabled, enabled.Roll)[t]) {
#ifdef REVOLUTION
case STABILIZATIONSTATUS_OUTERLOOP_ALTITUDE:
rateDesiredAxis[t] = stabilizationAltitudeHold(stabilizationDesiredAxis[t], ALTITUDEHOLD, reinit);
break;
case STABILIZATIONSTATUS_OUTERLOOP_VERTICALVELOCITY:
rateDesiredAxis[t] = stabilizationAltitudeHold(stabilizationDesiredAxis[t], ALTITUDEVARIO, reinit);
break;
#endif /* REVOLUTION */
case STABILIZATIONSTATUS_OUTERLOOP_DIRECT:
default:
rateDesiredAxis[t] = stabilizationDesiredAxis[t];
break;
}
}
}
RateDesiredSet(&rateDesired);
{
uint8_t armed;
FlightStatusArmedGet(&armed);
float throttleDesired;
ManualControlCommandThrottleGet(&throttleDesired);
if (armed != FLIGHTSTATUS_ARMED_ARMED ||
((stabSettings.settings.LowThrottleZeroIntegral == STABILIZATIONSETTINGS_LOWTHROTTLEZEROINTEGRAL_TRUE) && throttleDesired < 0)) {
// Force all axes to reinitialize when engaged
for (t = 0; t < AXES; t++) {
previous_mode[t] = 255;
}
}
}
// update cruisecontrol based on attitude
cruisecontrol_compute_factor(&attitudeState, rateDesired.Thrust);
stabSettings.monitor.rateupdates = 0;
}
static void AttitudeStateUpdatedCb(__attribute__((unused)) UAVObjEvent *ev)
{
// to reduce CPU utilisation, outer loop is not executed every state update
static uint8_t cpusafer = 0;
if ((cpusafer++ % OUTERLOOP_SKIPCOUNT) == 0) {
// this does not need mutex protection as both eventdispatcher and stabi run in same callback task!
AttitudeStateGet(&attitude);
PIOS_CALLBACKSCHEDULER_Dispatch(callbackHandle);
}
}
/**
* @}
* @}
*/

View File

@ -63,7 +63,7 @@ int stabilization_relay_rate(float error, float *output, int axis, bool reinit)
portTickType thisTime = xTaskGetTickCount();
static bool rateRelayRunning[MAX_AXES];
static bool rateRelayRunning[3];
// This indicates the current estimate of the smoothed error. So when it is high
// we are waiting for it to go low.

View File

@ -33,121 +33,56 @@
#include <openpilot.h>
#include <pios_struct_helper.h>
#include "stabilization.h"
#include "stabilizationsettings.h"
#include "stabilizationbank.h"
#include "stabilizationsettingsbank1.h"
#include "stabilizationsettingsbank2.h"
#include "stabilizationsettingsbank3.h"
#include "actuatordesired.h"
#include "ratedesired.h"
#include "relaytuning.h"
#include "relaytuningsettings.h"
#include "stabilizationdesired.h"
#include "attitudestate.h"
#include "airspeedstate.h"
#include "gyrostate.h"
#include "flightstatus.h"
#include "manualcontrolsettings.h"
#include "manualcontrolcommand.h"
#include "flightmodesettings.h"
#include "taskinfo.h"
#include <pid.h>
#include <manualcontrolcommand.h>
#include <flightmodesettings.h>
#include <stabilizationsettings.h>
#include <stabilizationdesired.h>
#include <stabilizationstatus.h>
#include <stabilizationbank.h>
#include <stabilizationsettingsbank1.h>
#include <stabilizationsettingsbank2.h>
#include <stabilizationsettingsbank3.h>
#include <relaytuning.h>
#include <relaytuningsettings.h>
#include <ratedesired.h>
#include <sin_lookup.h>
#include <stabilization.h>
#include <innerloop.h>
#include <outerloop.h>
#include <altitudeloop.h>
// Math libraries
#include "CoordinateConversions.h"
#include "pid.h"
#include "sin_lookup.h"
// Includes for various stabilization algorithms
#include "relay_tuning.h"
#include "virtualflybar.h"
// Includes for various stabilization algorithms
#include "relay_tuning.h"
// Private constants
#define UPDATE_EXPECTED (1.0f / 666.0f)
#define UPDATE_MIN 1.0e-6f
#define UPDATE_MAX 1.0f
#define UPDATE_ALPHA 1.0e-2f
#define MAX_QUEUE_SIZE 1
#if defined(PIOS_STABILIZATION_STACK_SIZE)
#define STACK_SIZE_BYTES PIOS_STABILIZATION_STACK_SIZE
#else
#define STACK_SIZE_BYTES 860
#endif
#define TASK_PRIORITY (tskIDLE_PRIORITY + 3) // FLIGHT CONTROL priority
#define FAILSAFE_TIMEOUT_MS 30
// The PID_RATE_ROLL set is used by Rate mode and the rate portion of Attitude mode
// The PID_RATE set is used by the attitude portion of Attitude mode
enum { PID_RATE_ROLL, PID_RATE_PITCH, PID_RATE_YAW, PID_ROLL, PID_PITCH, PID_YAW, PID_MAX };
enum { RATE_P, RATE_I, RATE_D, RATE_LIMIT, RATE_OFFSET };
enum { ATT_P, ATT_I, ATT_LIMIT, ATT_OFFSET };
// Public variables
StabilizationData stabSettings;
// Private variables
static xTaskHandle taskHandle;
static StabilizationSettingsData settings;
static xQueueHandle queue;
float gyro_alpha = 0;
float axis_lock_accum[3] = { 0, 0, 0 };
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_decay = 0.991f;
struct pid pids[PID_MAX];
int cur_flight_mode = -1;
static float rattitude_mode_transition_stick_position;
static float cruise_control_min_thrust;
static float cruise_control_max_thrust;
static uint8_t cruise_control_max_angle;
static float cruise_control_max_power_factor;
static float cruise_control_power_trim;
static int8_t cruise_control_inverted_power_switch;
static float cruise_control_neutral_thrust;
static uint8_t cruise_control_flight_mode_switch_pos_enable[FLIGHTMODESETTINGS_FLIGHTMODEPOSITION_NUMELEM];
static int cur_flight_mode = -1;
// Private functions
static void stabilizationTask(void *parameters);
static float bound(float val, float range);
static void ZeroPids(void);
static void SettingsUpdatedCb(UAVObjEvent *ev);
static void BankUpdatedCb(UAVObjEvent *ev);
static void SettingsBankUpdatedCb(UAVObjEvent *ev);
static void FlightModeSwitchUpdatedCb(UAVObjEvent *ev);
static void StabilizationDesiredUpdatedCb(UAVObjEvent *ev);
/**
* Module initialization
*/
int32_t StabilizationStart()
{
// Initialize variables
// Create object queue
queue = xQueueCreate(MAX_QUEUE_SIZE, sizeof(UAVObjEvent));
// Listen for updates.
// AttitudeStateConnectQueue(queue);
GyroStateConnectQueue(queue);
StabilizationSettingsConnectCallback(SettingsUpdatedCb);
SettingsUpdatedCb(StabilizationSettingsHandle());
ManualControlCommandConnectCallback(FlightModeSwitchUpdatedCb);
StabilizationBankConnectCallback(BankUpdatedCb);
StabilizationSettingsBank1ConnectCallback(SettingsBankUpdatedCb);
StabilizationSettingsBank2ConnectCallback(SettingsBankUpdatedCb);
StabilizationSettingsBank3ConnectCallback(SettingsBankUpdatedCb);
StabilizationDesiredConnectCallback(StabilizationDesiredUpdatedCb);
SettingsUpdatedCb(StabilizationSettingsHandle());
StabilizationDesiredUpdatedCb(StabilizationDesiredHandle());
FlightModeSwitchUpdatedCb(ManualControlCommandHandle());
BankUpdatedCb(StabilizationBankHandle());
// Start main task
xTaskCreate(stabilizationTask, (signed char *)"Stabilization", STACK_SIZE_BYTES / 4, NULL, TASK_PRIORITY, &taskHandle);
PIOS_TASK_MONITOR_RegisterTask(TASKINFO_RUNNING_STABILIZATION, taskHandle);
#ifdef PIOS_INCLUDE_WDG
PIOS_WDG_RegisterFlag(PIOS_WDG_STABILIZATION);
#endif
@ -160,650 +95,189 @@ int32_t StabilizationStart()
int32_t StabilizationInitialize()
{
// Initialize variables
ManualControlCommandInitialize();
ManualControlSettingsInitialize();
FlightStatusInitialize();
StabilizationDesiredInitialize();
StabilizationSettingsInitialize();
StabilizationStatusInitialize();
StabilizationBankInitialize();
StabilizationSettingsBank1Initialize();
StabilizationSettingsBank2Initialize();
StabilizationSettingsBank3Initialize();
ActuatorDesiredInitialize();
#ifdef DIAG_RATEDESIRED
RateDesiredInitialize();
#endif
#ifdef REVOLUTION
AirspeedStateInitialize();
#endif
ManualControlCommandInitialize(); // only used for PID bank selection based on flight mode switch
// Code required for relay tuning
sin_lookup_initalize();
RelayTuningSettingsInitialize();
RelayTuningInitialize();
stabilizationOuterloopInit();
stabilizationInnerloopInit();
#ifdef REVOLUTION
stabilizationAltitudeloopInit();
#endif
pid_zero(&stabSettings.outerPids[0]);
pid_zero(&stabSettings.outerPids[1]);
pid_zero(&stabSettings.outerPids[2]);
pid_zero(&stabSettings.innerPids[0]);
pid_zero(&stabSettings.innerPids[1]);
pid_zero(&stabSettings.innerPids[2]);
return 0;
}
MODULE_INITCALL(StabilizationInitialize, StabilizationStart);
/**
* Module task
*/
static void stabilizationTask(__attribute__((unused)) void *parameters)
static void StabilizationDesiredUpdatedCb(__attribute__((unused)) UAVObjEvent *ev)
{
UAVObjEvent ev;
PiOSDeltatimeConfig timeval;
StabilizationStatusData status;
StabilizationDesiredStabilizationModeData mode;
int t;
PIOS_DELTATIME_Init(&timeval, UPDATE_EXPECTED, UPDATE_MIN, UPDATE_MAX, UPDATE_ALPHA);
ActuatorDesiredData actuatorDesired;
StabilizationDesiredData stabDesired;
float throttleDesired;
RateDesiredData rateDesired;
AttitudeStateData attitudeState;
GyroStateData gyroStateData;
FlightStatusData flightStatus;
StabilizationBankData stabBank;
#ifdef REVOLUTION
AirspeedStateData airspeedState;
#endif
SettingsUpdatedCb((UAVObjEvent *)NULL);
// Main task loop
ZeroPids();
while (1) {
float dT;
#ifdef PIOS_INCLUDE_WDG
PIOS_WDG_UpdateFlag(PIOS_WDG_STABILIZATION);
#endif
// Wait until the Gyro object is updated, if a timeout then go to failsafe
if (xQueueReceive(queue, &ev, FAILSAFE_TIMEOUT_MS / portTICK_RATE_MS) != pdTRUE) {
AlarmsSet(SYSTEMALARMS_ALARM_STABILIZATION, SYSTEMALARMS_ALARM_WARNING);
continue;
StabilizationDesiredStabilizationModeGet(&mode);
for (t = 0; t < AXES; t++) {
switch (cast_struct_to_array(mode, mode.Roll)[t]) {
case STABILIZATIONDESIRED_STABILIZATIONMODE_MANUAL:
cast_struct_to_array(status.OuterLoop, status.OuterLoop.Roll)[t] = STABILIZATIONSTATUS_OUTERLOOP_DIRECT;
cast_struct_to_array(status.InnerLoop, status.InnerLoop.Roll)[t] = STABILIZATIONSTATUS_INNERLOOP_DIRECT;
break;
case STABILIZATIONDESIRED_STABILIZATIONMODE_RATE:
cast_struct_to_array(status.OuterLoop, status.OuterLoop.Roll)[t] = STABILIZATIONSTATUS_OUTERLOOP_DIRECT;
cast_struct_to_array(status.InnerLoop, status.InnerLoop.Roll)[t] = STABILIZATIONSTATUS_INNERLOOP_RATE;
break;
case STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE:
cast_struct_to_array(status.OuterLoop, status.OuterLoop.Roll)[t] = STABILIZATIONSTATUS_OUTERLOOP_ATTITUDE;
cast_struct_to_array(status.InnerLoop, status.InnerLoop.Roll)[t] = STABILIZATIONSTATUS_INNERLOOP_RATE;
break;
case STABILIZATIONDESIRED_STABILIZATIONMODE_AXISLOCK:
cast_struct_to_array(status.OuterLoop, status.OuterLoop.Roll)[t] = STABILIZATIONSTATUS_OUTERLOOP_DIRECT;
cast_struct_to_array(status.InnerLoop, status.InnerLoop.Roll)[t] = STABILIZATIONSTATUS_INNERLOOP_AXISLOCK;
break;
case STABILIZATIONDESIRED_STABILIZATIONMODE_WEAKLEVELING:
cast_struct_to_array(status.OuterLoop, status.OuterLoop.Roll)[t] = STABILIZATIONSTATUS_OUTERLOOP_WEAKLEVELING;
cast_struct_to_array(status.InnerLoop, status.InnerLoop.Roll)[t] = STABILIZATIONSTATUS_INNERLOOP_RATE;
break;
case STABILIZATIONDESIRED_STABILIZATIONMODE_VIRTUALBAR:
cast_struct_to_array(status.OuterLoop, status.OuterLoop.Roll)[t] = STABILIZATIONSTATUS_OUTERLOOP_DIRECT;
cast_struct_to_array(status.InnerLoop, status.InnerLoop.Roll)[t] = STABILIZATIONSTATUS_INNERLOOP_VIRTUALFLYBAR;
break;
case STABILIZATIONDESIRED_STABILIZATIONMODE_RATTITUDE:
cast_struct_to_array(status.OuterLoop, status.OuterLoop.Roll)[t] = STABILIZATIONSTATUS_OUTERLOOP_RATTITUDE;
cast_struct_to_array(status.InnerLoop, status.InnerLoop.Roll)[t] = STABILIZATIONSTATUS_INNERLOOP_RATE;
break;
case STABILIZATIONDESIRED_STABILIZATIONMODE_RELAYRATE:
cast_struct_to_array(status.OuterLoop, status.OuterLoop.Roll)[t] = STABILIZATIONSTATUS_OUTERLOOP_DIRECT;
cast_struct_to_array(status.InnerLoop, status.InnerLoop.Roll)[t] = STABILIZATIONSTATUS_INNERLOOP_RELAYTUNING;
break;
case STABILIZATIONDESIRED_STABILIZATIONMODE_RELAYATTITUDE:
cast_struct_to_array(status.OuterLoop, status.OuterLoop.Roll)[t] = STABILIZATIONSTATUS_OUTERLOOP_ATTITUDE;
cast_struct_to_array(status.InnerLoop, status.InnerLoop.Roll)[t] = STABILIZATIONSTATUS_INNERLOOP_RELAYTUNING;
break;
case STABILIZATIONDESIRED_STABILIZATIONMODE_ALTITUDEHOLD:
cast_struct_to_array(status.OuterLoop, status.OuterLoop.Roll)[t] = STABILIZATIONSTATUS_OUTERLOOP_ALTITUDE;
cast_struct_to_array(status.InnerLoop, status.InnerLoop.Roll)[t] = STABILIZATIONSTATUS_INNERLOOP_CRUISECONTROL;
break;
case STABILIZATIONDESIRED_STABILIZATIONMODE_VERTICALVELOCITY:
cast_struct_to_array(status.OuterLoop, status.OuterLoop.Roll)[t] = STABILIZATIONSTATUS_OUTERLOOP_VERTICALVELOCITY;
cast_struct_to_array(status.InnerLoop, status.InnerLoop.Roll)[t] = STABILIZATIONSTATUS_INNERLOOP_CRUISECONTROL;
break;
case STABILIZATIONDESIRED_STABILIZATIONMODE_CRUISECONTROL:
cast_struct_to_array(status.OuterLoop, status.OuterLoop.Roll)[t] = STABILIZATIONSTATUS_OUTERLOOP_DIRECT;
cast_struct_to_array(status.InnerLoop, status.InnerLoop.Roll)[t] = STABILIZATIONSTATUS_INNERLOOP_CRUISECONTROL;
break;
}
}
StabilizationStatusSet(&status);
}
dT = PIOS_DELTATIME_GetAverageSeconds(&timeval);
FlightStatusGet(&flightStatus);
StabilizationDesiredGet(&stabDesired);
ManualControlCommandThrottleGet(&throttleDesired);
AttitudeStateGet(&attitudeState);
GyroStateGet(&gyroStateData);
StabilizationBankGet(&stabBank);
#ifdef DIAG_RATEDESIRED
RateDesiredGet(&rateDesired);
#endif
uint8_t flight_mode_switch_position;
ManualControlCommandFlightModeSwitchPositionGet(&flight_mode_switch_position);
static void FlightModeSwitchUpdatedCb(__attribute__((unused)) UAVObjEvent *ev)
{
uint8_t fm;
if (cur_flight_mode != flight_mode_switch_position) {
cur_flight_mode = flight_mode_switch_position;
ManualControlCommandFlightModeSwitchPositionGet(&fm);
if (fm == cur_flight_mode) {
return;
}
cur_flight_mode = fm;
SettingsBankUpdatedCb(NULL);
}
#ifdef REVOLUTION
float speedScaleFactor;
// Scale PID coefficients based on current airspeed estimation - needed for fixed wing planes
AirspeedStateGet(&airspeedState);
if (settings.ScaleToAirspeed < 0.1f || airspeedState.CalibratedAirspeed < 0.1f) {
// feature has been turned off
speedScaleFactor = 1.0f;
} else {
// scale the factor to be 1.0 at the specified airspeed (for example 10m/s) but scaled by 1/speed^2
speedScaleFactor = (settings.ScaleToAirspeed * settings.ScaleToAirspeed) / (airspeedState.CalibratedAirspeed * airspeedState.CalibratedAirspeed);
if (speedScaleFactor < settings.ScaleToAirspeedLimits.Min) {
speedScaleFactor = settings.ScaleToAirspeedLimits.Min;
}
if (speedScaleFactor > settings.ScaleToAirspeedLimits.Max) {
speedScaleFactor = settings.ScaleToAirspeedLimits.Max;
}
}
#else
const float speedScaleFactor = 1.0f;
#endif
#if defined(PIOS_QUATERNION_STABILIZATION)
// Quaternion calculation of error in each axis. Uses more memory.
float rpy_desired[3];
float q_desired[4];
float q_error[4];
float local_error[3];
// Essentially zero errors for anything in rate or none
if (stabDesired.StabilizationMode.Roll == STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE) {
rpy_desired[0] = stabDesired.Roll;
} else {
rpy_desired[0] = attitudeState.Roll;
}
if (stabDesired.StabilizationMode.Pitch == STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE) {
rpy_desired[1] = stabDesired.Pitch;
} else {
rpy_desired[1] = attitudeState.Pitch;
}
if (stabDesired.StabilizationMode.Yaw == STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE) {
rpy_desired[2] = stabDesired.Yaw;
} else {
rpy_desired[2] = attitudeState.Yaw;
}
RPY2Quaternion(rpy_desired, q_desired);
quat_inverse(q_desired);
quat_mult(q_desired, &attitudeState.q1, q_error);
quat_inverse(q_error);
Quaternion2RPY(q_error, local_error);
#else /* if defined(PIOS_QUATERNION_STABILIZATION) */
// Simpler algorithm for CC, less memory
float local_error[3] = { stabDesired.Roll - attitudeState.Roll,
stabDesired.Pitch - attitudeState.Pitch,
stabDesired.Yaw - attitudeState.Yaw };
// find shortest way
float modulo = fmodf(local_error[2] + 180.0f, 360.0f);
if (modulo < 0) {
local_error[2] = modulo + 180.0f;
} else {
local_error[2] = modulo - 180.0f;
}
#endif /* if defined(PIOS_QUATERNION_STABILIZATION) */
float gyro_filtered[3];
gyro_filtered[0] = gyro_filtered[0] * gyro_alpha + gyroStateData.x * (1 - gyro_alpha);
gyro_filtered[1] = gyro_filtered[1] * gyro_alpha + gyroStateData.y * (1 - gyro_alpha);
gyro_filtered[2] = gyro_filtered[2] * gyro_alpha + gyroStateData.z * (1 - gyro_alpha);
float *stabDesiredAxis = &stabDesired.Roll;
float *actuatorDesiredAxis = &actuatorDesired.Roll;
float *rateDesiredAxis = &rateDesired.Roll;
ActuatorDesiredGet(&actuatorDesired);
// A flag to track which stabilization mode each axis is in
static uint8_t previous_mode[MAX_AXES] = { 255, 255, 255 };
bool error = false;
// Run the selected stabilization algorithm on each axis:
for (uint8_t i = 0; i < MAX_AXES; i++) {
// Check whether this axis mode needs to be reinitialized
bool reinit = (cast_struct_to_array(stabDesired.StabilizationMode, stabDesired.StabilizationMode.Roll)[i] != previous_mode[i]);
previous_mode[i] = cast_struct_to_array(stabDesired.StabilizationMode, stabDesired.StabilizationMode.Roll)[i];
// Apply the selected control law
switch (cast_struct_to_array(stabDesired.StabilizationMode, stabDesired.StabilizationMode.Roll)[i]) {
case STABILIZATIONDESIRED_STABILIZATIONMODE_RATE:
if (reinit) {
pids[PID_RATE_ROLL + i].iAccumulator = 0;
}
// Store to rate desired variable for storing to UAVO
rateDesiredAxis[i] =
bound(stabDesiredAxis[i], cast_struct_to_array(stabBank.ManualRate, stabBank.ManualRate.Roll)[i]);
// Compute the inner loop
actuatorDesiredAxis[i] = pid_apply_setpoint(&pids[PID_RATE_ROLL + i], speedScaleFactor, rateDesiredAxis[i], gyro_filtered[i], dT);
actuatorDesiredAxis[i] = bound(actuatorDesiredAxis[i], 1.0f);
break;
case STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE:
if (reinit) {
pids[PID_ROLL + i].iAccumulator = 0;
pids[PID_RATE_ROLL + i].iAccumulator = 0;
}
// Compute the outer loop
rateDesiredAxis[i] = pid_apply(&pids[PID_ROLL + i], local_error[i], dT);
rateDesiredAxis[i] = bound(rateDesiredAxis[i],
cast_struct_to_array(stabBank.MaximumRate, stabBank.MaximumRate.Roll)[i]);
// Compute the inner loop
actuatorDesiredAxis[i] = pid_apply_setpoint(&pids[PID_RATE_ROLL + i], speedScaleFactor, rateDesiredAxis[i], gyro_filtered[i], dT);
actuatorDesiredAxis[i] = bound(actuatorDesiredAxis[i], 1.0f);
break;
case STABILIZATIONDESIRED_STABILIZATIONMODE_RATTITUDE:
// A parameterization from Attitude mode at center stick
// - to Rate mode at full stick
// This is done by parameterizing to use the rotation rate that Attitude mode
// - would use at center stick to using the rotation rate that Rate mode
// - would use at full stick in a weighted average sort of way.
{
if (reinit) {
pids[PID_ROLL + i].iAccumulator = 0;
pids[PID_RATE_ROLL + i].iAccumulator = 0;
}
// Compute what Rate mode would give for this stick angle's rate
// Save Rate's rate in a temp for later merging with Attitude's rate
float rateDesiredAxisRate;
rateDesiredAxisRate = bound(stabDesiredAxis[i], 1.0f)
* cast_struct_to_array(stabBank.ManualRate, stabBank.ManualRate.Roll)[i];
// Compute what Attitude mode would give for this stick angle's rate
// stabDesired for this mode is [-1.0f,+1.0f]
// - multiply by Attitude mode max angle to get desired angle
// - subtract off the actual angle to get the angle error
// This is what local_error[] holds for Attitude mode
float attitude_error = stabDesiredAxis[i]
* cast_struct_to_array(stabBank.RollMax, stabBank.RollMax)[i]
- cast_struct_to_array(attitudeState.Roll, attitudeState.Roll)[i];
// Compute the outer loop just like Attitude mode does
float rateDesiredAxisAttitude;
rateDesiredAxisAttitude = pid_apply(&pids[PID_ROLL + i], attitude_error, dT);
rateDesiredAxisAttitude = bound(rateDesiredAxisAttitude,
cast_struct_to_array(stabBank.ManualRate,
stabBank.ManualRate.Roll)[i]);
// Compute the weighted average rate desired
// Using max() rather than sqrt() for cpu speed;
// - this makes the stick region into a square;
// - this is a feature!
// - hold a roll angle and add just pitch without the stick sensitivity changing
// magnitude = sqrt(stabDesired.Roll*stabDesired.Roll + stabDesired.Pitch*stabDesired.Pitch);
float magnitude;
magnitude = fmaxf(fabsf(stabDesired.Roll), fabsf(stabDesired.Pitch));
// modify magnitude to move the Att to Rate transition to the place
// specified by the user
// we are looking for where the stick angle == transition angle
// and the Att rate equals the Rate rate
// that's where Rate x (1-StickAngle) [Attitude pulling down max X Ratt proportion]
// == Rate x StickAngle [Rate pulling up according to stick angle]
// * StickAngle [X Ratt proportion]
// so 1-x == x*x or x*x+x-1=0 where xE(0,1)
// (-1+-sqrt(1+4))/2 = (-1+sqrt(5))/2
// and quadratic formula says that is 0.618033989f
// I tested 14.01 and came up with .61 without even remembering this number
// I thought that moving the P,I, and maxangle terms around would change this value
// and that I would have to take these into account, but varying
// all P's and I's by factors of 1/2 to 2 didn't change it noticeably
// and varying maxangle from 4 to 120 didn't either.
// so for now I'm not taking these into account
// while working with this, it occurred to me that Attitude mode,
// set up with maxangle=190 would be similar to Ratt, and it is.
#define STICK_VALUE_AT_MODE_TRANSITION 0.618033989f
// the following assumes the transition would otherwise be at 0.618033989f
// and THAT assumes that Att ramps up to max roll rate
// when a small number of degrees off of where it should be
// if below the transition angle (still in attitude mode)
// '<=' instead of '<' keeps rattitude_mode_transition_stick_position==1.0 from causing DZ
if (magnitude <= rattitude_mode_transition_stick_position) {
magnitude *= STICK_VALUE_AT_MODE_TRANSITION / rattitude_mode_transition_stick_position;
} else {
magnitude = (magnitude - rattitude_mode_transition_stick_position)
* (1.0f - STICK_VALUE_AT_MODE_TRANSITION)
/ (1.0f - rattitude_mode_transition_stick_position)
+ STICK_VALUE_AT_MODE_TRANSITION;
}
rateDesiredAxis[i] = (1.0f - magnitude) * rateDesiredAxisAttitude
+ magnitude * rateDesiredAxisRate;
// Compute the inner loop for the averaged rate
// actuatorDesiredAxis[i] is the weighted average
actuatorDesiredAxis[i] = pid_apply_setpoint(&pids[PID_RATE_ROLL + i], speedScaleFactor,
rateDesiredAxis[i], gyro_filtered[i], dT);
actuatorDesiredAxis[i] = bound(actuatorDesiredAxis[i], 1.0f);
break;
}
case STABILIZATIONDESIRED_STABILIZATIONMODE_VIRTUALBAR:
// Store for debugging output
rateDesiredAxis[i] = stabDesiredAxis[i];
// Run a virtual flybar stabilization algorithm on this axis
stabilization_virtual_flybar(gyro_filtered[i], rateDesiredAxis[i], &actuatorDesiredAxis[i], dT, reinit, i, &settings);
break;
case STABILIZATIONDESIRED_STABILIZATIONMODE_WEAKLEVELING:
// FIXME: local_error[] is rate - attitude for Weak Leveling
// The only ramifications are:
// Weak Leveling Kp is off by a factor of 3 to 12 and may need a different default in GCS
// Changing Rate mode max rate currently requires a change to Kp
// That would be changed to Attitude mode max angle affecting Kp
// Also does not take dT into account
{
if (reinit) {
pids[PID_RATE_ROLL + i].iAccumulator = 0;
}
float weak_leveling = local_error[i] * weak_leveling_kp;
weak_leveling = bound(weak_leveling, weak_leveling_max);
// Compute desired rate as input biased towards leveling
rateDesiredAxis[i] = stabDesiredAxis[i] + weak_leveling;
actuatorDesiredAxis[i] = pid_apply_setpoint(&pids[PID_RATE_ROLL + i], speedScaleFactor, rateDesiredAxis[i], gyro_filtered[i], dT);
actuatorDesiredAxis[i] = bound(actuatorDesiredAxis[i], 1.0f);
break;
}
case STABILIZATIONDESIRED_STABILIZATIONMODE_AXISLOCK:
if (reinit) {
pids[PID_RATE_ROLL + i].iAccumulator = 0;
}
if (fabsf(stabDesiredAxis[i]) > max_axislock_rate) {
// While getting strong commands act like rate mode
rateDesiredAxis[i] = stabDesiredAxis[i];
axis_lock_accum[i] = 0;
} else {
// For weaker commands or no command simply attitude lock (almost) on no gyro change
axis_lock_accum[i] += (stabDesiredAxis[i] - gyro_filtered[i]) * dT;
axis_lock_accum[i] = bound(axis_lock_accum[i], max_axis_lock);
rateDesiredAxis[i] = pid_apply(&pids[PID_ROLL + i], axis_lock_accum[i], dT);
}
rateDesiredAxis[i] = bound(rateDesiredAxis[i],
cast_struct_to_array(stabBank.ManualRate, stabBank.ManualRate.Roll)[i]);
actuatorDesiredAxis[i] = pid_apply_setpoint(&pids[PID_RATE_ROLL + i], speedScaleFactor, rateDesiredAxis[i], gyro_filtered[i], dT);
actuatorDesiredAxis[i] = bound(actuatorDesiredAxis[i], 1.0f);
break;
case STABILIZATIONDESIRED_STABILIZATIONMODE_RELAYRATE:
// Store to rate desired variable for storing to UAVO
rateDesiredAxis[i] = bound(stabDesiredAxis[i],
cast_struct_to_array(stabBank.ManualRate, stabBank.ManualRate.Roll)[i]);
// Run the relay controller which also estimates the oscillation parameters
stabilization_relay_rate(rateDesiredAxis[i] - gyro_filtered[i], &actuatorDesiredAxis[i], i, reinit);
actuatorDesiredAxis[i] = bound(actuatorDesiredAxis[i], 1.0f);
break;
case STABILIZATIONDESIRED_STABILIZATIONMODE_RELAYATTITUDE:
if (reinit) {
pids[PID_ROLL + i].iAccumulator = 0;
}
// Compute the outer loop like attitude mode
rateDesiredAxis[i] = pid_apply(&pids[PID_ROLL + i], local_error[i], dT);
rateDesiredAxis[i] = bound(rateDesiredAxis[i],
cast_struct_to_array(stabBank.MaximumRate, stabBank.MaximumRate.Roll)[i]);
// Run the relay controller which also estimates the oscillation parameters
stabilization_relay_rate(rateDesiredAxis[i] - gyro_filtered[i], &actuatorDesiredAxis[i], i, reinit);
actuatorDesiredAxis[i] = bound(actuatorDesiredAxis[i], 1.0f);
break;
case STABILIZATIONDESIRED_STABILIZATIONMODE_NONE:
actuatorDesiredAxis[i] = bound(stabDesiredAxis[i], 1.0f);
break;
default:
error = true;
break;
}
}
if (settings.VbarPiroComp == STABILIZATIONSETTINGS_VBARPIROCOMP_TRUE) {
stabilization_virtual_flybar_pirocomp(gyro_filtered[2], dT);
}
#ifdef DIAG_RATEDESIRED
RateDesiredSet(&rateDesired);
#endif
// Save dT
actuatorDesired.UpdateTime = dT * 1000;
actuatorDesired.Thrust = stabDesired.Thrust;
// modify thrust according to 1/cos(bank angle)
// to maintain same altitdue with changing bank angle
// but without manually adjusting thrust
// do it here and all the various flight modes (e.g. Altitude Hold) can use it
if (flight_mode_switch_position < FLIGHTMODESETTINGS_FLIGHTMODEPOSITION_NUMELEM
&& cruise_control_flight_mode_switch_pos_enable[flight_mode_switch_position] != (uint8_t)0
&& cruise_control_max_power_factor > 0.0001f) {
static uint8_t toggle;
static float factor;
float angle;
// get attitude state and calculate angle
// do it every 8th iteration to save CPU
if ((toggle++ & 7) == 0) {
// spherical right triangle
// 0 <= acosf() <= Pi
angle = RAD2DEG(acosf(cos_lookup_deg(attitudeState.Roll) * cos_lookup_deg(attitudeState.Pitch)));
// if past the cutoff angle (60 to 180 (180 means never))
if (angle > cruise_control_max_angle) {
// -1 reversed collective, 0 zero power, or 1 normal power
// these are all unboosted
factor = cruise_control_inverted_power_switch;
} else {
// avoid singularity
if (angle > 89.999f && angle < 90.001f) {
factor = cruise_control_max_power_factor;
} else {
factor = 1.0f / fabsf(cos_lookup_deg(angle));
if (factor > cruise_control_max_power_factor) {
factor = cruise_control_max_power_factor;
}
}
// factor in the power trim, no effect at 1.0, linear effect increases with factor
factor = (factor - 1.0f) * cruise_control_power_trim + 1.0f;
// if inverted and they want negative boost
if (angle > 90.0f && cruise_control_inverted_power_switch == (int8_t)-1) {
factor = -factor;
// as long as thrust is getting reversed
// we may as well do pitch and yaw for a complete "invert switch"
actuatorDesired.Pitch = -actuatorDesired.Pitch;
actuatorDesired.Yaw = -actuatorDesired.Yaw;
}
}
}
// also don't adjust thrust if <= 0, leaves neg alone and zero thrust stops motors
if (actuatorDesired.Thrust > cruise_control_min_thrust) {
// quad example factor of 2 at hover power of 40%: (0.4 - 0.0) * 2.0 + 0.0 = 0.8
// CP heli example factor of 2 at hover stick of 60%: (0.6 - 0.5) * 2.0 + 0.5 = 0.7
actuatorDesired.Thrust = (actuatorDesired.Thrust - cruise_control_neutral_thrust) * factor + cruise_control_neutral_thrust;
if (actuatorDesired.Thrust > cruise_control_max_thrust) {
actuatorDesired.Thrust = cruise_control_max_thrust;
} else if (actuatorDesired.Thrust < cruise_control_min_thrust) {
actuatorDesired.Thrust = cruise_control_min_thrust;
}
}
}
if (flightStatus.ControlChain.Stabilization == FLIGHTSTATUS_CONTROLCHAIN_TRUE) {
ActuatorDesiredSet(&actuatorDesired);
} else {
// Force all axes to reinitialize when engaged
for (uint8_t i = 0; i < MAX_AXES; i++) {
previous_mode[i] = 255;
}
}
if (flightStatus.Armed != FLIGHTSTATUS_ARMED_ARMED ||
(lowThrottleZeroIntegral && throttleDesired < 0)) {
// Force all axes to reinitialize when engaged
for (uint8_t i = 0; i < MAX_AXES; i++) {
previous_mode[i] = 255;
}
}
// Clear or set alarms. Done like this to prevent toggline each cycle
// and hammering system alarms
if (error) {
AlarmsSet(SYSTEMALARMS_ALARM_STABILIZATION, SYSTEMALARMS_ALARM_ERROR);
} else {
AlarmsClear(SYSTEMALARMS_ALARM_STABILIZATION);
}
}
}
/**
* Clear the accumulators and derivatives for all the axes
*/
static void ZeroPids(void)
{
for (uint32_t i = 0; i < PID_MAX; i++) {
pid_zero(&pids[i]);
}
for (uint8_t i = 0; i < 3; i++) {
axis_lock_accum[i] = 0.0f;
}
}
/**
* Bound input value between limits
*/
static float bound(float val, float range)
{
if (val < -range) {
return -range;
} else if (val > range) {
return range;
}
return val;
}
static void SettingsBankUpdatedCb(__attribute__((unused)) UAVObjEvent *ev)
{
if (cur_flight_mode < 0 || cur_flight_mode >= FLIGHTMODESETTINGS_FLIGHTMODEPOSITION_NUMELEM) {
return;
}
if ((ev) && ((settings.FlightModeMap[cur_flight_mode] == 0 && ev->obj != StabilizationSettingsBank1Handle()) ||
(settings.FlightModeMap[cur_flight_mode] == 1 && ev->obj != StabilizationSettingsBank2Handle()) ||
(settings.FlightModeMap[cur_flight_mode] == 2 && ev->obj != StabilizationSettingsBank3Handle()) ||
settings.FlightModeMap[cur_flight_mode] > 2)) {
if ((ev) && ((stabSettings.settings.FlightModeMap[cur_flight_mode] == 0 && ev->obj != StabilizationSettingsBank1Handle()) ||
(stabSettings.settings.FlightModeMap[cur_flight_mode] == 1 && ev->obj != StabilizationSettingsBank2Handle()) ||
(stabSettings.settings.FlightModeMap[cur_flight_mode] == 2 && ev->obj != StabilizationSettingsBank3Handle()) ||
stabSettings.settings.FlightModeMap[cur_flight_mode] > 2)) {
return;
}
StabilizationBankData bank;
switch (settings.FlightModeMap[cur_flight_mode]) {
switch (stabSettings.settings.FlightModeMap[cur_flight_mode]) {
case 0:
StabilizationSettingsBank1Get((StabilizationSettingsBank1Data *)&bank);
StabilizationSettingsBank1Get((StabilizationSettingsBank1Data *)&stabSettings.stabBank);
break;
case 1:
StabilizationSettingsBank2Get((StabilizationSettingsBank2Data *)&bank);
StabilizationSettingsBank2Get((StabilizationSettingsBank2Data *)&stabSettings.stabBank);
break;
case 2:
StabilizationSettingsBank3Get((StabilizationSettingsBank3Data *)&bank);
StabilizationSettingsBank3Get((StabilizationSettingsBank3Data *)&stabSettings.stabBank);
break;
}
StabilizationBankSet(&bank);
StabilizationBankSet(&stabSettings.stabBank);
}
static void BankUpdatedCb(__attribute__((unused)) UAVObjEvent *ev)
{
StabilizationBankData bank;
StabilizationBankGet(&bank);
// this code will be needed if any other modules alter stabilizationbank
/*
StabilizationBankData curBank;
if(flight_mode < 0) return;
switch(cast_struct_to_array(settings.FlightModeMap, settings.FlightModeMap.Stabilized1)[flight_mode])
{
case 0:
StabilizationSettingsBank1Get((StabilizationSettingsBank1Data *) &curBank);
if(memcmp(&curBank, &bank, sizeof(StabilizationBankDataPacked)) != 0)
{
StabilizationSettingsBank1Set((StabilizationSettingsBank1Data *) &bank);
}
break;
case 1:
StabilizationSettingsBank2Get((StabilizationSettingsBank2Data *) &curBank);
if(memcmp(&curBank, &bank, sizeof(StabilizationBankDataPacked)) != 0)
{
StabilizationSettingsBank2Set((StabilizationSettingsBank2Data *) &bank);
}
break;
case 2:
StabilizationSettingsBank3Get((StabilizationSettingsBank3Data *) &curBank);
if(memcmp(&curBank, &bank, sizeof(StabilizationBankDataPacked)) != 0)
{
StabilizationSettingsBank3Set((StabilizationSettingsBank3Data *) &bank);
}
break;
default:
return; //invalid bank number
}
*/
StabilizationBankGet(&stabSettings.stabBank);
// Set the roll rate PID constants
pid_configure(&pids[PID_RATE_ROLL], bank.RollRatePID.Kp,
bank.RollRatePID.Ki,
bank.RollRatePID.Kd,
bank.RollRatePID.ILimit);
pid_configure(&stabSettings.innerPids[0], stabSettings.stabBank.RollRatePID.Kp,
stabSettings.stabBank.RollRatePID.Ki,
stabSettings.stabBank.RollRatePID.Kd,
stabSettings.stabBank.RollRatePID.ILimit);
// Set the pitch rate PID constants
pid_configure(&pids[PID_RATE_PITCH], bank.PitchRatePID.Kp,
bank.PitchRatePID.Ki,
bank.PitchRatePID.Kd,
bank.PitchRatePID.ILimit);
pid_configure(&stabSettings.innerPids[1], stabSettings.stabBank.PitchRatePID.Kp,
stabSettings.stabBank.PitchRatePID.Ki,
stabSettings.stabBank.PitchRatePID.Kd,
stabSettings.stabBank.PitchRatePID.ILimit);
// Set the yaw rate PID constants
pid_configure(&pids[PID_RATE_YAW], bank.YawRatePID.Kp,
bank.YawRatePID.Ki,
bank.YawRatePID.Kd,
bank.YawRatePID.ILimit);
pid_configure(&stabSettings.innerPids[2], stabSettings.stabBank.YawRatePID.Kp,
stabSettings.stabBank.YawRatePID.Ki,
stabSettings.stabBank.YawRatePID.Kd,
stabSettings.stabBank.YawRatePID.ILimit);
// Set the roll attitude PI constants
pid_configure(&pids[PID_ROLL], bank.RollPI.Kp,
bank.RollPI.Ki,
pid_configure(&stabSettings.outerPids[0], stabSettings.stabBank.RollPI.Kp,
stabSettings.stabBank.RollPI.Ki,
0,
bank.RollPI.ILimit);
stabSettings.stabBank.RollPI.ILimit);
// Set the pitch attitude PI constants
pid_configure(&pids[PID_PITCH], bank.PitchPI.Kp,
bank.PitchPI.Ki,
pid_configure(&stabSettings.outerPids[1], stabSettings.stabBank.PitchPI.Kp,
stabSettings.stabBank.PitchPI.Ki,
0,
bank.PitchPI.ILimit);
stabSettings.stabBank.PitchPI.ILimit);
// Set the yaw attitude PI constants
pid_configure(&pids[PID_YAW], bank.YawPI.Kp,
bank.YawPI.Ki,
pid_configure(&stabSettings.outerPids[2], stabSettings.stabBank.YawPI.Kp,
stabSettings.stabBank.YawPI.Ki,
0,
bank.YawPI.ILimit);
stabSettings.stabBank.YawPI.ILimit);
}
static void SettingsUpdatedCb(__attribute__((unused)) UAVObjEvent *ev)
{
StabilizationSettingsGet(&settings);
// needs no mutex, as long as eventdispatcher and Stabilization are both TASK_PRIORITY_CRITICAL
StabilizationSettingsGet(&stabSettings.settings);
// Set up the derivative term
pid_configure_derivative(settings.DerivativeCutoff, settings.DerivativeGamma);
// Maximum deviation to accumulate for axis lock
max_axis_lock = settings.MaxAxisLock;
max_axislock_rate = settings.MaxAxisLockRate;
// Settings for weak leveling
weak_leveling_kp = settings.WeakLevelingKp;
weak_leveling_max = settings.MaxWeakLevelingRate;
// Whether to zero the PID integrals while thrust is low
lowThrottleZeroIntegral = settings.LowThrottleZeroIntegral == STABILIZATIONSETTINGS_LOWTHROTTLEZEROINTEGRAL_TRUE;
pid_configure_derivative(stabSettings.settings.DerivativeCutoff, stabSettings.settings.DerivativeGamma);
// The dT has some jitter iteration to iteration that we don't want to
// make thie result unpredictable. Still, it's nicer to specify the constant
@ -811,37 +285,29 @@ static void SettingsUpdatedCb(__attribute__((unused)) UAVObjEvent *ev)
// update rates on OP (~300 Hz) and CC (~475 Hz) is negligible for this
// calculation
const float fakeDt = 0.0025f;
if (settings.GyroTau < 0.0001f) {
gyro_alpha = 0; // not trusting this to resolve to 0
if (stabSettings.settings.GyroTau < 0.0001f) {
stabSettings.gyro_alpha = 0; // not trusting this to resolve to 0
} else {
gyro_alpha = expf(-fakeDt / settings.GyroTau);
stabSettings.gyro_alpha = expf(-fakeDt / stabSettings.settings.GyroTau);
}
// Compute time constant for vbar decay term based on a tau
vbar_decay = expf(-fakeDt / settings.VbarTau);
// force flight mode update
cur_flight_mode = -1;
// Rattitude stick angle where the attitude to rate transition happens
if (settings.RattitudeModeTransition < (uint8_t)10) {
rattitude_mode_transition_stick_position = 10.0f / 100.0f;
if (stabSettings.settings.RattitudeModeTransition < (uint8_t)10) {
stabSettings.rattitude_mode_transition_stick_position = 10.0f / 100.0f;
} else {
rattitude_mode_transition_stick_position = (float)settings.RattitudeModeTransition / 100.0f;
stabSettings.rattitude_mode_transition_stick_position = (float)stabSettings.settings.RattitudeModeTransition / 100.0f;
}
cruise_control_min_thrust = (float)settings.CruiseControlMinThrust / 100.0f;
cruise_control_max_thrust = (float)settings.CruiseControlMaxThrust / 100.0f;
cruise_control_max_angle = settings.CruiseControlMaxAngle;
cruise_control_max_power_factor = settings.CruiseControlMaxPowerFactor;
cruise_control_power_trim = settings.CruiseControlPowerTrim / 100.0f;
cruise_control_inverted_power_switch = settings.CruiseControlInvertedPowerSwitch;
cruise_control_neutral_thrust = (float)settings.CruiseControlNeutralThrust / 100.0f;
stabSettings.cruiseControl.min_thrust = (float)stabSettings.settings.CruiseControlMinThrust / 100.0f;
stabSettings.cruiseControl.max_thrust = (float)stabSettings.settings.CruiseControlMaxThrust / 100.0f;
stabSettings.cruiseControl.thrust_difference = stabSettings.cruiseControl.max_thrust - stabSettings.cruiseControl.min_thrust;
memcpy(
cruise_control_flight_mode_switch_pos_enable,
settings.CruiseControlFlightModeSwitchPosEnable,
sizeof(cruise_control_flight_mode_switch_pos_enable));
stabSettings.cruiseControl.power_trim = stabSettings.settings.CruiseControlPowerTrim / 100.0f;
stabSettings.cruiseControl.half_power_delay = stabSettings.settings.CruiseControlPowerDelayComp / 2.0f;
stabSettings.cruiseControl.max_power_factor_angle = RAD2DEG(acosf(1.0f / stabSettings.settings.CruiseControlMaxPowerFactor));
}
/**

View File

@ -37,12 +37,9 @@
#include "stabilizationsettings.h"
// ! Private variables
static float vbar_integral[MAX_AXES];
static float vbar_integral[3];
static float vbar_decay = 0.991f;
// ! Private methods
static float bound(float val, float range);
int stabilization_virtual_flybar(float gyro, float command, float *output, float dT, bool reinit, uint32_t axis, StabilizationSettingsData *settings)
{
float gyro_gain = 1.0f;
@ -54,7 +51,7 @@ int stabilization_virtual_flybar(float gyro, float command, float *output, float
// Track the angle of the virtual flybar which includes a slow decay
vbar_integral[axis] = vbar_integral[axis] * vbar_decay + gyro * dT;
vbar_integral[axis] = bound(vbar_integral[axis], settings->VbarMaxAngle);
vbar_integral[axis] = boundf(vbar_integral[axis], -settings->VbarMaxAngle, settings->VbarMaxAngle);
// Command signal can indicate how much to disregard the gyro feedback (fast flips)
if (settings->VbarGyroSuppress > 0) {
@ -64,15 +61,15 @@ int stabilization_virtual_flybar(float gyro, float command, float *output, float
// Get the settings for the correct axis
switch (axis) {
case ROLL:
case 0:
kp = settings->VbarRollPI.Kp;
ki = settings->VbarRollPI.Ki;
break;
case PITCH:
case 1:
kp = settings->VbarPitchPI.Kp;
ki = settings->VbarPitchPI.Ki;;
break;
case YAW:
case 2:
kp = settings->VbarYawPI.Kp;
ki = settings->VbarYawPI.Ki;
break;
@ -105,16 +102,3 @@ int stabilization_virtual_flybar_pirocomp(float z_gyro, float dT)
return 0;
}
/**
* Bound input value between limits
*/
static float bound(float val, float range)
{
if (val < -range) {
val = -range;
} else if (val > range) {
val = range;
}
return val;
}

View File

@ -33,21 +33,29 @@
#include "inc/stateestimation.h"
#include <attitudestate.h>
#include <altitudefiltersettings.h>
#include <homelocation.h>
#include <CoordinateConversions.h>
// Private constants
// duration of accel bias initialization phase
#define INITIALIZATION_DURATION_MS 5000
#define STACK_REQUIRED 128
#define DT_ALPHA 1e-2f
#define DT_MIN 1e-6f
#define DT_MAX 1.0f
#define DT_AVERAGE 1e-3f
static volatile bool reloadSettings;
// Private types
struct data {
float state[4]; // state = altitude,velocity,accel_offset,accel
float altitudeState; // state = altitude,velocity,accel_offset,accel
float velocityState;
float accelBiasState;
float accelState;
float pos[3]; // position updates from other filters
float vel[3]; // position updates from other filters
@ -56,7 +64,9 @@ struct data {
float accelLast;
float baroLast;
bool first_run;
portTickType initTimer;
AltitudeFilterSettingsData settings;
float gravity;
};
// Private variables
@ -65,6 +75,7 @@ struct data {
static int32_t init(stateFilter *self);
static int32_t filter(stateFilter *self, stateEstimation *state);
static void settingsUpdatedCb(UAVObjEvent *ev);
int32_t filterAltitudeInitialize(stateFilter *handle)
@ -72,8 +83,11 @@ int32_t filterAltitudeInitialize(stateFilter *handle)
handle->init = &init;
handle->filter = &filter;
handle->localdata = pvPortMalloc(sizeof(struct data));
HomeLocationInitialize();
AttitudeStateInitialize();
AltitudeFilterSettingsInitialize();
AltitudeFilterSettingsConnectCallback(&settingsUpdatedCb);
reloadSettings = true;
return STACK_REQUIRED;
}
@ -81,10 +95,10 @@ static int32_t init(stateFilter *self)
{
struct data *this = (struct data *)self->localdata;
this->state[0] = 0.0f;
this->state[1] = 0.0f;
this->state[2] = 0.0f;
this->state[3] = 0.0f;
this->altitudeState = 0.0f;
this->velocityState = 0.0f;
this->accelBiasState = 0.0f;
this->accelState = 0.0f;
this->pos[0] = 0.0f;
this->pos[1] = 0.0f;
this->pos[2] = 0.0f;
@ -96,7 +110,7 @@ static int32_t init(stateFilter *self)
this->baroLast = 0.0f;
this->accelLast = 0.0f;
this->first_run = 1;
AltitudeFilterSettingsGet(&this->settings);
HomeLocationg_eGet(&this->gravity);
return 0;
}
@ -104,10 +118,16 @@ static int32_t filter(stateFilter *self, stateEstimation *state)
{
struct data *this = (struct data *)self->localdata;
if (reloadSettings) {
reloadSettings = false;
AltitudeFilterSettingsGet(&this->settings);
}
if (this->first_run) {
// Initialize to current altitude reading at initial location
if (IS_SET(state->updated, SENSORUPDATES_baro)) {
this->first_run = 0;
this->initTimer = xTaskGetTickCount();
}
} else {
// save existing position and velocity updates so GPS will still work
@ -115,13 +135,13 @@ static int32_t filter(stateFilter *self, stateEstimation *state)
this->pos[0] = state->pos[0];
this->pos[1] = state->pos[1];
this->pos[2] = state->pos[2];
state->pos[2] = -this->state[0];
state->pos[2] = -this->altitudeState;
}
if (IS_SET(state->updated, SENSORUPDATES_vel)) {
this->vel[0] = state->vel[0];
this->vel[1] = state->vel[1];
this->vel[2] = state->vel[2];
state->vel[2] = -this->state[1];
state->vel[2] = -this->velocityState;
}
if (IS_SET(state->updated, SENSORUPDATES_accel)) {
// rotate accels into global coordinate frame
@ -129,54 +149,57 @@ static int32_t filter(stateFilter *self, stateEstimation *state)
AttitudeStateGet(&att);
float Rbe[3][3];
Quaternion2R(&att.q1, Rbe);
float current = -(Rbe[0][2] * state->accel[0] + Rbe[1][2] * state->accel[1] + Rbe[2][2] * state->accel[2] + 9.81f);
float current = -(Rbe[0][2] * state->accel[0] + Rbe[1][2] * state->accel[1] + Rbe[2][2] * state->accel[2] + this->gravity);
// low pass filter accelerometers
this->state[3] = (1.0f - this->settings.AccelLowPassKp) * this->state[3] + this->settings.AccelLowPassKp * current;
this->accelState = (1.0f - this->settings.AccelLowPassKp) * this->accelState + this->settings.AccelLowPassKp * current;
if (((xTaskGetTickCount() - this->initTimer) / portTICK_RATE_MS) < INITIALIZATION_DURATION_MS) {
// allow the offset to reach quickly the target value in case of small AccelDriftKi
this->accelBiasState = (1.0f - this->settings.InitializationAccelDriftKi) * this->accelBiasState + this->settings.InitializationAccelDriftKi * this->accelState;
} else {
// correct accel offset (low pass zeroing)
this->state[2] = (1.0f - this->settings.AccelDriftKi) * this->state[2] + this->settings.AccelDriftKi * this->state[3];
this->accelBiasState = (1.0f - this->settings.AccelDriftKi) * this->accelBiasState + this->settings.AccelDriftKi * this->accelState;
}
// correct velocity and position state (integration)
// low pass for average dT, compensate timing jitter from scheduler
//
float dT = PIOS_DELTATIME_GetAverageSeconds(&this->dt1config);
float speedLast = this->state[1];
float speedLast = this->velocityState;
this->state[1] += 0.5f * (this->accelLast + (this->state[3] - this->state[2])) * dT;
this->accelLast = this->state[3] - this->state[2];
this->velocityState += 0.5f * (this->accelLast + (this->accelState - this->accelBiasState)) * dT;
this->accelLast = this->accelState - this->accelBiasState;
this->state[0] += 0.5f * (speedLast + this->state[1]) * dT;
this->altitudeState += 0.5f * (speedLast + this->velocityState) * dT;
state->pos[0] = this->pos[0];
state->pos[1] = this->pos[1];
state->pos[2] = -this->state[0];
state->pos[2] = -this->altitudeState;
state->updated |= SENSORUPDATES_pos;
state->vel[0] = this->vel[0];
state->vel[1] = this->vel[1];
state->vel[2] = -this->state[1];
state->vel[2] = -this->velocityState;
state->updated |= SENSORUPDATES_vel;
}
if (IS_SET(state->updated, SENSORUPDATES_baro)) {
// correct the altitude state (simple low pass)
this->state[0] = (1.0f - this->settings.BaroKp) * this->state[0] + this->settings.BaroKp * state->baro[0];
this->altitudeState = (1.0f - this->settings.BaroKp) * this->altitudeState + this->settings.BaroKp * state->baro[0];
// correct the velocity state (low pass differentiation)
// low pass for average dT, compensate timing jitter from scheduler
float dT = PIOS_DELTATIME_GetAverageSeconds(&this->dt2config);
this->state[1] = (1.0f - (this->settings.BaroKp * this->settings.BaroKp)) * this->state[1] + (this->settings.BaroKp * this->settings.BaroKp) * (state->baro[0] - this->baroLast) / dT;
this->velocityState = (1.0f - (this->settings.BaroKp * this->settings.BaroKp)) * this->velocityState + (this->settings.BaroKp * this->settings.BaroKp) * (state->baro[0] - this->baroLast) / dT;
this->baroLast = state->baro[0];
state->pos[0] = this->pos[0];
state->pos[1] = this->pos[1];
state->pos[2] = -this->state[0];
state->pos[2] = -this->altitudeState;
state->updated |= SENSORUPDATES_pos;
state->vel[0] = this->vel[0];
state->vel[1] = this->vel[1];
state->vel[2] = -this->state[1];
state->vel[2] = -this->velocityState;
state->updated |= SENSORUPDATES_vel;
}
}
@ -184,6 +207,12 @@ static int32_t filter(stateFilter *self, stateEstimation *state)
return 0;
}
void settingsUpdatedCb(UAVObjEvent *ev)
{
if (ev->obj == AltitudeFilterSettingsHandle()) {
reloadSettings = true;
}
}
/**
* @}

View File

@ -36,7 +36,7 @@
// Private constants
#define STACK_REQUIRED 64
#define STACK_REQUIRED 128
#define INIT_CYCLES 100
// Private types
@ -44,30 +44,59 @@ struct data {
float baroOffset;
float baroGPSOffsetCorrectionAlpha;
float baroAlt;
float gpsAlt;
int16_t first_run;
bool useGPS;
};
// Private variables
// Private functions
static int32_t init(stateFilter *self);
static int32_t initwithgps(stateFilter *self);
static int32_t initwithoutgps(stateFilter *self);
static int32_t maininit(stateFilter *self);
static int32_t filter(stateFilter *self, stateEstimation *state);
int32_t filterBaroInitialize(stateFilter *handle)
{
handle->init = &init;
handle->init = &initwithgps;
handle->filter = &filter;
handle->localdata = pvPortMalloc(sizeof(struct data));
return STACK_REQUIRED;
}
static int32_t init(stateFilter *self)
int32_t filterBaroiInitialize(stateFilter *handle)
{
handle->init = &initwithoutgps;
handle->filter = &filter;
handle->localdata = pvPortMalloc(sizeof(struct data));
return STACK_REQUIRED;
}
static int32_t initwithgps(stateFilter *self)
{
struct data *this = (struct data *)self->localdata;
this->useGPS = 1;
return maininit(self);
}
static int32_t initwithoutgps(stateFilter *self)
{
struct data *this = (struct data *)self->localdata;
this->useGPS = 0;
return maininit(self);
}
static int32_t maininit(stateFilter *self)
{
struct data *this = (struct data *)self->localdata;
this->baroOffset = 0.0f;
this->gpsAlt = 0.0f;
this->first_run = INIT_CYCLES;
RevoSettingsInitialize();
@ -81,17 +110,29 @@ static int32_t filter(stateFilter *self, stateEstimation *state)
struct data *this = (struct data *)self->localdata;
if (this->first_run) {
// Make sure initial location is initialized properly before continuing
if (this->useGPS && IS_SET(state->updated, SENSORUPDATES_pos)) {
if (this->first_run == INIT_CYCLES) {
this->gpsAlt = state->pos[2];
this->first_run--;
}
}
// Initialize to current altitude reading at initial location
if (IS_SET(state->updated, SENSORUPDATES_baro)) {
this->baroOffset = ((float)(INIT_CYCLES)-this->first_run) / (float)(INIT_CYCLES)*this->baroOffset + (this->first_run / (float)(INIT_CYCLES)) * state->baro[0];
this->baroAlt = 0;
if (this->first_run < INIT_CYCLES || !this->useGPS) {
this->baroOffset = (((float)(INIT_CYCLES)-this->first_run) / (float)(INIT_CYCLES)) * this->baroOffset + (this->first_run / (float)(INIT_CYCLES)) * (state->baro[0] + this->gpsAlt);
this->baroAlt = state->baro[0];
this->first_run--;
}
UNSET_MASK(state->updated, SENSORUPDATES_baro);
}
// make sure we raise an error until properly initialized - would not be good if people arm and
// use altitudehold without initialized barometer filter
return 2;
} else {
// Track barometric altitude offset with a low pass filter
// based on GPS altitude if available
if (IS_SET(state->updated, SENSORUPDATES_pos)) {
if (this->useGPS && IS_SET(state->updated, SENSORUPDATES_pos)) {
this->baroOffset = this->baroOffset * this->baroGPSOffsetCorrectionAlpha +
(1.0f - this->baroGPSOffsetCorrectionAlpha) * (this->baroAlt + state->pos[2]);
}
@ -100,10 +141,9 @@ static int32_t filter(stateFilter *self, stateEstimation *state)
this->baroAlt = state->baro[0];
state->baro[0] -= this->baroOffset;
}
}
return 0;
}
}
/**

View File

@ -356,6 +356,7 @@ static int32_t filter(stateFilter *self, stateEstimation *state)
}
INSSetMagNorth(this->homeLocation.Be);
INSSetG(this->homeLocation.g_e);
if (!this->usePos) {
// position and velocity variance used in indoor mode

View File

@ -64,6 +64,7 @@ typedef struct stateFilterStruct {
int32_t filterMagInitialize(stateFilter *handle);
int32_t filterBaroiInitialize(stateFilter *handle);
int32_t filterBaroInitialize(stateFilter *handle);
int32_t filterAltitudeInitialize(stateFilter *handle);
int32_t filterAirInitialize(stateFilter *handle);

View File

@ -140,11 +140,12 @@ static DelayedCallbackInfo *stateEstimationCallback;
static volatile RevoSettingsData revoSettings;
static volatile sensorUpdates updatedSensors;
static volatile int32_t fusionAlgorithm = -1;
static filterPipeline *filterChain = NULL;
static const filterPipeline *filterChain = NULL;
// different filters available to state estimation
static stateFilter magFilter;
static stateFilter baroFilter;
static stateFilter baroiFilter;
static stateFilter altitudeFilter;
static stateFilter airFilter;
static stateFilter stationaryFilter;
@ -154,15 +155,17 @@ static stateFilter cfmFilter;
static stateFilter ekf13iFilter;
static stateFilter ekf13Filter;
// this is a hack to provide a computational shortcut for faster gyro state progression
static float gyroRaw[3];
static float gyroDelta[3];
// preconfigured filter chains selectable via revoSettings.FusionAlgorithm
static filterPipeline *cfQueue = &(filterPipeline) {
static const filterPipeline *cfQueue = &(filterPipeline) {
.filter = &magFilter,
.next = &(filterPipeline) {
.filter = &airFilter,
.next = &(filterPipeline) {
.filter = &llaFilter,
.next = &(filterPipeline) {
.filter = &baroFilter,
.filter = &baroiFilter,
.next = &(filterPipeline) {
.filter = &altitudeFilter,
.next = &(filterPipeline) {
@ -172,6 +175,21 @@ static filterPipeline *cfQueue = &(filterPipeline) {
}
}
}
};
static const filterPipeline *cfmiQueue = &(filterPipeline) {
.filter = &magFilter,
.next = &(filterPipeline) {
.filter = &airFilter,
.next = &(filterPipeline) {
.filter = &baroiFilter,
.next = &(filterPipeline) {
.filter = &altitudeFilter,
.next = &(filterPipeline) {
.filter = &cfmFilter,
.next = NULL,
}
}
}
}
};
static const filterPipeline *cfmQueue = &(filterPipeline) {
@ -198,9 +216,7 @@ static const filterPipeline *ekf13iQueue = &(filterPipeline) {
.next = &(filterPipeline) {
.filter = &airFilter,
.next = &(filterPipeline) {
.filter = &llaFilter,
.next = &(filterPipeline) {
.filter = &baroFilter,
.filter = &baroiFilter,
.next = &(filterPipeline) {
.filter = &stationaryFilter,
.next = &(filterPipeline) {
@ -210,7 +226,6 @@ static const filterPipeline *ekf13iQueue = &(filterPipeline) {
}
}
}
}
};
static const filterPipeline *ekf13Queue = &(filterPipeline) {
.filter = &magFilter,
@ -283,6 +298,7 @@ int32_t StateEstimationInitialize(void)
uint32_t stack_required = STACK_SIZE_BYTES;
// Initialize Filters
stack_required = maxint32_t(stack_required, filterMagInitialize(&magFilter));
stack_required = maxint32_t(stack_required, filterBaroiInitialize(&baroiFilter));
stack_required = maxint32_t(stack_required, filterBaroInitialize(&baroFilter));
stack_required = maxint32_t(stack_required, filterAltitudeInitialize(&altitudeFilter));
stack_required = maxint32_t(stack_required, filterAirInitialize(&airFilter));
@ -324,7 +340,7 @@ static void StateEstimationCb(void)
static int8_t alarm = 0;
static int8_t lastAlarm = -1;
static uint16_t alarmcounter = 0;
static filterPipeline *current;
static const filterPipeline *current;
static stateEstimation states;
static uint32_t last_time;
static uint16_t bootDelay = 64;
@ -361,19 +377,22 @@ static void StateEstimationCb(void)
newFilterChain = cfQueue;
break;
case REVOSETTINGS_FUSIONALGORITHM_COMPLEMENTARYMAG:
newFilterChain = cfmiQueue;
break;
case REVOSETTINGS_FUSIONALGORITHM_COMPLEMENTARYMAGGPSOUTDOOR:
newFilterChain = cfmQueue;
break;
case REVOSETTINGS_FUSIONALGORITHM_INS13INDOOR:
newFilterChain = ekf13iQueue;
break;
case REVOSETTINGS_FUSIONALGORITHM_INS13OUTDOOR:
case REVOSETTINGS_FUSIONALGORITHM_INS13GPSOUTDOOR:
newFilterChain = ekf13Queue;
break;
default:
newFilterChain = NULL;
}
// initialize filters in chain
current = (filterPipeline *)newFilterChain;
current = newFilterChain;
bool error = 0;
while (current != NULL) {
int32_t result = current->filter->init((stateFilter *)current->filter);
@ -388,7 +407,7 @@ static void StateEstimationCb(void)
return;
} else {
// set new fusion algortithm
filterChain = (filterPipeline *)newFilterChain;
filterChain = newFilterChain;
fusionAlgorithm = revoSettings.FusionAlgorithm;
}
}
@ -400,6 +419,11 @@ static void StateEstimationCb(void)
// fetch sensors, check values, and load into state struct
FETCH_SENSOR_FROM_UAVOBJECT_CHECK_AND_LOAD_TO_STATE_3_DIMENSIONS(GyroSensor, gyro, x, y, z);
if (IS_SET(states.updated, SENSORUPDATES_gyro)) {
gyroRaw[0] = states.gyro[0];
gyroRaw[1] = states.gyro[1];
gyroRaw[2] = states.gyro[2];
}
FETCH_SENSOR_FROM_UAVOBJECT_CHECK_AND_LOAD_TO_STATE_3_DIMENSIONS(AccelSensor, accel, x, y, z);
FETCH_SENSOR_FROM_UAVOBJECT_CHECK_AND_LOAD_TO_STATE_3_DIMENSIONS(MagSensor, mag, x, y, z);
FETCH_SENSOR_FROM_UAVOBJECT_CHECK_AND_LOAD_TO_STATE_3_DIMENSIONS(GPSVelocitySensor, vel, North, East, Down);
@ -411,7 +435,7 @@ static void StateEstimationCb(void)
// at this point sensor state is stored in "states" with some rudimentary filtering applied
// apply all filters in the current filter chain
current = (filterPipeline *)filterChain;
current = filterChain;
// we are not done, re-dispatch self execution
runState = RUNSTATE_FILTER;
@ -438,7 +462,12 @@ static void StateEstimationCb(void)
case RUNSTATE_SAVE:
// the final output of filters is saved in state variables
EXPORT_STATE_TO_UAVOBJECT_IF_UPDATED_3_DIMENSIONS(GyroState, gyro, x, y, z);
// EXPORT_STATE_TO_UAVOBJECT_IF_UPDATED_3_DIMENSIONS(GyroState, gyro, x, y, z) // replaced by performance shortcut
if (IS_SET(states.updated, SENSORUPDATES_gyro)) {
gyroDelta[0] = states.gyro[0] - gyroRaw[0];
gyroDelta[1] = states.gyro[1] - gyroRaw[1];
gyroDelta[2] = states.gyro[2] - gyroRaw[2];
}
EXPORT_STATE_TO_UAVOBJECT_IF_UPDATED_3_DIMENSIONS(AccelState, accel, x, y, z);
EXPORT_STATE_TO_UAVOBJECT_IF_UPDATED_3_DIMENSIONS(MagState, mag, x, y, z);
EXPORT_STATE_TO_UAVOBJECT_IF_UPDATED_3_DIMENSIONS(PositionState, pos, North, East, Down);
@ -525,6 +554,14 @@ static void sensorUpdatedCb(UAVObjEvent *ev)
if (ev->obj == GyroSensorHandle()) {
updatedSensors |= SENSORUPDATES_gyro;
// shortcut - update GyroState right away
GyroSensorData s;
GyroStateData t;
GyroSensorGet(&s);
t.x = s.x + gyroDelta[0];
t.y = s.y + gyroDelta[1];
t.z = s.z + gyroDelta[2];
GyroStateSet(&t);
}
if (ev->obj == AccelSensorHandle()) {

View File

@ -41,7 +41,21 @@
// Private constants
#define MAX_QUEUE_SIZE TELEM_QUEUE_SIZE
#define STACK_SIZE_BYTES PIOS_TELEM_STACK_SIZE
// Three different stack size parameter are accepted for Telemetry(RX PIOS_TELEM_RX_STACK_SIZE)
// Tx(PIOS_TELEM_TX_STACK_SIZE) and Radio RX(PIOS_TELEM_RADIO_RX_STACK_SIZE)
#ifdef PIOS_TELEM_RX_STACK_SIZE
#define STACK_SIZE_RX_BYTES PIOS_TELEM_RX_STACK_SIZE
#define STACK_SIZE_TX_BYTES PIOS_TELEM_TX_STACK_SIZE
#else
#define STACK_SIZE_RX_BYTES PIOS_TELEM_STACK_SIZE
#define STACK_SIZE_TX_BYTES PIOS_TELEM_STACK_SIZE
#endif
#ifdef PIOS_TELEM_RADIO_RX_STACK_SIZE
#define STACK_SIZE_RADIO_RX_BYTES PIOS_TELEM_RADIO_RX_STACK_SIZE
#else
#define STACK_SIZE_RADIO_RX_BYTES STACK_SIZE_RX_BYTES
#endif
#define TASK_PRIORITY_RX (tskIDLE_PRIORITY + 2)
#define TASK_PRIORITY_TX (tskIDLE_PRIORITY + 2)
#define TASK_PRIORITY_RADRX (tskIDLE_PRIORITY + 2)
@ -110,13 +124,13 @@ int32_t TelemetryStart(void)
GCSTelemetryStatsConnectQueue(priorityQueue);
// Start telemetry tasks
xTaskCreate(telemetryTxTask, (signed char *)"TelTx", STACK_SIZE_BYTES / 4, NULL, TASK_PRIORITY_TX, &telemetryTxTaskHandle);
xTaskCreate(telemetryTxTask, (signed char *)"TelTx", STACK_SIZE_TX_BYTES / 4, NULL, TASK_PRIORITY_TX, &telemetryTxTaskHandle);
PIOS_TASK_MONITOR_RegisterTask(TASKINFO_RUNNING_TELEMETRYTX, telemetryTxTaskHandle);
xTaskCreate(telemetryRxTask, (signed char *)"TelRx", STACK_SIZE_BYTES / 4, NULL, TASK_PRIORITY_RX, &telemetryRxTaskHandle);
xTaskCreate(telemetryRxTask, (signed char *)"TelRx", STACK_SIZE_RX_BYTES / 4, NULL, TASK_PRIORITY_RX, &telemetryRxTaskHandle);
PIOS_TASK_MONITOR_RegisterTask(TASKINFO_RUNNING_TELEMETRYRX, telemetryRxTaskHandle);
#ifdef PIOS_INCLUDE_RFM22B
xTaskCreate(radioRxTask, (signed char *)"RadioRx", STACK_SIZE_BYTES / 4, NULL, TASK_PRIORITY_RADRX, &radioRxTaskHandle);
xTaskCreate(radioRxTask, (signed char *)"RadioRx", STACK_SIZE_RADIO_RX_BYTES / 4, NULL, TASK_PRIORITY_RADRX, &radioRxTaskHandle);
PIOS_TASK_MONITOR_RegisterTask(TASKINFO_RUNNING_RADIORX, radioRxTaskHandle);
#endif
@ -391,7 +405,6 @@ static void telemetryTxTask(__attribute__((unused)) void *parameters)
if (xQueueReceive(queue, &ev, 0) == pdTRUE) {
// Process event
processObjEvent(&ev);
// if both queues are empty, wait on priority queue for updates (1 tick) then repeat cycle
} else if (xQueueReceive(priorityQueue, &ev, 1) == pdTRUE) {
// Process event
@ -458,8 +471,6 @@ static void radioRxTask(__attribute__((unused)) void *parameters)
}
}
}
/**
* Transmit data buffer to the radioport.
* \param[in] data Data buffer to send

View File

@ -101,7 +101,6 @@ static void updatePathVelocity();
static void updateEndpointVelocity();
static void updateFixedAttitude(float *attitude);
static void updateVtolDesiredAttitude(bool yaw_attitude);
static float bound(float val, float min, float max);
static bool vtolpathfollower_enabled;
static void accessoryUpdated(UAVObjEvent *ev);
@ -140,6 +139,7 @@ int32_t VtolPathFollowerInitialize()
AccessoryDesiredInitialize();
PoiLearnSettingsInitialize();
PoiLocationInitialize();
HomeLocationInitialize();
vtolpathfollower_enabled = true;
} else {
vtolpathfollower_enabled = false;
@ -159,6 +159,7 @@ static float eastPosIntegral = 0;
static float downPosIntegral = 0;
static float thrustOffset = 0;
static float gravity;
/**
* Module thread, should not return.
*/
@ -182,6 +183,7 @@ static void vtolPathFollowerTask(__attribute__((unused)) void *parameters)
// 2. Flight mode is PositionHold and PathDesired.Mode is Endpoint OR
// FlightMode is PathPlanner and PathDesired.Mode is Endpoint or Path
HomeLocationg_eGet(&gravity);
SystemSettingsGet(&systemSettings);
if ((systemSettings.AirframeType != SYSTEMSETTINGS_AIRFRAMETYPE_VTOL) && (systemSettings.AirframeType != SYSTEMSETTINGS_AIRFRAMETYPE_QUADP)
&& (systemSettings.AirframeType != SYSTEMSETTINGS_AIRFRAMETYPE_OCTOCOAXX) && (systemSettings.AirframeType != SYSTEMSETTINGS_AIRFRAMETYPE_QUADX)
@ -394,7 +396,7 @@ static void updatePathVelocity()
break;
case PATHDESIRED_MODE_FLYENDPOINT:
case PATHDESIRED_MODE_DRIVEENDPOINT:
groundspeed = pathDesired.EndingVelocity - pathDesired.EndingVelocity * bound(progress.fractional_progress, 0, 1);
groundspeed = pathDesired.EndingVelocity - pathDesired.EndingVelocity * boundf(progress.fractional_progress, 0, 1);
if (progress.fractional_progress > 1) {
groundspeed = 0;
}
@ -403,7 +405,7 @@ static void updatePathVelocity()
case PATHDESIRED_MODE_DRIVEVECTOR:
default:
groundspeed = pathDesired.StartingVelocity
+ (pathDesired.EndingVelocity - pathDesired.StartingVelocity) * bound(progress.fractional_progress, 0, 1);
+ (pathDesired.EndingVelocity - pathDesired.StartingVelocity) * boundf(progress.fractional_progress, 0, 1);
if (progress.fractional_progress > 1) {
groundspeed = 0;
}
@ -427,14 +429,14 @@ static void updatePathVelocity()
velocityDesired.North += progress.correction_direction[0] * error_speed * scale;
velocityDesired.East += progress.correction_direction[1] * error_speed * scale;
float altitudeSetpoint = pathDesired.Start.Down + (pathDesired.End.Down - pathDesired.Start.Down) * bound(progress.fractional_progress, 0, 1);
float altitudeSetpoint = pathDesired.Start.Down + (pathDesired.End.Down - pathDesired.Start.Down) * boundf(progress.fractional_progress, 0, 1);
float downError = altitudeSetpoint - positionState.Down;
downPosIntegral = bound(downPosIntegral + downError * dT * vtolpathfollowerSettings.VerticalPosPI.Ki,
downPosIntegral = boundf(downPosIntegral + downError * dT * vtolpathfollowerSettings.VerticalPosPI.Ki,
-vtolpathfollowerSettings.VerticalPosPI.ILimit,
vtolpathfollowerSettings.VerticalPosPI.ILimit);
downCommand = (downError * vtolpathfollowerSettings.VerticalPosPI.Kp + downPosIntegral);
velocityDesired.Down = bound(downCommand, -vtolpathfollowerSettings.VerticalVelMax, vtolpathfollowerSettings.VerticalVelMax);
velocityDesired.Down = boundf(downCommand, -vtolpathfollowerSettings.VerticalVelMax, vtolpathfollowerSettings.VerticalVelMax);
// update pathstatus
pathStatus.error = progress.error;
@ -470,49 +472,15 @@ void updateEndpointVelocity()
float eastCommand;
float downCommand;
float northPos = 0, eastPos = 0, downPos = 0;
switch (vtolpathfollowerSettings.PositionSource) {
case VTOLPATHFOLLOWERSETTINGS_POSITIONSOURCE_EKF:
northPos = positionState.North;
eastPos = positionState.East;
downPos = positionState.Down;
break;
case VTOLPATHFOLLOWERSETTINGS_POSITIONSOURCE_GPSPOS:
{
// this used to work with the NEDposition UAVObject
// however this UAVObject has been removed
GPSPositionSensorData gpsPosition;
GPSPositionSensorGet(&gpsPosition);
HomeLocationData homeLocation;
HomeLocationGet(&homeLocation);
float lat = DEG2RAD(homeLocation.Latitude / 10.0e6f);
float alt = homeLocation.Altitude;
float T[3] = { alt + 6.378137E6f,
cosf(lat) * (alt + 6.378137E6f),
-1.0f };
float NED[3] = { T[0] * (DEG2RAD((gpsPosition.Latitude - homeLocation.Latitude) / 10.0e6f)),
T[1] * (DEG2RAD((gpsPosition.Longitude - homeLocation.Longitude) / 10.0e6f)),
T[2] * ((gpsPosition.Altitude + gpsPosition.GeoidSeparation - homeLocation.Altitude)) };
northPos = NED[0];
eastPos = NED[1];
downPos = NED[2];
}
break;
default:
PIOS_Assert(0);
break;
}
// Compute desired north command
northError = pathDesired.End.North - northPos;
northPosIntegral = bound(northPosIntegral + northError * dT * vtolpathfollowerSettings.HorizontalPosPI.Ki,
northError = pathDesired.End.North - positionState.North;
northPosIntegral = boundf(northPosIntegral + northError * dT * vtolpathfollowerSettings.HorizontalPosPI.Ki,
-vtolpathfollowerSettings.HorizontalPosPI.ILimit,
vtolpathfollowerSettings.HorizontalPosPI.ILimit);
northCommand = (northError * vtolpathfollowerSettings.HorizontalPosPI.Kp + northPosIntegral);
eastError = pathDesired.End.East - eastPos;
eastPosIntegral = bound(eastPosIntegral + eastError * dT * vtolpathfollowerSettings.HorizontalPosPI.Ki,
eastError = pathDesired.End.East - positionState.East;
eastPosIntegral = boundf(eastPosIntegral + eastError * dT * vtolpathfollowerSettings.HorizontalPosPI.Ki,
-vtolpathfollowerSettings.HorizontalPosPI.ILimit,
vtolpathfollowerSettings.HorizontalPosPI.ILimit);
eastCommand = (eastError * vtolpathfollowerSettings.HorizontalPosPI.Kp + eastPosIntegral);
@ -527,12 +495,12 @@ void updateEndpointVelocity()
velocityDesired.North = northCommand * scale;
velocityDesired.East = eastCommand * scale;
downError = pathDesired.End.Down - downPos;
downPosIntegral = bound(downPosIntegral + downError * dT * vtolpathfollowerSettings.VerticalPosPI.Ki,
downError = pathDesired.End.Down - positionState.Down;
downPosIntegral = boundf(downPosIntegral + downError * dT * vtolpathfollowerSettings.VerticalPosPI.Ki,
-vtolpathfollowerSettings.VerticalPosPI.ILimit,
vtolpathfollowerSettings.VerticalPosPI.ILimit);
downCommand = (downError * vtolpathfollowerSettings.VerticalPosPI.Kp + downPosIntegral);
velocityDesired.Down = bound(downCommand, -vtolpathfollowerSettings.VerticalVelMax, vtolpathfollowerSettings.VerticalVelMax);
velocityDesired.Down = boundf(downCommand, -vtolpathfollowerSettings.VerticalVelMax, vtolpathfollowerSettings.VerticalVelMax);
VelocityDesiredSet(&velocityDesired);
}
@ -553,6 +521,7 @@ static void updateFixedAttitude(float *attitude)
stabDesired.StabilizationMode.Roll = STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE;
stabDesired.StabilizationMode.Pitch = STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE;
stabDesired.StabilizationMode.Yaw = STABILIZATIONDESIRED_STABILIZATIONMODE_AXISLOCK;
stabDesired.StabilizationMode.Thrust = STABILIZATIONDESIRED_STABILIZATIONMODE_MANUAL;
StabilizationDesiredSet(&stabDesired);
}
@ -595,12 +564,12 @@ static void updateVtolDesiredAttitude(bool yaw_attitude)
float northVel = 0, eastVel = 0, downVel = 0;
switch (vtolpathfollowerSettings.VelocitySource) {
case VTOLPATHFOLLOWERSETTINGS_VELOCITYSOURCE_EKF:
case VTOLPATHFOLLOWERSETTINGS_VELOCITYSOURCE_STATE_ESTIMATION:
northVel = velocityState.North;
eastVel = velocityState.East;
downVel = velocityState.Down;
break;
case VTOLPATHFOLLOWERSETTINGS_VELOCITYSOURCE_NEDVEL:
case VTOLPATHFOLLOWERSETTINGS_VELOCITYSOURCE_GPS_VELNED:
{
GPSVelocitySensorData gpsVelocity;
GPSVelocitySensorGet(&gpsVelocity);
@ -609,7 +578,7 @@ static void updateVtolDesiredAttitude(bool yaw_attitude)
downVel = gpsVelocity.Down;
}
break;
case VTOLPATHFOLLOWERSETTINGS_VELOCITYSOURCE_GPSPOS:
case VTOLPATHFOLLOWERSETTINGS_VELOCITYSOURCE_GPS_GROUNDSPEED:
{
GPSPositionSensorData gpsPosition;
GPSPositionSensorGet(&gpsPosition);
@ -629,7 +598,7 @@ static void updateVtolDesiredAttitude(bool yaw_attitude)
// Compute desired north command
northError = velocityDesired.North - northVel;
northVelIntegral = bound(northVelIntegral + northError * dT * vtolpathfollowerSettings.HorizontalVelPID.Ki,
northVelIntegral = boundf(northVelIntegral + northError * dT * vtolpathfollowerSettings.HorizontalVelPID.Ki,
-vtolpathfollowerSettings.HorizontalVelPID.ILimit,
vtolpathfollowerSettings.HorizontalVelPID.ILimit);
northCommand = (northError * vtolpathfollowerSettings.HorizontalVelPID.Kp + northVelIntegral
@ -638,7 +607,7 @@ static void updateVtolDesiredAttitude(bool yaw_attitude)
// Compute desired east command
eastError = velocityDesired.East - eastVel;
eastVelIntegral = bound(eastVelIntegral + eastError * dT * vtolpathfollowerSettings.HorizontalVelPID.Ki,
eastVelIntegral = boundf(eastVelIntegral + eastError * dT * vtolpathfollowerSettings.HorizontalVelPID.Ki,
-vtolpathfollowerSettings.HorizontalVelPID.ILimit,
vtolpathfollowerSettings.HorizontalVelPID.ILimit);
eastCommand = (eastError * vtolpathfollowerSettings.HorizontalVelPID.Kp + eastVelIntegral
@ -649,20 +618,20 @@ static void updateVtolDesiredAttitude(bool yaw_attitude)
downError = velocityDesired.Down - downVel;
// Must flip this sign
downError = -downError;
downVelIntegral = bound(downVelIntegral + downError * dT * vtolpathfollowerSettings.VerticalVelPID.Ki,
downVelIntegral = boundf(downVelIntegral + downError * dT * vtolpathfollowerSettings.VerticalVelPID.Ki,
-vtolpathfollowerSettings.VerticalVelPID.ILimit,
vtolpathfollowerSettings.VerticalVelPID.ILimit);
downCommand = (downError * vtolpathfollowerSettings.VerticalVelPID.Kp + downVelIntegral
- nedAccel.Down * vtolpathfollowerSettings.VerticalVelPID.Kd);
stabDesired.Thrust = bound(downCommand + thrustOffset, 0, 1);
stabDesired.Thrust = boundf(downCommand + thrustOffset, 0, 1);
// Project the north and east command signals into the pitch and roll based on yaw. For this to behave well the
// craft should move similarly for 5 deg roll versus 5 deg pitch
stabDesired.Pitch = bound(-northCommand * cosf(DEG2RAD(attitudeState.Yaw)) +
stabDesired.Pitch = boundf(-northCommand * cosf(DEG2RAD(attitudeState.Yaw)) +
-eastCommand * sinf(DEG2RAD(attitudeState.Yaw)),
-vtolpathfollowerSettings.MaxRollPitch, vtolpathfollowerSettings.MaxRollPitch);
stabDesired.Roll = bound(-northCommand * sinf(DEG2RAD(attitudeState.Yaw)) +
stabDesired.Roll = boundf(-northCommand * sinf(DEG2RAD(attitudeState.Yaw)) +
eastCommand * cosf(DEG2RAD(attitudeState.Yaw)),
-vtolpathfollowerSettings.MaxRollPitch, vtolpathfollowerSettings.MaxRollPitch);
@ -681,6 +650,7 @@ static void updateVtolDesiredAttitude(bool yaw_attitude)
stabDesired.StabilizationMode.Yaw = STABILIZATIONDESIRED_STABILIZATIONMODE_AXISLOCK;
stabDesired.Yaw = stabSettings.MaximumRate.Yaw * manualControlData.Yaw;
}
stabDesired.StabilizationMode.Thrust = STABILIZATIONDESIRED_STABILIZATIONMODE_MANUAL;
StabilizationDesiredSet(&stabDesired);
}
@ -716,7 +686,7 @@ static void updateNedAccel()
accel_ned[i] += Rbe[j][i] * accel[j];
}
}
accel_ned[2] += 9.81f;
accel_ned[2] += gravity;
NedAccelData accelData;
NedAccelGet(&accelData);
@ -726,19 +696,6 @@ static void updateNedAccel()
NedAccelSet(&accelData);
}
/**
* Bound input value between limits
*/
static float bound(float val, float min, float max)
{
if (val < min) {
val = min;
} else if (val > max) {
val = max;
}
return val;
}
static void SettingsUpdatedCb(__attribute__((unused)) UAVObjEvent *ev)
{
VtolPathFollowerSettingsGet(&vtolpathfollowerSettings);

View File

@ -33,7 +33,7 @@
// Private constants
#define STACK_SAFETYCOUNT 16
#define STACK_SIZE (384 + STACK_SAFETYSIZE)
#define STACK_SIZE (190 + STACK_SAFETYSIZE)
#define STACK_SAFETYSIZE 8
#define MAX_SLEEP 1000

View File

@ -34,10 +34,6 @@
#ifdef PIOS_INCLUDE_MS4525DO
/* Local Defs and Variables */
static int8_t PIOS_MS4525DO_ReadI2C(uint8_t *buffer, uint8_t len);
static int8_t PIOS_MS4525DO_WriteI2C(uint8_t *buffer, uint8_t len);
static bool pios_ms4525do_requested = false;
static int8_t PIOS_MS4525DO_ReadI2C(uint8_t *buffer, uint8_t len)
@ -56,50 +52,15 @@ static int8_t PIOS_MS4525DO_ReadI2C(uint8_t *buffer, uint8_t len)
}
static int8_t PIOS_MS4525DO_WriteI2C(uint8_t *buffer, uint8_t len)
{
const struct pios_i2c_txn txn_list[] = {
{
.info = __func__,
.addr = MS4525DO_I2C_ADDR,
.rw = PIOS_I2C_TXN_WRITE,
.len = len,
.buf = buffer,
}
};
return PIOS_I2C_Transfer(PIOS_I2C_MS4525DO_ADAPTER, txn_list, NELEMENTS(txn_list));
}
int8_t PIOS_MS4525DO_Request(void)
{
// MS4525DO expects a zero length write.
// Sending one byte is a workaround that works for the moment
uint8_t data = 0;
int8_t retVal = PIOS_MS4525DO_WriteI2C(&data, sizeof(data));
/* requested only when transfer worked */
pios_ms4525do_requested = (retVal == 0);
return retVal;
}
// values has to ba an arrray with two elements
// values stay untouched on error
int8_t PIOS_MS4525DO_Read(uint16_t *values)
{
if (!pios_ms4525do_requested) {
/* Do not try to read when not requested */
/* else probably stale data will be obtained */
return -4;
}
uint8_t data[4];
int8_t retVal = PIOS_MS4525DO_ReadI2C(data, sizeof(data));
uint8_t status = data[0] & 0xC0;
if (status == 0x80) {
/* stale data */
return -5;
@ -117,9 +78,6 @@ int8_t PIOS_MS4525DO_Read(uint16_t *values)
values[1] += data[3];
values[1] = (values[1] >> 5);
/* not requested anymore, only when transfer worked */
pios_ms4525do_requested = !(retVal == 0);
return retVal;
}

View File

@ -139,7 +139,11 @@ static const uint8_t FULL_PREAMBLE[FIFO_SIZE] = {
PREAMBLE_BYTE, PREAMBLE_BYTE, PREAMBLE_BYTE, PREAMBLE_BYTE, PREAMBLE_BYTE,
PREAMBLE_BYTE, PREAMBLE_BYTE, PREAMBLE_BYTE, PREAMBLE_BYTE
}; // 64 bytes
static const uint8_t HEADER[(TX_PREAMBLE_NIBBLES + 1) / 2 + 2] = { PREAMBLE_BYTE, PREAMBLE_BYTE, PREAMBLE_BYTE, PREAMBLE_BYTE, PREAMBLE_BYTE, PREAMBLE_BYTE, SYNC_BYTE_1, SYNC_BYTE_2 };
static const uint8_t HEADER[(TX_PREAMBLE_NIBBLES + 1) / 2 + 2] = {
PREAMBLE_BYTE, PREAMBLE_BYTE, PREAMBLE_BYTE, PREAMBLE_BYTE, PREAMBLE_BYTE, PREAMBLE_BYTE, SYNC_BYTE_1, SYNC_BYTE_2
};
static const uint8_t OUT_FF[64] = {
0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
@ -150,8 +154,21 @@ static const uint8_t OUT_FF[64] = {
0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF
};
// The randomized channel list.
static const uint8_t channel_list[] = { 68, 34, 2, 184, 166, 94, 204, 18, 47, 118, 239, 176, 5, 213, 218, 186, 104, 160, 199, 209, 231, 197, 92, 191, 88, 129, 40, 19, 93, 200, 156, 14, 247, 182, 193, 194, 208, 210, 248, 76, 244, 48, 179, 105, 25, 74, 155, 203, 39, 97, 195, 81, 83, 180, 134, 172, 235, 132, 198, 119, 207, 154, 0, 61, 140, 171, 245, 26, 95, 3, 22, 62, 169, 55, 127, 144, 45, 33, 170, 91, 158, 167, 63, 201, 41, 21, 190, 51, 103, 49, 189, 205, 240, 89, 181, 149, 6, 157, 249, 230, 115, 72, 163, 17, 29, 99, 28, 117, 219, 73, 78, 53, 69, 216, 161, 124, 110, 242, 214, 145, 13, 11, 220, 113, 138, 58, 54, 162, 237, 37, 152, 187, 232, 77, 126, 85, 38, 238, 173, 23, 188, 100, 131, 226, 31, 9, 114, 106, 221, 42, 233, 139, 4, 241, 96, 211, 8, 98, 121, 147, 24, 217, 27, 87, 122, 125, 135, 148, 178, 71, 206, 57, 141, 35, 30, 246, 159, 16, 32, 15, 229, 20, 12, 223, 150, 101, 79, 56, 102, 111, 174, 236, 137, 143, 52, 225, 64, 224, 112, 168, 243, 130, 108, 202, 123, 146, 228, 75, 46, 153, 7, 192, 175, 151, 222, 59, 82, 90, 1, 65, 109, 44, 165, 84, 43, 36, 128, 196, 67, 80, 136, 86, 70, 234, 66, 185, 10, 164, 177, 116, 50, 107, 183, 215, 212, 60, 227, 133, 120, 142 };
static const uint8_t channel_list[] = {
68, 34, 2, 184, 166, 94, 204, 18, 47, 118, 239, 176, 5, 213, 218, 186, 104, 160, 199, 209, 231, 197, 92,
191, 88, 129, 40, 19, 93, 200, 156, 14, 247, 182, 193, 194, 208, 210, 248, 76, 244, 48, 179, 105, 25, 74,
155, 203, 39, 97, 195, 81, 83, 180, 134, 172, 235, 132, 198, 119, 207, 154, 0, 61, 140, 171, 245, 26, 95,
3, 22, 62, 169, 55, 127, 144, 45, 33, 170, 91, 158, 167, 63, 201, 41, 21, 190, 51, 103, 49, 189, 205,
240, 89, 181, 149, 6, 157, 249, 230, 115, 72, 163, 17, 29, 99, 28, 117, 219, 73, 78, 53, 69, 216, 161,
124, 110, 242, 214, 145, 13, 11, 220, 113, 138, 58, 54, 162, 237, 37, 152, 187, 232, 77, 126, 85, 38, 238,
173, 23, 188, 100, 131, 226, 31, 9, 114, 106, 221, 42, 233, 139, 4, 241, 96, 211, 8, 98, 121, 147, 24,
217, 27, 87, 122, 125, 135, 148, 178, 71, 206, 57, 141, 35, 30, 246, 159, 16, 32, 15, 229, 20, 12, 223,
150, 101, 79, 56, 102, 111, 174, 236, 137, 143, 52, 225, 64, 224, 112, 168, 243, 130, 108, 202, 123, 146, 228,
75, 46, 153, 7, 192, 175, 151, 222, 59, 82, 90, 1, 65, 109, 44, 165, 84, 43, 36, 128, 196, 67, 80,
136, 86, 70, 234, 66, 185, 10, 164, 177, 116, 50, 107, 183, 215, 212, 60, 227, 133, 120, 14
};
/* Local function forwared declarations */
static void pios_rfm22_task(void *parameters);

View File

@ -92,6 +92,10 @@ struct pios_i2c_adapter {
uint8_t busy;
#endif
/* variables for transfer timeouts */
uint32_t transfer_delay_uS; // approx time to transfer one byte, calculated later basen on setting use here time based on 100 kbits/s
uint32_t transfer_timeout_ticks; // take something tha makes sense for small transaction, calculated later based upon transmission desired
bool bus_error;
bool nack;

View File

@ -29,25 +29,24 @@
/* -------------- Buffer Description Table -----------------*/
/*-------------------------------------------------------------*/
/* buffer table base address */
/* buffer table base address */
#define BTABLE_ADDRESS (0x00)
/* EP0 */
/* EP0 (Control) */
/* rx/tx buffer base address */
#define ENDP0_RXADDR (0x20)
#define ENDP0_TXADDR (0x40)
/* EP1 */
/* EP1 (HID) */
/* rx/tx buffer base address */
#define ENDP1_TXADDR (0x60)
#define ENDP1_RXADDR (0x80)
#define ENDP1_RXADDR (0xA0)
/* EP2 */
/* EP2 (CDC Call Control) */
/* rx/tx buffer base address */
#define ENDP2_TXADDR (0x100)
#define ENDP2_RXADDR (0x140)
/* EP3 */
/* EP3 (CDC Data) */
/* rx/tx buffer base address */
#define ENDP3_TXADDR (0x180)
#define ENDP3_RXADDR (0x1C0)

View File

@ -933,9 +933,9 @@ int32_t PIOS_I2C_Transfer(uint32_t i2c_id, const struct pios_i2c_txn txn_list[],
{
struct pios_i2c_adapter *i2c_adapter = (struct pios_i2c_adapter *)i2c_id;
bool valid = PIOS_I2C_validate(i2c_adapter);
PIOS_Assert(valid)
if (!PIOS_I2C_validate(i2c_adapter)) {
return -1;
}
PIOS_DEBUG_Assert(txn_list);
PIOS_DEBUG_Assert(num_txns);
@ -977,6 +977,14 @@ int32_t PIOS_I2C_Transfer(uint32_t i2c_id, const struct pios_i2c_txn txn_list[],
semaphore_success &= (xSemaphoreTake(i2c_adapter->sem_ready, timeout) == pdTRUE);
#endif
// Estimate bytes of transmission. Per txns: 1 adress byte + length
i2c_adapter->transfer_timeout_ticks = num_txns;
for (uint32_t i = 0; i < num_txns; i++) {
i2c_adapter->transfer_timeout_ticks += txn_list[i].len;
}
// timeout if it takes eight times the expected time
i2c_adapter->transfer_timeout_ticks <<= 3;
i2c_adapter->bus_error = false;
i2c_adapter_inject_event(i2c_adapter, I2C_EVENT_START);
@ -992,7 +1000,15 @@ int32_t PIOS_I2C_Transfer(uint32_t i2c_id, const struct pios_i2c_txn txn_list[],
/* Spin waiting for the transfer to finish */
while (!i2c_adapter_fsm_terminated(i2c_adapter)) {
;
/* sleep 9 clock ticks (1 byte), because FSM can't be faster than one byte
FIXME: clock streching could make problems, but citing NPX: alsmost no slave device implements clock stretching
three times the expected time should cover clock delay */
PIOS_DELAY_WaituS(i2c_adapter->transfer_delay_uS);
i2c_adapter->transfer_timeout_ticks--;
if (i2c_adapter->transfer_timeout_ticks == 0) {
break;
}
}
if (i2c_adapter_wait_for_stopped(i2c_adapter)) {
@ -1019,9 +1035,9 @@ void PIOS_I2C_EV_IRQ_Handler(uint32_t i2c_id)
{
struct pios_i2c_adapter *i2c_adapter = (struct pios_i2c_adapter *)i2c_id;
bool valid = PIOS_I2C_validate(i2c_adapter);
PIOS_Assert(valid)
if (!PIOS_I2C_validate(i2c_adapter)) {
return;
}
uint32_t event = I2C_GetLastEvent(i2c_adapter->cfg->regs);
@ -1145,9 +1161,10 @@ void PIOS_I2C_ER_IRQ_Handler(uint32_t i2c_id)
{
struct pios_i2c_adapter *i2c_adapter = (struct pios_i2c_adapter *)i2c_id;
bool valid = PIOS_I2C_validate(i2c_adapter);
if (!PIOS_I2C_validate(i2c_adapter)) {
return;
}
PIOS_Assert(valid)
#if defined(PIOS_I2C_DIAGNOSTICS)
uint32_t event = I2C_GetLastEvent(i2c_adapter->cfg->regs);

View File

@ -32,8 +32,6 @@
/* Includes ------------------------------------------------------------------*/
#include "stm32f4xx.h"
#include "usb_conf.h"
/** @addtogroup USB_OTG_DRIVER
* @{
*/

View File

@ -754,6 +754,11 @@ static void i2c_adapter_reset_bus(struct pios_i2c_adapter *i2c_adapter)
/* Initialize the I2C block */
I2C_Init(i2c_adapter->cfg->regs, (I2C_InitTypeDef *)&(i2c_adapter->cfg->init));
// for delays during transfer timeouts
// one tick correspond to transmission of 1 byte i.e. 9 clock ticks
i2c_adapter->transfer_delay_uS = 9000000 / (((I2C_InitTypeDef *)&(i2c_adapter->cfg->init))->I2C_ClockSpeed);
if (i2c_adapter->cfg->regs->SR2 & I2C_FLAG_BUSY) {
/* Reset the I2C block */
I2C_SoftwareResetCmd(i2c_adapter->cfg->regs, ENABLE);
@ -761,7 +766,6 @@ static void i2c_adapter_reset_bus(struct pios_i2c_adapter *i2c_adapter)
}
}
#include <pios_i2c_priv.h>
/* Return true if the FSM is in a terminal state */
static bool i2c_adapter_fsm_terminated(struct pios_i2c_adapter *i2c_adapter)
@ -789,9 +793,18 @@ static bool i2c_adapter_callback_handler(struct pios_i2c_adapter *i2c_adapter)
xSemaphoreGive(i2c_adapter->sem_ready);
#endif /* USE_FREERTOS */
/* transfer_timeout_ticks is set by PIOS_I2C_Transfer_Callback */
/* Spin waiting for the transfer to finish */
while (!i2c_adapter_fsm_terminated(i2c_adapter)) {
;
// sleep 1 byte, as FSM can't be faster
// FIXME: clock stretching could make problems, but citing NPX: alsmost no slave device implements clock stretching
// three times the expected time should cover clock delay
PIOS_DELAY_WaituS(i2c_adapter->transfer_delay_uS);
i2c_adapter->transfer_timeout_ticks--;
if (i2c_adapter->transfer_timeout_ticks == 0) {
break;
}
}
if (i2c_adapter_wait_for_stopped(i2c_adapter)) {
@ -957,6 +970,7 @@ int32_t PIOS_I2C_Init(uint32_t *i2c_id, const struct pios_i2c_adapter_cfg *cfg)
NVIC_Init((NVIC_InitTypeDef *)&(i2c_adapter->cfg->event.init));
NVIC_Init((NVIC_InitTypeDef *)&(i2c_adapter->cfg->error.init));
/* No error */
return 0;
@ -968,9 +982,9 @@ int32_t PIOS_I2C_Transfer(uint32_t i2c_id, const struct pios_i2c_txn txn_list[],
{
struct pios_i2c_adapter *i2c_adapter = (struct pios_i2c_adapter *)i2c_id;
bool valid = PIOS_I2C_validate(i2c_adapter);
PIOS_Assert(valid)
if (!PIOS_I2C_validate(i2c_adapter)) {
return -1;
}
PIOS_DEBUG_Assert(txn_list);
PIOS_DEBUG_Assert(num_txns);
@ -1005,6 +1019,14 @@ int32_t PIOS_I2C_Transfer(uint32_t i2c_id, const struct pios_i2c_txn txn_list[],
semaphore_success &= (xSemaphoreTake(i2c_adapter->sem_ready, timeout) == pdTRUE);
#endif
// Estimate bytes of transmission. Per txns: 1 adress byte + length
i2c_adapter->transfer_timeout_ticks = num_txns;
for (uint32_t i = 0; i < num_txns; i++) {
i2c_adapter->transfer_timeout_ticks += txn_list[i].len;
}
// timeout if it takes eight times the expected time
i2c_adapter->transfer_timeout_ticks <<= 3;
i2c_adapter->callback = NULL;
i2c_adapter->bus_error = false;
i2c_adapter->nack = false;
@ -1018,7 +1040,15 @@ int32_t PIOS_I2C_Transfer(uint32_t i2c_id, const struct pios_i2c_txn txn_list[],
/* Spin waiting for the transfer to finish */
while (!i2c_adapter_fsm_terminated(i2c_adapter)) {
;
/* sleep 9 clock ticks (1 byte), because FSM can't be faster than one byte
FIXME: clock stretching could make problems, but citing NPX: alsmost no slave device implements clock stretching
three times the expected time should cover clock delay */
PIOS_DELAY_WaituS(i2c_adapter->transfer_delay_uS);
i2c_adapter->transfer_timeout_ticks--;
if (i2c_adapter->transfer_timeout_ticks == 0) {
break;
}
}
if (i2c_adapter_wait_for_stopped(i2c_adapter)) {
@ -1049,9 +1079,10 @@ int32_t PIOS_I2C_Transfer_Callback(uint32_t i2c_id, const struct pios_i2c_txn tx
{
struct pios_i2c_adapter *i2c_adapter = (struct pios_i2c_adapter *)i2c_id;
bool valid = PIOS_I2C_validate(i2c_adapter);
if (!PIOS_I2C_validate(i2c_adapter)) {
return -1;
}
PIOS_Assert(valid)
PIOS_Assert(callback);
PIOS_DEBUG_Assert(txn_list);
@ -1084,6 +1115,15 @@ int32_t PIOS_I2C_Transfer_Callback(uint32_t i2c_id, const struct pios_i2c_txn tx
semaphore_success &= (xSemaphoreTake(i2c_adapter->sem_ready, timeout) == pdTRUE);
#endif
// used in the i2c_adapter_callback_handler function
// Estimate bytes of transmission. Per txns: 1 adress byte + length
i2c_adapter->transfer_timeout_ticks = num_txns;
for (uint32_t i = 0; i < num_txns; i++) {
i2c_adapter->transfer_timeout_ticks += txn_list[i].len;
}
// timeout if it takes eight times the expected time
i2c_adapter->transfer_timeout_ticks <<= 3;
i2c_adapter->callback = callback;
i2c_adapter->bus_error = false;
i2c_adapter_inject_event(i2c_adapter, I2C_EVENT_START);
@ -1095,9 +1135,9 @@ void PIOS_I2C_EV_IRQ_Handler(uint32_t i2c_id)
{
struct pios_i2c_adapter *i2c_adapter = (struct pios_i2c_adapter *)i2c_id;
bool valid = PIOS_I2C_validate(i2c_adapter);
PIOS_Assert(valid)
if (!PIOS_I2C_validate(i2c_adapter)) {
return;
}
uint32_t event = I2C_GetLastEvent(i2c_adapter->cfg->regs);
@ -1205,9 +1245,9 @@ void PIOS_I2C_EV_IRQ_Handler(uint32_t i2c_id)
/* Ignore this event and wait for TRANSMITTED in case we can't keep up */
goto skip_event;
break;
case 0x30084: /* Occurs between byte tranmistted and master mode selected */
case 0x30000: /* Need to throw away this spurious event */
case 0x30403 & EVENT_MASK: /* Detected this after got a NACK, probably stop bit */
case 0x30084: /* BUSY + MSL + TXE + BFT Occurs between byte transmitted and master mode selected */
case 0x30000: /* BUSY + MSL Need to throw away this spurious event */
case 0x30403 & EVENT_MASK: /* BUSY + MSL + SB + ADDR Detected this after got a NACK, probably stop bit */
goto skip_event;
break;
default:
@ -1228,16 +1268,15 @@ void PIOS_I2C_ER_IRQ_Handler(uint32_t i2c_id)
{
struct pios_i2c_adapter *i2c_adapter = (struct pios_i2c_adapter *)i2c_id;
bool valid = PIOS_I2C_validate(i2c_adapter);
if (!PIOS_I2C_validate(i2c_adapter)) {
return;
}
PIOS_Assert(valid)
#if defined(PIOS_I2C_DIAGNOSTICS)
uint32_t event = I2C_GetLastEvent(i2c_adapter->cfg->regs);
#if defined(PIOS_I2C_DIAGNOSTICS)
i2c_erirq_history[i2c_erirq_history_pointer] = event;
i2c_erirq_history_pointer = (i2c_erirq_history_pointer + 1) % 5;
#endif
if (event & I2C_FLAG_AF) {

View File

@ -31,6 +31,7 @@
#ifndef PIOS_USB_BOARD_DATA_H
#define PIOS_USB_BOARD_DATA_H
// Note : changing below length will require changes to the USB buffer setup
#define PIOS_USB_BOARD_HID_DATA_LENGTH 64
#define PIOS_USB_BOARD_EP_NUM 2

View File

@ -91,6 +91,7 @@ ifndef TESTAPP
SRC += $(OPUAVSYNTHDIR)/stabilizationsettingsbank1.c
SRC += $(OPUAVSYNTHDIR)/stabilizationsettingsbank2.c
SRC += $(OPUAVSYNTHDIR)/stabilizationsettingsbank3.c
SRC += $(OPUAVSYNTHDIR)/stabilizationstatus.c
SRC += $(OPUAVSYNTHDIR)/stabilizationbank.c
SRC += $(OPUAVSYNTHDIR)/actuatorcommand.c
SRC += $(OPUAVSYNTHDIR)/actuatordesired.c

View File

@ -23,7 +23,7 @@
/* Notes: We use 5 task priorities */
#define configUSE_PREEMPTION 1
#define configUSE_IDLE_HOOK 1
#define configUSE_IDLE_HOOK 0
#define configUSE_TICK_HOOK 0
#define configUSE_MALLOC_FAILED_HOOK 1
#define configCPU_CLOCK_HZ ((unsigned long)72000000)
@ -31,7 +31,7 @@
#define configMAX_PRIORITIES ((unsigned portBASE_TYPE)5)
#define configMINIMAL_STACK_SIZE ((unsigned short)48)
#define configTOTAL_HEAP_SIZE ((size_t)(53 * 256))
#define configMAX_TASK_NAME_LEN (16)
#define configMAX_TASK_NAME_LEN (6)
#define configUSE_TRACE_FACILITY 0
#define configUSE_16_BIT_TICKS 0
#define configIDLE_SHOULD_YIELD 0
@ -39,7 +39,7 @@
#define configUSE_RECURSIVE_MUTEXES 1
#define configUSE_COUNTING_SEMAPHORES 0
#define configUSE_ALTERNATIVE_API 0
#define configQUEUE_REGISTRY_SIZE 10
#define configQUEUE_REGISTRY_SIZE 0
/* Co-routine definitions. */
#define configUSE_CO_ROUTINES 0
@ -52,10 +52,10 @@
#define INCLUDE_uxTaskPriorityGet 1
#define INCLUDE_vTaskDelete 1
#define INCLUDE_vTaskCleanUpResources 0
#define INCLUDE_vTaskSuspend 1
#define INCLUDE_vTaskSuspend 0
#define INCLUDE_vTaskDelayUntil 1
#define INCLUDE_vTaskDelay 1
#define INCLUDE_xTaskGetSchedulerState 1
#define INCLUDE_xTaskGetSchedulerState 0
#define INCLUDE_xTaskGetCurrentTaskHandle 1
#define INCLUDE_uxTaskGetStackHighWaterMark 1

View File

@ -39,6 +39,7 @@
#include <uavtalk.h>
#include "alarms.h"
#include <mathmisc.h>
/* Global Functions */
void OpenPilotInit(void);

View File

@ -144,7 +144,7 @@
/* Stabilization options */
/* #define PIOS_QUATERNION_STABILIZATION */
#define PIOS_EXCLUDE_ADVANCED_FEATURES
/* Performance counters */
#define IDLE_COUNTS_PER_SEC_AT_NO_LOAD 1995998
@ -157,15 +157,19 @@
#define CPULOAD_LIMIT_CRITICAL 95
/* Task stack sizes */
#define PIOS_ACTUATOR_STACK_SIZE 1020
#define PIOS_MANUAL_STACK_SIZE 850
#define PIOS_ACTUATOR_STACK_SIZE 820
#define PIOS_MANUAL_STACK_SIZE 635
#define PIOS_RECEIVER_STACK_SIZE 620
#define PIOS_STABILIZATION_STACK_SIZE 400
#ifdef DIAG_TASKS
#define PIOS_SYSTEM_STACK_SIZE 720
#define PIOS_SYSTEM_STACK_SIZE 740
#else
#define PIOS_SYSTEM_STACK_SIZE 660
#endif
#define PIOS_TELEM_STACK_SIZE 540
#define PIOS_EVENTDISPATCHER_STACK_SIZE 160
#define PIOS_TELEM_RX_STACK_SIZE 410
#define PIOS_TELEM_TX_STACK_SIZE 560
#define PIOS_EVENTDISPATCHER_STACK_SIZE 95
/* This can't be too high to stop eventdispatcher thread overflowing */
#define PIOS_EVENTDISAPTCHER_QUEUE 10

View File

@ -31,6 +31,7 @@
#ifndef PIOS_USB_BOARD_DATA_H
#define PIOS_USB_BOARD_DATA_H
// Note : changing below length will require changes to the USB buffer setup
#define PIOS_USB_BOARD_CDC_DATA_LENGTH 64
#define PIOS_USB_BOARD_CDC_MGMT_LENGTH 32
#define PIOS_USB_BOARD_HID_DATA_LENGTH 64

View File

@ -31,6 +31,7 @@
#ifndef PIOS_USB_BOARD_DATA_H
#define PIOS_USB_BOARD_DATA_H
// Note : changing below length will require changes to the USB buffer setup
#define PIOS_USB_BOARD_HID_DATA_LENGTH 64
#define PIOS_USB_BOARD_EP_NUM 2

View File

@ -40,6 +40,7 @@
#include <uavtalk.h>
#include "alarms.h"
#include <mathmisc.h>
/* Global Functions */
void OpenPilotInit(void);

View File

@ -31,6 +31,7 @@
#ifndef PIOS_USB_BOARD_DATA_H
#define PIOS_USB_BOARD_DATA_H
// Note : changing below length will require changes to the USB buffer setup
#define PIOS_USB_BOARD_CDC_DATA_LENGTH 64
#define PIOS_USB_BOARD_CDC_MGMT_LENGTH 32
#define PIOS_USB_BOARD_HID_DATA_LENGTH 64

View File

@ -31,6 +31,7 @@
#ifndef PIOS_USB_BOARD_DATA_H
#define PIOS_USB_BOARD_DATA_H
// Note : changing below length will require changes to the USB buffer setup
#define PIOS_USB_BOARD_HID_DATA_LENGTH 64
#define PIOS_USB_BOARD_EP_NUM 2

View File

@ -39,6 +39,7 @@
#include <uavtalk.h>
#include "alarms.h"
#include <mathmisc.h>
/* Global Functions */
void OpenPilotInit(void);

View File

@ -31,6 +31,7 @@
#ifndef PIOS_USB_BOARD_DATA_H
#define PIOS_USB_BOARD_DATA_H
// Note : changing below length will require changes to the USB buffer setup
#define PIOS_USB_BOARD_CDC_DATA_LENGTH 64
#define PIOS_USB_BOARD_CDC_MGMT_LENGTH 32
#define PIOS_USB_BOARD_HID_DATA_LENGTH 64

View File

@ -31,6 +31,7 @@
#ifndef PIOS_USB_BOARD_DATA_H
#define PIOS_USB_BOARD_DATA_H
// Note : changing below length will require changes to the USB buffer setup
#define PIOS_USB_BOARD_HID_DATA_LENGTH 64
#define PIOS_USB_BOARD_EP_NUM 2

View File

@ -33,7 +33,7 @@ MODULES += Sensors
MODULES += StateEstimation # use instead of Attitude
MODULES += Altitude/revolution
MODULES += Airspeed
MODULES += AltitudeHold
#MODULES += AltitudeHold # now integrated in Stabilization
MODULES += Stabilization
MODULES += VtolPathFollower
MODULES += ManualControl

View File

@ -87,6 +87,7 @@ UAVOBJSRCFILENAMES += stabilizationsettings
UAVOBJSRCFILENAMES += stabilizationsettingsbank1
UAVOBJSRCFILENAMES += stabilizationsettingsbank2
UAVOBJSRCFILENAMES += stabilizationsettingsbank3
UAVOBJSRCFILENAMES += stabilizationstatus
UAVOBJSRCFILENAMES += stabilizationbank
UAVOBJSRCFILENAMES += systemalarms
UAVOBJSRCFILENAMES += systemsettings
@ -105,7 +106,6 @@ UAVOBJSRCFILENAMES += altitudeholdsettings
UAVOBJSRCFILENAMES += oplinksettings
UAVOBJSRCFILENAMES += oplinkstatus
UAVOBJSRCFILENAMES += altitudefiltersettings
UAVOBJSRCFILENAMES += altitudeholddesired
UAVOBJSRCFILENAMES += altitudeholdstatus
UAVOBJSRCFILENAMES += waypoint
UAVOBJSRCFILENAMES += waypointactive

View File

@ -40,6 +40,7 @@
#include <uavtalk.h>
#include "alarms.h"
#include <mathmisc.h>
/* Global Functions */
void OpenPilotInit(void);

View File

@ -144,7 +144,7 @@
#define PIOS_GPS_SETS_HOMELOCATION
/* Stabilization options */
/* #define PIOS_QUATERNION_STABILIZATION */
// #define PIOS_QUATERNION_STABILIZATION
/* Performance counters */
#define IDLE_COUNTS_PER_SEC_AT_NO_LOAD 8379692

View File

@ -31,6 +31,7 @@
#ifndef PIOS_USB_BOARD_DATA_H
#define PIOS_USB_BOARD_DATA_H
// Note : changing below length will require changes to the USB buffer setup
#define PIOS_USB_BOARD_CDC_DATA_LENGTH 64
#define PIOS_USB_BOARD_CDC_MGMT_LENGTH 32
#define PIOS_USB_BOARD_HID_DATA_LENGTH 64

View File

@ -31,6 +31,7 @@
#ifndef PIOS_USB_BOARD_DATA_H
#define PIOS_USB_BOARD_DATA_H
// Note : changing below length will require changes to the USB buffer setup
#define PIOS_USB_BOARD_HID_DATA_LENGTH 64
#define PIOS_USB_BOARD_EP_NUM 2

View File

@ -33,7 +33,7 @@ MODULES += Sensors
MODULES += StateEstimation # use instead of Attitude
MODULES += Altitude/revolution
MODULES += Airspeed
MODULES += AltitudeHold
#MODULES += AltitudeHold # now integrated in Stabilization
MODULES += Stabilization
MODULES += VtolPathFollower
MODULES += ManualControl

View File

@ -87,6 +87,7 @@ UAVOBJSRCFILENAMES += stabilizationsettings
UAVOBJSRCFILENAMES += stabilizationsettingsbank1
UAVOBJSRCFILENAMES += stabilizationsettingsbank2
UAVOBJSRCFILENAMES += stabilizationsettingsbank3
UAVOBJSRCFILENAMES += stabilizationstatus
UAVOBJSRCFILENAMES += stabilizationbank
UAVOBJSRCFILENAMES += systemalarms
UAVOBJSRCFILENAMES += systemsettings
@ -105,7 +106,6 @@ UAVOBJSRCFILENAMES += altitudeholdsettings
UAVOBJSRCFILENAMES += oplinksettings
UAVOBJSRCFILENAMES += oplinkstatus
UAVOBJSRCFILENAMES += altitudefiltersettings
UAVOBJSRCFILENAMES += altitudeholddesired
UAVOBJSRCFILENAMES += altitudeholdstatus
UAVOBJSRCFILENAMES += waypoint
UAVOBJSRCFILENAMES += waypointactive

View File

@ -40,6 +40,7 @@
#include <uavtalk.h>
#include "alarms.h"
#include <mathmisc.h>
/* Global Functions */
void OpenPilotInit(void);

View File

@ -31,6 +31,7 @@
#ifndef PIOS_USB_BOARD_DATA_H
#define PIOS_USB_BOARD_DATA_H
// Note : changing below length will require changes to the USB buffer setup
#define PIOS_USB_BOARD_CDC_DATA_LENGTH 64
#define PIOS_USB_BOARD_CDC_MGMT_LENGTH 32
#define PIOS_USB_BOARD_HID_DATA_LENGTH 64

View File

@ -42,7 +42,7 @@ MODULES += FirmwareIAP
MODULES += StateEstimation
#MODULES += Sensors/simulated/Sensors
MODULES += Airspeed
MODULES += AltitudeHold
#MODULES += AltitudeHold # now integrated in Stabilization
#MODULES += OveroSync
SRC += $(FLIGHTLIB)/notification.c
@ -98,6 +98,7 @@ SRC += $(FLIGHTLIB)/sanitycheck.c
SRC += $(MATHLIB)/sin_lookup.c
SRC += $(MATHLIB)/pid.c
SRC += $(MATHLIB)/mathmisc.c
SRC += $(PIOSCORECOMMON)/pios_task_monitor.c
SRC += $(PIOSCORECOMMON)/pios_dosfs_logfs.c

View File

@ -86,6 +86,7 @@ UAVOBJSRCFILENAMES += stabilizationsettings
UAVOBJSRCFILENAMES += stabilizationsettingsbank1
UAVOBJSRCFILENAMES += stabilizationsettingsbank2
UAVOBJSRCFILENAMES += stabilizationsettingsbank3
UAVOBJSRCFILENAMES += stabilizationstatus
UAVOBJSRCFILENAMES += stabilizationbank
UAVOBJSRCFILENAMES += systemalarms
UAVOBJSRCFILENAMES += systemsettings
@ -107,7 +108,6 @@ UAVOBJSRCFILENAMES += camerastabsettings
UAVOBJSRCFILENAMES += altitudeholdsettings
UAVOBJSRCFILENAMES += altitudefiltersettings
UAVOBJSRCFILENAMES += revosettings
UAVOBJSRCFILENAMES += altitudeholddesired
UAVOBJSRCFILENAMES += altitudeholdstatus
UAVOBJSRCFILENAMES += ekfconfiguration
UAVOBJSRCFILENAMES += ekfstatevariance

View File

@ -40,6 +40,7 @@
#include <uavtalk.h>
#include "alarms.h"
#include <mathmisc.h>
/* Global Functions */
void OpenPilotInit(void);

View File

@ -1,2849 +0,0 @@
<gcs>
<General>
<AutoConnect>true</AutoConnect>
<AutoSelect>true</AutoSelect>
<Description>Developer</Description>
<Details>Developer mode configuration</Details>
<ExpertMode>true</ExpertMode>
<LastPreferenceCategory>OPMapGadget</LastPreferenceCategory>
<LastPreferencePage>default</LastPreferencePage>
<SaveSettingsOnExit>true</SaveSettingsOnExit>
<SettingsWindowHeight>628</SettingsWindowHeight>
<SettingsWindowWidth>697</SettingsWindowWidth>
<StyleSheet>default</StyleSheet>
<UDPMirror>false</UDPMirror>
</General>
<IPconnection>
<Current>
<arr_1>
<Port>9000</Port>
<UseTCP>0</UseTCP>
</arr_1>
<size>1</size>
</Current>
</IPconnection>
<KeyBindings>
<size>0</size>
</KeyBindings>
<MainWindow>
<Color>#666666</Color>
<FullScreen>false</FullScreen>
<Maximized>true</Maximized>
</MainWindow>
<ModePriorities>
<Mode1>91</Mode1>
<Mode2>90</Mode2>
<Mode3>89</Mode3>
<Mode4>88</Mode4>
<Mode5>87</Mode5>
<Mode6>86</Mode6>
<Welcome>100</Welcome>
</ModePriorities>
<Plugins>
<SoundNotifyPlugin>
<configInfo>
<locked>false</locked>
<version>1.0.0</version>
</configInfo>
<data>
<Current>
<arr_1>
<CurrentLanguage>default</CurrentLanguage>
<DataObject>AccelState</DataObject>
<ExpireTimeout>0</ExpireTimeout>
<Mute>false</Mute>
<ObjectField></ObjectField>
<RangeLimit>-1</RangeLimit>
<Repeat>0</Repeat>
<SayOrder>0</SayOrder>
<Sound1></Sound1>
<Sound2></Sound2>
<Sound3></Sound3>
<SoundCollectionPath>%%DATAPATH%%sounds</SoundCollectionPath>
<Value1></Value1>
<Value2>0</Value2>
</arr_1>
<size>1</size>
</Current>
<EnableSound>false</EnableSound>
<listNotifies>
<size>0</size>
</listNotifies>
</data>
</SoundNotifyPlugin>
</Plugins>
<SerialConnection>
<speed>57600</speed>
</SerialConnection>
<UAVGadgetConfigurations>
<ConfigGadget>
<default>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
</default>
</ConfigGadget>
<DialGadget>
<Attitude>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<beSmooth>false</beSmooth>
<dialBackgroundID>background</dialBackgroundID>
<dialFile>%%DATAPATH%%dials/default/attitude.svg</dialFile>
<dialForegroundID>foreground</dialForegroundID>
<dialNeedleID1>needle</dialNeedleID1>
<dialNeedleID2>needle</dialNeedleID2>
<dialNeedleID3>needle3</dialNeedleID3>
<font>Lucida Grande,13,-1,5,50,0,0,0,0,0</font>
<needle1DataObject>AttitudeState</needle1DataObject>
<needle1Factor>-1</needle1Factor>
<needle1MaxValue>360</needle1MaxValue>
<needle1MinValue>0</needle1MinValue>
<needle1Move>Rotate</needle1Move>
<needle1ObjectField>Roll</needle1ObjectField>
<needle2DataObject>AttitudeState</needle2DataObject>
<needle2Factor>75</needle2Factor>
<needle2MaxValue>20</needle2MaxValue>
<needle2MinValue>0</needle2MinValue>
<needle2Move>Vertical</needle2Move>
<needle2ObjectField>Pitch</needle2ObjectField>
<needle3DataObject>AttitudeState</needle3DataObject>
<needle3Factor>-1</needle3Factor>
<needle3MaxValue>360</needle3MaxValue>
<needle3MinValue>0</needle3MinValue>
<needle3Move>Rotate</needle3Move>
<needle3ObjectField>Roll</needle3ObjectField>
<useOpenGLFlag>false</useOpenGLFlag>
</data>
</Attitude>
<Baro__PCT__20Altimeter>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<beSmooth>false</beSmooth>
<dialBackgroundID>background</dialBackgroundID>
<dialFile>%%DATAPATH%%dials/default/altimeter.svg</dialFile>
<dialForegroundID>foreground</dialForegroundID>
<dialNeedleID1>needle</dialNeedleID1>
<dialNeedleID2>needle2</dialNeedleID2>
<dialNeedleID3>needle3</dialNeedleID3>
<font>Lucida Grande,13,-1,5,50,0,0,0,0,0</font>
<needle1DataObject>BaroSensor</needle1DataObject>
<needle1Factor>1</needle1Factor>
<needle1MaxValue>10</needle1MaxValue>
<needle1MinValue>0</needle1MinValue>
<needle1Move>Rotate</needle1Move>
<needle1ObjectField>Altitude</needle1ObjectField>
<needle2DataObject>BaroSensor</needle2DataObject>
<needle2Factor>1</needle2Factor>
<needle2MaxValue>100</needle2MaxValue>
<needle2MinValue>0</needle2MinValue>
<needle2Move>Rotate</needle2Move>
<needle2ObjectField>Altitude</needle2ObjectField>
<needle3DataObject>BaroSensor</needle3DataObject>
<needle3Factor>1</needle3Factor>
<needle3MaxValue>1000</needle3MaxValue>
<needle3MinValue>0</needle3MinValue>
<needle3Move>Rotate</needle3Move>
<needle3ObjectField>Altitude</needle3ObjectField>
<useOpenGLFlag>false</useOpenGLFlag>
</data>
</Baro__PCT__20Altimeter>
<Barometer>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<beSmooth>false</beSmooth>
<dialBackgroundID>background</dialBackgroundID>
<dialFile>%%DATAPATH%%dials/default/barometer.svg</dialFile>
<dialForegroundID></dialForegroundID>
<dialNeedleID1>needle</dialNeedleID1>
<dialNeedleID2></dialNeedleID2>
<dialNeedleID3></dialNeedleID3>
<font>Lucida Grande,13,-1,5,50,0,0,0,0,0</font>
<needle1DataObject>BaroSensor</needle1DataObject>
<needle1Factor>10</needle1Factor>
<needle1MaxValue>1120</needle1MaxValue>
<needle1MinValue>1000</needle1MinValue>
<needle1Move>Rotate</needle1Move>
<needle1ObjectField>Pressure</needle1ObjectField>
<needle2DataObject>BaroSensor</needle2DataObject>
<needle2Factor>1</needle2Factor>
<needle2MaxValue>100</needle2MaxValue>
<needle2MinValue>0</needle2MinValue>
<needle2Move>Rotate</needle2Move>
<needle2ObjectField>Altitude</needle2ObjectField>
<needle3DataObject>BaroSensor</needle3DataObject>
<needle3Factor>1</needle3Factor>
<needle3MaxValue>1000</needle3MaxValue>
<needle3MinValue>0</needle3MinValue>
<needle3Move>Rotate</needle3Move>
<needle3ObjectField>Altitude</needle3ObjectField>
<useOpenGLFlag>false</useOpenGLFlag>
</data>
</Barometer>
<Climbrate>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<beSmooth>false</beSmooth>
<dialBackgroundID>background</dialBackgroundID>
<dialFile>%%DATAPATH%%dials/default/vsi.svg</dialFile>
<dialForegroundID></dialForegroundID>
<dialNeedleID1>needle</dialNeedleID1>
<dialNeedleID2></dialNeedleID2>
<dialNeedleID3></dialNeedleID3>
<font>Lucida Grande,13,-1,5,50,0,0,0,0,0</font>
<needle1DataObject>VelocityState</needle1DataObject>
<needle1Factor>0.01</needle1Factor>
<needle1MaxValue>12</needle1MaxValue>
<needle1MinValue>-12</needle1MinValue>
<needle1Move>Rotate</needle1Move>
<needle1ObjectField>Down</needle1ObjectField>
<needle2DataObject>BaroSensor</needle2DataObject>
<needle2Factor>1</needle2Factor>
<needle2MaxValue>100</needle2MaxValue>
<needle2MinValue>0</needle2MinValue>
<needle2Move>Rotate</needle2Move>
<needle2ObjectField>Altitude</needle2ObjectField>
<needle3DataObject>BaroSensor</needle3DataObject>
<needle3Factor>1</needle3Factor>
<needle3MaxValue>1000</needle3MaxValue>
<needle3MinValue>0</needle3MinValue>
<needle3Move>Rotate</needle3Move>
<needle3ObjectField>Altitude</needle3ObjectField>
<useOpenGLFlag>false</useOpenGLFlag>
</data>
</Climbrate>
<Compass>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<beSmooth>false</beSmooth>
<dialBackgroundID>background</dialBackgroundID>
<dialFile>%%DATAPATH%%dials/default/compass.svg</dialFile>
<dialForegroundID>foreground</dialForegroundID>
<dialNeedleID1>needle</dialNeedleID1>
<dialNeedleID2></dialNeedleID2>
<dialNeedleID3></dialNeedleID3>
<font>Lucida Grande,13,-1,5,50,0,0,0,0,0</font>
<needle1DataObject>AttitudeState</needle1DataObject>
<needle1Factor>-1</needle1Factor>
<needle1MaxValue>360</needle1MaxValue>
<needle1MinValue>0</needle1MinValue>
<needle1Move>Rotate</needle1Move>
<needle1ObjectField>Yaw</needle1ObjectField>
<needle2DataObject>BaroSensor</needle2DataObject>
<needle2Factor>1</needle2Factor>
<needle2MaxValue>100</needle2MaxValue>
<needle2MinValue>0</needle2MinValue>
<needle2Move>Rotate</needle2Move>
<needle2ObjectField>Altitude</needle2ObjectField>
<needle3DataObject>BaroSensor</needle3DataObject>
<needle3Factor>1</needle3Factor>
<needle3MaxValue>1000</needle3MaxValue>
<needle3MinValue>0</needle3MinValue>
<needle3Move>Rotate</needle3Move>
<needle3ObjectField>Altitude</needle3ObjectField>
<useOpenGLFlag>false</useOpenGLFlag>
</data>
</Compass>
<Deluxe__PCT__20Attitude>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<beSmooth>false</beSmooth>
<dialBackgroundID>background</dialBackgroundID>
<dialFile>%%DATAPATH%%dials/deluxe/attitude.svg</dialFile>
<dialForegroundID>foreground</dialForegroundID>
<dialNeedleID1>needle</dialNeedleID1>
<dialNeedleID2>needle</dialNeedleID2>
<dialNeedleID3>needle3</dialNeedleID3>
<font>Lucida Grande,13,-1,5,50,0,0,0,0,0</font>
<needle1DataObject>AttitudeState</needle1DataObject>
<needle1Factor>-1</needle1Factor>
<needle1MaxValue>360</needle1MaxValue>
<needle1MinValue>0</needle1MinValue>
<needle1Move>Rotate</needle1Move>
<needle1ObjectField>Roll</needle1ObjectField>
<needle2DataObject>AttitudeState</needle2DataObject>
<needle2Factor>75</needle2Factor>
<needle2MaxValue>20</needle2MaxValue>
<needle2MinValue>0</needle2MinValue>
<needle2Move>Vertical</needle2Move>
<needle2ObjectField>Pitch</needle2ObjectField>
<needle3DataObject>AttitudeState</needle3DataObject>
<needle3Factor>-1</needle3Factor>
<needle3MaxValue>360</needle3MaxValue>
<needle3MinValue>0</needle3MinValue>
<needle3Move>Rotate</needle3Move>
<needle3ObjectField>Roll</needle3ObjectField>
<useOpenGLFlag>false</useOpenGLFlag>
</data>
</Deluxe__PCT__20Attitude>
<Deluxe__PCT__20Baro__PCT__20Altimeter>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<beSmooth>false</beSmooth>
<dialBackgroundID>background</dialBackgroundID>
<dialFile>%%DATAPATH%%dials/deluxe/altimeter.svg</dialFile>
<dialForegroundID>foreground</dialForegroundID>
<dialNeedleID1>needle</dialNeedleID1>
<dialNeedleID2>needle2</dialNeedleID2>
<dialNeedleID3>needle3</dialNeedleID3>
<font>Lucida Grande,13,-1,5,50,0,0,0,0,0</font>
<needle1DataObject>BaroSensor</needle1DataObject>
<needle1Factor>1</needle1Factor>
<needle1MaxValue>10</needle1MaxValue>
<needle1MinValue>0</needle1MinValue>
<needle1Move>Rotate</needle1Move>
<needle1ObjectField>Altitude</needle1ObjectField>
<needle2DataObject>BaroSensor</needle2DataObject>
<needle2Factor>1</needle2Factor>
<needle2MaxValue>100</needle2MaxValue>
<needle2MinValue>0</needle2MinValue>
<needle2Move>Rotate</needle2Move>
<needle2ObjectField>Altitude</needle2ObjectField>
<needle3DataObject>BaroSensor</needle3DataObject>
<needle3Factor>1</needle3Factor>
<needle3MaxValue>1000</needle3MaxValue>
<needle3MinValue>0</needle3MinValue>
<needle3Move>Rotate</needle3Move>
<needle3ObjectField>Altitude</needle3ObjectField>
<useOpenGLFlag>false</useOpenGLFlag>
</data>
</Deluxe__PCT__20Baro__PCT__20Altimeter>
<Deluxe__PCT__20Barometer>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<beSmooth>false</beSmooth>
<dialBackgroundID>background</dialBackgroundID>
<dialFile>%%DATAPATH%%dials/deluxe/barometer.svg</dialFile>
<dialForegroundID>foreground</dialForegroundID>
<dialNeedleID1>needle</dialNeedleID1>
<dialNeedleID2></dialNeedleID2>
<dialNeedleID3></dialNeedleID3>
<font>Lucida Grande,13,-1,5,50,0,0,0,0,0</font>
<needle1DataObject>BaroSensor</needle1DataObject>
<needle1Factor>10</needle1Factor>
<needle1MaxValue>1120</needle1MaxValue>
<needle1MinValue>1000</needle1MinValue>
<needle1Move>Rotate</needle1Move>
<needle1ObjectField>Pressure</needle1ObjectField>
<needle2DataObject>BaroSensor</needle2DataObject>
<needle2Factor>1</needle2Factor>
<needle2MaxValue>100</needle2MaxValue>
<needle2MinValue>0</needle2MinValue>
<needle2Move>Rotate</needle2Move>
<needle2ObjectField>Altitude</needle2ObjectField>
<needle3DataObject>BaroSensor</needle3DataObject>
<needle3Factor>1</needle3Factor>
<needle3MaxValue>1000</needle3MaxValue>
<needle3MinValue>0</needle3MinValue>
<needle3Move>Rotate</needle3Move>
<needle3ObjectField>Altitude</needle3ObjectField>
<useOpenGLFlag>false</useOpenGLFlag>
</data>
</Deluxe__PCT__20Barometer>
<Deluxe__PCT__20Climbrate>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<beSmooth>false</beSmooth>
<dialBackgroundID>background</dialBackgroundID>
<dialFile>%%DATAPATH%%dials/deluxe/vsi.svg</dialFile>
<dialForegroundID>foreground</dialForegroundID>
<dialNeedleID1>needle</dialNeedleID1>
<dialNeedleID2></dialNeedleID2>
<dialNeedleID3></dialNeedleID3>
<font>Lucida Grande,13,-1,5,50,0,0,0,0,0</font>
<needle1DataObject>VelocityState</needle1DataObject>
<needle1Factor>0.01</needle1Factor>
<needle1MaxValue>11.2</needle1MaxValue>
<needle1MinValue>-11.2</needle1MinValue>
<needle1Move>Rotate</needle1Move>
<needle1ObjectField>Down</needle1ObjectField>
<needle2DataObject>BaroSensor</needle2DataObject>
<needle2Factor>1</needle2Factor>
<needle2MaxValue>100</needle2MaxValue>
<needle2MinValue>0</needle2MinValue>
<needle2Move>Rotate</needle2Move>
<needle2ObjectField>Altitude</needle2ObjectField>
<needle3DataObject>BaroSensor</needle3DataObject>
<needle3Factor>1</needle3Factor>
<needle3MaxValue>1000</needle3MaxValue>
<needle3MinValue>0</needle3MinValue>
<needle3Move>Rotate</needle3Move>
<needle3ObjectField>Altitude</needle3ObjectField>
<useOpenGLFlag>false</useOpenGLFlag>
</data>
</Deluxe__PCT__20Climbrate>
<Deluxe__PCT__20Compass>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<beSmooth>false</beSmooth>
<dialBackgroundID>background</dialBackgroundID>
<dialFile>%%DATAPATH%%dials/deluxe/compass.svg</dialFile>
<dialForegroundID>foreground</dialForegroundID>
<dialNeedleID1>needle</dialNeedleID1>
<dialNeedleID2></dialNeedleID2>
<dialNeedleID3></dialNeedleID3>
<font>Lucida Grande,13,-1,5,50,0,0,0,0,0</font>
<needle1DataObject>AttitudeState</needle1DataObject>
<needle1Factor>-1</needle1Factor>
<needle1MaxValue>360</needle1MaxValue>
<needle1MinValue>0</needle1MinValue>
<needle1Move>Rotate</needle1Move>
<needle1ObjectField>Yaw</needle1ObjectField>
<needle2DataObject>BaroSensor</needle2DataObject>
<needle2Factor>1</needle2Factor>
<needle2MaxValue>100</needle2MaxValue>
<needle2MinValue>0</needle2MinValue>
<needle2Move>Rotate</needle2Move>
<needle2ObjectField>Altitude</needle2ObjectField>
<needle3DataObject>BaroSensor</needle3DataObject>
<needle3Factor>1</needle3Factor>
<needle3MaxValue>1000</needle3MaxValue>
<needle3MinValue>0</needle3MinValue>
<needle3Move>Rotate</needle3Move>
<needle3ObjectField>Altitude</needle3ObjectField>
<useOpenGLFlag>false</useOpenGLFlag>
</data>
</Deluxe__PCT__20Compass>
<Deluxe__PCT__20Groundspeed__PCT__20kph>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<beSmooth>false</beSmooth>
<dialBackgroundID>background</dialBackgroundID>
<dialFile>%%DATAPATH%%dials/deluxe/speed.svg</dialFile>
<dialForegroundID>foreground</dialForegroundID>
<dialNeedleID1>needle</dialNeedleID1>
<dialNeedleID2></dialNeedleID2>
<dialNeedleID3></dialNeedleID3>
<font>Lucida Grande,13,-1,5,50,0,0,0,0,0</font>
<needle1DataObject>GPSPositionSensor</needle1DataObject>
<needle1Factor>3.6</needle1Factor>
<needle1MaxValue>120</needle1MaxValue>
<needle1MinValue>0</needle1MinValue>
<needle1Move>Rotate</needle1Move>
<needle1ObjectField>Groundspeed</needle1ObjectField>
<needle2DataObject>BaroSensor</needle2DataObject>
<needle2Factor>1</needle2Factor>
<needle2MaxValue>100</needle2MaxValue>
<needle2MinValue>0</needle2MinValue>
<needle2Move>Rotate</needle2Move>
<needle2ObjectField>Altitude</needle2ObjectField>
<needle3DataObject>BaroSensor</needle3DataObject>
<needle3Factor>1</needle3Factor>
<needle3MaxValue>1000</needle3MaxValue>
<needle3MinValue>0</needle3MinValue>
<needle3Move>Rotate</needle3Move>
<needle3ObjectField>Altitude</needle3ObjectField>
<useOpenGLFlag>false</useOpenGLFlag>
</data>
</Deluxe__PCT__20Groundspeed__PCT__20kph>
<Deluxe__PCT__20Temperature>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<beSmooth>false</beSmooth>
<dialBackgroundID>background</dialBackgroundID>
<dialFile>%%DATAPATH%%dials/deluxe/thermometer.svg</dialFile>
<dialForegroundID>foreground</dialForegroundID>
<dialNeedleID1>needle</dialNeedleID1>
<dialNeedleID2>needle2</dialNeedleID2>
<dialNeedleID3>needle3</dialNeedleID3>
<font>Lucida Grande,13,-1,5,50,0,0,0,0,0</font>
<needle1DataObject>BaroSensor</needle1DataObject>
<needle1Factor>1</needle1Factor>
<needle1MaxValue>120</needle1MaxValue>
<needle1MinValue>0</needle1MinValue>
<needle1Move>Rotate</needle1Move>
<needle1ObjectField>Temperature</needle1ObjectField>
<needle2DataObject>BaroSensor</needle2DataObject>
<needle2Factor>1</needle2Factor>
<needle2MaxValue>100</needle2MaxValue>
<needle2MinValue>0</needle2MinValue>
<needle2Move>Rotate</needle2Move>
<needle2ObjectField>Altitude</needle2ObjectField>
<needle3DataObject>BaroSensor</needle3DataObject>
<needle3Factor>1</needle3Factor>
<needle3MaxValue>1000</needle3MaxValue>
<needle3MinValue>0</needle3MinValue>
<needle3Move>Rotate</needle3Move>
<needle3ObjectField>Altitude</needle3ObjectField>
<useOpenGLFlag>false</useOpenGLFlag>
</data>
</Deluxe__PCT__20Temperature>
<Deluxe__PCT__20Turn__PCT__20Coordinator>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<beSmooth>false</beSmooth>
<dialBackgroundID>background</dialBackgroundID>
<dialFile>/home/lafargue/OP/OpenPilot/trunk/artwork/Dials/deluxe/turncoordinator.svg</dialFile>
<dialForegroundID>foreground</dialForegroundID>
<dialNeedleID1>needle</dialNeedleID1>
<dialNeedleID2>needle2</dialNeedleID2>
<dialNeedleID3>needle2</dialNeedleID3>
<font>Lucida Grande,13,-1,5,50,0,0,0,0,0</font>
<needle1DataObject>AttitudeState</needle1DataObject>
<needle1Factor>-1</needle1Factor>
<needle1MaxValue>360</needle1MaxValue>
<needle1MinValue>0</needle1MinValue>
<needle1Move>Rotate</needle1Move>
<needle1ObjectField>Roll</needle1ObjectField>
<needle2DataObject>AccelState</needle2DataObject>
<needle2Factor>1</needle2Factor>
<needle2MaxValue>20</needle2MaxValue>
<needle2MinValue>-20</needle2MinValue>
<needle2Move>Horizontal</needle2Move>
<needle2ObjectField>x</needle2ObjectField>
<needle3DataObject>AccelState</needle3DataObject>
<needle3Factor>-1</needle3Factor>
<needle3MaxValue>360</needle3MaxValue>
<needle3MinValue>0</needle3MinValue>
<needle3Move>Rotate</needle3Move>
<needle3ObjectField>x</needle3ObjectField>
<useOpenGLFlag>false</useOpenGLFlag>
</data>
</Deluxe__PCT__20Turn__PCT__20Coordinator>
<Groundspeed__PCT__20kph>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<beSmooth>false</beSmooth>
<dialBackgroundID>background</dialBackgroundID>
<dialFile>%%DATAPATH%%dials/default/speed.svg</dialFile>
<dialForegroundID></dialForegroundID>
<dialNeedleID1>needle</dialNeedleID1>
<dialNeedleID2></dialNeedleID2>
<dialNeedleID3></dialNeedleID3>
<font>Lucida Grande,13,-1,5,50,0,0,0,0,0</font>
<needle1DataObject>GPSPositionSensor</needle1DataObject>
<needle1Factor>3.6</needle1Factor>
<needle1MaxValue>120</needle1MaxValue>
<needle1MinValue>0</needle1MinValue>
<needle1Move>Rotate</needle1Move>
<needle1ObjectField>Groundspeed</needle1ObjectField>
<needle2DataObject>BaroSensor</needle2DataObject>
<needle2Factor>1</needle2Factor>
<needle2MaxValue>100</needle2MaxValue>
<needle2MinValue>0</needle2MinValue>
<needle2Move>Rotate</needle2Move>
<needle2ObjectField>Altitude</needle2ObjectField>
<needle3DataObject>BaroSensor</needle3DataObject>
<needle3Factor>1</needle3Factor>
<needle3MaxValue>1000</needle3MaxValue>
<needle3MinValue>0</needle3MinValue>
<needle3Move>Rotate</needle3Move>
<needle3ObjectField>Altitude</needle3ObjectField>
<useOpenGLFlag>false</useOpenGLFlag>
</data>
</Groundspeed__PCT__20kph>
<HiContrast__PCT__20Attitude>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<beSmooth>false</beSmooth>
<dialBackgroundID>background</dialBackgroundID>
<dialFile>%%DATAPATH%%dials/hi-contrast/attitude.svg</dialFile>
<dialForegroundID>foreground</dialForegroundID>
<dialNeedleID1>needle</dialNeedleID1>
<dialNeedleID2>needle</dialNeedleID2>
<dialNeedleID3>needle3</dialNeedleID3>
<font>Lucida Grande,13,-1,5,50,0,0,0,0,0</font>
<needle1DataObject>AttitudeState</needle1DataObject>
<needle1Factor>-1</needle1Factor>
<needle1MaxValue>360</needle1MaxValue>
<needle1MinValue>0</needle1MinValue>
<needle1Move>Rotate</needle1Move>
<needle1ObjectField>Roll</needle1ObjectField>
<needle2DataObject>AttitudeState</needle2DataObject>
<needle2Factor>75</needle2Factor>
<needle2MaxValue>20</needle2MaxValue>
<needle2MinValue>0</needle2MinValue>
<needle2Move>Vertical</needle2Move>
<needle2ObjectField>Pitch</needle2ObjectField>
<needle3DataObject>AttitudeState</needle3DataObject>
<needle3Factor>-1</needle3Factor>
<needle3MaxValue>360</needle3MaxValue>
<needle3MinValue>0</needle3MinValue>
<needle3Move>Rotate</needle3Move>
<needle3ObjectField>Roll</needle3ObjectField>
<useOpenGLFlag>false</useOpenGLFlag>
</data>
</HiContrast__PCT__20Attitude>
<HiContrast__PCT__20Baro__PCT__20Altimeter>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<beSmooth>false</beSmooth>
<dialBackgroundID>background</dialBackgroundID>
<dialFile>%%DATAPATH%%dials/hi-contrast/altimeter.svg</dialFile>
<dialForegroundID>foreground</dialForegroundID>
<dialNeedleID1>needle</dialNeedleID1>
<dialNeedleID2>needle2</dialNeedleID2>
<dialNeedleID3>needle3</dialNeedleID3>
<font>Lucida Grande,13,-1,5,50,0,0,0,0,0</font>
<needle1DataObject>BaroSensor</needle1DataObject>
<needle1Factor>1</needle1Factor>
<needle1MaxValue>10</needle1MaxValue>
<needle1MinValue>0</needle1MinValue>
<needle1Move>Rotate</needle1Move>
<needle1ObjectField>Altitude</needle1ObjectField>
<needle2DataObject>BaroSensor</needle2DataObject>
<needle2Factor>1</needle2Factor>
<needle2MaxValue>100</needle2MaxValue>
<needle2MinValue>0</needle2MinValue>
<needle2Move>Rotate</needle2Move>
<needle2ObjectField>Altitude</needle2ObjectField>
<needle3DataObject>BaroSensor</needle3DataObject>
<needle3Factor>1</needle3Factor>
<needle3MaxValue>1000</needle3MaxValue>
<needle3MinValue>0</needle3MinValue>
<needle3Move>Rotate</needle3Move>
<needle3ObjectField>Altitude</needle3ObjectField>
<useOpenGLFlag>false</useOpenGLFlag>
</data>
</HiContrast__PCT__20Baro__PCT__20Altimeter>
<HiContrast__PCT__20Barometer>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<beSmooth>false</beSmooth>
<dialBackgroundID>background</dialBackgroundID>
<dialFile>%%DATAPATH%%dials/hi-contrast/barometer.svg</dialFile>
<dialForegroundID></dialForegroundID>
<dialNeedleID1>needle</dialNeedleID1>
<dialNeedleID2></dialNeedleID2>
<dialNeedleID3></dialNeedleID3>
<font>Lucida Grande,13,-1,5,50,0,0,0,0,0</font>
<needle1DataObject>BaroSensor</needle1DataObject>
<needle1Factor>10</needle1Factor>
<needle1MaxValue>1120</needle1MaxValue>
<needle1MinValue>1000</needle1MinValue>
<needle1Move>Rotate</needle1Move>
<needle1ObjectField>Pressure</needle1ObjectField>
<needle2DataObject>BaroSensor</needle2DataObject>
<needle2Factor>1</needle2Factor>
<needle2MaxValue>100</needle2MaxValue>
<needle2MinValue>0</needle2MinValue>
<needle2Move>Rotate</needle2Move>
<needle2ObjectField>Altitude</needle2ObjectField>
<needle3DataObject>BaroSensor</needle3DataObject>
<needle3Factor>1</needle3Factor>
<needle3MaxValue>1000</needle3MaxValue>
<needle3MinValue>0</needle3MinValue>
<needle3Move>Rotate</needle3Move>
<needle3ObjectField>Altitude</needle3ObjectField>
<useOpenGLFlag>false</useOpenGLFlag>
</data>
</HiContrast__PCT__20Barometer>
<HiContrast__PCT__20Climbrate>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<beSmooth>false</beSmooth>
<dialBackgroundID>background</dialBackgroundID>
<dialFile>%%DATAPATH%%dials/hi-contrast/vsi.svg</dialFile>
<dialForegroundID></dialForegroundID>
<dialNeedleID1>needle</dialNeedleID1>
<dialNeedleID2></dialNeedleID2>
<dialNeedleID3></dialNeedleID3>
<font>Lucida Grande,13,-1,5,50,0,0,0,0,0</font>
<needle1DataObject>VelocityState</needle1DataObject>
<needle1Factor>0.01</needle1Factor>
<needle1MaxValue>12</needle1MaxValue>
<needle1MinValue>-12</needle1MinValue>
<needle1Move>Rotate</needle1Move>
<needle1ObjectField>Down</needle1ObjectField>
<needle2DataObject>BaroSensor</needle2DataObject>
<needle2Factor>1</needle2Factor>
<needle2MaxValue>100</needle2MaxValue>
<needle2MinValue>0</needle2MinValue>
<needle2Move>Rotate</needle2Move>
<needle2ObjectField>Altitude</needle2ObjectField>
<needle3DataObject>BaroSensor</needle3DataObject>
<needle3Factor>1</needle3Factor>
<needle3MaxValue>1000</needle3MaxValue>
<needle3MinValue>0</needle3MinValue>
<needle3Move>Rotate</needle3Move>
<needle3ObjectField>Altitude</needle3ObjectField>
<useOpenGLFlag>false</useOpenGLFlag>
</data>
</HiContrast__PCT__20Climbrate>
<HiContrast__PCT__20Compass>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<beSmooth>false</beSmooth>
<dialBackgroundID>background</dialBackgroundID>
<dialFile>%%DATAPATH%%dials/hi-contrast/compass.svg</dialFile>
<dialForegroundID>foreground</dialForegroundID>
<dialNeedleID1>needle</dialNeedleID1>
<dialNeedleID2></dialNeedleID2>
<dialNeedleID3></dialNeedleID3>
<font>Lucida Grande,13,-1,5,50,0,0,0,0,0</font>
<needle1DataObject>AttitudeState</needle1DataObject>
<needle1Factor>-1</needle1Factor>
<needle1MaxValue>360</needle1MaxValue>
<needle1MinValue>0</needle1MinValue>
<needle1Move>Rotate</needle1Move>
<needle1ObjectField>Yaw</needle1ObjectField>
<needle2DataObject>BaroSensor</needle2DataObject>
<needle2Factor>1</needle2Factor>
<needle2MaxValue>100</needle2MaxValue>
<needle2MinValue>0</needle2MinValue>
<needle2Move>Rotate</needle2Move>
<needle2ObjectField>Altitude</needle2ObjectField>
<needle3DataObject>BaroSensor</needle3DataObject>
<needle3Factor>1</needle3Factor>
<needle3MaxValue>1000</needle3MaxValue>
<needle3MinValue>0</needle3MinValue>
<needle3Move>Rotate</needle3Move>
<needle3ObjectField>Altitude</needle3ObjectField>
<useOpenGLFlag>false</useOpenGLFlag>
</data>
</HiContrast__PCT__20Compass>
<HiContrast__PCT__20Groundspeed__PCT__20kph>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<beSmooth>false</beSmooth>
<dialBackgroundID>background</dialBackgroundID>
<dialFile>%%DATAPATH%%dials/hi-contrast/speed.svg</dialFile>
<dialForegroundID></dialForegroundID>
<dialNeedleID1>needle</dialNeedleID1>
<dialNeedleID2></dialNeedleID2>
<dialNeedleID3></dialNeedleID3>
<font>Lucida Grande,13,-1,5,50,0,0,0,0,0</font>
<needle1DataObject>GPSPositionSensor</needle1DataObject>
<needle1Factor>3.6</needle1Factor>
<needle1MaxValue>120</needle1MaxValue>
<needle1MinValue>0</needle1MinValue>
<needle1Move>Rotate</needle1Move>
<needle1ObjectField>Groundspeed</needle1ObjectField>
<needle2DataObject>BaroSensor</needle2DataObject>
<needle2Factor>1</needle2Factor>
<needle2MaxValue>100</needle2MaxValue>
<needle2MinValue>0</needle2MinValue>
<needle2Move>Rotate</needle2Move>
<needle2ObjectField>Altitude</needle2ObjectField>
<needle3DataObject>BaroSensor</needle3DataObject>
<needle3Factor>1</needle3Factor>
<needle3MaxValue>1000</needle3MaxValue>
<needle3MinValue>0</needle3MinValue>
<needle3Move>Rotate</needle3Move>
<needle3ObjectField>Altitude</needle3ObjectField>
<useOpenGLFlag>false</useOpenGLFlag>
</data>
</HiContrast__PCT__20Groundspeed__PCT__20kph>
<HiContrast__PCT__20Temperature>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<beSmooth>false</beSmooth>
<dialBackgroundID>background</dialBackgroundID>
<dialFile>%%DATAPATH%%dials/hi-contrast/thermometer.svg</dialFile>
<dialForegroundID></dialForegroundID>
<dialNeedleID1>needle</dialNeedleID1>
<dialNeedleID2>needle2</dialNeedleID2>
<dialNeedleID3>needle3</dialNeedleID3>
<font>Lucida Grande,13,-1,5,50,0,0,0,0,0</font>
<needle1DataObject>BaroSensor</needle1DataObject>
<needle1Factor>1</needle1Factor>
<needle1MaxValue>120</needle1MaxValue>
<needle1MinValue>0</needle1MinValue>
<needle1Move>Rotate</needle1Move>
<needle1ObjectField>Temperature</needle1ObjectField>
<needle2DataObject>BaroSensor</needle2DataObject>
<needle2Factor>1</needle2Factor>
<needle2MaxValue>100</needle2MaxValue>
<needle2MinValue>0</needle2MinValue>
<needle2Move>Rotate</needle2Move>
<needle2ObjectField>Altitude</needle2ObjectField>
<needle3DataObject>BaroSensor</needle3DataObject>
<needle3Factor>1</needle3Factor>
<needle3MaxValue>1000</needle3MaxValue>
<needle3MinValue>0</needle3MinValue>
<needle3Move>Rotate</needle3Move>
<needle3ObjectField>Altitude</needle3ObjectField>
<useOpenGLFlag>false</useOpenGLFlag>
</data>
</HiContrast__PCT__20Temperature>
<Servo__PCT__20Channel__PCT__201>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<beSmooth>false</beSmooth>
<dialBackgroundID>background</dialBackgroundID>
<dialFile>%%DATAPATH%%dials/default/thermometer.svg</dialFile>
<dialForegroundID></dialForegroundID>
<dialNeedleID1>needle</dialNeedleID1>
<dialNeedleID2>needle2</dialNeedleID2>
<dialNeedleID3>needle3</dialNeedleID3>
<font>Lucida Grande,13,-1,5,50,0,0,0,0,0</font>
<needle1DataObject>ManualControlCommand</needle1DataObject>
<needle1Factor>1</needle1Factor>
<needle1MaxValue>2000</needle1MaxValue>
<needle1MinValue>1000</needle1MinValue>
<needle1Move>Rotate</needle1Move>
<needle1ObjectField>Channel-3</needle1ObjectField>
<needle2DataObject>BaroSensor</needle2DataObject>
<needle2Factor>1</needle2Factor>
<needle2MaxValue>100</needle2MaxValue>
<needle2MinValue>0</needle2MinValue>
<needle2Move>Rotate</needle2Move>
<needle2ObjectField>Altitude</needle2ObjectField>
<needle3DataObject>BaroSensor</needle3DataObject>
<needle3Factor>1</needle3Factor>
<needle3MaxValue>1000</needle3MaxValue>
<needle3MinValue>0</needle3MinValue>
<needle3Move>Rotate</needle3Move>
<needle3ObjectField>Altitude</needle3ObjectField>
<useOpenGLFlag>false</useOpenGLFlag>
</data>
</Servo__PCT__20Channel__PCT__201>
<Temperature>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<beSmooth>false</beSmooth>
<dialBackgroundID>background</dialBackgroundID>
<dialFile>%%DATAPATH%%dials/default/thermometer.svg</dialFile>
<dialForegroundID></dialForegroundID>
<dialNeedleID1>needle</dialNeedleID1>
<dialNeedleID2>needle2</dialNeedleID2>
<dialNeedleID3>needle3</dialNeedleID3>
<font>Lucida Grande,13,-1,5,50,0,0,0,0,0</font>
<needle1DataObject>BaroSensor</needle1DataObject>
<needle1Factor>1</needle1Factor>
<needle1MaxValue>120</needle1MaxValue>
<needle1MinValue>0</needle1MinValue>
<needle1Move>Rotate</needle1Move>
<needle1ObjectField>Temperature</needle1ObjectField>
<needle2DataObject>BaroSensor</needle2DataObject>
<needle2Factor>1</needle2Factor>
<needle2MaxValue>100</needle2MaxValue>
<needle2MinValue>0</needle2MinValue>
<needle2Move>Rotate</needle2Move>
<needle2ObjectField>Altitude</needle2ObjectField>
<needle3DataObject>BaroSensor</needle3DataObject>
<needle3Factor>1</needle3Factor>
<needle3MaxValue>1000</needle3MaxValue>
<needle3MinValue>0</needle3MinValue>
<needle3Move>Rotate</needle3Move>
<needle3ObjectField>Altitude</needle3ObjectField>
<useOpenGLFlag>false</useOpenGLFlag>
</data>
</Temperature>
</DialGadget>
<GCSControlGadget>
<MS__PCT__20Sidewinder>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<button0Action>0</button0Action>
<button0Amount>0</button0Amount>
<button0Function>0</button0Function>
<button1Action>0</button1Action>
<button1Amount>0</button1Amount>
<button1Function>0</button1Function>
<button2Action>0</button2Action>
<button2Amount>0.1</button2Amount>
<button2Function>3</button2Function>
<button3Action>0</button3Action>
<button3Amount>0.1</button3Amount>
<button3Function>3</button3Function>
<button4Action>0</button4Action>
<button4Amount>0</button4Amount>
<button4Function>0</button4Function>
<button5Action>0</button5Action>
<button5Amount>0</button5Amount>
<button5Function>0</button5Function>
<button6Action>0</button6Action>
<button6Amount>0</button6Amount>
<button6Function>0</button6Function>
<button7Action>0</button7Action>
<button7Amount>0</button7Amount>
<button7Function>0</button7Function>
<channel0Reverse>false</channel0Reverse>
<channel1Reverse>false</channel1Reverse>
<channel2Reverse>true</channel2Reverse>
<channel3Reverse>false</channel3Reverse>
<channel4Reverse>false</channel4Reverse>
<channel5Reverse>false</channel5Reverse>
<channel6Reverse>false</channel6Reverse>
<channel7Reverse>false</channel7Reverse>
<controlHostUDP></controlHostUDP>
<controlPortUDP>0</controlPortUDP>
<controlsMode>2</controlsMode>
<pitchChannel>1</pitchChannel>
<rollChannel>0</rollChannel>
<throttleChannel>2</throttleChannel>
<yawChannel>3</yawChannel>
</data>
</MS__PCT__20Sidewinder>
</GCSControlGadget>
<GpsDisplayGadget>
<Flight__PCT__20GPS>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<connectionMode>Telemetry</connectionMode>
<defaultDataBits>3</defaultDataBits>
<defaultFlow>0</defaultFlow>
<defaultParity>0</defaultParity>
<defaultPort>/dev/cu.Bluetooth-Modem</defaultPort>
<defaultSpeed>11</defaultSpeed>
<defaultStopBits>0</defaultStopBits>
</data>
</Flight__PCT__20GPS>
<GPS__PCT__20Mouse>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<connectionMode>Serial</connectionMode>
<defaultDataBits>3</defaultDataBits>
<defaultFlow>0</defaultFlow>
<defaultParity>0</defaultParity>
<defaultPort>/dev/cu.Bluetooth-Modem</defaultPort>
<defaultSpeed>17</defaultSpeed>
<defaultStopBits>0</defaultStopBits>
</data>
</GPS__PCT__20Mouse>
</GpsDisplayGadget>
<HITL>
<Flightgear__PCT__20HITL>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<binPath>\usr\games\fgfs</binPath>
<dataPath>\usr\share\games\FlightGear</dataPath>
<hostAddress>127.0.0.1</hostAddress>
<inPort>9009</inPort>
<latitude></latitude>
<longitude></longitude>
<manual>false</manual>
<outPort>9010</outPort>
<remoteHostAddress>127.0.0.1</remoteHostAddress>
<simulatorId>FG</simulatorId>
<startSim>true</startSim>
</data>
</Flightgear__PCT__20HITL>
<XPlane__PCT__20HITL>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<binPath>\home\lafargue\X-Plane 9\X-Plane-i686</binPath>
<dataPath>\usr\share\games\FlightGear</dataPath>
<hostAddress>127.0.0.3</hostAddress>
<inPort>6756</inPort>
<latitude></latitude>
<longitude></longitude>
<manual>false</manual>
<outPort>49000</outPort>
<remoteHostAddress>127.0.0.1</remoteHostAddress>
<simulatorId>X-Plane</simulatorId>
<startSim>false</startSim>
</data>
</XPlane__PCT__20HITL>
</HITL>
<HITLv2>
<default>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<attActCalc>false</attActCalc>
<attActHW>false</attActHW>
<attActSim>true</attActSim>
<attState>true</attState>
<attRaw>true</attRaw>
<attRawRate>20</attRawRate>
<binPath></binPath>
<dataPath></dataPath>
<gcsReciever>true</gcsReciever>
<gpsPosRate>200</gpsPosRate>
<gpsPosition>true</gpsPosition>
<homeLocRate>0</homeLocRate>
<homeLocation>true</homeLocation>
<hostAddress>127.0.0.1</hostAddress>
<inPort>40100</inPort>
<inputCommand>true</inputCommand>
<manualControl>false</manualControl>
<manualOutput>false</manualOutput>
<outPort>40200</outPort>
<outputRate>20</outputRate>
<remoteAddress>127.0.0.1</remoteAddress>
<simulatorId>ASimRC</simulatorId>
<sonarAltRate>50</sonarAltRate>
<sonarAltitude>false</sonarAltitude>
<sonarMaxAlt>@Variant(AAAAh0CgAAA=)</sonarMaxAlt>
</data>
</default>
</HITLv2>
<LineardialGadget>
<Accel__PCT__20Horizontal__PCT__20X>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<dFile>%%DATAPATH%%dials/deluxe/lineardial-horizontal.svg</dFile>
<decimalPlaces>2</decimalPlaces>
<factor>1</factor>
<font>Andale Mono,8,-1,5,50,0,0,0,0,0</font>
<greenMax>-9</greenMax>
<greenMin>-10</greenMin>
<maxValue>11</maxValue>
<minValue>-11</minValue>
<redMax>11</redMax>
<redMin>-11</redMin>
<sourceDataObject>AccelState</sourceDataObject>
<sourceObjectField>x</sourceObjectField>
<useOpenGLFlag>false</useOpenGLFlag>
<yellowMax>-5</yellowMax>
<yellowMin>-11</yellowMin>
</data>
</Accel__PCT__20Horizontal__PCT__20X>
<Accel__PCT__20Horizontal__PCT__20Y>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<dFile>%%DATAPATH%%dials/deluxe/lineardial-horizontal.svg</dFile>
<decimalPlaces>2</decimalPlaces>
<factor>1</factor>
<font>Andale Mono,6,-1,5,50,0,0,0,0,0</font>
<greenMax>-9</greenMax>
<greenMin>-10</greenMin>
<maxValue>11</maxValue>
<minValue>-11</minValue>
<redMax>11</redMax>
<redMin>-11</redMin>
<sourceDataObject>AccelState</sourceDataObject>
<sourceObjectField>y</sourceObjectField>
<useOpenGLFlag>false</useOpenGLFlag>
<yellowMax>-5</yellowMax>
<yellowMin>-11</yellowMin>
</data>
</Accel__PCT__20Horizontal__PCT__20Y>
<Accel__PCT__20Horizontal__PCT__20Z>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<dFile>%%DATAPATH%%dials/deluxe/lineardial-horizontal.svg</dFile>
<decimalPlaces>2</decimalPlaces>
<factor>1</factor>
<font>Andale Mono,8,-1,5,50,0,0,0,0,0</font>
<greenMax>-9</greenMax>
<greenMin>-10</greenMin>
<maxValue>11</maxValue>
<minValue>-11</minValue>
<redMax>11</redMax>
<redMin>-11</redMin>
<sourceDataObject>AccelState</sourceDataObject>
<sourceObjectField>z</sourceObjectField>
<useOpenGLFlag>false</useOpenGLFlag>
<yellowMax>-5</yellowMax>
<yellowMin>-11</yellowMin>
</data>
</Accel__PCT__20Horizontal__PCT__20Z>
<Arm__PCT__20Status>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<dFile>%%DATAPATH%%dials/default/arm-status.svg</dFile>
<decimalPlaces>0</decimalPlaces>
<factor>1</factor>
<font>,12,-1,5,50,0,0,0,0,0</font>
<greenMax>100</greenMax>
<greenMin>66</greenMin>
<maxValue>100</maxValue>
<minValue>0</minValue>
<redMax>33</redMax>
<redMin>0</redMin>
<sourceDataObject>FlightStatus</sourceDataObject>
<sourceObjectField>Armed</sourceObjectField>
<useOpenGLFlag>false</useOpenGLFlag>
<yellowMax>66</yellowMax>
<yellowMin>33</yellowMin>
</data>
</Arm__PCT__20Status>
<Flight__PCT__20Time>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<dFile>%%DATAPATH%%dials/default/textonly.svg</dFile>
<decimalPlaces>0</decimalPlaces>
<factor>0.001</factor>
<font>,12,-1,5,50,0,0,0,0,0</font>
<greenMax>100</greenMax>
<greenMin>66</greenMin>
<maxValue>100</maxValue>
<minValue>0</minValue>
<redMax>33</redMax>
<redMin>0</redMin>
<sourceDataObject>SystemStats</sourceDataObject>
<sourceObjectField>FlightTime</sourceObjectField>
<useOpenGLFlag>false</useOpenGLFlag>
<yellowMax>66</yellowMax>
<yellowMin>33</yellowMin>
</data>
</Flight__PCT__20Time>
<Flight__PCT__20mode>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<dFile>%%DATAPATH%%dials/default/flightmode-status.svg</dFile>
<decimalPlaces>0</decimalPlaces>
<factor>1</factor>
<font>,12,-1,5,50,0,0,0,0,0</font>
<greenMax>100</greenMax>
<greenMin>66</greenMin>
<maxValue>100</maxValue>
<minValue>0</minValue>
<redMax>33</redMax>
<redMin>0</redMin>
<sourceDataObject>FlightStatus</sourceDataObject>
<sourceObjectField>FlightMode</sourceObjectField>
<useOpenGLFlag>false</useOpenGLFlag>
<yellowMax>66</yellowMax>
<yellowMin>33</yellowMin>
</data>
</Flight__PCT__20mode>
<GPS__PCT__20Sats>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<dFile>%%DATAPATH%%dials/default/gps-signal.svg</dFile>
<decimalPlaces>0</decimalPlaces>
<factor>1</factor>
<font>,12,-1,5,50,0,0,0,0,0</font>
<greenMax>0</greenMax>
<greenMin>0</greenMin>
<maxValue>12</maxValue>
<minValue>0</minValue>
<redMax>0</redMax>
<redMin>0</redMin>
<sourceDataObject>GPSPositionSensor</sourceDataObject>
<sourceObjectField>Satellites</sourceObjectField>
<useOpenGLFlag>false</useOpenGLFlag>
<yellowMax>0</yellowMax>
<yellowMin>0</yellowMin>
</data>
</GPS__PCT__20Sats>
<GPS__PCT__20Status>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<dFile>%%DATAPATH%%dials/default/gps-status.svg</dFile>
<decimalPlaces>0</decimalPlaces>
<factor>1</factor>
<font>,12,-1,5,50,0,0,0,0,0</font>
<greenMax>100</greenMax>
<greenMin>66</greenMin>
<maxValue>100</maxValue>
<minValue>0</minValue>
<redMax>33</redMax>
<redMin>0</redMin>
<sourceDataObject>GPSPositionSensor</sourceDataObject>
<sourceObjectField>Status</sourceObjectField>
<useOpenGLFlag>false</useOpenGLFlag>
<yellowMax>66</yellowMax>
<yellowMin>33</yellowMin>
</data>
</GPS__PCT__20Status>
<Mainboard__PCT__20CPU>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<dFile>%%DATAPATH%%dials/deluxe/lineardial-vertical.svg</dFile>
<decimalPlaces>0</decimalPlaces>
<factor>1</factor>
<font>Andale Mono,12,-1,5,75,0,0,0,0,0</font>
<greenMax>90</greenMax>
<greenMin>0</greenMin>
<maxValue>100</maxValue>
<minValue>0</minValue>
<redMax>100</redMax>
<redMin>95</redMin>
<sourceDataObject>SystemStats</sourceDataObject>
<sourceObjectField>CPULoad</sourceObjectField>
<useOpenGLFlag>false</useOpenGLFlag>
<yellowMax>95</yellowMax>
<yellowMin>90</yellowMin>
</data>
</Mainboard__PCT__20CPU>
<Pitch__PCT__20Desired>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<dFile>%%DATAPATH%%dials/deluxe/lineardial-vertical.svg</dFile>
<decimalPlaces>2</decimalPlaces>
<factor>1</factor>
<font>Andale Mono,12,-1,5,75,0,0,0,0,0</font>
<greenMax>0.5</greenMax>
<greenMin>-0.5</greenMin>
<maxValue>1</maxValue>
<minValue>-1</minValue>
<redMax>1</redMax>
<redMin>-1</redMin>
<sourceDataObject>ActuatorDesired</sourceDataObject>
<sourceObjectField>Pitch</sourceObjectField>
<useOpenGLFlag>false</useOpenGLFlag>
<yellowMax>0.8</yellowMax>
<yellowMin>-0.8</yellowMin>
</data>
</Pitch__PCT__20Desired>
<Pitch>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<dFile>%%DATAPATH%%dials/deluxe/lineardial-vertical.svg</dFile>
<decimalPlaces>2</decimalPlaces>
<factor>1</factor>
<font>Andale Mono,12,-1,5,75,0,0,0,0,0</font>
<greenMax>0.5</greenMax>
<greenMin>-0.5</greenMin>
<maxValue>1</maxValue>
<minValue>-1</minValue>
<redMax>1</redMax>
<redMin>-1</redMin>
<sourceDataObject>ManualControlCommand</sourceDataObject>
<sourceObjectField>Pitch</sourceObjectField>
<useOpenGLFlag>false</useOpenGLFlag>
<yellowMax>0.8</yellowMax>
<yellowMin>-0.8</yellowMin>
</data>
</Pitch>
<PitchState>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<dFile>%%DATAPATH%%dials/deluxe/lineardial-vertical.svg</dFile>
<decimalPlaces>2</decimalPlaces>
<factor>1</factor>
<font>Andale Mono,12,-1,5,75,0,0,0,0,0</font>
<greenMax>0.8</greenMax>
<greenMin>0.3</greenMin>
<maxValue>90</maxValue>
<minValue>-90</minValue>
<redMax>1</redMax>
<redMin>0</redMin>
<sourceDataObject>AttitudeState</sourceDataObject>
<sourceObjectField>Pitch</sourceObjectField>
<useOpenGLFlag>false</useOpenGLFlag>
<yellowMax>0.9</yellowMax>
<yellowMin>0.1</yellowMin>
</data>
</PitchState>
<Roll__PCT__20Desired>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<dFile>%%DATAPATH%%dials/deluxe/lineardial-vertical.svg</dFile>
<decimalPlaces>2</decimalPlaces>
<factor>1</factor>
<font>Andale Mono,12,-1,5,75,0,0,0,0,0</font>
<greenMax>0.5</greenMax>
<greenMin>-0.5</greenMin>
<maxValue>1</maxValue>
<minValue>-1</minValue>
<redMax>1</redMax>
<redMin>-1</redMin>
<sourceDataObject>ActuatorDesired</sourceDataObject>
<sourceObjectField>Roll</sourceObjectField>
<useOpenGLFlag>false</useOpenGLFlag>
<yellowMax>0.8</yellowMax>
<yellowMin>-0.8</yellowMin>
</data>
</Roll__PCT__20Desired>
<Roll>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<dFile>%%DATAPATH%%dials/deluxe/lineardial-vertical.svg</dFile>
<decimalPlaces>2</decimalPlaces>
<factor>1</factor>
<font>Andale Mono,12,-1,5,75,0,0,0,0,0</font>
<greenMax>0.5</greenMax>
<greenMin>-0.5</greenMin>
<maxValue>1</maxValue>
<minValue>-1</minValue>
<redMax>1</redMax>
<redMin>-1</redMin>
<sourceDataObject>ManualControlCommand</sourceDataObject>
<sourceObjectField>Roll</sourceObjectField>
<useOpenGLFlag>false</useOpenGLFlag>
<yellowMax>0.8</yellowMax>
<yellowMin>-0.8</yellowMin>
</data>
</Roll>
<Telemetry__PCT__20RX__PCT__20Rate__PCT__20Horizontal>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<dFile>%%DATAPATH%%dials/deluxe/lineardial-horizontal.svg</dFile>
<decimalPlaces>0</decimalPlaces>
<factor>1</factor>
<font>Andale Mono,12,-1,5,75,0,0,0,0,0</font>
<greenMax>650</greenMax>
<greenMin>0</greenMin>
<maxValue>1200</maxValue>
<minValue>0</minValue>
<redMax>1200</redMax>
<redMin>900</redMin>
<sourceDataObject>GCSTelemetryStats</sourceDataObject>
<sourceObjectField>RxDataRate</sourceObjectField>
<useOpenGLFlag>false</useOpenGLFlag>
<yellowMax>900</yellowMax>
<yellowMin>650</yellowMin>
</data>
</Telemetry__PCT__20RX__PCT__20Rate__PCT__20Horizontal>
<Telemetry__PCT__20TX__PCT__20Rate__PCT__20Horizontal>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<dFile>%%DATAPATH%%dials/deluxe/lineardial-horizontal.svg</dFile>
<decimalPlaces>0</decimalPlaces>
<factor>1</factor>
<font>Andale Mono,12,-1,5,75,0,0,0,0,0</font>
<greenMax>650</greenMax>
<greenMin>0</greenMin>
<maxValue>1200</maxValue>
<minValue>0</minValue>
<redMax>1200</redMax>
<redMin>900</redMin>
<sourceDataObject>GCSTelemetryStats</sourceDataObject>
<sourceObjectField>TxDataRate</sourceObjectField>
<useOpenGLFlag>false</useOpenGLFlag>
<yellowMax>900</yellowMax>
<yellowMin>650</yellowMin>
</data>
</Telemetry__PCT__20TX__PCT__20Rate__PCT__20Horizontal>
<Throttle>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<dFile>%%DATAPATH%%dials/deluxe/lineardial-vertical.svg</dFile>
<decimalPlaces>2</decimalPlaces>
<factor>1</factor>
<font>Andale Mono,12,-1,5,75,0,0,0,0,0</font>
<greenMax>0.5</greenMax>
<greenMin>0</greenMin>
<maxValue>1</maxValue>
<minValue>0</minValue>
<redMax>1</redMax>
<redMin>0.75</redMin>
<sourceDataObject>ManualControlCommand</sourceDataObject>
<sourceObjectField>Throttle</sourceObjectField>
<useOpenGLFlag>false</useOpenGLFlag>
<yellowMax>0.75</yellowMax>
<yellowMin>0.5</yellowMin>
</data>
</Throttle>
<Yaw__PCT__20Desired>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<dFile>%%DATAPATH%%dials/deluxe/lineardial-vertical.svg</dFile>
<decimalPlaces>2</decimalPlaces>
<factor>1</factor>
<font>Andale Mono,12,-1,5,75,0,0,0,0,0</font>
<greenMax>0.5</greenMax>
<greenMin>-0.5</greenMin>
<maxValue>1</maxValue>
<minValue>-1</minValue>
<redMax>1</redMax>
<redMin>-1</redMin>
<sourceDataObject>ActuatorDesired</sourceDataObject>
<sourceObjectField>Yaw</sourceObjectField>
<useOpenGLFlag>false</useOpenGLFlag>
<yellowMax>0.8</yellowMax>
<yellowMin>-0.8</yellowMin>
</data>
</Yaw__PCT__20Desired>
<Yaw>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<dFile>%%DATAPATH%%dials/deluxe/lineardial-vertical.svg</dFile>
<decimalPlaces>2</decimalPlaces>
<factor>1</factor>
<font>Andale Mono,12,-1,5,75,0,0,0,0,0</font>
<greenMax>0.5</greenMax>
<greenMin>-0.5</greenMin>
<maxValue>1</maxValue>
<minValue>-1</minValue>
<redMax>1</redMax>
<redMin>-1</redMin>
<sourceDataObject>ManualControlCommand</sourceDataObject>
<sourceObjectField>Yaw</sourceObjectField>
<useOpenGLFlag>false</useOpenGLFlag>
<yellowMax>0.8</yellowMax>
<yellowMin>-0.8</yellowMin>
</data>
</Yaw>
</LineardialGadget>
<ModelViewGadget>
<Aeroquad__PCT__20__PCT__2B>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<acFilename>%%DATAPATH%%models/multi/aeroquad/aeroquad_+.3ds</acFilename>
<bgFilename>%%DATAPATH%%models/backgrounds/default_background.png</bgFilename>
<enableVbo>false</enableVbo>
</data>
</Aeroquad__PCT__20__PCT__2B>
<CC3D>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<acFilename>%%DATAPATH%%models/boards/CC3D/CC3D.3ds</acFilename>
<bgFilename>%%DATAPATH%%models/backgrounds/default_background.png</bgFilename>
<enableVbo>false</enableVbo>
</data>
</CC3D>
<CopterControl>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<acFilename>%%DATAPATH%%models/boards/CopterControl/CopterControl.3ds</acFilename>
<bgFilename>%%DATAPATH%%models/backgrounds/default_background.png</bgFilename>
<enableVbo>false</enableVbo>
</data>
</CopterControl>
<Danker__PCT__27s__PCT__20Quad>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<acFilename>%%DATAPATH%%models/multi/dankers_quad/dankers_quad.3ds</acFilename>
<bgFilename>%%DATAPATH%%models/backgrounds/default_background.png</bgFilename>
<enableVbo>false</enableVbo>
</data>
</Danker__PCT__27s__PCT__20Quad>
<Easyquad__PCT__20X>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<acFilename>%%DATAPATH%%models/multi/easy_quad/easy_quad_X.3ds</acFilename>
<bgFilename>%%DATAPATH%%models/backgrounds/default_background.png</bgFilename>
<enableVbo>false</enableVbo>
</data>
</Easyquad__PCT__20X>
<Easystar>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<acFilename>%%DATAPATH%%models/planes/Easystar/easystar.3ds</acFilename>
<bgFilename>%%DATAPATH%%models/backgrounds/default_background.png</bgFilename>
<enableVbo>false</enableVbo>
</data>
</Easystar>
<Firecracker>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<acFilename>%%DATAPATH%%models/planes/firecracker/firecracker.3ds</acFilename>
<bgFilename>%%DATAPATH%%models/backgrounds/default_background.png</bgFilename>
<enableVbo>false</enableVbo>
</data>
</Firecracker>
<Funjet>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<acFilename>%%DATAPATH%%models/planes/funjet/funjet.3ds</acFilename>
<bgFilename>%%DATAPATH%%models/backgrounds/default_background.png</bgFilename>
<enableVbo>false</enableVbo>
</data>
</Funjet>
<Gaui__PCT__20330X>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<acFilename>%%DATAPATH%%models/multi/gaui_330x/gaui_330x.3ds</acFilename>
<bgFilename>%%DATAPATH%%models/backgrounds/default_background.png</bgFilename>
<enableVbo>false</enableVbo>
</data>
</Gaui__PCT__20330X>
<Helicopter__PCT__20-__PCT__20TRex__PCT__20450>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<acFilename>%%DATAPATH%%models/helis/t-rex/t-rex_450_xl.3ds</acFilename>
<bgFilename>%%DATAPATH%%models/backgrounds/default_background.png</bgFilename>
<enableVbo>false</enableVbo>
</data>
</Helicopter__PCT__20-__PCT__20TRex__PCT__20450>
<Hexacopter>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<acFilename>%%DATAPATH%%models/multi/mikrokopter/MK_Hexa.3ds</acFilename>
<bgFilename>%%DATAPATH%%models/backgrounds/default_background.png</bgFilename>
<enableVbo>false</enableVbo>
</data>
</Hexacopter>
<Joe__PCT__27s__PCT__2014__PCT__22__PCT__20Quad__PCT__20__PCT__2B>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<acFilename>%%DATAPATH%%models/multi/joes_cnc/J14-Q_+.3DS</acFilename>
<bgFilename>%%DATAPATH%%models/backgrounds/default_background.png</bgFilename>
<enableVbo>false</enableVbo>
</data>
</Joe__PCT__27s__PCT__2014__PCT__22__PCT__20Quad__PCT__20__PCT__2B>
<Joe__PCT__27s__PCT__2014__PCT__22__PCT__20Quad__PCT__20X__PCT__20>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<acFilename>%%DATAPATH%%models/multi/joes_cnc/J14-Q_X.3DS</acFilename>
<bgFilename>%%DATAPATH%%models/backgrounds/default_background.png</bgFilename>
<enableVbo>false</enableVbo>
</data>
</Joe__PCT__27s__PCT__2014__PCT__22__PCT__20Quad__PCT__20X__PCT__20>
<Joe__PCT__27s__PCT__2014__PCT__22__PCT__20T__PCT__20Quad__PCT__20__PCT__2B>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<acFilename>%%DATAPATH%%models/multi/joes_cnc/J14-QT_+.3DS</acFilename>
<bgFilename>%%DATAPATH%%models/backgrounds/default_background.png</bgFilename>
<enableVbo>false</enableVbo>
</data>
</Joe__PCT__27s__PCT__2014__PCT__22__PCT__20T__PCT__20Quad__PCT__20__PCT__2B>
<Joe__PCT__27s__PCT__2014__PCT__22__PCT__20T__PCT__20Quad__PCT__20X>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<acFilename>%%DATAPATH%%models/multi/joes_cnc/J14-QT_X.3DS</acFilename>
<bgFilename>%%DATAPATH%%models/backgrounds/default_background.png</bgFilename>
<enableVbo>false</enableVbo>
</data>
</Joe__PCT__27s__PCT__2014__PCT__22__PCT__20T__PCT__20Quad__PCT__20X>
<MattL__PCT__27s__PCT__20Y6>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<acFilename>%%DATAPATH%%models/multi/mattL_Y6/mattL_Y6.3ds</acFilename>
<bgFilename>%%DATAPATH%%models/backgrounds/default_background.png</bgFilename>
<enableVbo>false</enableVbo>
</data>
</MattL__PCT__27s__PCT__20Y6>
<Quadcopter>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<acFilename>%%DATAPATH%%models/multi/mikrokopter/MK_L4-ME.3ds</acFilename>
<bgFilename>%%DATAPATH%%models/backgrounds/default_background.png</bgFilename>
<enableVbo>false</enableVbo>
</data>
</Quadcopter>
<Ricoo>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<acFilename>%%DATAPATH%%models/multi/ricoo/ricoo.3DS</acFilename>
<bgFilename>%%DATAPATH%%models/backgrounds/default_background.png</bgFilename>
<enableVbo>false</enableVbo>
</data>
</Ricoo>
<Scorpion__PCT__20Tricopter>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<acFilename>%%DATAPATH%%models/multi/scorpion_tricopter/scorpion_tricopter.3ds</acFilename>
<bgFilename>%%DATAPATH%%models/backgrounds/default_background.png</bgFilename>
<enableVbo>false</enableVbo>
</data>
</Scorpion__PCT__20Tricopter>
<Test__PCT__20Quad__PCT__20__PCT__2B>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<acFilename>%%DATAPATH%%models/multi/test_quad/test_quad_+.3ds</acFilename>
<bgFilename>%%DATAPATH%%models/backgrounds/default_background.png</bgFilename>
<enableVbo>false</enableVbo>
</data>
</Test__PCT__20Quad__PCT__20__PCT__2B>
<Test__PCT__20Quad__PCT__20X>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<acFilename>%%DATAPATH%%models/multi/test_quad/test_quad_X.3ds</acFilename>
<bgFilename>%%DATAPATH%%models/backgrounds/default_background.png</bgFilename>
<enableVbo>false</enableVbo>
</data>
</Test__PCT__20Quad__PCT__20X>
</ModelViewGadget>
<OPMapGadget>
<Google__PCT__20Sat>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<accessMode>ServerAndCache</accessMode>
<cacheLocation>%%STOREPATH%%mapscache/</cacheLocation>
<defaultLatitude>0</defaultLatitude>
<defaultLongitude>0</defaultLongitude>
<defaultZoom>2</defaultZoom>
<mapProvider>GoogleSatellite</mapProvider>
<maxUpdateRate>2000</maxUpdateRate>
<overlayOpacity>1</overlayOpacity>
<showTileGridLines>false</showTileGridLines>
<uavSymbol>mapquad.png</uavSymbol>
<useMemoryCache>true</useMemoryCache>
<useOpenGL>false</useOpenGL>
</data>
</Google__PCT__20Sat>
<Memory__PCT__20Only>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<accessMode>CacheOnly</accessMode>
<cacheLocation>%%STOREPATH%%mapscache/</cacheLocation>
<defaultLatitude>0</defaultLatitude>
<defaultLongitude>0</defaultLongitude>
<defaultZoom>2</defaultZoom>
<mapProvider>GoogleMap</mapProvider>
<maxUpdateRate>2000</maxUpdateRate>
<overlayOpacity>1</overlayOpacity>
<showTileGridLines>false</showTileGridLines>
<uavSymbol>airplanepip.png</uavSymbol>
<useMemoryCache>true</useMemoryCache>
<useOpenGL>false</useOpenGL>
</data>
</Memory__PCT__20Only>
<default>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<accessMode>ServerAndCache</accessMode>
<cacheLocation>%%STOREPATH%%mapscache/</cacheLocation>
<defaultLatitude>29.97</defaultLatitude>
<defaultLongitude>95.35</defaultLongitude>
<defaultZoom>7</defaultZoom>
<mapProvider>GoogleMap</mapProvider>
<maxUpdateRate>2000</maxUpdateRate>
<overlayOpacity>1</overlayOpacity>
<showTileGridLines>false</showTileGridLines>
<uavSymbol>mapquad.png</uavSymbol>
<useMemoryCache>true</useMemoryCache>
<useOpenGL>true</useOpenGL>
</data>
</default>
</OPMapGadget>
<PfdQmlGadget>
<NoTerrain>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<actualPositionUsed>false</actualPositionUsed>
<altitude>2000</altitude>
<altitudeFactor>1</altitudeFactor>
<cacheOnly>false</cacheOnly>
<earthFile>%%DATAPATH%%pfd/default/readymap.earth</earthFile>
<latitude>46.6715</latitude>
<longitude>10.1589</longitude>
<openGLEnabled>true</openGLEnabled>
<qmlFile>%%DATAPATH%%pfd/default/Pfd.qml</qmlFile>
<speedFactor>1</speedFactor>
<terrainEnabled>false</terrainEnabled>
</data>
</NoTerrain>
<Terrain>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<actualPositionUsed>false</actualPositionUsed>
<altitude>2000</altitude>
<cacheOnly>false</cacheOnly>
<earthFile>%%DATAPATH%%pfd/default/readymap.earth</earthFile>
<latitude>46.6715</latitude>
<longitude>10.1589</longitude>
<openGLEnabled>true</openGLEnabled>
<qmlFile>%%DATAPATH%%pfd/default/Pfd.qml</qmlFile>
<terrainEnabled>false</terrainEnabled>
</data>
</Terrain>
</PfdQmlGadget>
<QmlViewGadget>
<default>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<dialFile>Unknown</dialFile>
<useOpenGLFlag>true</useOpenGLFlag>
</data>
</default>
</QmlViewGadget>
<ScopeGadget>
<Accel>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<LoggingEnabled>false</LoggingEnabled>
<LoggingNewFileOnConnect>false</LoggingNewFileOnConnect>
<LoggingPath></LoggingPath>
<configurationStreamVersion>1000</configurationStreamVersion>
<dataSize>60</dataSize>
<plotCurve0>
<color>4294901760</color>
<mathFunction>None</mathFunction>
<uavField>x</uavField>
<uavObject>AccelState</uavObject>
<yMaximum>0</yMaximum>
<yMeanSamples>1</yMeanSamples>
<yMinimum>6.92920863607354e-310</yMinimum>
<yScalePower>0</yScalePower>
</plotCurve0>
<plotCurve1>
<color>4283782655</color>
<mathFunction>None</mathFunction>
<uavField>y</uavField>
<uavObject>AccelState</uavObject>
<yMaximum>1.78017180972965e-306</yMaximum>
<yMeanSamples>1</yMeanSamples>
<yMinimum>9.34609790258712e-307</yMinimum>
<yScalePower>0</yScalePower>
</plotCurve1>
<plotCurve2>
<color>4283804160</color>
<mathFunction>None</mathFunction>
<uavField>z</uavField>
<uavObject>AccelState</uavObject>
<yMaximum>2.6501977682312e-318</yMaximum>
<yMeanSamples>1</yMeanSamples>
<yMinimum>6.92920723246466e-310</yMinimum>
<yScalePower>0</yScalePower>
</plotCurve2>
<plotCurveCount>3</plotCurveCount>
<plotType>1</plotType>
<refreshInterval>100</refreshInterval>
</data>
</Accel>
<Actuators>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<LoggingEnabled>false</LoggingEnabled>
<LoggingNewFileOnConnect>false</LoggingNewFileOnConnect>
<LoggingPath></LoggingPath>
<configurationStreamVersion>1000</configurationStreamVersion>
<dataSize>20</dataSize>
<plotCurve0>
<color>4294901760</color>
<mathFunction>None</mathFunction>
<uavField>Channel-4</uavField>
<uavObject>ActuatorCommand</uavObject>
<yMaximum>1.72723371101889e-77</yMaximum>
<yMeanSamples>1</yMeanSamples>
<yMinimum>6.02760087926321e-322</yMinimum>
<yScalePower>0</yScalePower>
</plotCurve0>
<plotCurve1>
<color>4294901760</color>
<mathFunction>None</mathFunction>
<uavField>Channel-5</uavField>
<uavObject>ActuatorCommand</uavObject>
<yMaximum>3.55727265005698e-322</yMaximum>
<yMeanSamples>1</yMeanSamples>
<yMinimum>2.19822614387826e-314</yMinimum>
<yScalePower>0</yScalePower>
</plotCurve1>
<plotCurve2>
<color>4289374847</color>
<mathFunction>None</mathFunction>
<uavField>Channel-6</uavField>
<uavObject>ActuatorCommand</uavObject>
<yMaximum>1.72723371101889e-77</yMaximum>
<yMeanSamples>1</yMeanSamples>
<yMinimum>1.72723371101889e-77</yMinimum>
<yScalePower>0</yScalePower>
</plotCurve2>
<plotCurve3>
<color>4289374847</color>
<mathFunction>None</mathFunction>
<uavField>Channel-7</uavField>
<uavObject>ActuatorCommand</uavObject>
<yMaximum>6.92916505779426e-310</yMaximum>
<yMeanSamples>1</yMeanSamples>
<yMinimum>4.22277162500408e-312</yMinimum>
<yScalePower>0</yScalePower>
</plotCurve3>
<plotCurveCount>4</plotCurveCount>
<plotType>1</plotType>
<refreshInterval>100</refreshInterval>
</data>
</Actuators>
<Attitude>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<LoggingEnabled>false</LoggingEnabled>
<LoggingNewFileOnConnect>false</LoggingNewFileOnConnect>
<LoggingPath></LoggingPath>
<configurationStreamVersion>1000</configurationStreamVersion>
<dataSize>60</dataSize>
<plotCurve0>
<color>4283760895</color>
<mathFunction>None</mathFunction>
<uavField>Roll</uavField>
<uavObject>AttitudeState</uavObject>
<yMaximum>6.92921152826347e-310</yMaximum>
<yMeanSamples>1</yMeanSamples>
<yMinimum>6.92921152826031e-310</yMinimum>
<yScalePower>0</yScalePower>
</plotCurve0>
<plotCurve1>
<color>4278233600</color>
<mathFunction>None</mathFunction>
<uavField>Yaw</uavField>
<uavObject>AttitudeState</uavObject>
<yMaximum>0</yMaximum>
<yMeanSamples>1</yMeanSamples>
<yMinimum>0</yMinimum>
<yScalePower>0</yScalePower>
</plotCurve1>
<plotCurve2>
<color>4294901760</color>
<mathFunction>None</mathFunction>
<uavField>Pitch</uavField>
<uavObject>AttitudeState</uavObject>
<yMaximum>0</yMaximum>
<yMeanSamples>1</yMeanSamples>
<yMinimum>0</yMinimum>
<yScalePower>0</yScalePower>
</plotCurve2>
<plotCurveCount>3</plotCurveCount>
<plotType>1</plotType>
<refreshInterval>100</refreshInterval>
</data>
</Attitude>
<Barometer>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<LoggingEnabled>false</LoggingEnabled>
<LoggingNewFileOnConnect>false</LoggingNewFileOnConnect>
<LoggingPath></LoggingPath>
<configurationStreamVersion>1000</configurationStreamVersion>
<dataSize>60</dataSize>
<plotCurve0>
<color>4278190080</color>
<mathFunction>None</mathFunction>
<uavField>Pressure</uavField>
<uavObject>BaroSensor</uavObject>
<yMaximum>1.72723371102043e-77</yMaximum>
<yMeanSamples>1</yMeanSamples>
<yMinimum>3.86203233966055e-312</yMinimum>
<yScalePower>0</yScalePower>
</plotCurve0>
<plotCurveCount>1</plotCurveCount>
<plotType>1</plotType>
<refreshInterval>1000</refreshInterval>
</data>
</Barometer>
<Inputs>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<LoggingEnabled>false</LoggingEnabled>
<LoggingNewFileOnConnect>false</LoggingNewFileOnConnect>
<LoggingPath></LoggingPath>
<configurationStreamVersion>1000</configurationStreamVersion>
<dataSize>40</dataSize>
<plotCurve0>
<color>4278190207</color>
<mathFunction>None</mathFunction>
<uavField>Channel-1</uavField>
<uavObject>ManualControlCommand</uavObject>
<yMaximum>0</yMaximum>
<yMeanSamples>1</yMeanSamples>
<yMinimum>0</yMinimum>
<yScalePower>0</yScalePower>
</plotCurve0>
<plotCurve1>
<color>4294901760</color>
<mathFunction>None</mathFunction>
<uavField>Channel-4</uavField>
<uavObject>ManualControlCommand</uavObject>
<yMaximum>6.92916505599784e-310</yMaximum>
<yMeanSamples>1</yMeanSamples>
<yMinimum>7.21478569792807e-313</yMinimum>
<yScalePower>0</yScalePower>
</plotCurve1>
<plotCurve2>
<color>4294901760</color>
<mathFunction>None</mathFunction>
<uavField>Channel-5</uavField>
<uavObject>ManualControlCommand</uavObject>
<yMaximum>8.34448532677451e-308</yMaximum>
<yMeanSamples>1</yMeanSamples>
<yMinimum>1.78019353780608e-306</yMinimum>
<yScalePower>0</yScalePower>
</plotCurve2>
<plotCurve3>
<color>4294901760</color>
<mathFunction>None</mathFunction>
<uavField>Channel-6</uavField>
<uavObject>ManualControlCommand</uavObject>
<yMaximum>6.9291650571421e-310</yMaximum>
<yMeanSamples>1</yMeanSamples>
<yMinimum>4.22277162500408e-312</yMinimum>
<yScalePower>0</yScalePower>
</plotCurve3>
<plotCurve4>
<color>4294901760</color>
<mathFunction>None</mathFunction>
<uavField>Channel-7</uavField>
<uavObject>ManualControlCommand</uavObject>
<yMaximum>4.24399158193054e-314</yMaximum>
<yMeanSamples>1</yMeanSamples>
<yMinimum>4.172013484701e-309</yMinimum>
<yScalePower>0</yScalePower>
</plotCurve4>
<plotCurve5>
<color>4283825920</color>
<mathFunction>None</mathFunction>
<uavField>Channel-2</uavField>
<uavObject>ManualControlCommand</uavObject>
<yMaximum>1.72723371101889e-77</yMaximum>
<yMeanSamples>1</yMeanSamples>
<yMinimum>2.48782786590693e-310</yMinimum>
<yScalePower>0</yScalePower>
</plotCurve5>
<plotCurve6>
<color>4294923520</color>
<mathFunction>None</mathFunction>
<uavField>Channel-3</uavField>
<uavObject>ManualControlCommand</uavObject>
<yMaximum>6.92921442541857e-310</yMaximum>
<yMeanSamples>1</yMeanSamples>
<yMinimum>6.92921441189619e-310</yMinimum>
<yScalePower>0</yScalePower>
</plotCurve6>
<plotCurve7>
<color>4294967040</color>
<mathFunction>None</mathFunction>
<uavField>Channel-0</uavField>
<uavObject>ManualControlCommand</uavObject>
<yMaximum>6.92921439506975e-310</yMaximum>
<yMeanSamples>1</yMeanSamples>
<yMinimum>1.72723371101889e-77</yMinimum>
<yScalePower>0</yScalePower>
</plotCurve7>
<plotCurveCount>8</plotCurveCount>
<plotType>1</plotType>
<refreshInterval>200</refreshInterval>
</data>
</Inputs>
<Raw__PCT__20AccelState>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<LoggingEnabled>false</LoggingEnabled>
<LoggingNewFileOnConnect>false</LoggingNewFileOnConnect>
<LoggingPath></LoggingPath>
<configurationStreamVersion>1000</configurationStreamVersion>
<dataSize>60</dataSize>
<plotCurve0>
<color>4294901760</color>
<mathFunction>None</mathFunction>
<uavField>x</uavField>
<uavObject>AccelState</uavObject>
<yMaximum>0</yMaximum>
<yMeanSamples>1</yMeanSamples>
<yMinimum>0</yMinimum>
<yScalePower>0</yScalePower>
</plotCurve0>
<plotCurve1>
<color>4283782655</color>
<mathFunction>None</mathFunction>
<uavField>y</uavField>
<uavObject>AccelState</uavObject>
<yMaximum>0</yMaximum>
<yMeanSamples>1</yMeanSamples>
<yMinimum>0</yMinimum>
<yScalePower>0</yScalePower>
</plotCurve1>
<plotCurve2>
<color>4283804160</color>
<mathFunction>None</mathFunction>
<uavField>z</uavField>
<uavObject>AccelState</uavObject>
<yMaximum>0</yMaximum>
<yMeanSamples>1</yMeanSamples>
<yMinimum>0</yMinimum>
<yScalePower>0</yScalePower>
</plotCurve2>
<plotCurveCount>3</plotCurveCount>
<plotType>1</plotType>
<refreshInterval>500</refreshInterval>
</data>
</Raw__PCT__20AccelState>
<Raw__PCT__20gyroState>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<LoggingEnabled>false</LoggingEnabled>
<LoggingNewFileOnConnect>false</LoggingNewFileOnConnect>
<LoggingPath></LoggingPath>
<configurationStreamVersion>1000</configurationStreamVersion>
<dataSize>60</dataSize>
<plotCurve0>
<color>4283804160</color>
<mathFunction>None</mathFunction>
<uavField>z</uavField>
<uavObject>gyroState</uavObject>
<yMaximum>1.02360527502876e-306</yMaximum>
<yMeanSamples>1</yMeanSamples>
<yMinimum>6.92921152846347e-310</yMinimum>
<yScalePower>0</yScalePower>
</plotCurve0>
<plotCurve1>
<color>4283782655</color>
<mathFunction>None</mathFunction>
<uavField>y</uavField>
<uavObject>gyroState</uavObject>
<yMaximum>0</yMaximum>
<yMeanSamples>1</yMeanSamples>
<yMinimum>0</yMinimum>
<yScalePower>0</yScalePower>
</plotCurve1>
<plotCurve2>
<color>4294901760</color>
<mathFunction>None</mathFunction>
<uavField>x</uavField>
<uavObject>gyroState</uavObject>
<yMaximum>0</yMaximum>
<yMeanSamples>1</yMeanSamples>
<yMinimum>0</yMinimum>
<yScalePower>0</yScalePower>
</plotCurve2>
<plotCurveCount>3</plotCurveCount>
<plotType>1</plotType>
<refreshInterval>500</refreshInterval>
</data>
</Raw__PCT__20gyroState>
<Raw__PCT__20magnetometers>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<LoggingEnabled>false</LoggingEnabled>
<LoggingNewFileOnConnect>false</LoggingNewFileOnConnect>
<LoggingPath></LoggingPath>
<configurationStreamVersion>1000</configurationStreamVersion>
<dataSize>60</dataSize>
<plotCurve0>
<color>4294901760</color>
<mathFunction>None</mathFunction>
<uavField>x</uavField>
<uavObject>MagState</uavObject>
<yMaximum>6.92916505601691e-310</yMaximum>
<yMeanSamples>1</yMeanSamples>
<yMinimum>3.86203233966055e-312</yMinimum>
<yScalePower>0</yScalePower>
</plotCurve0>
<plotCurve1>
<color>4283782655</color>
<mathFunction>None</mathFunction>
<uavField>y</uavField>
<uavObject>MagState</uavObject>
<yMaximum>1.72723371101889e-77</yMaximum>
<yMeanSamples>1</yMeanSamples>
<yMinimum>-1</yMinimum>
<yScalePower>0</yScalePower>
</plotCurve1>
<plotCurve2>
<color>4283804160</color>
<mathFunction>None</mathFunction>
<uavField>z</uavField>
<uavObject>MagState</uavObject>
<yMaximum>1.72723371102028e-77</yMaximum>
<yMeanSamples>1</yMeanSamples>
<yMinimum>7.21478569792807e-313</yMinimum>
<yScalePower>0</yScalePower>
</plotCurve2>
<plotCurveCount>3</plotCurveCount>
<plotType>1</plotType>
<refreshInterval>500</refreshInterval>
</data>
</Raw__PCT__20magnetometers>
<Stacks__PCT__20monitor>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<LoggingEnabled>false</LoggingEnabled>
<LoggingNewFileOnConnect>false</LoggingNewFileOnConnect>
<LoggingPath></LoggingPath>
<configurationStreamVersion>1000</configurationStreamVersion>
<dataSize>240</dataSize>
<plotCurve0>
<color>4294901760</color>
<mathFunction>None</mathFunction>
<uavField>StackRemaining-System</uavField>
<uavObject>TaskInfo</uavObject>
<yMaximum>0</yMaximum>
<yMeanSamples>1</yMeanSamples>
<yMinimum>0</yMinimum>
<yScalePower>0</yScalePower>
</plotCurve0>
<plotCurve1>
<color>4294945280</color>
<mathFunction>None</mathFunction>
<uavField>StackRemaining-CallbackScheduler0</uavField>
<uavObject>TaskInfo</uavObject>
<yMaximum>0</yMaximum>
<yMeanSamples>1</yMeanSamples>
<yMinimum>0</yMinimum>
<yScalePower>0</yScalePower>
</plotCurve1>
<plotCurve2>
<color>4278190335</color>
<mathFunction>None</mathFunction>
<uavField>StackRemaining-CallbackScheduler1</uavField>
<uavObject>TaskInfo</uavObject>
<yMaximum>0</yMaximum>
<yMeanSamples>1</yMeanSamples>
<yMinimum>0</yMinimum>
<yScalePower>0</yScalePower>
</plotCurve2>
<plotCurve3>
<color>4294967040</color>
<mathFunction>None</mathFunction>
<uavField>StackRemaining-ManualControl</uavField>
<uavObject>TaskInfo</uavObject>
<yMaximum>0</yMaximum>
<yMeanSamples>1</yMeanSamples>
<yMinimum>0</yMinimum>
<yScalePower>0</yScalePower>
</plotCurve3>
<plotCurve4>
<color>4278255615</color>
<mathFunction>None</mathFunction>
<uavField>StackRemaining-Stabilization</uavField>
<uavObject>TaskInfo</uavObject>
<yMaximum>0</yMaximum>
<yMeanSamples>1</yMeanSamples>
<yMinimum>0</yMinimum>
<yScalePower>0</yScalePower>
</plotCurve4>
<plotCurve5>
<color>4294923775</color>
<mathFunction>None</mathFunction>
<uavField>StackRemaining-Actuator</uavField>
<uavObject>TaskInfo</uavObject>
<yMaximum>0</yMaximum>
<yMeanSamples>1</yMeanSamples>
<yMinimum>0</yMinimum>
<yScalePower>0</yScalePower>
</plotCurve5>
<plotCurve6>
<color>4289331327</color>
<mathFunction>None</mathFunction>
<uavField>StackRemaining-Sensors</uavField>
<uavObject>TaskInfo</uavObject>
<yMaximum>0</yMaximum>
<yMeanSamples>1</yMeanSamples>
<yMinimum>0</yMinimum>
<yScalePower>0</yScalePower>
</plotCurve6>
<plotCurve7>
<color>4294945280</color>
<mathFunction>None</mathFunction>
<uavField>StackRemaining-Altitude</uavField>
<uavObject>TaskInfo</uavObject>
<yMaximum>0</yMaximum>
<yMeanSamples>1</yMeanSamples>
<yMinimum>0</yMinimum>
<yScalePower>0</yScalePower>
</plotCurve7>
<plotCurve8>
<color>4283760767</color>
<mathFunction>None</mathFunction>
<uavField>StackRemaining-TelemetryTx</uavField>
<uavObject>TaskInfo</uavObject>
<yMaximum>0</yMaximum>
<yMeanSamples>1</yMeanSamples>
<yMinimum>0</yMinimum>
<yScalePower>0</yScalePower>
</plotCurve8>
<plotCurve9>
<color>4294901760</color>
<mathFunction>None</mathFunction>
<uavField>StackRemaining-TelemetryRx</uavField>
<uavObject>TaskInfo</uavObject>
<yMaximum>0</yMaximum>
<yMeanSamples>1</yMeanSamples>
<yMinimum>0</yMinimum>
<yScalePower>0</yScalePower>
</plotCurve9>
<plotCurve10>
<color>4283782527</color>
<mathFunction>None</mathFunction>
<uavField>StackRemaining-RadioRx</uavField>
<uavObject>TaskInfo</uavObject>
<yMaximum>0</yMaximum>
<yMeanSamples>1</yMeanSamples>
<yMinimum>0</yMinimum>
<yScalePower>0</yScalePower>
</plotCurve10>
<plotCurveCount>11</plotCurveCount>
<plotType>1</plotType>
<refreshInterval>1000</refreshInterval>
</data>
</Stacks__PCT__20monitor>
<Telemetry__PCT__20quality>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<LoggingEnabled>false</LoggingEnabled>
<LoggingNewFileOnConnect>false</LoggingNewFileOnConnect>
<LoggingPath></LoggingPath>
<configurationStreamVersion>1000</configurationStreamVersion>
<dataSize>20</dataSize>
<plotCurve0>
<color>4289374847</color>
<mathFunction>None</mathFunction>
<uavField>TxFailures</uavField>
<uavObject>GCSTelemetryStats</uavObject>
<yMaximum>0</yMaximum>
<yMeanSamples>1</yMeanSamples>
<yMinimum>0</yMinimum>
<yScalePower>0</yScalePower>
</plotCurve0>
<plotCurve1>
<color>4283782655</color>
<mathFunction>None</mathFunction>
<uavField>RxFailures</uavField>
<uavObject>GCSTelemetryStats</uavObject>
<yMaximum>0</yMaximum>
<yMeanSamples>1</yMeanSamples>
<yMinimum>0</yMinimum>
<yScalePower>0</yScalePower>
</plotCurve1>
<plotCurve2>
<color>4294901760</color>
<mathFunction>None</mathFunction>
<uavField>TxRetries</uavField>
<uavObject>GCSTelemetryStats</uavObject>
<yMaximum>0</yMaximum>
<yMeanSamples>1</yMeanSamples>
<yMinimum>0</yMinimum>
<yScalePower>0</yScalePower>
</plotCurve2>
<plotCurveCount>3</plotCurveCount>
<plotType>1</plotType>
<refreshInterval>100</refreshInterval>
</data>
</Telemetry__PCT__20quality>
<Uptimes>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<LoggingEnabled>false</LoggingEnabled>
<LoggingNewFileOnConnect>false</LoggingNewFileOnConnect>
<LoggingPath></LoggingPath>
<configurationStreamVersion>1000</configurationStreamVersion>
<dataSize>240</dataSize>
<plotCurve0>
<color>4294945407</color>
<mathFunction>None</mathFunction>
<uavField>FlightTime</uavField>
<uavObject>SystemStats</uavObject>
<yMaximum>1.02360527502876e-306</yMaximum>
<yMeanSamples>1</yMeanSamples>
<yMinimum>6.92921153586022e-310</yMinimum>
<yScalePower>0</yScalePower>
</plotCurve0>
<plotCurve1>
<color>0</color>
<mathFunction></mathFunction>
<uavField></uavField>
<uavObject></uavObject>
<yMaximum>0</yMaximum>
<yMeanSamples>1</yMeanSamples>
<yMinimum>0</yMinimum>
<yScalePower>0</yScalePower>
</plotCurve1>
<plotCurveCount>2</plotCurveCount>
<plotType>1</plotType>
<refreshInterval>800</refreshInterval>
</data>
</Uptimes>
</ScopeGadget>
<SystemHealthGadget>
<default>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<diagram>%%DATAPATH%%diagrams/default/system-health.svg</diagram>
</data>
</default>
</SystemHealthGadget>
<UAVObjectBrowser>
<default>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<CategorizedView>false</CategorizedView>
<ScientificView>false</ScientificView>
<manuallyChangedColor>#5baa56</manuallyChangedColor>
<onlyHilightChangedValues>false</onlyHilightChangedValues>
<recentlyUpdatedColor>#ff7957</recentlyUpdatedColor>
<recentlyUpdatedTimeout>500</recentlyUpdatedTimeout>
<showMetaData>false</showMetaData>
</data>
</default>
</UAVObjectBrowser>
<Uploader>
<default>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<defaultDataBits>3</defaultDataBits>
<defaultFlow>0</defaultFlow>
<defaultParity>0</defaultParity>
<defaultPort>/dev/ttyS0</defaultPort>
<defaultSpeed>14</defaultSpeed>
<defaultStopBits>0</defaultStopBits>
</data>
</default>
</Uploader>
<configInfo>
<locked>false</locked>
<version>1.2.0</version>
</configInfo>
</UAVGadgetConfigurations>
<UAVGadgetManager>
<Mode1>
<showToolbars>false</showToolbars>
<splitter>
<side0>
<side0>
<side0>
<side0>
<classId>LineardialGadget</classId>
<gadget>
<activeConfiguration>Flight Time</activeConfiguration>
</gadget>
<type>uavGadget</type>
</side0>
<side1>
<side0>
<classId>LineardialGadget</classId>
<gadget>
<activeConfiguration>Arm Status</activeConfiguration>
</gadget>
<type>uavGadget</type>
</side0>
<side1>
<classId>LineardialGadget</classId>
<gadget>
<activeConfiguration>Flight mode</activeConfiguration>
</gadget>
<type>uavGadget</type>
</side1>
<splitterOrientation>1</splitterOrientation>
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAAAYwAAAAIAAAB7)</splitterSizes>
<type>splitter</type>
</side1>
<splitterOrientation>1</splitterOrientation>
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAAAZgAAAAIAAADf)</splitterSizes>
<type>splitter</type>
</side0>
<side1>
<classId>PFDGadget</classId>
<gadget>
<activeConfiguration>raw</activeConfiguration>
</gadget>
<type>uavGadget</type>
</side1>
<splitterOrientation>2</splitterOrientation>
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAAAQAAAAAIAAAG4)</splitterSizes>
<type>splitter</type>
</side0>
<side1>
<side0>
<classId>ModelViewGadget</classId>
<gadget>
<activeConfiguration>Test Quad X</activeConfiguration>
</gadget>
<type>uavGadget</type>
</side0>
<side1>
<classId>SystemHealthGadget</classId>
<gadget>
<activeConfiguration>default</activeConfiguration>
</gadget>
<type>uavGadget</type>
</side1>
<splitterOrientation>1</splitterOrientation>
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAABIAAAAAIAAAFV)</splitterSizes>
<type>splitter</type>
</side1>
<splitterOrientation>2</splitterOrientation>
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAAB7wAAAAIAAAEf)</splitterSizes>
<type>splitter</type>
</side0>
<side1>
<classId>OPMapGadget</classId>
<gadget>
<activeConfiguration>Google Sat</activeConfiguration>
</gadget>
<type>uavGadget</type>
</side1>
<splitterOrientation>1</splitterOrientation>
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAACdgAAAAIAAAMp)</splitterSizes>
<type>splitter</type>
</splitter>
<version>UAVGadgetManagerV1</version>
</Mode1>
<Mode2>
<showToolbars>false</showToolbars>
<splitter>
<side0>
<classId>ConfigGadget</classId>
<gadget>
<activeConfiguration>default</activeConfiguration>
</gadget>
<type>uavGadget</type>
</side0>
<side1>
<classId>UAVObjectBrowser</classId>
<gadget>
<activeConfiguration>default</activeConfiguration>
</gadget>
<type>uavGadget</type>
</side1>
<splitterOrientation>1</splitterOrientation>
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAADRgAAAAIAAAJV)</splitterSizes>
<type>splitter</type>
</splitter>
<version>UAVGadgetManagerV1</version>
</Mode2>
<Mode3>
<showToolbars>false</showToolbars>
<splitter>
<side0>
<classId>UAVObjectBrowser</classId>
<gadget>
<activeConfiguration>default</activeConfiguration>
</gadget>
<type>uavGadget</type>
</side0>
<side1>
<side0>
<side0>
<classId>LoggingGadget</classId>
<type>uavGadget</type>
</side0>
<side1>
<classId>GpsDisplayGadget</classId>
<gadget>
<activeConfiguration>Flight GPS</activeConfiguration>
</gadget>
<type>uavGadget</type>
</side1>
<splitterOrientation>2</splitterOrientation>
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAAAcAAAAAIAAAHo)</splitterSizes>
<type>splitter</type>
</side0>
<side1>
<classId>DebugGadget</classId>
<type>uavGadget</type>
</side1>
<splitterOrientation>2</splitterOrientation>
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAAB3wAAAAIAAAEp)</splitterSizes>
<type>splitter</type>
</side1>
<splitterOrientation>1</splitterOrientation>
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAACJgAAAAIAAADo)</splitterSizes>
<type>splitter</type>
</splitter>
<version>UAVGadgetManagerV1</version>
</Mode3>
<Mode4>
<showToolbars>false</showToolbars>
<splitter>
<side0>
<side0>
<classId>ScopeGadget</classId>
<gadget>
<activeConfiguration>Accel</activeConfiguration>
</gadget>
<type>uavGadget</type>
</side0>
<side1>
<classId>ScopeGadget</classId>
<gadget>
<activeConfiguration>Raw gyroState</activeConfiguration>
</gadget>
<type>uavGadget</type>
</side1>
<splitterOrientation>2</splitterOrientation>
<splitterSizes>@Variant(AAAACQAAAAA=)</splitterSizes>
<type>splitter</type>
</side0>
<side1>
<side0>
<classId>ScopeGadget</classId>
<gadget>
<activeConfiguration>Attitude</activeConfiguration>
</gadget>
<type>uavGadget</type>
</side0>
<side1>
<classId>ScopeGadget</classId>
<gadget>
<activeConfiguration>Uptimes</activeConfiguration>
</gadget>
<type>uavGadget</type>
</side1>
<splitterOrientation>2</splitterOrientation>
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAAClQAAAAIAAAB3)</splitterSizes>
<type>splitter</type>
</side1>
<splitterOrientation>1</splitterOrientation>
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAACjQAAAAIAAAKU)</splitterSizes>
<type>splitter</type>
</splitter>
<version>UAVGadgetManagerV1</version>
</Mode4>
<Mode5>
<showToolbars>false</showToolbars>
<splitter>
<side0>
<side0>
<classId>HITL</classId>
<gadget>
<activeConfiguration>XPlane HITL</activeConfiguration>
</gadget>
<type>uavGadget</type>
</side0>
<side1>
<classId>HITLv2</classId>
<gadget>
<activeConfiguration>default</activeConfiguration>
</gadget>
<type>uavGadget</type>
</side1>
<splitterOrientation>1</splitterOrientation>
<splitterSizes>@Variant(AAAACQAAAAA=)</splitterSizes>
<type>splitter</type>
</side0>
<side1>
<side0>
<classId>EmptyGadget</classId>
<type>uavGadget</type>
</side0>
<side1>
<classId>GCSControlGadget</classId>
<gadget>
<activeConfiguration>MS Sidewinder</activeConfiguration>
</gadget>
<type>uavGadget</type>
</side1>
<splitterOrientation>1</splitterOrientation>
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAAB6AAAAAIAAADC)</splitterSizes>
<type>splitter</type>
</side1>
<splitterOrientation>2</splitterOrientation>
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAADDAAAAAIAAAJJ)</splitterSizes>
<type>splitter</type>
</splitter>
<version>UAVGadgetManagerV1</version>
</Mode5>
<Mode6>
<showToolbars>false</showToolbars>
<splitter>
<side0>
<classId>Uploader</classId>
<gadget>
<activeConfiguration>default</activeConfiguration>
</gadget>
<type>uavGadget</type>
</side0>
<side1>
<side0>
<side0>
<classId>LineardialGadget</classId>
<gadget>
<activeConfiguration>Flight Time</activeConfiguration>
</gadget>
<type>uavGadget</type>
</side0>
<side1>
<classId>SystemHealthGadget</classId>
<gadget>
<activeConfiguration>default</activeConfiguration>
</gadget>
<type>uavGadget</type>
</side1>
<splitterOrientation>1</splitterOrientation>
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAABQgAAAAIAAAGM)</splitterSizes>
<type>splitter</type>
</side0>
<side1>
<side0>
<side0>
<classId>DialGadget</classId>
<gadget>
<activeConfiguration>Deluxe Attitude</activeConfiguration>
</gadget>
<type>uavGadget</type>
</side0>
<side1>
<classId>DialGadget</classId>
<gadget>
<activeConfiguration>Deluxe Baro Altimeter</activeConfiguration>
</gadget>
<type>uavGadget</type>
</side1>
<splitterOrientation>2</splitterOrientation>
<splitterSizes>@Variant(AAAACQAAAAA=)</splitterSizes>
<type>splitter</type>
</side0>
<side1>
<side0>
<classId>DialGadget</classId>
<gadget>
<activeConfiguration>Deluxe Compass</activeConfiguration>
</gadget>
<type>uavGadget</type>
</side0>
<side1>
<classId>DialGadget</classId>
<gadget>
<activeConfiguration>Deluxe Climbrate</activeConfiguration>
</gadget>
<type>uavGadget</type>
</side1>
<splitterOrientation>2</splitterOrientation>
<splitterSizes>@Variant(AAAACQAAAAA=)</splitterSizes>
<type>splitter</type>
</side1>
<splitterOrientation>1</splitterOrientation>
<splitterSizes>@Variant(AAAACQAAAAA=)</splitterSizes>
<type>splitter</type>
</side1>
<splitterOrientation>2</splitterOrientation>
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAABLwAAAAIAAAHf)</splitterSizes>
<type>splitter</type>
</side1>
<splitterOrientation>1</splitterOrientation>
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAADVQAAAAIAAAJK)</splitterSizes>
<type>splitter</type>
</splitter>
<version>UAVGadgetManagerV1</version>
</Mode6>
</UAVGadgetManager>
<Workspace>
<AllowTabBarMovement>false</AllowTabBarMovement>
<Icon1>:/core/images/ah.png</Icon1>
<Icon10>:/core/images/openpilot_logo_64.png</Icon10>
<Icon2>:/core/images/config.png</Icon2>
<Icon3>:/core/images/cog.png</Icon3>
<Icon4>:/core/images/scopes.png</Icon4>
<Icon5>:/core/images/joystick.png</Icon5>
<Icon6>:/core/images/cpu.png</Icon6>
<Icon7>:/core/images/openpilot_logo_64.png</Icon7>
<Icon8>:/core/images/openpilot_logo_64.png</Icon8>
<Icon9>:/core/images/openpilot_logo_64.png</Icon9>
<NumberOfWorkspaces>6</NumberOfWorkspaces>
<TabBarPlacementIndex>1</TabBarPlacementIndex>
<Workspace1>Flight data</Workspace1>
<Workspace10>Workspace10</Workspace10>
<Workspace2>Configuration</Workspace2>
<Workspace3>System</Workspace3>
<Workspace4>Scopes</Workspace4>
<Workspace5>HITL</Workspace5>
<Workspace6>Firmware</Workspace6>
<Workspace7>Workspace7</Workspace7>
<Workspace8>Workspace8</Workspace8>
<Workspace9>Workspace9</Workspace9>
</Workspace>
</gcs>

View File

@ -1146,7 +1146,7 @@
<dFile>%%DATAPATH%%dials/default/arm-status.svg</dFile>
<decimalPlaces>0</decimalPlaces>
<factor>1</factor>
<font>,12,-1,5,50,0,0,0,0,0</font>
<font>MS Shell Dlg 2,12,-1,5,50,0,0,0,0,0</font>
<greenMax>100</greenMax>
<greenMin>66</greenMin>
<maxValue>100</maxValue>
@ -1169,7 +1169,7 @@
<dFile>%%DATAPATH%%dials/default/textonly.svg</dFile>
<decimalPlaces>0</decimalPlaces>
<factor>0.001</factor>
<font>,12,-1,5,50,0,0,0,0,0</font>
<font>MS Shell Dlg 2,12,-1,5,50,0,0,0,0,0</font>
<greenMax>100</greenMax>
<greenMin>66</greenMin>
<maxValue>100</maxValue>
@ -1192,7 +1192,7 @@
<dFile>%%DATAPATH%%dials/default/flightmode-status.svg</dFile>
<decimalPlaces>0</decimalPlaces>
<factor>1</factor>
<font>,12,-1,5,50,0,0,0,0,0</font>
<font>MS Shell Dlg 2,12,-1,5,50,0,0,0,0,0</font>
<greenMax>100</greenMax>
<greenMin>66</greenMin>
<maxValue>100</maxValue>
@ -1215,7 +1215,7 @@
<dFile>%%DATAPATH%%dials/default/gps-signal.svg</dFile>
<decimalPlaces>0</decimalPlaces>
<factor>1</factor>
<font>,12,-1,5,50,0,0,0,0,0</font>
<font>MS Shell Dlg 2,12,-1,5,50,0,0,0,0,0</font>
<greenMax>0</greenMax>
<greenMin>0</greenMin>
<maxValue>12</maxValue>
@ -1238,7 +1238,7 @@
<dFile>%%DATAPATH%%dials/default/gps-status.svg</dFile>
<decimalPlaces>0</decimalPlaces>
<factor>1</factor>
<font>,12,-1,5,50,0,0,0,0,0</font>
<font>MS Shell Dlg 2,12,-1,5,50,0,0,0,0,0</font>
<greenMax>100</greenMax>
<greenMin>66</greenMin>
<maxValue>100</maxValue>

View File

@ -1,2832 +0,0 @@
<gcs>
<General>
<AutoConnect>true</AutoConnect>
<AutoSelect>true</AutoSelect>
<Description>Wide configuration</Description>
<Details>Default configuration built for wide screens (17" and up)</Details>
<ExpertMode>false</ExpertMode>
<LastPreferenceCategory></LastPreferenceCategory>
<LastPreferencePage></LastPreferencePage>
<SaveSettingsOnExit>true</SaveSettingsOnExit>
<SettingsWindowHeight>600</SettingsWindowHeight>
<SettingsWindowWidth>800</SettingsWindowWidth>
<StyleSheet>default</StyleSheet>
<UDPMirror>false</UDPMirror>
</General>
<IPconnection>
<Current>
<arr_1>
<Port>9000</Port>
<UseTCP>0</UseTCP>
</arr_1>
<size>1</size>
</Current>
</IPconnection>
<KeyBindings>
<size>0</size>
</KeyBindings>
<MainWindow>
<Color>#666666</Color>
<FullScreen>false</FullScreen>
<Maximized>true</Maximized>
</MainWindow>
<ModePriorities>
<Mode1>91</Mode1>
<Mode2>90</Mode2>
<Mode3>89</Mode3>
<Mode4>88</Mode4>
<Mode5>87</Mode5>
<Mode6>86</Mode6>
<Welcome>100</Welcome>
</ModePriorities>
<Plugins>
<SoundNotifyPlugin>
<configInfo>
<locked>false</locked>
<version>1.0.0</version>
</configInfo>
<data>
<Current>
<arr_1>
<CurrentLanguage>default</CurrentLanguage>
<DataObject>FlightStatus</DataObject>
<ExpireTimeout>0</ExpireTimeout>
<Mute>false</Mute>
<ObjectField>Armed</ObjectField>
<RangeLimit>0</RangeLimit>
<Repeat>0</Repeat>
<SayOrder>0</SayOrder>
<Sound1>armed</Sound1>
<Sound2></Sound2>
<Sound3></Sound3>
<SoundCollectionPath>%%DATAPATH%%sounds</SoundCollectionPath>
<Value1>Armed</Value1>
<Value2>0</Value2>
</arr_1>
<size>1</size>
</Current>
<EnableSound>true</EnableSound>
<listNotifies>
<arr_1>
<CurrentLanguage>default</CurrentLanguage>
<DataObject>FlightStatus</DataObject>
<ExpireTimeout>15</ExpireTimeout>
<Mute>false</Mute>
<ObjectField>Armed</ObjectField>
<RangeLimit>0</RangeLimit>
<Repeat>0</Repeat>
<SayOrder>0</SayOrder>
<Sound1>armed</Sound1>
<Sound2></Sound2>
<Sound3></Sound3>
<SoundCollectionPath>%%DATAPATH%%sounds</SoundCollectionPath>
<Value1>Armed</Value1>
<Value2>0</Value2>
</arr_1>
<size>1</size>
</listNotifies>
</data>
</SoundNotifyPlugin>
</Plugins>
<SerialConnection>
<speed>57600</speed>
</SerialConnection>
<UAVGadgetConfigurations>
<ConfigGadget>
<default>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
</default>
</ConfigGadget>
<DialGadget>
<Attitude>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<beSmooth>false</beSmooth>
<dialBackgroundID>background</dialBackgroundID>
<dialFile>%%DATAPATH%%dials/default/attitude.svg</dialFile>
<dialForegroundID>foreground</dialForegroundID>
<dialNeedleID1>needle</dialNeedleID1>
<dialNeedleID2>needle</dialNeedleID2>
<dialNeedleID3>needle3</dialNeedleID3>
<font>MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0</font>
<needle1DataObject>AttitudeState</needle1DataObject>
<needle1Factor>-1</needle1Factor>
<needle1MaxValue>360</needle1MaxValue>
<needle1MinValue>0</needle1MinValue>
<needle1Move>Rotate</needle1Move>
<needle1ObjectField>Roll</needle1ObjectField>
<needle2DataObject>AttitudeState</needle2DataObject>
<needle2Factor>75</needle2Factor>
<needle2MaxValue>20</needle2MaxValue>
<needle2MinValue>0</needle2MinValue>
<needle2Move>Vertical</needle2Move>
<needle2ObjectField>Pitch</needle2ObjectField>
<needle3DataObject>AttitudeState</needle3DataObject>
<needle3Factor>-1</needle3Factor>
<needle3MaxValue>360</needle3MaxValue>
<needle3MinValue>0</needle3MinValue>
<needle3Move>Rotate</needle3Move>
<needle3ObjectField>Roll</needle3ObjectField>
<useOpenGLFlag>false</useOpenGLFlag>
</data>
</Attitude>
<Baro__PCT__20Altimeter>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<beSmooth>false</beSmooth>
<dialBackgroundID>background</dialBackgroundID>
<dialFile>%%DATAPATH%%dials/default/altimeter.svg</dialFile>
<dialForegroundID>foreground</dialForegroundID>
<dialNeedleID1>needle</dialNeedleID1>
<dialNeedleID2>needle2</dialNeedleID2>
<dialNeedleID3>needle3</dialNeedleID3>
<font>MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0</font>
<needle1DataObject>BaroSensor</needle1DataObject>
<needle1Factor>1</needle1Factor>
<needle1MaxValue>10</needle1MaxValue>
<needle1MinValue>0</needle1MinValue>
<needle1Move>Rotate</needle1Move>
<needle1ObjectField>Altitude</needle1ObjectField>
<needle2DataObject>BaroSensor</needle2DataObject>
<needle2Factor>1</needle2Factor>
<needle2MaxValue>100</needle2MaxValue>
<needle2MinValue>0</needle2MinValue>
<needle2Move>Rotate</needle2Move>
<needle2ObjectField>Altitude</needle2ObjectField>
<needle3DataObject>BaroSensor</needle3DataObject>
<needle3Factor>1</needle3Factor>
<needle3MaxValue>1000</needle3MaxValue>
<needle3MinValue>0</needle3MinValue>
<needle3Move>Rotate</needle3Move>
<needle3ObjectField>Altitude</needle3ObjectField>
<useOpenGLFlag>false</useOpenGLFlag>
</data>
</Baro__PCT__20Altimeter>
<Barometer>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<beSmooth>false</beSmooth>
<dialBackgroundID>background</dialBackgroundID>
<dialFile>%%DATAPATH%%dials/default/barometer.svg</dialFile>
<dialNeedleID1>needle</dialNeedleID1>
<font>MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0</font>
<needle1DataObject>BaroSensor</needle1DataObject>
<needle1Factor>10</needle1Factor>
<needle1MaxValue>1120</needle1MaxValue>
<needle1MinValue>1000</needle1MinValue>
<needle1Move>Rotate</needle1Move>
<needle1ObjectField>Pressure</needle1ObjectField>
<needle2DataObject>BaroSensor</needle2DataObject>
<needle2Factor>1</needle2Factor>
<needle2MaxValue>100</needle2MaxValue>
<needle2MinValue>0</needle2MinValue>
<needle2Move>Rotate</needle2Move>
<needle2ObjectField>Altitude</needle2ObjectField>
<needle3DataObject>BaroSensor</needle3DataObject>
<needle3Factor>1</needle3Factor>
<needle3MaxValue>1000</needle3MaxValue>
<needle3MinValue>0</needle3MinValue>
<needle3Move>Rotate</needle3Move>
<needle3ObjectField>Altitude</needle3ObjectField>
<useOpenGLFlag>false</useOpenGLFlag>
</data>
</Barometer>
<Climbrate>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<beSmooth>false</beSmooth>
<dialBackgroundID>background</dialBackgroundID>
<dialFile>%%DATAPATH%%dials/default/vsi.svg</dialFile>
<dialNeedleID1>needle</dialNeedleID1>
<font>MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0</font>
<needle1DataObject>VelocityState</needle1DataObject>
<needle1Factor>0.01</needle1Factor>
<needle1MaxValue>12</needle1MaxValue>
<needle1MinValue>-12</needle1MinValue>
<needle1Move>Rotate</needle1Move>
<needle1ObjectField>Down</needle1ObjectField>
<needle2DataObject>BaroSensor</needle2DataObject>
<needle2Factor>1</needle2Factor>
<needle2MaxValue>100</needle2MaxValue>
<needle2MinValue>0</needle2MinValue>
<needle2Move>Rotate</needle2Move>
<needle2ObjectField>Altitude</needle2ObjectField>
<needle3DataObject>BaroSensor</needle3DataObject>
<needle3Factor>1</needle3Factor>
<needle3MaxValue>1000</needle3MaxValue>
<needle3MinValue>0</needle3MinValue>
<needle3Move>Rotate</needle3Move>
<needle3ObjectField>Altitude</needle3ObjectField>
<useOpenGLFlag>false</useOpenGLFlag>
</data>
</Climbrate>
<Compass>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<beSmooth>false</beSmooth>
<dialBackgroundID>background</dialBackgroundID>
<dialFile>%%DATAPATH%%dials/default/compass.svg</dialFile>
<dialForegroundID>foreground</dialForegroundID>
<dialNeedleID1>needle</dialNeedleID1>
<font>MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0</font>
<needle1DataObject>AttitudeState</needle1DataObject>
<needle1Factor>-1</needle1Factor>
<needle1MaxValue>360</needle1MaxValue>
<needle1MinValue>0</needle1MinValue>
<needle1Move>Rotate</needle1Move>
<needle1ObjectField>Yaw</needle1ObjectField>
<needle2DataObject>BaroSensor</needle2DataObject>
<needle2Factor>1</needle2Factor>
<needle2MaxValue>100</needle2MaxValue>
<needle2MinValue>0</needle2MinValue>
<needle2Move>Rotate</needle2Move>
<needle2ObjectField>Altitude</needle2ObjectField>
<needle3DataObject>BaroSensor</needle3DataObject>
<needle3Factor>1</needle3Factor>
<needle3MaxValue>1000</needle3MaxValue>
<needle3MinValue>0</needle3MinValue>
<needle3Move>Rotate</needle3Move>
<needle3ObjectField>Altitude</needle3ObjectField>
<useOpenGLFlag>false</useOpenGLFlag>
</data>
</Compass>
<Deluxe__PCT__20Attitude>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<beSmooth>false</beSmooth>
<dialBackgroundID>background</dialBackgroundID>
<dialFile>%%DATAPATH%%dials/deluxe/attitude.svg</dialFile>
<dialForegroundID>foreground</dialForegroundID>
<dialNeedleID1>needle</dialNeedleID1>
<dialNeedleID2>needle</dialNeedleID2>
<dialNeedleID3>needle3</dialNeedleID3>
<font>MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0</font>
<needle1DataObject>AttitudeState</needle1DataObject>
<needle1Factor>-1</needle1Factor>
<needle1MaxValue>360</needle1MaxValue>
<needle1MinValue>0</needle1MinValue>
<needle1Move>Rotate</needle1Move>
<needle1ObjectField>Roll</needle1ObjectField>
<needle2DataObject>AttitudeState</needle2DataObject>
<needle2Factor>75</needle2Factor>
<needle2MaxValue>20</needle2MaxValue>
<needle2MinValue>0</needle2MinValue>
<needle2Move>Vertical</needle2Move>
<needle2ObjectField>Pitch</needle2ObjectField>
<needle3DataObject>AttitudeState</needle3DataObject>
<needle3Factor>-1</needle3Factor>
<needle3MaxValue>360</needle3MaxValue>
<needle3MinValue>0</needle3MinValue>
<needle3Move>Rotate</needle3Move>
<needle3ObjectField>Roll</needle3ObjectField>
<useOpenGLFlag>false</useOpenGLFlag>
</data>
</Deluxe__PCT__20Attitude>
<Deluxe__PCT__20Baro__PCT__20Altimeter>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<beSmooth>false</beSmooth>
<dialBackgroundID>background</dialBackgroundID>
<dialFile>%%DATAPATH%%dials/deluxe/altimeter.svg</dialFile>
<dialForegroundID>foreground</dialForegroundID>
<dialNeedleID1>needle</dialNeedleID1>
<dialNeedleID2>needle2</dialNeedleID2>
<dialNeedleID3>needle3</dialNeedleID3>
<font>MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0</font>
<needle1DataObject>BaroSensor</needle1DataObject>
<needle1Factor>1</needle1Factor>
<needle1MaxValue>10</needle1MaxValue>
<needle1MinValue>0</needle1MinValue>
<needle1Move>Rotate</needle1Move>
<needle1ObjectField>Altitude</needle1ObjectField>
<needle2DataObject>BaroSensor</needle2DataObject>
<needle2Factor>1</needle2Factor>
<needle2MaxValue>100</needle2MaxValue>
<needle2MinValue>0</needle2MinValue>
<needle2Move>Rotate</needle2Move>
<needle2ObjectField>Altitude</needle2ObjectField>
<needle3DataObject>BaroSensor</needle3DataObject>
<needle3Factor>1</needle3Factor>
<needle3MaxValue>1000</needle3MaxValue>
<needle3MinValue>0</needle3MinValue>
<needle3Move>Rotate</needle3Move>
<needle3ObjectField>Altitude</needle3ObjectField>
<useOpenGLFlag>false</useOpenGLFlag>
</data>
</Deluxe__PCT__20Baro__PCT__20Altimeter>
<Deluxe__PCT__20Barometer>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<beSmooth>false</beSmooth>
<dialBackgroundID>background</dialBackgroundID>
<dialFile>%%DATAPATH%%dials/deluxe/barometer.svg</dialFile>
<dialForegroundID>foreground</dialForegroundID>
<dialNeedleID1>needle</dialNeedleID1>
<font>MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0</font>
<needle1DataObject>BaroSensor</needle1DataObject>
<needle1Factor>10</needle1Factor>
<needle1MaxValue>1120</needle1MaxValue>
<needle1MinValue>1000</needle1MinValue>
<needle1Move>Rotate</needle1Move>
<needle1ObjectField>Pressure</needle1ObjectField>
<needle2DataObject>BaroSensor</needle2DataObject>
<needle2Factor>1</needle2Factor>
<needle2MaxValue>100</needle2MaxValue>
<needle2MinValue>0</needle2MinValue>
<needle2Move>Rotate</needle2Move>
<needle2ObjectField>Altitude</needle2ObjectField>
<needle3DataObject>BaroSensor</needle3DataObject>
<needle3Factor>1</needle3Factor>
<needle3MaxValue>1000</needle3MaxValue>
<needle3MinValue>0</needle3MinValue>
<needle3Move>Rotate</needle3Move>
<needle3ObjectField>Altitude</needle3ObjectField>
<useOpenGLFlag>false</useOpenGLFlag>
</data>
</Deluxe__PCT__20Barometer>
<Deluxe__PCT__20Climbrate>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<beSmooth>false</beSmooth>
<dialBackgroundID>background</dialBackgroundID>
<dialFile>%%DATAPATH%%dials/deluxe/vsi.svg</dialFile>
<dialForegroundID>foreground</dialForegroundID>
<dialNeedleID1>needle</dialNeedleID1>
<font>MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0</font>
<needle1DataObject>VelocityState</needle1DataObject>
<needle1Factor>0.01</needle1Factor>
<needle1MaxValue>11.2</needle1MaxValue>
<needle1MinValue>-11.2</needle1MinValue>
<needle1Move>Rotate</needle1Move>
<needle1ObjectField>Down</needle1ObjectField>
<needle2DataObject>BaroSensor</needle2DataObject>
<needle2Factor>1</needle2Factor>
<needle2MaxValue>100</needle2MaxValue>
<needle2MinValue>0</needle2MinValue>
<needle2Move>Rotate</needle2Move>
<needle2ObjectField>Altitude</needle2ObjectField>
<needle3DataObject>BaroSensor</needle3DataObject>
<needle3Factor>1</needle3Factor>
<needle3MaxValue>1000</needle3MaxValue>
<needle3MinValue>0</needle3MinValue>
<needle3Move>Rotate</needle3Move>
<needle3ObjectField>Altitude</needle3ObjectField>
<useOpenGLFlag>false</useOpenGLFlag>
</data>
</Deluxe__PCT__20Climbrate>
<Deluxe__PCT__20Compass>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<beSmooth>false</beSmooth>
<dialBackgroundID>background</dialBackgroundID>
<dialFile>%%DATAPATH%%dials/deluxe/compass.svg</dialFile>
<dialForegroundID>foreground</dialForegroundID>
<dialNeedleID1>needle</dialNeedleID1>
<font>MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0</font>
<needle1DataObject>AttitudeState</needle1DataObject>
<needle1Factor>-1</needle1Factor>
<needle1MaxValue>360</needle1MaxValue>
<needle1MinValue>0</needle1MinValue>
<needle1Move>Rotate</needle1Move>
<needle1ObjectField>Yaw</needle1ObjectField>
<needle2DataObject>BaroSensor</needle2DataObject>
<needle2Factor>1</needle2Factor>
<needle2MaxValue>100</needle2MaxValue>
<needle2MinValue>0</needle2MinValue>
<needle2Move>Rotate</needle2Move>
<needle2ObjectField>Altitude</needle2ObjectField>
<needle3DataObject>BaroSensor</needle3DataObject>
<needle3Factor>1</needle3Factor>
<needle3MaxValue>1000</needle3MaxValue>
<needle3MinValue>0</needle3MinValue>
<needle3Move>Rotate</needle3Move>
<needle3ObjectField>Altitude</needle3ObjectField>
<useOpenGLFlag>false</useOpenGLFlag>
</data>
</Deluxe__PCT__20Compass>
<Deluxe__PCT__20Groundspeed__PCT__20kph>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<beSmooth>false</beSmooth>
<dialBackgroundID>background</dialBackgroundID>
<dialFile>%%DATAPATH%%dials/deluxe/speed.svg</dialFile>
<dialForegroundID>foreground</dialForegroundID>
<dialNeedleID1>needle</dialNeedleID1>
<font>MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0</font>
<needle1DataObject>GPSPositionSensor</needle1DataObject>
<needle1Factor>3.6</needle1Factor>
<needle1MaxValue>120</needle1MaxValue>
<needle1MinValue>0</needle1MinValue>
<needle1Move>Rotate</needle1Move>
<needle1ObjectField>Groundspeed</needle1ObjectField>
<needle2DataObject>BaroSensor</needle2DataObject>
<needle2Factor>1</needle2Factor>
<needle2MaxValue>100</needle2MaxValue>
<needle2MinValue>0</needle2MinValue>
<needle2Move>Rotate</needle2Move>
<needle2ObjectField>Altitude</needle2ObjectField>
<needle3DataObject>BaroSensor</needle3DataObject>
<needle3Factor>1</needle3Factor>
<needle3MaxValue>1000</needle3MaxValue>
<needle3MinValue>0</needle3MinValue>
<needle3Move>Rotate</needle3Move>
<needle3ObjectField>Altitude</needle3ObjectField>
<useOpenGLFlag>false</useOpenGLFlag>
</data>
</Deluxe__PCT__20Groundspeed__PCT__20kph>
<Deluxe__PCT__20Temperature>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<beSmooth>false</beSmooth>
<dialBackgroundID>background</dialBackgroundID>
<dialFile>%%DATAPATH%%dials/deluxe/thermometer.svg</dialFile>
<dialForegroundID>foreground</dialForegroundID>
<dialNeedleID1>needle</dialNeedleID1>
<dialNeedleID2>needle2</dialNeedleID2>
<dialNeedleID3>needle3</dialNeedleID3>
<font>MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0</font>
<needle1DataObject>BaroSensor</needle1DataObject>
<needle1Factor>1</needle1Factor>
<needle1MaxValue>120</needle1MaxValue>
<needle1MinValue>0</needle1MinValue>
<needle1Move>Rotate</needle1Move>
<needle1ObjectField>Temperature</needle1ObjectField>
<needle2DataObject>BaroSensor</needle2DataObject>
<needle2Factor>1</needle2Factor>
<needle2MaxValue>100</needle2MaxValue>
<needle2MinValue>0</needle2MinValue>
<needle2Move>Rotate</needle2Move>
<needle2ObjectField>Altitude</needle2ObjectField>
<needle3DataObject>BaroSensor</needle3DataObject>
<needle3Factor>1</needle3Factor>
<needle3MaxValue>1000</needle3MaxValue>
<needle3MinValue>0</needle3MinValue>
<needle3Move>Rotate</needle3Move>
<needle3ObjectField>Altitude</needle3ObjectField>
<useOpenGLFlag>false</useOpenGLFlag>
</data>
</Deluxe__PCT__20Temperature>
<Deluxe__PCT__20Turn__PCT__20Coordinator>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<beSmooth>false</beSmooth>
<dialBackgroundID>background</dialBackgroundID>
<dialFile>/home/lafargue/OP/OpenPilot/trunk/artwork/Dials/deluxe/turncoordinator.svg</dialFile>
<dialForegroundID>foreground</dialForegroundID>
<dialNeedleID1>needle</dialNeedleID1>
<dialNeedleID2>needle2</dialNeedleID2>
<dialNeedleID3>needle2</dialNeedleID3>
<font>MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0</font>
<needle1DataObject>AttitudeState</needle1DataObject>
<needle1Factor>-1</needle1Factor>
<needle1MaxValue>360</needle1MaxValue>
<needle1MinValue>0</needle1MinValue>
<needle1Move>Rotate</needle1Move>
<needle1ObjectField>Roll</needle1ObjectField>
<needle2DataObject>AccelState</needle2DataObject>
<needle2Factor>1</needle2Factor>
<needle2MaxValue>20</needle2MaxValue>
<needle2MinValue>-20</needle2MinValue>
<needle2Move>Horizontal</needle2Move>
<needle2ObjectField>x</needle2ObjectField>
<needle3DataObject>AccelState</needle3DataObject>
<needle3Factor>-1</needle3Factor>
<needle3MaxValue>360</needle3MaxValue>
<needle3MinValue>0</needle3MinValue>
<needle3Move>Rotate</needle3Move>
<needle3ObjectField>x</needle3ObjectField>
<useOpenGLFlag>false</useOpenGLFlag>
</data>
</Deluxe__PCT__20Turn__PCT__20Coordinator>
<Groundspeed__PCT__20kph>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<beSmooth>false</beSmooth>
<dialBackgroundID>background</dialBackgroundID>
<dialFile>%%DATAPATH%%dials/default/speed.svg</dialFile>
<dialNeedleID1>needle</dialNeedleID1>
<font>MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0</font>
<needle1DataObject>GPSPositionSensor</needle1DataObject>
<needle1Factor>3.6</needle1Factor>
<needle1MaxValue>120</needle1MaxValue>
<needle1MinValue>0</needle1MinValue>
<needle1Move>Rotate</needle1Move>
<needle1ObjectField>Groundspeed</needle1ObjectField>
<needle2DataObject>BaroSensor</needle2DataObject>
<needle2Factor>1</needle2Factor>
<needle2MaxValue>100</needle2MaxValue>
<needle2MinValue>0</needle2MinValue>
<needle2Move>Rotate</needle2Move>
<needle2ObjectField>Altitude</needle2ObjectField>
<needle3DataObject>BaroSensor</needle3DataObject>
<needle3Factor>1</needle3Factor>
<needle3MaxValue>1000</needle3MaxValue>
<needle3MinValue>0</needle3MinValue>
<needle3Move>Rotate</needle3Move>
<needle3ObjectField>Altitude</needle3ObjectField>
<useOpenGLFlag>false</useOpenGLFlag>
</data>
</Groundspeed__PCT__20kph>
<HiContrast__PCT__20Attitude>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<beSmooth>false</beSmooth>
<dialBackgroundID>background</dialBackgroundID>
<dialFile>%%DATAPATH%%dials/hi-contrast/attitude.svg</dialFile>
<dialForegroundID>foreground</dialForegroundID>
<dialNeedleID1>needle</dialNeedleID1>
<dialNeedleID2>needle</dialNeedleID2>
<dialNeedleID3>needle3</dialNeedleID3>
<font>MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0</font>
<needle1DataObject>AttitudeState</needle1DataObject>
<needle1Factor>-1</needle1Factor>
<needle1MaxValue>360</needle1MaxValue>
<needle1MinValue>0</needle1MinValue>
<needle1Move>Rotate</needle1Move>
<needle1ObjectField>Roll</needle1ObjectField>
<needle2DataObject>AttitudeState</needle2DataObject>
<needle2Factor>75</needle2Factor>
<needle2MaxValue>20</needle2MaxValue>
<needle2MinValue>0</needle2MinValue>
<needle2Move>Vertical</needle2Move>
<needle2ObjectField>Pitch</needle2ObjectField>
<needle3DataObject>AttitudeState</needle3DataObject>
<needle3Factor>-1</needle3Factor>
<needle3MaxValue>360</needle3MaxValue>
<needle3MinValue>0</needle3MinValue>
<needle3Move>Rotate</needle3Move>
<needle3ObjectField>Roll</needle3ObjectField>
<useOpenGLFlag>false</useOpenGLFlag>
</data>
</HiContrast__PCT__20Attitude>
<HiContrast__PCT__20Baro__PCT__20Altimeter>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<beSmooth>false</beSmooth>
<dialBackgroundID>background</dialBackgroundID>
<dialFile>%%DATAPATH%%dials/hi-contrast/altimeter.svg</dialFile>
<dialForegroundID>foreground</dialForegroundID>
<dialNeedleID1>needle</dialNeedleID1>
<dialNeedleID2>needle2</dialNeedleID2>
<dialNeedleID3>needle3</dialNeedleID3>
<font>MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0</font>
<needle1DataObject>BaroSensor</needle1DataObject>
<needle1Factor>1</needle1Factor>
<needle1MaxValue>10</needle1MaxValue>
<needle1MinValue>0</needle1MinValue>
<needle1Move>Rotate</needle1Move>
<needle1ObjectField>Altitude</needle1ObjectField>
<needle2DataObject>BaroSensor</needle2DataObject>
<needle2Factor>1</needle2Factor>
<needle2MaxValue>100</needle2MaxValue>
<needle2MinValue>0</needle2MinValue>
<needle2Move>Rotate</needle2Move>
<needle2ObjectField>Altitude</needle2ObjectField>
<needle3DataObject>BaroSensor</needle3DataObject>
<needle3Factor>1</needle3Factor>
<needle3MaxValue>1000</needle3MaxValue>
<needle3MinValue>0</needle3MinValue>
<needle3Move>Rotate</needle3Move>
<needle3ObjectField>Altitude</needle3ObjectField>
<useOpenGLFlag>false</useOpenGLFlag>
</data>
</HiContrast__PCT__20Baro__PCT__20Altimeter>
<HiContrast__PCT__20Barometer>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<beSmooth>false</beSmooth>
<dialBackgroundID>background</dialBackgroundID>
<dialFile>%%DATAPATH%%dials/hi-contrast/barometer.svg</dialFile>
<dialNeedleID1>needle</dialNeedleID1>
<font>MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0</font>
<needle1DataObject>BaroSensor</needle1DataObject>
<needle1Factor>10</needle1Factor>
<needle1MaxValue>1120</needle1MaxValue>
<needle1MinValue>1000</needle1MinValue>
<needle1Move>Rotate</needle1Move>
<needle1ObjectField>Pressure</needle1ObjectField>
<needle2DataObject>BaroSensor</needle2DataObject>
<needle2Factor>1</needle2Factor>
<needle2MaxValue>100</needle2MaxValue>
<needle2MinValue>0</needle2MinValue>
<needle2Move>Rotate</needle2Move>
<needle2ObjectField>Altitude</needle2ObjectField>
<needle3DataObject>BaroSensor</needle3DataObject>
<needle3Factor>1</needle3Factor>
<needle3MaxValue>1000</needle3MaxValue>
<needle3MinValue>0</needle3MinValue>
<needle3Move>Rotate</needle3Move>
<needle3ObjectField>Altitude</needle3ObjectField>
<useOpenGLFlag>false</useOpenGLFlag>
</data>
</HiContrast__PCT__20Barometer>
<HiContrast__PCT__20Climbrate>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<beSmooth>false</beSmooth>
<dialBackgroundID>background</dialBackgroundID>
<dialFile>%%DATAPATH%%dials/hi-contrast/vsi.svg</dialFile>
<dialNeedleID1>needle</dialNeedleID1>
<font>MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0</font>
<needle1DataObject>VelocityState</needle1DataObject>
<needle1Factor>0.01</needle1Factor>
<needle1MaxValue>12</needle1MaxValue>
<needle1MinValue>-12</needle1MinValue>
<needle1Move>Rotate</needle1Move>
<needle1ObjectField>Down</needle1ObjectField>
<needle2DataObject>BaroSensor</needle2DataObject>
<needle2Factor>1</needle2Factor>
<needle2MaxValue>100</needle2MaxValue>
<needle2MinValue>0</needle2MinValue>
<needle2Move>Rotate</needle2Move>
<needle2ObjectField>Altitude</needle2ObjectField>
<needle3DataObject>BaroSensor</needle3DataObject>
<needle3Factor>1</needle3Factor>
<needle3MaxValue>1000</needle3MaxValue>
<needle3MinValue>0</needle3MinValue>
<needle3Move>Rotate</needle3Move>
<needle3ObjectField>Altitude</needle3ObjectField>
<useOpenGLFlag>false</useOpenGLFlag>
</data>
</HiContrast__PCT__20Climbrate>
<HiContrast__PCT__20Compass>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<beSmooth>false</beSmooth>
<dialBackgroundID>background</dialBackgroundID>
<dialFile>%%DATAPATH%%dials/hi-contrast/compass.svg</dialFile>
<dialForegroundID>foreground</dialForegroundID>
<dialNeedleID1>needle</dialNeedleID1>
<font>MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0</font>
<needle1DataObject>AttitudeState</needle1DataObject>
<needle1Factor>-1</needle1Factor>
<needle1MaxValue>360</needle1MaxValue>
<needle1MinValue>0</needle1MinValue>
<needle1Move>Rotate</needle1Move>
<needle1ObjectField>Yaw</needle1ObjectField>
<needle2DataObject>BaroSensor</needle2DataObject>
<needle2Factor>1</needle2Factor>
<needle2MaxValue>100</needle2MaxValue>
<needle2MinValue>0</needle2MinValue>
<needle2Move>Rotate</needle2Move>
<needle2ObjectField>Altitude</needle2ObjectField>
<needle3DataObject>BaroSensor</needle3DataObject>
<needle3Factor>1</needle3Factor>
<needle3MaxValue>1000</needle3MaxValue>
<needle3MinValue>0</needle3MinValue>
<needle3Move>Rotate</needle3Move>
<needle3ObjectField>Altitude</needle3ObjectField>
<useOpenGLFlag>false</useOpenGLFlag>
</data>
</HiContrast__PCT__20Compass>
<HiContrast__PCT__20Groundspeed__PCT__20kph>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<beSmooth>false</beSmooth>
<dialBackgroundID>background</dialBackgroundID>
<dialFile>%%DATAPATH%%dials/hi-contrast/speed.svg</dialFile>
<dialNeedleID1>needle</dialNeedleID1>
<font>MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0</font>
<needle1DataObject>GPSPositionSensor</needle1DataObject>
<needle1Factor>3.6</needle1Factor>
<needle1MaxValue>120</needle1MaxValue>
<needle1MinValue>0</needle1MinValue>
<needle1Move>Rotate</needle1Move>
<needle1ObjectField>Groundspeed</needle1ObjectField>
<needle2DataObject>BaroSensor</needle2DataObject>
<needle2Factor>1</needle2Factor>
<needle2MaxValue>100</needle2MaxValue>
<needle2MinValue>0</needle2MinValue>
<needle2Move>Rotate</needle2Move>
<needle2ObjectField>Altitude</needle2ObjectField>
<needle3DataObject>BaroSensor</needle3DataObject>
<needle3Factor>1</needle3Factor>
<needle3MaxValue>1000</needle3MaxValue>
<needle3MinValue>0</needle3MinValue>
<needle3Move>Rotate</needle3Move>
<needle3ObjectField>Altitude</needle3ObjectField>
<useOpenGLFlag>false</useOpenGLFlag>
</data>
</HiContrast__PCT__20Groundspeed__PCT__20kph>
<HiContrast__PCT__20Temperature>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<beSmooth>false</beSmooth>
<dialBackgroundID>background</dialBackgroundID>
<dialFile>%%DATAPATH%%dials/hi-contrast/thermometer.svg</dialFile>
<dialNeedleID1>needle</dialNeedleID1>
<dialNeedleID2>needle2</dialNeedleID2>
<dialNeedleID3>needle3</dialNeedleID3>
<font>MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0</font>
<needle1DataObject>BaroSensor</needle1DataObject>
<needle1Factor>1</needle1Factor>
<needle1MaxValue>120</needle1MaxValue>
<needle1MinValue>0</needle1MinValue>
<needle1Move>Rotate</needle1Move>
<needle1ObjectField>Temperature</needle1ObjectField>
<needle2DataObject>BaroSensor</needle2DataObject>
<needle2Factor>1</needle2Factor>
<needle2MaxValue>100</needle2MaxValue>
<needle2MinValue>0</needle2MinValue>
<needle2Move>Rotate</needle2Move>
<needle2ObjectField>Altitude</needle2ObjectField>
<needle3DataObject>BaroSensor</needle3DataObject>
<needle3Factor>1</needle3Factor>
<needle3MaxValue>1000</needle3MaxValue>
<needle3MinValue>0</needle3MinValue>
<needle3Move>Rotate</needle3Move>
<needle3ObjectField>Altitude</needle3ObjectField>
<useOpenGLFlag>false</useOpenGLFlag>
</data>
</HiContrast__PCT__20Temperature>
<Servo__PCT__20Channel__PCT__201>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<beSmooth>false</beSmooth>
<dialBackgroundID>background</dialBackgroundID>
<dialFile>%%DATAPATH%%dials/default/thermometer.svg</dialFile>
<dialNeedleID1>needle</dialNeedleID1>
<dialNeedleID2>needle2</dialNeedleID2>
<dialNeedleID3>needle3</dialNeedleID3>
<font>MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0</font>
<needle1DataObject>ManualControlCommand</needle1DataObject>
<needle1Factor>1</needle1Factor>
<needle1MaxValue>2000</needle1MaxValue>
<needle1MinValue>1000</needle1MinValue>
<needle1Move>Rotate</needle1Move>
<needle1ObjectField>Channel-3</needle1ObjectField>
<needle2DataObject>BaroSensor</needle2DataObject>
<needle2Factor>1</needle2Factor>
<needle2MaxValue>100</needle2MaxValue>
<needle2MinValue>0</needle2MinValue>
<needle2Move>Rotate</needle2Move>
<needle2ObjectField>Altitude</needle2ObjectField>
<needle3DataObject>BaroSensor</needle3DataObject>
<needle3Factor>1</needle3Factor>
<needle3MaxValue>1000</needle3MaxValue>
<needle3MinValue>0</needle3MinValue>
<needle3Move>Rotate</needle3Move>
<needle3ObjectField>Altitude</needle3ObjectField>
<useOpenGLFlag>false</useOpenGLFlag>
</data>
</Servo__PCT__20Channel__PCT__201>
<Temperature>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<beSmooth>false</beSmooth>
<dialBackgroundID>background</dialBackgroundID>
<dialFile>%%DATAPATH%%dials/default/thermometer.svg</dialFile>
<dialNeedleID1>needle</dialNeedleID1>
<dialNeedleID2>needle2</dialNeedleID2>
<dialNeedleID3>needle3</dialNeedleID3>
<font>MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0</font>
<needle1DataObject>BaroSensor</needle1DataObject>
<needle1Factor>1</needle1Factor>
<needle1MaxValue>120</needle1MaxValue>
<needle1MinValue>0</needle1MinValue>
<needle1Move>Rotate</needle1Move>
<needle1ObjectField>Temperature</needle1ObjectField>
<needle2DataObject>BaroSensor</needle2DataObject>
<needle2Factor>1</needle2Factor>
<needle2MaxValue>100</needle2MaxValue>
<needle2MinValue>0</needle2MinValue>
<needle2Move>Rotate</needle2Move>
<needle2ObjectField>Altitude</needle2ObjectField>
<needle3DataObject>BaroSensor</needle3DataObject>
<needle3Factor>1</needle3Factor>
<needle3MaxValue>1000</needle3MaxValue>
<needle3MinValue>0</needle3MinValue>
<needle3Move>Rotate</needle3Move>
<needle3ObjectField>Altitude</needle3ObjectField>
<useOpenGLFlag>false</useOpenGLFlag>
</data>
</Temperature>
</DialGadget>
<GCSControlGadget>
<MS__PCT__20Sidewinder>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<button0Action>0</button0Action>
<button0Amount>0</button0Amount>
<button0Function>0</button0Function>
<button1Action>0</button1Action>
<button1Amount>0</button1Amount>
<button1Function>0</button1Function>
<button2Action>0</button2Action>
<button2Amount>0.1</button2Amount>
<button2Function>3</button2Function>
<button3Action>0</button3Action>
<button3Amount>0.1</button3Amount>
<button3Function>3</button3Function>
<button4Action>0</button4Action>
<button4Amount>0</button4Amount>
<button4Function>0</button4Function>
<button5Action>0</button5Action>
<button5Amount>0</button5Amount>
<button5Function>0</button5Function>
<button6Action>0</button6Action>
<button6Amount>0</button6Amount>
<button6Function>0</button6Function>
<button7Action>0</button7Action>
<button7Amount>0</button7Amount>
<button7Function>0</button7Function>
<channel0Reverse>false</channel0Reverse>
<channel1Reverse>false</channel1Reverse>
<channel2Reverse>true</channel2Reverse>
<channel3Reverse>false</channel3Reverse>
<channel4Reverse>false</channel4Reverse>
<channel5Reverse>false</channel5Reverse>
<channel6Reverse>false</channel6Reverse>
<channel7Reverse>false</channel7Reverse>
<controlPortUDP>0</controlPortUDP>
<controlsMode>2</controlsMode>
<pitchChannel>1</pitchChannel>
<rollChannel>0</rollChannel>
<throttleChannel>2</throttleChannel>
<yawChannel>3</yawChannel>
</data>
</MS__PCT__20Sidewinder>
</GCSControlGadget>
<GpsDisplayGadget>
<Flight__PCT__20GPS>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<connectionMode>Telemetry</connectionMode>
<defaultDataBits>3</defaultDataBits>
<defaultFlow>0</defaultFlow>
<defaultParity>0</defaultParity>
<defaultPort>Communications Port (COM1)</defaultPort>
<defaultSpeed>11</defaultSpeed>
<defaultStopBits>0</defaultStopBits>
</data>
</Flight__PCT__20GPS>
<GPS__PCT__20Mouse>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<connectionMode>Serial</connectionMode>
<defaultDataBits>3</defaultDataBits>
<defaultFlow>0</defaultFlow>
<defaultParity>0</defaultParity>
<defaultPort>Communications Port (COM1)</defaultPort>
<defaultSpeed>17</defaultSpeed>
<defaultStopBits>0</defaultStopBits>
</data>
</GPS__PCT__20Mouse>
</GpsDisplayGadget>
<HITL>
<AeroSimRC__PCT__20HITL>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<addNoise>false</addNoise>
<attActCalc>false</attActCalc>
<attActHW>false</attActHW>
<attActSim>true</attActSim>
<attStateEnabled>true</attStateEnabled>
<attRawEnabled>true</attRawEnabled>
<attRawRate>20</attRawRate>
<baroAltRate>50</baroAltRate>
<baroAltitudeEnabled>false</baroAltitudeEnabled>
<binPath></binPath>
<dataPath></dataPath>
<gcsReceiverEnabled>true</gcsReceiverEnabled>
<gpsPosRate>100</gpsPosRate>
<gpsPositionEnabled>false</gpsPositionEnabled>
<groundTruthEnabled>true</groundTruthEnabled>
<groundTruthRate>100</groundTruthRate>
<hostAddress>0.0.0.0</hostAddress>
<inPort>40100</inPort>
<inputCommand>true</inputCommand>
<latitude></latitude>
<longitude></longitude>
<manualControlEnabled>false</manualControlEnabled>
<manualOutput>false</manualOutput>
<minOutputPeriod>40</minOutputPeriod>
<outPort>40200</outPort>
<remoteAddress>127.0.0.1</remoteAddress>
<simulatorId>ASimRC</simulatorId>
<startSim>false</startSim>
</data>
</AeroSimRC__PCT__20HITL>
<Flightgear__PCT__20HITL>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<addNoise>false</addNoise>
<attActCalc>false</attActCalc>
<attActHW>false</attActHW>
<attActSim>true</attActSim>
<attStateEnabled>true</attStateEnabled>
<attRawEnabled>true</attRawEnabled>
<attRawRate>20</attRawRate>
<baroAltRate>50</baroAltRate>
<baroAltitudeEnabled>false</baroAltitudeEnabled>
<binPath>\usr\games\fgfs</binPath>
<dataPath>\usr\share\games\FlightGear</dataPath>
<gcsReceiverEnabled>false</gcsReceiverEnabled>
<gpsPosRate>100</gpsPosRate>
<gpsPositionEnabled>false</gpsPositionEnabled>
<groundTruthEnabled>true</groundTruthEnabled>
<groundTruthRate>100</groundTruthRate>
<hostAddress>127.0.0.1</hostAddress>
<inPort>9009</inPort>
<inputCommand>true</inputCommand>
<latitude></latitude>
<longitude></longitude>
<manualControlEnabled>true</manualControlEnabled>
<manualOutput>false</manualOutput>
<minOutputPeriod>40</minOutputPeriod>
<outPort>9010</outPort>
<remoteAddress>127.0.0.1</remoteAddress>
<simulatorId>FG</simulatorId>
<startSim>true</startSim>
</data>
</Flightgear__PCT__20HITL>
<XPlane__PCT__20HITL>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<addNoise>false</addNoise>
<attActCalc>false</attActCalc>
<attActHW>false</attActHW>
<attActSim>true</attActSim>
<attStateEnabled>true</attStateEnabled>
<attRawEnabled>true</attRawEnabled>
<attRawRate>20</attRawRate>
<baroAltRate>50</baroAltRate>
<baroAltitudeEnabled>false</baroAltitudeEnabled>
<binPath></binPath>
<dataPath></dataPath>
<gcsReceiverEnabled>false</gcsReceiverEnabled>
<gpsPosRate>100</gpsPosRate>
<gpsPositionEnabled>false</gpsPositionEnabled>
<groundTruthEnabled>true</groundTruthEnabled>
<groundTruthRate>100</groundTruthRate>
<hostAddress>0.0.0.0</hostAddress>
<inPort>6756</inPort>
<inputCommand>true</inputCommand>
<latitude></latitude>
<longitude></longitude>
<manualControlEnabled>true</manualControlEnabled>
<manualOutput>false</manualOutput>
<minOutputPeriod>40</minOutputPeriod>
<outPort>49000</outPort>
<remoteAddress>127.0.0.1</remoteAddress>
<simulatorId>X-Plane</simulatorId>
<startSim>false</startSim>
</data>
</XPlane__PCT__20HITL>
</HITL>
<LineardialGadget>
<Accel__PCT__20Horizontal__PCT__20X>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<dFile>%%DATAPATH%%dials/deluxe/lineardial-horizontal.svg</dFile>
<decimalPlaces>2</decimalPlaces>
<factor>1</factor>
<font>Andale Mono,8,-1,5,50,0,0,0,0,0</font>
<greenMax>-9</greenMax>
<greenMin>-10</greenMin>
<maxValue>11</maxValue>
<minValue>-11</minValue>
<redMax>11</redMax>
<redMin>-11</redMin>
<sourceDataObject>AccelState</sourceDataObject>
<sourceObjectField>x</sourceObjectField>
<useOpenGLFlag>false</useOpenGLFlag>
<yellowMax>-5</yellowMax>
<yellowMin>-11</yellowMin>
</data>
</Accel__PCT__20Horizontal__PCT__20X>
<Accel__PCT__20Horizontal__PCT__20Y>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<dFile>%%DATAPATH%%dials/deluxe/lineardial-horizontal.svg</dFile>
<decimalPlaces>2</decimalPlaces>
<factor>1</factor>
<font>Andale Mono,6,-1,5,50,0,0,0,0,0</font>
<greenMax>-9</greenMax>
<greenMin>-10</greenMin>
<maxValue>11</maxValue>
<minValue>-11</minValue>
<redMax>11</redMax>
<redMin>-11</redMin>
<sourceDataObject>AccelState</sourceDataObject>
<sourceObjectField>y</sourceObjectField>
<useOpenGLFlag>false</useOpenGLFlag>
<yellowMax>-5</yellowMax>
<yellowMin>-11</yellowMin>
</data>
</Accel__PCT__20Horizontal__PCT__20Y>
<Accel__PCT__20Horizontal__PCT__20Z>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<dFile>%%DATAPATH%%dials/deluxe/lineardial-horizontal.svg</dFile>
<decimalPlaces>2</decimalPlaces>
<factor>1</factor>
<font>Andale Mono,8,-1,5,50,0,0,0,0,0</font>
<greenMax>-9</greenMax>
<greenMin>-10</greenMin>
<maxValue>11</maxValue>
<minValue>-11</minValue>
<redMax>11</redMax>
<redMin>-11</redMin>
<sourceDataObject>AccelState</sourceDataObject>
<sourceObjectField>z</sourceObjectField>
<useOpenGLFlag>false</useOpenGLFlag>
<yellowMax>-5</yellowMax>
<yellowMin>-11</yellowMin>
</data>
</Accel__PCT__20Horizontal__PCT__20Z>
<Arm__PCT__20Status>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<dFile>%%DATAPATH%%dials/default/arm-status.svg</dFile>
<decimalPlaces>0</decimalPlaces>
<factor>1</factor>
<font>,12,-1,5,50,0,0,0,0,0</font>
<greenMax>100</greenMax>
<greenMin>66</greenMin>
<maxValue>100</maxValue>
<minValue>0</minValue>
<redMax>33</redMax>
<redMin>0</redMin>
<sourceDataObject>FlightStatus</sourceDataObject>
<sourceObjectField>Armed</sourceObjectField>
<useOpenGLFlag>false</useOpenGLFlag>
<yellowMax>66</yellowMax>
<yellowMin>33</yellowMin>
</data>
</Arm__PCT__20Status>
<Flight__PCT__20Time>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<dFile>%%DATAPATH%%dials/default/textonly.svg</dFile>
<decimalPlaces>0</decimalPlaces>
<factor>0.001</factor>
<font>,12,-1,5,50,0,0,0,0,0</font>
<greenMax>100</greenMax>
<greenMin>66</greenMin>
<maxValue>100</maxValue>
<minValue>0</minValue>
<redMax>33</redMax>
<redMin>0</redMin>
<sourceDataObject>SystemStats</sourceDataObject>
<sourceObjectField>FlightTime</sourceObjectField>
<useOpenGLFlag>false</useOpenGLFlag>
<yellowMax>66</yellowMax>
<yellowMin>33</yellowMin>
</data>
</Flight__PCT__20Time>
<Flight__PCT__20mode>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<dFile>%%DATAPATH%%dials/default/flightmode-status.svg</dFile>
<decimalPlaces>0</decimalPlaces>
<factor>1</factor>
<font>,12,-1,5,50,0,0,0,0,0</font>
<greenMax>100</greenMax>
<greenMin>66</greenMin>
<maxValue>100</maxValue>
<minValue>0</minValue>
<redMax>33</redMax>
<redMin>0</redMin>
<sourceDataObject>FlightStatus</sourceDataObject>
<sourceObjectField>FlightMode</sourceObjectField>
<useOpenGLFlag>false</useOpenGLFlag>
<yellowMax>66</yellowMax>
<yellowMin>33</yellowMin>
</data>
</Flight__PCT__20mode>
<GPS__PCT__20Sats>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<dFile>%%DATAPATH%%dials/default/gps-signal.svg</dFile>
<decimalPlaces>0</decimalPlaces>
<factor>1</factor>
<font>,12,-1,5,50,0,0,0,0,0</font>
<greenMax>0</greenMax>
<greenMin>0</greenMin>
<maxValue>12</maxValue>
<minValue>0</minValue>
<redMax>0</redMax>
<redMin>0</redMin>
<sourceDataObject>GPSPositionSensor</sourceDataObject>
<sourceObjectField>Satellites</sourceObjectField>
<useOpenGLFlag>false</useOpenGLFlag>
<yellowMax>0</yellowMax>
<yellowMin>0</yellowMin>
</data>
</GPS__PCT__20Sats>
<GPS__PCT__20Status>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<dFile>%%DATAPATH%%dials/default/gps-status.svg</dFile>
<decimalPlaces>0</decimalPlaces>
<factor>1</factor>
<font>,12,-1,5,50,0,0,0,0,0</font>
<greenMax>100</greenMax>
<greenMin>66</greenMin>
<maxValue>100</maxValue>
<minValue>0</minValue>
<redMax>33</redMax>
<redMin>0</redMin>
<sourceDataObject>GPSPositionSensor</sourceDataObject>
<sourceObjectField>Status</sourceObjectField>
<useOpenGLFlag>false</useOpenGLFlag>
<yellowMax>66</yellowMax>
<yellowMin>33</yellowMin>
</data>
</GPS__PCT__20Status>
<Mainboard__PCT__20CPU>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<dFile>%%DATAPATH%%dials/deluxe/lineardial-vertical.svg</dFile>
<decimalPlaces>0</decimalPlaces>
<factor>1</factor>
<font>Andale Mono,12,-1,5,75,0,0,0,0,0</font>
<greenMax>90</greenMax>
<greenMin>0</greenMin>
<maxValue>100</maxValue>
<minValue>0</minValue>
<redMax>100</redMax>
<redMin>95</redMin>
<sourceDataObject>SystemStats</sourceDataObject>
<sourceObjectField>CPULoad</sourceObjectField>
<useOpenGLFlag>false</useOpenGLFlag>
<yellowMax>95</yellowMax>
<yellowMin>90</yellowMin>
</data>
</Mainboard__PCT__20CPU>
<Pitch__PCT__20Desired>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<dFile>%%DATAPATH%%dials/deluxe/lineardial-vertical.svg</dFile>
<decimalPlaces>2</decimalPlaces>
<factor>1</factor>
<font>Andale Mono,12,-1,5,75,0,0,0,0,0</font>
<greenMax>0.5</greenMax>
<greenMin>-0.5</greenMin>
<maxValue>1</maxValue>
<minValue>-1</minValue>
<redMax>1</redMax>
<redMin>-1</redMin>
<sourceDataObject>ActuatorDesired</sourceDataObject>
<sourceObjectField>Pitch</sourceObjectField>
<useOpenGLFlag>false</useOpenGLFlag>
<yellowMax>0.8</yellowMax>
<yellowMin>-0.8</yellowMin>
</data>
</Pitch__PCT__20Desired>
<Pitch>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<dFile>%%DATAPATH%%dials/deluxe/lineardial-vertical.svg</dFile>
<decimalPlaces>2</decimalPlaces>
<factor>1</factor>
<font>Andale Mono,12,-1,5,75,0,0,0,0,0</font>
<greenMax>0.5</greenMax>
<greenMin>-0.5</greenMin>
<maxValue>1</maxValue>
<minValue>-1</minValue>
<redMax>1</redMax>
<redMin>-1</redMin>
<sourceDataObject>ManualControlCommand</sourceDataObject>
<sourceObjectField>Pitch</sourceObjectField>
<useOpenGLFlag>false</useOpenGLFlag>
<yellowMax>0.8</yellowMax>
<yellowMin>-0.8</yellowMin>
</data>
</Pitch>
<PitchState>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<dFile>%%DATAPATH%%dials/deluxe/lineardial-vertical.svg</dFile>
<decimalPlaces>2</decimalPlaces>
<factor>1</factor>
<font>Andale Mono,12,-1,5,75,0,0,0,0,0</font>
<greenMax>0.8</greenMax>
<greenMin>0.3</greenMin>
<maxValue>90</maxValue>
<minValue>-90</minValue>
<redMax>1</redMax>
<redMin>0</redMin>
<sourceDataObject>AttitudeState</sourceDataObject>
<sourceObjectField>Pitch</sourceObjectField>
<useOpenGLFlag>false</useOpenGLFlag>
<yellowMax>0.9</yellowMax>
<yellowMin>0.1</yellowMin>
</data>
</PitchState>
<Roll__PCT__20Desired>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<dFile>%%DATAPATH%%dials/deluxe/lineardial-vertical.svg</dFile>
<decimalPlaces>2</decimalPlaces>
<factor>1</factor>
<font>Andale Mono,12,-1,5,75,0,0,0,0,0</font>
<greenMax>0.5</greenMax>
<greenMin>-0.5</greenMin>
<maxValue>1</maxValue>
<minValue>-1</minValue>
<redMax>1</redMax>
<redMin>-1</redMin>
<sourceDataObject>ActuatorDesired</sourceDataObject>
<sourceObjectField>Roll</sourceObjectField>
<useOpenGLFlag>false</useOpenGLFlag>
<yellowMax>0.8</yellowMax>
<yellowMin>-0.8</yellowMin>
</data>
</Roll__PCT__20Desired>
<Roll>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<dFile>%%DATAPATH%%dials/deluxe/lineardial-vertical.svg</dFile>
<decimalPlaces>2</decimalPlaces>
<factor>1</factor>
<font>Andale Mono,12,-1,5,75,0,0,0,0,0</font>
<greenMax>0.5</greenMax>
<greenMin>-0.5</greenMin>
<maxValue>1</maxValue>
<minValue>-1</minValue>
<redMax>1</redMax>
<redMin>-1</redMin>
<sourceDataObject>ManualControlCommand</sourceDataObject>
<sourceObjectField>Roll</sourceObjectField>
<useOpenGLFlag>false</useOpenGLFlag>
<yellowMax>0.8</yellowMax>
<yellowMin>-0.8</yellowMin>
</data>
</Roll>
<Telemetry__PCT__20RX__PCT__20Rate__PCT__20Horizontal>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<dFile>%%DATAPATH%%dials/deluxe/lineardial-horizontal.svg</dFile>
<decimalPlaces>0</decimalPlaces>
<factor>1</factor>
<font>Andale Mono,12,-1,5,75,0,0,0,0,0</font>
<greenMax>650</greenMax>
<greenMin>0</greenMin>
<maxValue>1200</maxValue>
<minValue>0</minValue>
<redMax>1200</redMax>
<redMin>900</redMin>
<sourceDataObject>GCSTelemetryStats</sourceDataObject>
<sourceObjectField>RxDataRate</sourceObjectField>
<useOpenGLFlag>false</useOpenGLFlag>
<yellowMax>900</yellowMax>
<yellowMin>650</yellowMin>
</data>
</Telemetry__PCT__20RX__PCT__20Rate__PCT__20Horizontal>
<Telemetry__PCT__20TX__PCT__20Rate__PCT__20Horizontal>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<dFile>%%DATAPATH%%dials/deluxe/lineardial-horizontal.svg</dFile>
<decimalPlaces>0</decimalPlaces>
<factor>1</factor>
<font>Andale Mono,12,-1,5,75,0,0,0,0,0</font>
<greenMax>650</greenMax>
<greenMin>0</greenMin>
<maxValue>1200</maxValue>
<minValue>0</minValue>
<redMax>1200</redMax>
<redMin>900</redMin>
<sourceDataObject>GCSTelemetryStats</sourceDataObject>
<sourceObjectField>TxDataRate</sourceObjectField>
<useOpenGLFlag>false</useOpenGLFlag>
<yellowMax>900</yellowMax>
<yellowMin>650</yellowMin>
</data>
</Telemetry__PCT__20TX__PCT__20Rate__PCT__20Horizontal>
<Throttle>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<dFile>%%DATAPATH%%dials/deluxe/lineardial-vertical.svg</dFile>
<decimalPlaces>2</decimalPlaces>
<factor>1</factor>
<font>Andale Mono,12,-1,5,75,0,0,0,0,0</font>
<greenMax>0.5</greenMax>
<greenMin>0</greenMin>
<maxValue>1</maxValue>
<minValue>0</minValue>
<redMax>1</redMax>
<redMin>0.75</redMin>
<sourceDataObject>ManualControlCommand</sourceDataObject>
<sourceObjectField>Throttle</sourceObjectField>
<useOpenGLFlag>false</useOpenGLFlag>
<yellowMax>0.75</yellowMax>
<yellowMin>0.5</yellowMin>
</data>
</Throttle>
<Yaw__PCT__20Desired>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<dFile>%%DATAPATH%%dials/deluxe/lineardial-vertical.svg</dFile>
<decimalPlaces>2</decimalPlaces>
<factor>1</factor>
<font>Andale Mono,12,-1,5,75,0,0,0,0,0</font>
<greenMax>0.5</greenMax>
<greenMin>-0.5</greenMin>
<maxValue>1</maxValue>
<minValue>-1</minValue>
<redMax>1</redMax>
<redMin>-1</redMin>
<sourceDataObject>ActuatorDesired</sourceDataObject>
<sourceObjectField>Yaw</sourceObjectField>
<useOpenGLFlag>false</useOpenGLFlag>
<yellowMax>0.8</yellowMax>
<yellowMin>-0.8</yellowMin>
</data>
</Yaw__PCT__20Desired>
<Yaw>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<dFile>%%DATAPATH%%dials/deluxe/lineardial-vertical.svg</dFile>
<decimalPlaces>2</decimalPlaces>
<factor>1</factor>
<font>Andale Mono,12,-1,5,75,0,0,0,0,0</font>
<greenMax>0.5</greenMax>
<greenMin>-0.5</greenMin>
<maxValue>1</maxValue>
<minValue>-1</minValue>
<redMax>1</redMax>
<redMin>-1</redMin>
<sourceDataObject>ManualControlCommand</sourceDataObject>
<sourceObjectField>Yaw</sourceObjectField>
<useOpenGLFlag>false</useOpenGLFlag>
<yellowMax>0.8</yellowMax>
<yellowMin>-0.8</yellowMin>
</data>
</Yaw>
</LineardialGadget>
<ModelViewGadget>
<Aeroquad__PCT__20__PCT__2B>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<acFilename>%%DATAPATH%%models/multi/aeroquad/aeroquad_+.3ds</acFilename>
<bgFilename>%%DATAPATH%%models/backgrounds/default_background.png</bgFilename>
<enableVbo>false</enableVbo>
</data>
</Aeroquad__PCT__20__PCT__2B>
<CC3D>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<acFilename>%%DATAPATH%%models/boards/CC3D/CC3D.3ds</acFilename>
<bgFilename>%%DATAPATH%%models/backgrounds/default_background.png</bgFilename>
<enableVbo>false</enableVbo>
</data>
</CC3D>
<CopterControl>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<acFilename>%%DATAPATH%%models/boards/CopterControl/CopterControl.3ds</acFilename>
<bgFilename>%%DATAPATH%%models/backgrounds/default_background.png</bgFilename>
<enableVbo>false</enableVbo>
</data>
</CopterControl>
<Danker__PCT__27s__PCT__20Quad>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<acFilename>%%DATAPATH%%models/multi/dankers_quad/dankers_quad.3ds</acFilename>
<bgFilename>%%DATAPATH%%models/backgrounds/default_background.png</bgFilename>
<enableVbo>false</enableVbo>
</data>
</Danker__PCT__27s__PCT__20Quad>
<Easyquad__PCT__20X>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<acFilename>%%DATAPATH%%models/multi/easy_quad/easy_quad_X.3ds</acFilename>
<bgFilename>%%DATAPATH%%models/backgrounds/default_background.png</bgFilename>
<enableVbo>false</enableVbo>
</data>
</Easyquad__PCT__20X>
<Easystar>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<acFilename>%%DATAPATH%%models/planes/Easystar/easystar.3ds</acFilename>
<bgFilename>%%DATAPATH%%models/backgrounds/default_background.png</bgFilename>
<enableVbo>false</enableVbo>
</data>
</Easystar>
<Firecracker>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<acFilename>%%DATAPATH%%models/planes/firecracker/firecracker.3ds</acFilename>
<bgFilename>%%DATAPATH%%models/backgrounds/default_background.png</bgFilename>
<enableVbo>false</enableVbo>
</data>
</Firecracker>
<Funjet>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<acFilename>%%DATAPATH%%models/planes/funjet/funjet.3ds</acFilename>
<bgFilename>%%DATAPATH%%models/backgrounds/default_background.png</bgFilename>
<enableVbo>false</enableVbo>
</data>
</Funjet>
<Gaui__PCT__20330X>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<acFilename>%%DATAPATH%%models/multi/gaui_330x/gaui_330x.3ds</acFilename>
<bgFilename>%%DATAPATH%%models/backgrounds/default_background.png</bgFilename>
<enableVbo>false</enableVbo>
</data>
</Gaui__PCT__20330X>
<Helicopter__PCT__20-__PCT__20TRex__PCT__20450>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<acFilename>%%DATAPATH%%models/helis/t-rex/t-rex_450_xl.3ds</acFilename>
<bgFilename>%%DATAPATH%%models/backgrounds/default_background.png</bgFilename>
<enableVbo>false</enableVbo>
</data>
</Helicopter__PCT__20-__PCT__20TRex__PCT__20450>
<Hexacopter>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<acFilename>%%DATAPATH%%models/multi/mikrokopter/MK_Hexa.3ds</acFilename>
<bgFilename>%%DATAPATH%%models/backgrounds/default_background.png</bgFilename>
<enableVbo>false</enableVbo>
</data>
</Hexacopter>
<Joe__PCT__27s__PCT__2014__PCT__22__PCT__20Quad__PCT__20__PCT__2B>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<acFilename>%%DATAPATH%%models/multi/joes_cnc/J14-Q_+.3DS</acFilename>
<bgFilename>%%DATAPATH%%models/backgrounds/default_background.png</bgFilename>
<enableVbo>false</enableVbo>
</data>
</Joe__PCT__27s__PCT__2014__PCT__22__PCT__20Quad__PCT__20__PCT__2B>
<Joe__PCT__27s__PCT__2014__PCT__22__PCT__20Quad__PCT__20X__PCT__20>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<acFilename>%%DATAPATH%%models/multi/joes_cnc/J14-Q_X.3DS</acFilename>
<bgFilename>%%DATAPATH%%models/backgrounds/default_background.png</bgFilename>
<enableVbo>false</enableVbo>
</data>
</Joe__PCT__27s__PCT__2014__PCT__22__PCT__20Quad__PCT__20X__PCT__20>
<Joe__PCT__27s__PCT__2014__PCT__22__PCT__20T__PCT__20Quad__PCT__20__PCT__2B>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<acFilename>%%DATAPATH%%models/multi/joes_cnc/J14-QT_+.3DS</acFilename>
<bgFilename>%%DATAPATH%%models/backgrounds/default_background.png</bgFilename>
<enableVbo>false</enableVbo>
</data>
</Joe__PCT__27s__PCT__2014__PCT__22__PCT__20T__PCT__20Quad__PCT__20__PCT__2B>
<Joe__PCT__27s__PCT__2014__PCT__22__PCT__20T__PCT__20Quad__PCT__20X>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<acFilename>%%DATAPATH%%models/multi/joes_cnc/J14-QT_X.3DS</acFilename>
<bgFilename>%%DATAPATH%%models/backgrounds/default_background.png</bgFilename>
<enableVbo>false</enableVbo>
</data>
</Joe__PCT__27s__PCT__2014__PCT__22__PCT__20T__PCT__20Quad__PCT__20X>
<MattL__PCT__27s__PCT__20Y6>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<acFilename>%%DATAPATH%%models/multi/mattL_Y6/mattL_Y6.3ds</acFilename>
<bgFilename>%%DATAPATH%%models/backgrounds/default_background.png</bgFilename>
<enableVbo>false</enableVbo>
</data>
</MattL__PCT__27s__PCT__20Y6>
<Quadcopter>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<acFilename>%%DATAPATH%%models/multi/mikrokopter/MK_L4-ME.3ds</acFilename>
<bgFilename>%%DATAPATH%%models/backgrounds/default_background.png</bgFilename>
<enableVbo>false</enableVbo>
</data>
</Quadcopter>
<Ricoo>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<acFilename>%%DATAPATH%%models/multi/ricoo/ricoo.3DS</acFilename>
<bgFilename>%%DATAPATH%%models/backgrounds/default_background.png</bgFilename>
<enableVbo>false</enableVbo>
</data>
</Ricoo>
<Scorpion__PCT__20Tricopter>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<acFilename>%%DATAPATH%%models/multi/scorpion_tricopter/scorpion_tricopter.3ds</acFilename>
<bgFilename>%%DATAPATH%%models/backgrounds/default_background.png</bgFilename>
<enableVbo>false</enableVbo>
</data>
</Scorpion__PCT__20Tricopter>
<Test__PCT__20Quad__PCT__20__PCT__2B>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<acFilename>%%DATAPATH%%models/multi/test_quad/test_quad_+.3ds</acFilename>
<bgFilename>%%DATAPATH%%models/backgrounds/default_background.png</bgFilename>
<enableVbo>false</enableVbo>
</data>
</Test__PCT__20Quad__PCT__20__PCT__2B>
<Test__PCT__20Quad__PCT__20X>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<acFilename>%%DATAPATH%%models/multi/test_quad/test_quad_X.3ds</acFilename>
<bgFilename>%%DATAPATH%%models/backgrounds/default_background.png</bgFilename>
<enableVbo>false</enableVbo>
</data>
</Test__PCT__20Quad__PCT__20X>
</ModelViewGadget>
<OPMapGadget>
<Google__PCT__20Sat>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<accessMode>ServerAndCache</accessMode>
<cacheLocation>%%STOREPATH%%mapscache/</cacheLocation>
<defaultLatitude>0</defaultLatitude>
<defaultLongitude>0</defaultLongitude>
<defaultZoom>2</defaultZoom>
<mapProvider>GoogleSatellite</mapProvider>
<maxUpdateRate>2000</maxUpdateRate>
<overlayOpacity>1</overlayOpacity>
<showTileGridLines>false</showTileGridLines>
<uavSymbol>mapquad.png</uavSymbol>
<useMemoryCache>true</useMemoryCache>
<useOpenGL>true</useOpenGL>
</data>
</Google__PCT__20Sat>
<Memory__PCT__20Only>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<accessMode>CacheOnly</accessMode>
<cacheLocation>%%STOREPATH%%mapscache/</cacheLocation>
<defaultLatitude>0</defaultLatitude>
<defaultLongitude>0</defaultLongitude>
<defaultZoom>2</defaultZoom>
<mapProvider>GoogleMap</mapProvider>
<maxUpdateRate>2000</maxUpdateRate>
<overlayOpacity>1</overlayOpacity>
<showTileGridLines>false</showTileGridLines>
<uavSymbol>airplanepip.png</uavSymbol>
<useMemoryCache>true</useMemoryCache>
<useOpenGL>true</useOpenGL>
</data>
</Memory__PCT__20Only>
<default>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<accessMode>ServerAndCache</accessMode>
<cacheLocation>%%STOREPATH%%mapscache/</cacheLocation>
<defaultLatitude>0</defaultLatitude>
<defaultLongitude>0</defaultLongitude>
<defaultZoom>2</defaultZoom>
<mapProvider>GoogleMap</mapProvider>
<maxUpdateRate>2000</maxUpdateRate>
<overlayOpacity>1</overlayOpacity>
<showTileGridLines>false</showTileGridLines>
<uavSymbol>mapquad.png</uavSymbol>
<useMemoryCache>true</useMemoryCache>
<useOpenGL>true</useOpenGL>
</data>
</default>
</OPMapGadget>
<PfdQmlGadget>
<NoTerrain>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<actualPositionUsed>false</actualPositionUsed>
<altitude>2000</altitude>
<altitudeFactor>1</altitudeFactor>
<cacheOnly>false</cacheOnly>
<earthFile>%%DATAPATH%%pfd/default/readymap.earth</earthFile>
<latitude>46.6715</latitude>
<longitude>10.1589</longitude>
<openGLEnabled>true</openGLEnabled>
<qmlFile>%%DATAPATH%%pfd/default/Pfd.qml</qmlFile>
<speedFactor>1</speedFactor>
<terrainEnabled>false</terrainEnabled>
</data>
</NoTerrain>
<Terrain>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<actualPositionUsed>false</actualPositionUsed>
<altitude>2000</altitude>
<cacheOnly>false</cacheOnly>
<earthFile>%%DATAPATH%%pfd/default/readymap.earth</earthFile>
<latitude>46.6715</latitude>
<longitude>10.1589</longitude>
<openGLEnabled>true</openGLEnabled>
<qmlFile>%%DATAPATH%%pfd/default/Pfd.qml</qmlFile>
<terrainEnabled>false</terrainEnabled>
</data>
</Terrain>
</PfdQmlGadget>
<QmlViewGadget>
<default>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<dialFile>Unknown</dialFile>
<useOpenGLFlag>true</useOpenGLFlag>
</data>
</default>
</QmlViewGadget>
<ScopeGadget>
<Accel>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<LoggingEnabled>false</LoggingEnabled>
<LoggingNewFileOnConnect>false</LoggingNewFileOnConnect>
<configurationStreamVersion>1000</configurationStreamVersion>
<dataSize>60</dataSize>
<plotCurve0>
<color>4294901760</color>
<mathFunction>None</mathFunction>
<uavField>x</uavField>
<uavObject>AccelState</uavObject>
<yMaximum>0</yMaximum>
<yMeanSamples>1</yMeanSamples>
<yMinimum>0</yMinimum>
<yScalePower>0</yScalePower>
</plotCurve0>
<plotCurve1>
<color>4283782655</color>
<mathFunction>None</mathFunction>
<uavField>y</uavField>
<uavObject>AccelState</uavObject>
<yMaximum>0</yMaximum>
<yMeanSamples>1</yMeanSamples>
<yMinimum>0</yMinimum>
<yScalePower>0</yScalePower>
</plotCurve1>
<plotCurve2>
<color>4283804160</color>
<mathFunction>None</mathFunction>
<uavField>z</uavField>
<uavObject>AccelState</uavObject>
<yMaximum>0</yMaximum>
<yMeanSamples>1</yMeanSamples>
<yMinimum>0</yMinimum>
<yScalePower>0</yScalePower>
</plotCurve2>
<plotCurveCount>3</plotCurveCount>
<plotType>1</plotType>
<refreshInterval>100</refreshInterval>
</data>
</Accel>
<Actuators>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<LoggingEnabled>false</LoggingEnabled>
<LoggingNewFileOnConnect>false</LoggingNewFileOnConnect>
<configurationStreamVersion>1000</configurationStreamVersion>
<dataSize>20</dataSize>
<plotCurve0>
<color>4294901760</color>
<mathFunction>None</mathFunction>
<uavField>Channel-4</uavField>
<uavObject>ActuatorCommand</uavObject>
<yMaximum>0</yMaximum>
<yMeanSamples>1</yMeanSamples>
<yMinimum>0</yMinimum>
<yScalePower>0</yScalePower>
</plotCurve0>
<plotCurve1>
<color>4294901760</color>
<mathFunction>None</mathFunction>
<uavField>Channel-5</uavField>
<uavObject>ActuatorCommand</uavObject>
<yMaximum>0</yMaximum>
<yMeanSamples>1</yMeanSamples>
<yMinimum>0</yMinimum>
<yScalePower>0</yScalePower>
</plotCurve1>
<plotCurve2>
<color>4289374847</color>
<mathFunction>None</mathFunction>
<uavField>Channel-6</uavField>
<uavObject>ActuatorCommand</uavObject>
<yMaximum>0</yMaximum>
<yMeanSamples>1</yMeanSamples>
<yMinimum>0</yMinimum>
<yScalePower>0</yScalePower>
</plotCurve2>
<plotCurve3>
<color>4289374847</color>
<mathFunction>None</mathFunction>
<uavField>Channel-7</uavField>
<uavObject>ActuatorCommand</uavObject>
<yMaximum>0</yMaximum>
<yMeanSamples>1</yMeanSamples>
<yMinimum>0</yMinimum>
<yScalePower>0</yScalePower>
</plotCurve3>
<plotCurveCount>4</plotCurveCount>
<plotType>1</plotType>
<refreshInterval>100</refreshInterval>
</data>
</Actuators>
<Attitude>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<LoggingEnabled>false</LoggingEnabled>
<LoggingNewFileOnConnect>false</LoggingNewFileOnConnect>
<configurationStreamVersion>1000</configurationStreamVersion>
<dataSize>60</dataSize>
<plotCurve0>
<color>4283760895</color>
<mathFunction>None</mathFunction>
<uavField>Roll</uavField>
<uavObject>AttitudeState</uavObject>
<yMaximum>0</yMaximum>
<yMeanSamples>1</yMeanSamples>
<yMinimum>0</yMinimum>
<yScalePower>0</yScalePower>
</plotCurve0>
<plotCurve1>
<color>4278233600</color>
<mathFunction>None</mathFunction>
<uavField>Yaw</uavField>
<uavObject>AttitudeState</uavObject>
<yMaximum>0</yMaximum>
<yMeanSamples>1</yMeanSamples>
<yMinimum>0</yMinimum>
<yScalePower>0</yScalePower>
</plotCurve1>
<plotCurve2>
<color>4294901760</color>
<mathFunction>None</mathFunction>
<uavField>Pitch</uavField>
<uavObject>AttitudeState</uavObject>
<yMaximum>0</yMaximum>
<yMeanSamples>1</yMeanSamples>
<yMinimum>0</yMinimum>
<yScalePower>0</yScalePower>
</plotCurve2>
<plotCurveCount>3</plotCurveCount>
<plotType>1</plotType>
<refreshInterval>100</refreshInterval>
</data>
</Attitude>
<Barometer>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<LoggingEnabled>false</LoggingEnabled>
<LoggingNewFileOnConnect>false</LoggingNewFileOnConnect>
<configurationStreamVersion>1000</configurationStreamVersion>
<dataSize>60</dataSize>
<plotCurve0>
<color>4278190080</color>
<mathFunction>None</mathFunction>
<uavField>Pressure</uavField>
<uavObject>BaroSensor</uavObject>
<yMaximum>0</yMaximum>
<yMeanSamples>1</yMeanSamples>
<yMinimum>0</yMinimum>
<yScalePower>0</yScalePower>
</plotCurve0>
<plotCurveCount>1</plotCurveCount>
<plotType>1</plotType>
<refreshInterval>1000</refreshInterval>
</data>
</Barometer>
<Inputs>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<LoggingEnabled>false</LoggingEnabled>
<LoggingNewFileOnConnect>false</LoggingNewFileOnConnect>
<configurationStreamVersion>1000</configurationStreamVersion>
<dataSize>40</dataSize>
<plotCurve0>
<color>4278190207</color>
<mathFunction>None</mathFunction>
<uavField>Channel-1</uavField>
<uavObject>ManualControlCommand</uavObject>
<yMaximum>0</yMaximum>
<yMeanSamples>1</yMeanSamples>
<yMinimum>0</yMinimum>
<yScalePower>0</yScalePower>
</plotCurve0>
<plotCurve1>
<color>4294901760</color>
<mathFunction>None</mathFunction>
<uavField>Channel-4</uavField>
<uavObject>ManualControlCommand</uavObject>
<yMaximum>0</yMaximum>
<yMeanSamples>1</yMeanSamples>
<yMinimum>0</yMinimum>
<yScalePower>0</yScalePower>
</plotCurve1>
<plotCurve2>
<color>4294901760</color>
<mathFunction>None</mathFunction>
<uavField>Channel-5</uavField>
<uavObject>ManualControlCommand</uavObject>
<yMaximum>0</yMaximum>
<yMeanSamples>1</yMeanSamples>
<yMinimum>0</yMinimum>
<yScalePower>0</yScalePower>
</plotCurve2>
<plotCurve3>
<color>4294901760</color>
<mathFunction>None</mathFunction>
<uavField>Channel-6</uavField>
<uavObject>ManualControlCommand</uavObject>
<yMaximum>0</yMaximum>
<yMeanSamples>1</yMeanSamples>
<yMinimum>0</yMinimum>
<yScalePower>0</yScalePower>
</plotCurve3>
<plotCurve4>
<color>4294901760</color>
<mathFunction>None</mathFunction>
<uavField>Channel-7</uavField>
<uavObject>ManualControlCommand</uavObject>
<yMaximum>0</yMaximum>
<yMeanSamples>1</yMeanSamples>
<yMinimum>0</yMinimum>
<yScalePower>0</yScalePower>
</plotCurve4>
<plotCurve5>
<color>4283825920</color>
<mathFunction>None</mathFunction>
<uavField>Channel-2</uavField>
<uavObject>ManualControlCommand</uavObject>
<yMaximum>0</yMaximum>
<yMeanSamples>1</yMeanSamples>
<yMinimum>0</yMinimum>
<yScalePower>0</yScalePower>
</plotCurve5>
<plotCurve6>
<color>4294923520</color>
<mathFunction>None</mathFunction>
<uavField>Channel-3</uavField>
<uavObject>ManualControlCommand</uavObject>
<yMaximum>0</yMaximum>
<yMeanSamples>1</yMeanSamples>
<yMinimum>0</yMinimum>
<yScalePower>0</yScalePower>
</plotCurve6>
<plotCurve7>
<color>4294967040</color>
<mathFunction>None</mathFunction>
<uavField>Channel-0</uavField>
<uavObject>ManualControlCommand</uavObject>
<yMaximum>0</yMaximum>
<yMeanSamples>1</yMeanSamples>
<yMinimum>0</yMinimum>
<yScalePower>0</yScalePower>
</plotCurve7>
<plotCurveCount>8</plotCurveCount>
<plotType>1</plotType>
<refreshInterval>200</refreshInterval>
</data>
</Inputs>
<Raw__PCT__20AccelState>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<LoggingEnabled>false</LoggingEnabled>
<LoggingNewFileOnConnect>false</LoggingNewFileOnConnect>
<configurationStreamVersion>1000</configurationStreamVersion>
<dataSize>60</dataSize>
<plotCurve0>
<color>4294901760</color>
<mathFunction>None</mathFunction>
<uavField>x</uavField>
<uavObject>AccelState</uavObject>
<yMaximum>0</yMaximum>
<yMeanSamples>1</yMeanSamples>
<yMinimum>0</yMinimum>
<yScalePower>0</yScalePower>
</plotCurve0>
<plotCurve1>
<color>4283782655</color>
<mathFunction>None</mathFunction>
<uavField>y</uavField>
<uavObject>AccelState</uavObject>
<yMaximum>0</yMaximum>
<yMeanSamples>1</yMeanSamples>
<yMinimum>0</yMinimum>
<yScalePower>0</yScalePower>
</plotCurve1>
<plotCurve2>
<color>4283804160</color>
<mathFunction>None</mathFunction>
<uavField>z</uavField>
<uavObject>AccelState</uavObject>
<yMaximum>0</yMaximum>
<yMeanSamples>1</yMeanSamples>
<yMinimum>0</yMinimum>
<yScalePower>0</yScalePower>
</plotCurve2>
<plotCurveCount>3</plotCurveCount>
<plotType>1</plotType>
<refreshInterval>500</refreshInterval>
</data>
</Raw__PCT__20AccelState>
<Raw__PCT__20GyroState>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<LoggingEnabled>false</LoggingEnabled>
<LoggingNewFileOnConnect>false</LoggingNewFileOnConnect>
<configurationStreamVersion>1000</configurationStreamVersion>
<dataSize>60</dataSize>
<plotCurve0>
<color>4283804160</color>
<mathFunction>None</mathFunction>
<uavField>z</uavField>
<uavObject>GyroState</uavObject>
<yMaximum>0</yMaximum>
<yMeanSamples>1</yMeanSamples>
<yMinimum>0</yMinimum>
<yScalePower>0</yScalePower>
</plotCurve0>
<plotCurve1>
<color>4283782655</color>
<mathFunction>None</mathFunction>
<uavField>y</uavField>
<uavObject>GyroState</uavObject>
<yMaximum>0</yMaximum>
<yMeanSamples>1</yMeanSamples>
<yMinimum>0</yMinimum>
<yScalePower>0</yScalePower>
</plotCurve1>
<plotCurve2>
<color>4294901760</color>
<mathFunction>None</mathFunction>
<uavField>x</uavField>
<uavObject>GyroState</uavObject>
<yMaximum>0</yMaximum>
<yMeanSamples>1</yMeanSamples>
<yMinimum>0</yMinimum>
<yScalePower>0</yScalePower>
</plotCurve2>
<plotCurveCount>3</plotCurveCount>
<plotType>1</plotType>
<refreshInterval>500</refreshInterval>
</data>
</Raw__PCT__20GyroState>
<Raw__PCT__20magnetometers>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<LoggingEnabled>false</LoggingEnabled>
<LoggingNewFileOnConnect>false</LoggingNewFileOnConnect>
<configurationStreamVersion>1000</configurationStreamVersion>
<dataSize>60</dataSize>
<plotCurve0>
<color>4294901760</color>
<mathFunction>None</mathFunction>
<uavField>x</uavField>
<uavObject>MagState</uavObject>
<yMaximum>0</yMaximum>
<yMeanSamples>1</yMeanSamples>
<yMinimum>0</yMinimum>
<yScalePower>0</yScalePower>
</plotCurve0>
<plotCurve1>
<color>4283782655</color>
<mathFunction>None</mathFunction>
<uavField>y</uavField>
<uavObject>MagState</uavObject>
<yMaximum>0</yMaximum>
<yMeanSamples>1</yMeanSamples>
<yMinimum>0</yMinimum>
<yScalePower>0</yScalePower>
</plotCurve1>
<plotCurve2>
<color>4283804160</color>
<mathFunction>None</mathFunction>
<uavField>z</uavField>
<uavObject>MagState</uavObject>
<yMaximum>0</yMaximum>
<yMeanSamples>1</yMeanSamples>
<yMinimum>0</yMinimum>
<yScalePower>0</yScalePower>
</plotCurve2>
<plotCurveCount>3</plotCurveCount>
<plotType>1</plotType>
<refreshInterval>500</refreshInterval>
</data>
</Raw__PCT__20magnetometers>
<Stacks__PCT__20monitor>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<LoggingEnabled>false</LoggingEnabled>
<LoggingNewFileOnConnect>false</LoggingNewFileOnConnect>
<configurationStreamVersion>1000</configurationStreamVersion>
<dataSize>240</dataSize>
<plotCurve0>
<color>4294901760</color>
<mathFunction>None</mathFunction>
<uavField>StackRemaining-System</uavField>
<uavObject>TaskInfo</uavObject>
<yMaximum>0</yMaximum>
<yMeanSamples>1</yMeanSamples>
<yMinimum>0</yMinimum>
<yScalePower>0</yScalePower>
</plotCurve0>
<plotCurve1>
<color>4294945280</color>
<mathFunction>None</mathFunction>
<uavField>StackRemaining-CallbackScheduler0</uavField>
<uavObject>TaskInfo</uavObject>
<yMaximum>0</yMaximum>
<yMeanSamples>1</yMeanSamples>
<yMinimum>0</yMinimum>
<yScalePower>0</yScalePower>
</plotCurve1>
<plotCurve2>
<color>4278190335</color>
<mathFunction>None</mathFunction>
<uavField>StackRemaining-CallbackScheduler1</uavField>
<uavObject>TaskInfo</uavObject>
<yMaximum>0</yMaximum>
<yMeanSamples>1</yMeanSamples>
<yMinimum>0</yMinimum>
<yScalePower>0</yScalePower>
</plotCurve2>
<plotCurve3>
<color>4294967040</color>
<mathFunction>None</mathFunction>
<uavField>StackRemaining-ManualControl</uavField>
<uavObject>TaskInfo</uavObject>
<yMaximum>0</yMaximum>
<yMeanSamples>1</yMeanSamples>
<yMinimum>0</yMinimum>
<yScalePower>0</yScalePower>
</plotCurve3>
<plotCurve4>
<color>4278255615</color>
<mathFunction>None</mathFunction>
<uavField>StackRemaining-Stabilization</uavField>
<uavObject>TaskInfo</uavObject>
<yMaximum>0</yMaximum>
<yMeanSamples>1</yMeanSamples>
<yMinimum>0</yMinimum>
<yScalePower>0</yScalePower>
</plotCurve4>
<plotCurve5>
<color>4294923775</color>
<mathFunction>None</mathFunction>
<uavField>StackRemaining-Actuator</uavField>
<uavObject>TaskInfo</uavObject>
<yMaximum>0</yMaximum>
<yMeanSamples>1</yMeanSamples>
<yMinimum>0</yMinimum>
<yScalePower>0</yScalePower>
</plotCurve5>
<plotCurve6>
<color>4289331327</color>
<mathFunction>None</mathFunction>
<uavField>StackRemaining-Sensors</uavField>
<uavObject>TaskInfo</uavObject>
<yMaximum>0</yMaximum>
<yMeanSamples>1</yMeanSamples>
<yMinimum>0</yMinimum>
<yScalePower>0</yScalePower>
</plotCurve6>
<plotCurve7>
<color>4294945280</color>
<mathFunction>None</mathFunction>
<uavField>StackRemaining-Altitude</uavField>
<uavObject>TaskInfo</uavObject>
<yMaximum>0</yMaximum>
<yMeanSamples>1</yMeanSamples>
<yMinimum>0</yMinimum>
<yScalePower>0</yScalePower>
</plotCurve7>
<plotCurve8>
<color>4283760767</color>
<mathFunction>None</mathFunction>
<uavField>StackRemaining-TelemetryTx</uavField>
<uavObject>TaskInfo</uavObject>
<yMaximum>0</yMaximum>
<yMeanSamples>1</yMeanSamples>
<yMinimum>0</yMinimum>
<yScalePower>0</yScalePower>
</plotCurve8>
<plotCurve9>
<color>4294901760</color>
<mathFunction>None</mathFunction>
<uavField>StackRemaining-TelemetryRx</uavField>
<uavObject>TaskInfo</uavObject>
<yMaximum>0</yMaximum>
<yMeanSamples>1</yMeanSamples>
<yMinimum>0</yMinimum>
<yScalePower>0</yScalePower>
</plotCurve9>
<plotCurve10>
<color>4283782527</color>
<mathFunction>None</mathFunction>
<uavField>StackRemaining-RadioRx</uavField>
<uavObject>TaskInfo</uavObject>
<yMaximum>0</yMaximum>
<yMeanSamples>1</yMeanSamples>
<yMinimum>0</yMinimum>
<yScalePower>0</yScalePower>
</plotCurve10>
<plotCurveCount>11</plotCurveCount>
<plotType>1</plotType>
<refreshInterval>1000</refreshInterval>
</data>
</Stacks__PCT__20monitor>
<Telemetry__PCT__20quality>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<LoggingEnabled>false</LoggingEnabled>
<LoggingNewFileOnConnect>false</LoggingNewFileOnConnect>
<configurationStreamVersion>1000</configurationStreamVersion>
<dataSize>20</dataSize>
<plotCurve0>
<color>4289374847</color>
<mathFunction>None</mathFunction>
<uavField>TxFailures</uavField>
<uavObject>GCSTelemetryStats</uavObject>
<yMaximum>0</yMaximum>
<yMeanSamples>1</yMeanSamples>
<yMinimum>0</yMinimum>
<yScalePower>0</yScalePower>
</plotCurve0>
<plotCurve1>
<color>4283782655</color>
<mathFunction>None</mathFunction>
<uavField>RxFailures</uavField>
<uavObject>GCSTelemetryStats</uavObject>
<yMaximum>0</yMaximum>
<yMeanSamples>1</yMeanSamples>
<yMinimum>0</yMinimum>
<yScalePower>0</yScalePower>
</plotCurve1>
<plotCurve2>
<color>4294901760</color>
<mathFunction>None</mathFunction>
<uavField>TxRetries</uavField>
<uavObject>GCSTelemetryStats</uavObject>
<yMaximum>0</yMaximum>
<yMeanSamples>1</yMeanSamples>
<yMinimum>0</yMinimum>
<yScalePower>0</yScalePower>
</plotCurve2>
<plotCurveCount>3</plotCurveCount>
<plotType>1</plotType>
<refreshInterval>100</refreshInterval>
</data>
</Telemetry__PCT__20quality>
<Uptimes>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<LoggingEnabled>false</LoggingEnabled>
<LoggingNewFileOnConnect>false</LoggingNewFileOnConnect>
<configurationStreamVersion>1000</configurationStreamVersion>
<dataSize>240</dataSize>
<plotCurve0>
<color>4294945407</color>
<mathFunction>None</mathFunction>
<uavField>FlightTime</uavField>
<uavObject>SystemStats</uavObject>
<yMaximum>0</yMaximum>
<yMeanSamples>1</yMeanSamples>
<yMinimum>0</yMinimum>
<yScalePower>0</yScalePower>
</plotCurve0>
<plotCurveCount>1</plotCurveCount>
<plotType>1</plotType>
<refreshInterval>800</refreshInterval>
</data>
</Uptimes>
</ScopeGadget>
<SystemHealthGadget>
<default>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<diagram>%%DATAPATH%%diagrams/default/system-health.svg</diagram>
</data>
</default>
</SystemHealthGadget>
<UAVObjectBrowser>
<default>
<configInfo>
<locked>false</locked>
<version>0.0.0</version>
</configInfo>
<data>
<CategorizedView>false</CategorizedView>
<ScientificView>false</ScientificView>
<manuallyChangedColor>#5baa56</manuallyChangedColor>
<onlyHilightChangedValues>false</onlyHilightChangedValues>
<recentlyUpdatedColor>#ff7957</recentlyUpdatedColor>
<recentlyUpdatedTimeout>500</recentlyUpdatedTimeout>
<showMetaData>false</showMetaData>
</data>
</default>
</UAVObjectBrowser>
<configInfo>
<locked>false</locked>
<version>1.2.0</version>
</configInfo>
</UAVGadgetConfigurations>
<UAVGadgetManager>
<Mode1>
<showToolbars>false</showToolbars>
<splitter>
<side0>
<side0>
<side0>
<side0>
<classId>LineardialGadget</classId>
<gadget>
<activeConfiguration>Flight Time</activeConfiguration>
</gadget>
<type>uavGadget</type>
</side0>
<side1>
<side0>
<classId>LineardialGadget</classId>
<gadget>
<activeConfiguration>Arm Status</activeConfiguration>
</gadget>
<type>uavGadget</type>
</side0>
<side1>
<classId>LineardialGadget</classId>
<gadget>
<activeConfiguration>Flight mode</activeConfiguration>
</gadget>
<type>uavGadget</type>
</side1>
<splitterOrientation>1</splitterOrientation>
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAAAYwAAAAIAAAB7)</splitterSizes>
<type>splitter</type>
</side1>
<splitterOrientation>1</splitterOrientation>
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAAAZgAAAAIAAADf)</splitterSizes>
<type>splitter</type>
</side0>
<side1>
<classId>PfdQmlGadget</classId>
<gadget>
<activeConfiguration>NoTerrain</activeConfiguration>
</gadget>
<type>uavGadget</type>
</side1>
<splitterOrientation>2</splitterOrientation>
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAAAQAAAAAIAAAG4)</splitterSizes>
<type>splitter</type>
</side0>
<side1>
<side0>
<classId>ModelViewGadget</classId>
<gadget>
<activeConfiguration>Test Quad X</activeConfiguration>
</gadget>
<type>uavGadget</type>
</side0>
<side1>
<classId>SystemHealthGadget</classId>
<gadget>
<activeConfiguration>default</activeConfiguration>
</gadget>
<type>uavGadget</type>
</side1>
<splitterOrientation>1</splitterOrientation>
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAAB1AAAAAIAAAGI)</splitterSizes>
<type>splitter</type>
</side1>
<splitterOrientation>2</splitterOrientation>
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAACegAAAAIAAAFC)</splitterSizes>
<type>splitter</type>
</side0>
<side1>
<classId>OPMapGadget</classId>
<gadget>
<activeConfiguration>Google Sat</activeConfiguration>
</gadget>
<type>uavGadget</type>
</side1>
<splitterOrientation>1</splitterOrientation>
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAADXgAAAAIAAAQd)</splitterSizes>
<type>splitter</type>
</splitter>
<version>UAVGadgetManagerV1</version>
</Mode1>
<Mode2>
<showToolbars>false</showToolbars>
<splitter>
<side0>
<classId>ConfigGadget</classId>
<gadget>
<activeConfiguration>default</activeConfiguration>
</gadget>
<type>uavGadget</type>
</side0>
<side1>
<classId>UAVObjectBrowser</classId>
<gadget>
<activeConfiguration>default</activeConfiguration>
</gadget>
<type>uavGadget</type>
</side1>
<splitterOrientation>1</splitterOrientation>
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAAEeQAAAAIAAAMC)</splitterSizes>
<type>splitter</type>
</splitter>
<version>UAVGadgetManagerV1</version>
</Mode2>
<Mode3>
<showToolbars>false</showToolbars>
<splitter>
<side0>
<classId>UAVObjectBrowser</classId>
<gadget>
<activeConfiguration>default</activeConfiguration>
</gadget>
<type>uavGadget</type>
</side0>
<side1>
<side0>
<classId>LoggingGadget</classId>
<type>uavGadget</type>
</side0>
<side1>
<classId>GpsDisplayGadget</classId>
<gadget>
<activeConfiguration>Flight GPS</activeConfiguration>
</gadget>
<type>uavGadget</type>
</side1>
<splitterOrientation>2</splitterOrientation>
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAAAVAAAAAIAAAGu)</splitterSizes>
<type>splitter</type>
</side1>
<splitterOrientation>1</splitterOrientation>
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAAEvwAAAAIAAAK8)</splitterSizes>
<type>splitter</type>
</splitter>
<version>UAVGadgetManagerV1</version>
</Mode3>
<Mode4>
<showToolbars>false</showToolbars>
<splitter>
<side0>
<side0>
<classId>ScopeGadget</classId>
<gadget>
<activeConfiguration>Accel</activeConfiguration>
</gadget>
<type>uavGadget</type>
</side0>
<side1>
<classId>ScopeGadget</classId>
<gadget>
<activeConfiguration>Raw GyroState</activeConfiguration>
</gadget>
<type>uavGadget</type>
</side1>
<splitterOrientation>2</splitterOrientation>
<splitterSizes>@Variant(AAAACQAAAAA=)</splitterSizes>
<type>splitter</type>
</side0>
<side1>
<side0>
<classId>ScopeGadget</classId>
<gadget>
<activeConfiguration>Attitude</activeConfiguration>
</gadget>
<type>uavGadget</type>
</side0>
<side1>
<classId>ScopeGadget</classId>
<gadget>
<activeConfiguration>Uptimes</activeConfiguration>
</gadget>
<type>uavGadget</type>
</side1>
<splitterOrientation>2</splitterOrientation>
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAABhAAAAAIAAAGE)</splitterSizes>
<type>splitter</type>
</side1>
<splitterOrientation>1</splitterOrientation>
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAACjQAAAAIAAAKU)</splitterSizes>
<type>splitter</type>
</splitter>
<version>UAVGadgetManagerV1</version>
</Mode4>
<Mode5>
<showToolbars>false</showToolbars>
<splitter>
<side0>
<side0>
<classId>HITL</classId>
<gadget>
<activeConfiguration>XPlane HITL</activeConfiguration>
</gadget>
<type>uavGadget</type>
</side0>
<side1>
<classId>HITLv2</classId>
<gadget>
<activeConfiguration>default</activeConfiguration>
</gadget>
<type>uavGadget</type>
</side1>
<splitterOrientation>1</splitterOrientation>
<splitterSizes>@Variant(AAAACQAAAAA=)</splitterSizes>
<type>splitter</type>
</side0>
<side1>
<side0>
<side0>
<classId>PfdQmlGadget</classId>
<gadget>
<activeConfiguration>NoTerrain</activeConfiguration>
</gadget>
<type>uavGadget</type>
</side0>
<side1>
<classId>MagicWaypointGadget</classId>
<type>uavGadget</type>
</side1>
<splitterOrientation>1</splitterOrientation>
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAAB7wAAAAIAAAGU)</splitterSizes>
<type>splitter</type>
</side0>
<side1>
<classId>GCSControlGadget</classId>
<gadget>
<activeConfiguration>MS Sidewinder</activeConfiguration>
</gadget>
<type>uavGadget</type>
</side1>
<splitterOrientation>1</splitterOrientation>
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAADhAAAAAIAAAIX)</splitterSizes>
<type>splitter</type>
</side1>
<splitterOrientation>2</splitterOrientation>
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAADDAAAAAIAAAJJ)</splitterSizes>
<type>splitter</type>
</splitter>
<version>UAVGadgetManagerV1</version>
</Mode5>
<Mode6>
<showToolbars>false</showToolbars>
<splitter>
<side0>
<classId>Uploader</classId>
<gadget>
<activeConfiguration>default</activeConfiguration>
</gadget>
<type>uavGadget</type>
</side0>
<side1>
<side0>
<side0>
<classId>LineardialGadget</classId>
<gadget>
<activeConfiguration>Flight Time</activeConfiguration>
</gadget>
<type>uavGadget</type>
</side0>
<side1>
<classId>SystemHealthGadget</classId>
<gadget>
<activeConfiguration>default</activeConfiguration>
</gadget>
<type>uavGadget</type>
</side1>
<splitterOrientation>1</splitterOrientation>
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAABQgAAAAIAAAGM)</splitterSizes>
<type>splitter</type>
</side0>
<side1>
<side0>
<side0>
<classId>DialGadget</classId>
<gadget>
<activeConfiguration>Deluxe Attitude</activeConfiguration>
</gadget>
<type>uavGadget</type>
</side0>
<side1>
<classId>DialGadget</classId>
<gadget>
<activeConfiguration>Deluxe Baro Altimeter</activeConfiguration>
</gadget>
<type>uavGadget</type>
</side1>
<splitterOrientation>2</splitterOrientation>
<splitterSizes>@Variant(AAAACQAAAAA=)</splitterSizes>
<type>splitter</type>
</side0>
<side1>
<side0>
<classId>DialGadget</classId>
<gadget>
<activeConfiguration>Deluxe Compass</activeConfiguration>
</gadget>
<type>uavGadget</type>
</side0>
<side1>
<classId>DialGadget</classId>
<gadget>
<activeConfiguration>Deluxe Climbrate</activeConfiguration>
</gadget>
<type>uavGadget</type>
</side1>
<splitterOrientation>2</splitterOrientation>
<splitterSizes>@Variant(AAAACQAAAAA=)</splitterSizes>
<type>splitter</type>
</side1>
<splitterOrientation>1</splitterOrientation>
<splitterSizes>@Variant(AAAACQAAAAA=)</splitterSizes>
<type>splitter</type>
</side1>
<splitterOrientation>2</splitterOrientation>
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAABLwAAAAIAAAHf)</splitterSizes>
<type>splitter</type>
</side1>
<splitterOrientation>1</splitterOrientation>
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAADVQAAAAIAAAJK)</splitterSizes>
<type>splitter</type>
</splitter>
<version>UAVGadgetManagerV1</version>
</Mode6>
</UAVGadgetManager>
<Workspace>
<AllowTabBarMovement>false</AllowTabBarMovement>
<Icon1>:/core/images/ah.png</Icon1>
<Icon10>:/core/images/openpilot_logo_64.png</Icon10>
<Icon2>:/core/images/config.png</Icon2>
<Icon3>:/core/images/cog.png</Icon3>
<Icon4>:/core/images/scopes.png</Icon4>
<Icon5>:/core/images/joystick.png</Icon5>
<Icon6>:/core/images/cpu.png</Icon6>
<Icon7>:/core/images/openpilot_logo_64.png</Icon7>
<Icon8>:/core/images/openpilot_logo_64.png</Icon8>
<Icon9>:/core/images/openpilot_logo_64.png</Icon9>
<NumberOfWorkspaces>6</NumberOfWorkspaces>
<TabBarPlacementIndex>1</TabBarPlacementIndex>
<Workspace1>Flight data</Workspace1>
<Workspace10>Workspace10</Workspace10>
<Workspace2>Configuration</Workspace2>
<Workspace3>System</Workspace3>
<Workspace4>Scopes</Workspace4>
<Workspace5>HITL</Workspace5>
<Workspace6>Firmware</Workspace6>
<Workspace7>Workspace7</Workspace7>
<Workspace8>Workspace8</Workspace8>
<Workspace9>Workspace9</Workspace9>
</Workspace>
</gcs>

View File

@ -15,7 +15,7 @@
id="svg3604"
version="1.1"
inkscape:version="0.48.4 r9939"
sodipodi:docname="system-health-mod.svg"
sodipodi:docname="system-health.svg"
inkscape:export-filename="C:\NoBackup\OpenPilot\mainboard-health.png"
inkscape:export-xdpi="269.53"
inkscape:export-ydpi="269.53"
@ -27,19 +27,20 @@
borderopacity="1.0"
inkscape:pageopacity="0.0"
inkscape:pageshadow="2"
inkscape:zoom="10.554213"
inkscape:cx="47.1292"
inkscape:cy="39.787519"
inkscape:current-layer="svg3604"
inkscape:zoom="7.4629556"
inkscape:cx="32.393349"
inkscape:cy="37.450437"
inkscape:current-layer="foreground"
id="namedview3608"
showgrid="false"
inkscape:window-width="1920"
inkscape:window-height="1025"
inkscape:window-x="-2"
inkscape:window-y="-3"
showgrid="true"
inkscape:window-width="1366"
inkscape:window-height="712"
inkscape:window-x="-4"
inkscape:window-y="-4"
inkscape:window-maximized="1"
showguides="true"
inkscape:guide-bbox="true">
inkscape:guide-bbox="true"
inkscape:snap-global="false">
<sodipodi:guide
id="guide3857"
position="68.372091,-63.708224"
@ -56,6 +57,13 @@
id="guide3168"
position="34.202366,114.41506"
orientation="0,1" />
<inkscape:grid
type="xygrid"
id="grid4540" />
<sodipodi:guide
orientation="0,1"
position="86.912617,26.949779"
id="guide4221" />
</sodipodi:namedview>
<defs
id="defs3606">
@ -521,17 +529,6 @@
inkscape:vp_z="1 : 0.5 : 1"
inkscape:persp3d-origin="0.5 : 0.33333333 : 1"
id="perspective3185" />
<radialGradient
r="20.397499"
fy="3.9900031"
fx="23.895569"
cy="3.9900031"
cx="23.895569"
gradientTransform="matrix(0,0.77065835,-1.0172554,0,470.40485,337.23242)"
gradientUnits="userSpaceOnUse"
id="radialGradient10901"
xlink:href="#linearGradient3242-4"
inkscape:collect="always" />
<linearGradient
id="linearGradient3242-4">
<stop
@ -551,16 +548,6 @@
style="stop-color:#690b54;stop-opacity:1"
id="stop3250-5" />
</linearGradient>
<linearGradient
y2="3.0816143"
x2="18.379412"
y1="44.980297"
x1="18.379412"
gradientTransform="matrix(0.3229028,0,0,0.32290287,458.59633,354.96299)"
gradientUnits="userSpaceOnUse"
id="linearGradient10903"
xlink:href="#linearGradient2490-8"
inkscape:collect="always" />
<linearGradient
id="linearGradient2490-8">
<stop
@ -572,17 +559,6 @@
style="stop-color:#dd3b27;stop-opacity:1"
id="stop2494-1" />
</linearGradient>
<radialGradient
r="20.397499"
fy="3.9900031"
fx="23.895569"
cy="3.9900031"
cx="23.895569"
gradientTransform="matrix(0,0.77065835,-1.0172554,0,470.40485,337.23242)"
gradientUnits="userSpaceOnUse"
id="radialGradient10905"
xlink:href="#linearGradient3242-4"
inkscape:collect="always" />
<linearGradient
id="linearGradient11125">
<stop
@ -602,16 +578,6 @@
style="stop-color:#690b54;stop-opacity:1"
id="stop11133" />
</linearGradient>
<linearGradient
y2="3.0816143"
x2="18.379412"
y1="44.980297"
x1="18.379412"
gradientTransform="matrix(0.3229028,0,0,0.32290287,458.59633,354.96299)"
gradientUnits="userSpaceOnUse"
id="linearGradient10907"
xlink:href="#linearGradient2490-8"
inkscape:collect="always" />
<linearGradient
id="linearGradient11136">
<stop
@ -623,6 +589,90 @@
style="stop-color:#dd3b27;stop-opacity:1"
id="stop11140" />
</linearGradient>
<radialGradient
inkscape:collect="always"
xlink:href="#linearGradient3242-4"
id="radialGradient4542"
gradientUnits="userSpaceOnUse"
gradientTransform="matrix(0,0.77065835,-1.0172554,0,470.40485,337.23242)"
cx="23.895569"
cy="3.9900031"
fx="23.895569"
fy="3.9900031"
r="20.397499" />
<linearGradient
inkscape:collect="always"
xlink:href="#linearGradient2490-8"
id="linearGradient4544"
gradientUnits="userSpaceOnUse"
gradientTransform="matrix(0.3229028,0,0,0.32290287,458.59633,354.96299)"
x1="18.379412"
y1="44.980297"
x2="18.379412"
y2="3.0816143" />
<radialGradient
inkscape:collect="always"
xlink:href="#linearGradient3242-4"
id="radialGradient4546"
gradientUnits="userSpaceOnUse"
gradientTransform="matrix(0,0.77065835,-1.0172554,0,470.40485,337.23242)"
cx="23.895569"
cy="3.9900031"
fx="23.895569"
fy="3.9900031"
r="20.397499" />
<linearGradient
inkscape:collect="always"
xlink:href="#linearGradient2490-8"
id="linearGradient4548"
gradientUnits="userSpaceOnUse"
gradientTransform="matrix(0.3229028,0,0,0.32290287,458.59633,354.96299)"
x1="18.379412"
y1="44.980297"
x2="18.379412"
y2="3.0816143" />
<radialGradient
inkscape:collect="always"
xlink:href="#linearGradient3242-4"
id="radialGradient6313"
gradientUnits="userSpaceOnUse"
gradientTransform="matrix(0,0.77065835,-1.0172554,0,470.40485,337.23242)"
cx="23.895569"
cy="3.9900031"
fx="23.895569"
fy="3.9900031"
r="20.397499" />
<linearGradient
inkscape:collect="always"
xlink:href="#linearGradient2490-8"
id="linearGradient6315"
gradientUnits="userSpaceOnUse"
gradientTransform="matrix(0.3229028,0,0,0.32290287,458.59633,354.96299)"
x1="18.379412"
y1="44.980297"
x2="18.379412"
y2="3.0816143" />
<radialGradient
inkscape:collect="always"
xlink:href="#linearGradient3242-4"
id="radialGradient6317"
gradientUnits="userSpaceOnUse"
gradientTransform="matrix(0,0.77065835,-1.0172554,0,470.40485,337.23242)"
cx="23.895569"
cy="3.9900031"
fx="23.895569"
fy="3.9900031"
r="20.397499" />
<linearGradient
inkscape:collect="always"
xlink:href="#linearGradient2490-8"
id="linearGradient6319"
gradientUnits="userSpaceOnUse"
gradientTransform="matrix(0.3229028,0,0,0.32290287,458.59633,354.96299)"
x1="18.379412"
y1="44.980297"
x2="18.379412"
y2="3.0816143" />
</defs>
<metadata
id="metadata3610">
@ -643,2845 +693,2249 @@
inkscape:groupmode="layer"
inkscape:label="Background">
<rect
ry="1.628684"
y="344.5361"
x="497.92136"
height="79.063599"
width="93.746948"
ry="1.6285406"
y="344.53958"
x="497.92484"
height="79.056633"
width="95.066467"
id="Background"
style="fill:#453e3e;fill-opacity:1;fill-rule:evenodd;stroke:#000000;stroke-width:0.99921262;stroke-linecap:butt;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
<g
id="MainBoard"
style="font-size:13.40719509px;font-style:normal;font-weight:normal;fill:#ffffff;fill-opacity:1;stroke:none;font-family:Bitstream Vera Sans">
<path
id="path4061"
style="font-size:9px;fill:#ffffff"
d="m 524.3844,367.59399 1.32275,0 1.67432,4.46485 1.68311,-4.46485 1.32275,0 0,6.56104 -0.86572,0 0,-5.76123 -1.6919,4.5 -0.89209,0 -1.69189,-4.5 0,5.76123 -0.86133,0 0,-6.56104"
inkscape:connector-curvature="0" />
<path
id="path4063"
style="font-size:9px;fill:#ffffff"
d="m 534.35559,371.68091 c -0.65332,0 -1.10596,0.0747 -1.35791,0.22412 -0.25195,0.14942 -0.37793,0.4043 -0.37793,0.76465 0,0.28711 0.0937,0.51562 0.28125,0.68554 0.19043,0.167 0.44824,0.25049 0.77344,0.25049 0.44824,0 0.80712,-0.1582 1.07666,-0.47461 0.27246,-0.31933 0.40869,-0.74267 0.40869,-1.27002 l 0,-0.18017 -0.8042,0 m 1.61279,-0.33399 0,2.80811 -0.80859,0 0,-0.74707 c -0.18457,0.29883 -0.41455,0.52002 -0.68994,0.66357 -0.27539,0.14063 -0.61231,0.21094 -1.01074,0.21094 -0.50391,0 -0.90528,-0.14062 -1.20411,-0.42187 -0.29589,-0.28418 -0.44384,-0.66358 -0.44384,-1.13819 0,-0.55371 0.18457,-0.97119 0.55371,-1.25244 0.37207,-0.28125 0.92578,-0.42187 1.66113,-0.42187 l 1.13379,0 0,-0.0791 c 0,-0.37206 -0.12305,-0.65917 -0.36914,-0.86132 -0.24317,-0.20508 -0.58594,-0.30762 -1.02832,-0.30762 -0.28125,0 -0.55518,0.0337 -0.82178,0.10107 -0.2666,0.0674 -0.52295,0.16846 -0.76904,0.30323 l 0,-0.74707 c 0.2959,-0.11426 0.58301,-0.19922 0.86133,-0.25489 0.27832,-0.0586 0.54931,-0.0879 0.81299,-0.0879 0.71191,10e-6 1.24364,0.18458 1.59521,0.55371 0.35156,0.36915 0.52734,0.92872 0.52734,1.67871"
inkscape:connector-curvature="0" />
<path
id="path4065"
style="font-size:9px;fill:#ffffff"
d="m 537.63831,369.23315 0.80859,0 0,4.92188 -0.80859,0 0,-4.92188 m 0,-1.91601 0.80859,0 0,1.02392 -0.80859,0 0,-1.02392"
inkscape:connector-curvature="0" />
<path
id="path4067"
style="font-size:9px;fill:#ffffff"
d="m 544.22571,371.18433 0,2.9707 -0.8086,0 0,-2.94434 c 0,-0.46581 -0.0908,-0.81445 -0.27246,-1.0459 -0.18164,-0.23144 -0.4541,-0.34716 -0.81738,-0.34716 -0.43653,0 -0.78076,0.13916 -1.03271,0.41748 -0.25196,0.27832 -0.37794,0.65772 -0.37793,1.13818 l 0,2.78174 -0.81299,0 0,-4.92188 0.81299,0 0,0.76465 c 0.19335,-0.29589 0.4204,-0.51708 0.68115,-0.66357 0.26367,-0.14648 0.56689,-0.21972 0.90967,-0.21973 0.56542,10e-6 0.99316,0.17579 1.2832,0.52735 0.29003,0.34863 0.43505,0.86279 0.43506,1.54248"
inkscape:connector-curvature="0" />
<path
id="path4069"
style="font-size:9px;fill:#ffffff"
d="m 549.38049,371.69849 c 0,-0.59473 -0.12305,-1.06055 -0.36914,-1.39746 -0.24317,-0.33984 -0.57861,-0.50977 -1.00635,-0.50977 -0.42773,0 -0.76465,0.16993 -1.01074,0.50977 -0.24316,0.33691 -0.36475,0.80273 -0.36474,1.39746 -10e-6,0.59472 0.12158,1.06201 0.36474,1.40185 0.24609,0.33692 0.58301,0.50537 1.01074,0.50537 0.42774,0 0.76318,-0.16845 1.00635,-0.50537 0.24609,-0.33984 0.36914,-0.80713 0.36914,-1.40185 m -2.75097,-1.71827 c 0.16992,-0.29296 0.38378,-0.50976 0.6416,-0.65039 0.26074,-0.14355 0.57128,-0.21532 0.93164,-0.21533 0.59765,10e-6 1.08251,0.23731 1.45459,0.71192 0.37499,0.47461 0.56249,1.09863 0.5625,1.87207 -10e-6,0.77344 -0.18751,1.39746 -0.5625,1.87207 -0.37208,0.47461 -0.85694,0.71191 -1.45459,0.71191 -0.36036,0 -0.6709,-0.0703 -0.93164,-0.21094 -0.25782,-0.14355 -0.47168,-0.36181 -0.6416,-0.65478 l 0,0.73828 -0.81299,0 0,-6.83789 0.81299,0 0,2.66308"
inkscape:connector-curvature="0" />
<path
id="path4071"
style="font-size:9px;fill:#ffffff"
d="m 553.46741,369.80005 c -0.4336,0 -0.77637,0.16992 -1.02832,0.50976 -0.25196,0.33692 -0.37793,0.79981 -0.37793,1.38868 0,0.58887 0.12451,1.05322 0.37353,1.39306 0.25195,0.33692 0.59619,0.50537 1.03272,0.50537 0.43066,0 0.77197,-0.16992 1.02392,-0.50976 0.25195,-0.33984 0.37793,-0.80273 0.37793,-1.38867 0,-0.58301 -0.12598,-1.04443 -0.37793,-1.38428 -0.25195,-0.34277 -0.59326,-0.51416 -1.02392,-0.51416 m 0,-0.68555 c 0.70312,10e-6 1.25536,0.22852 1.65674,0.68555 0.40136,0.45703 0.60204,1.08985 0.60205,1.89844 -10e-6,0.80566 -0.20069,1.43847 -0.60205,1.89843 -0.40138,0.45704 -0.95362,0.68555 -1.65674,0.68555 -0.70606,0 -1.25977,-0.22851 -1.66114,-0.68555 -0.39843,-0.45996 -0.59765,-1.09277 -0.59765,-1.89843 0,-0.80859 0.19922,-1.44141 0.59765,-1.89844 0.40137,-0.45703 0.95508,-0.68554 1.66114,-0.68555"
inkscape:connector-curvature="0" />
<path
id="path4073"
style="font-size:9px;fill:#ffffff"
d="m 559.29895,371.68091 c -0.65332,0 -1.10596,0.0747 -1.35791,0.22412 -0.25195,0.14942 -0.37793,0.4043 -0.37793,0.76465 0,0.28711 0.0937,0.51562 0.28125,0.68554 0.19043,0.167 0.44824,0.25049 0.77344,0.25049 0.44824,0 0.80712,-0.1582 1.07666,-0.47461 0.27246,-0.31933 0.40869,-0.74267 0.40869,-1.27002 l 0,-0.18017 -0.8042,0 m 1.61279,-0.33399 0,2.80811 -0.80859,0 0,-0.74707 c -0.18457,0.29883 -0.41455,0.52002 -0.68994,0.66357 -0.2754,0.14063 -0.61231,0.21094 -1.01074,0.21094 -0.50391,0 -0.90528,-0.14062 -1.20411,-0.42187 -0.29589,-0.28418 -0.44384,-0.66358 -0.44384,-1.13819 0,-0.55371 0.18457,-0.97119 0.55371,-1.25244 0.37207,-0.28125 0.92578,-0.42187 1.66113,-0.42187 l 1.13379,0 0,-0.0791 c 0,-0.37206 -0.12305,-0.65917 -0.36914,-0.86132 -0.24317,-0.20508 -0.58594,-0.30762 -1.02832,-0.30762 -0.28125,0 -0.55518,0.0337 -0.82178,0.10107 -0.2666,0.0674 -0.52295,0.16846 -0.76904,0.30323 l 0,-0.74707 c 0.2959,-0.11426 0.583,-0.19922 0.86133,-0.25489 0.27831,-0.0586 0.54931,-0.0879 0.81298,-0.0879 0.71192,10e-6 1.24365,0.18458 1.59522,0.55371 0.35156,0.36915 0.52734,0.92872 0.52734,1.67871"
inkscape:connector-curvature="0" />
<path
id="path4075"
style="font-size:9px;fill:#ffffff"
d="m 565.43372,369.98901 c -0.0908,-0.0527 -0.19044,-0.0908 -0.29883,-0.11425 -0.10547,-0.0264 -0.22266,-0.0395 -0.35156,-0.0395 -0.45704,0 -0.8086,0.14941 -1.05469,0.44824 -0.24317,0.2959 -0.36475,0.72217 -0.36475,1.27881 l 0,2.59277 -0.81299,0 0,-4.92188 0.81299,0 0,0.76465 c 0.16992,-0.29882 0.39111,-0.52001 0.66358,-0.66357 0.27245,-0.14648 0.60351,-0.21972 0.99316,-0.21973 0.0557,10e-6 0.11718,0.004 0.18457,0.0132 0.0674,0.006 0.14209,0.0161 0.22412,0.0308 l 0.004,0.83056"
inkscape:connector-curvature="0" />
<path
id="path4077"
style="font-size:9px;fill:#ffffff"
d="m 569.37122,369.98022 0,-2.66308 0.80859,0 0,6.83789 -0.80859,0 0,-0.73828 c -0.16993,0.29297 -0.38526,0.51123 -0.646,0.65478 -0.25782,0.14063 -0.56836,0.21094 -0.93164,0.21094 -0.59473,0 -1.07959,-0.2373 -1.45459,-0.71191 -0.37207,-0.47461 -0.55811,-1.09863 -0.55811,-1.87207 0,-0.77344 0.18604,-1.39746 0.55811,-1.87207 0.375,-0.47461 0.85986,-0.71191 1.45459,-0.71192 0.36328,10e-6 0.67382,0.0718 0.93164,0.21533 0.26074,0.14063 0.47607,0.35743 0.646,0.65039 m -2.75538,1.71827 c 0,0.59472 0.12159,1.06201 0.36475,1.40185 0.24609,0.33692 0.58301,0.50537 1.01074,0.50537 0.42773,0 0.76465,-0.16845 1.01075,-0.50537 0.24608,-0.33984 0.36913,-0.80713 0.36914,-1.40185 -10e-6,-0.59473 -0.12306,-1.06055 -0.36914,-1.39746 -0.2461,-0.33984 -0.58302,-0.50977 -1.01075,-0.50977 -0.42773,0 -0.76465,0.16993 -1.01074,0.50977 -0.24316,0.33691 -0.36475,0.80273 -0.36475,1.39746"
inkscape:connector-curvature="0" />
</g>
style="fill:#483737;fill-opacity:1;fill-rule:evenodd;stroke:#000000;stroke-width:1.00617588;stroke-linecap:butt;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
<rect
inkscape:label="#rect4000-8-5"
style="fill:#332d2d;fill-opacity:1;stroke:#ffffff;stroke-width:0.53149605;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
id="Actuator"
width="13.893178"
height="56.637238"
x="499.10913"
y="365.44907" />
style="fill:#241c1c;fill-opacity:1;stroke:#ffffff;stroke-width:0.45410183;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
id="rect4550-8-7-82"
width="10.470912"
height="8.5405388"
x="547.97754"
y="411.38937"
ry="1" />
<rect
inkscape:label="#rect4000-8-0-9"
style="fill:#332d2d;fill-opacity:1;stroke:#ffffff;stroke-width:0.53149605;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
style="fill:#6c5d53;fill-opacity:1;stroke:none"
id="rect1234"
width="63.478992"
height="12.219843"
x="527.70123"
y="409.64447"
ry="0" />
<rect
style="fill:#241c1c;fill-opacity:1;stroke:none"
id="Receiver"
width="13.893178"
height="56.637238"
x="576.71594"
y="365.44907" />
width="19.129522"
height="10.639811"
x="504.99179"
y="387.5629"
ry="0.24124773"
inkscape:label="#rect4550" />
<rect
inkscape:label="#rect4000-7-6-2-2"
style="fill:#332d2d;fill-opacity:1;stroke:#ffffff;stroke-width:0.53149605;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
id="Power"
width="18.023544"
height="8.2846708"
x="499.24579"
y="346.10165" />
style="fill:#6c5d53;fill-opacity:1;stroke:none;display:inline"
id="rect4358-7"
width="37.799622"
height="13.255064"
x="553.24451"
y="395.2457"
ry="0" />
<rect
inkscape:label="#rect4000-7-6-2-2111"
style="fill:#332d2d;fill-opacity:1;stroke:#ffffff;stroke-width:0.53149605;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
id="Battery"
width="18.023544"
height="8.2846708"
x="499.13889"
y="355.57822" />
style="fill:#6c5d53;fill-opacity:1;stroke:none;display:inline"
id="rect4358-4"
width="63.468098"
height="12.839675"
x="527.57617"
y="381.38202"
ry="0" />
<rect
style="fill:#332d2d;fill-opacity:1;stroke:#ffffff;stroke-width:0.53149605;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
id="Sensors"
width="8"
height="20.208858"
x="551.89978"
y="345.96741"
inkscape:label="#Sensors" />
style="fill:#6c5d53;fill-opacity:1;stroke:none;display:inline"
id="rect4358-0"
width="91.066727"
height="13.183137"
x="499.96637"
y="346.05209"
ry="0" />
<rect
style="fill:#332d2d;fill-opacity:1;stroke:#ffffff;stroke-width:0.53149605;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
id="Airspeed"
width="8"
height="20.208858"
x="562.37372"
y="345.95883"
inkscape:label="#Airspeed" />
style="fill:#6c5d53;fill-opacity:1;stroke:none;display:inline"
id="rect4358-0-9"
width="91.019348"
height="13.183137"
x="500.06686"
y="360.27713"
ry="0" />
<rect
style="fill:#332d2d;fill-opacity:1;stroke:#ffffff;stroke-width:0.53149605;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
id="I2C"
width="18.023544"
height="8.0567961"
x="572.51758"
y="345.79932" />
style="fill:#6c5d53;fill-opacity:1;stroke:none;display:inline"
id="rect4358-7-4"
width="24.646557"
height="13.221018"
x="527.58087"
y="395.29047"
ry="0" />
<rect
style="fill:#332d2d;fill-opacity:1;stroke:#ffffff;stroke-width:0.51991701;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
id="Temp-Baro"
width="18.036383"
height="8.0690594"
x="572.60791"
y="355.2207" />
<rect
style="fill:#332d2d;fill-opacity:1;stroke:#ffffff;stroke-width:0.53149605;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
id="USB"
width="5.311192"
height="15.007023"
x="552.6358"
y="407.05673" />
<rect
y="407.05673"
x="560.98218"
height="15.007023"
width="5.311192"
id="JTAG"
style="fill:#332d2d;fill-opacity:1;stroke:#ffffff;stroke-width:0.53149605;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
<rect
style="fill:#332d2d;fill-opacity:1;stroke:#ffffff;stroke-width:0.53149605;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
id="GPIO"
width="5.311192"
height="15.007023"
x="544.28949"
y="407.05673" />
<rect
style="fill:#332d2d;fill-opacity:1;stroke:#ffffff;stroke-width:0.53369814;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
id="Pwr-Sense"
width="9.9426785"
height="14.938984"
x="514.80487"
y="407.0524" />
<rect
style="fill:#332d2d;fill-opacity:1;stroke:#ffffff;stroke-width:0.53585184;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
id="ADC"
width="16.179909"
height="15.034504"
x="526.39636"
y="406.95688" />
<rect
inkscape:label="#rect4000-7-6-7-1"
style="fill:#332d2d;fill-opacity:1;stroke:#ffffff;stroke-width:0.53149605;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
style="fill:#241c1c;fill-opacity:1;stroke:none;display:inline"
id="CPUOverload"
width="18.153212"
height="8.1216154"
x="515.23181"
y="385.55762" />
width="10.470912"
height="8.5405388"
x="532.78839"
y="411.4689"
ry="1"
inkscape:label="#rect4550-8" />
<rect
inkscape:label="#rect6258"
y="385.55762"
x="535.7182"
height="8.1216154"
width="18.153212"
id="StackOverflow"
style="fill:#332d2d;fill-opacity:1;stroke:#ffffff;stroke-width:0.53149605;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
<rect
inkscape:label="#rect6260"
style="fill:#332d2d;fill-opacity:1;stroke:#ffffff;stroke-width:0.53149605;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
style="fill:#241c1c;fill-opacity:1;stroke:none;display:inline"
id="OutOfMemory"
width="18.153212"
height="8.1216154"
x="556.20465"
y="385.55762" />
width="10.470912"
height="8.5405388"
x="544.5553"
y="411.4689"
ry="1"
inkscape:label="#rect4550-8-7" />
<rect
y="395.55762"
x="515.23181"
height="8.1216154"
width="18.153212"
style="fill:#241c1c;fill-opacity:1;stroke:none;display:inline"
id="StackOverflow"
width="10.470912"
height="8.5405388"
x="556.32214"
y="411.4689"
ry="1"
inkscape:label="#rect4550-8-1" />
<rect
style="fill:#241c1c;fill-opacity:1;stroke:none;display:inline"
id="EventSystem"
style="fill:#332d2d;fill-opacity:1;stroke:#ffffff;stroke-width:0.53149605;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
inkscape:label="#rect4000-7-6-7-1" />
width="10.470912"
height="8.5405388"
x="568.08905"
y="411.4689"
ry="1"
inkscape:label="#rect4550-8-15" />
<rect
style="fill:#332d2d;fill-opacity:1;stroke:#ffffff;stroke-width:0.55302167;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
id="USARTs"
width="30.08411"
height="20.040594"
x="519.2749"
y="346.19791" />
style="fill:#241c1c;fill-opacity:1;stroke:none;display:inline"
id="I2C"
width="10.470912"
height="8.5405388"
x="579.8559"
y="411.4689"
ry="1"
inkscape:label="#rect4550-8-2" />
<text
xml:space="preserve"
style="font-size:6px;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:#ffffff;fill-opacity:1;stroke:none;font-family:Sans;-inkscape-font-specification:Sans Bold"
x="521.74384"
y="379.36826"
id="text5334"
sodipodi:linespacing="125%"><tspan
sodipodi:role="line"
id="tspan4263"
x="521.74384"
y="379.36826">SYSTEM HEALTH</tspan></text>
<text
xml:space="preserve"
style="font-size:3.38406372px;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:#f4d7d7;fill-opacity:1;stroke:none;display:inline;font-family:Sans;-inkscape-font-specification:Sans Bold"
x="-426.01138"
y="440.49539"
id="text4641-5-2"
sodipodi:linespacing="125%"
transform="matrix(0,-0.87458357,1.1434013,0,0,0)"><tspan
sodipodi:role="line"
id="tspan5401"
x="-426.01138"
y="440.49539">Sensors</tspan></text>
<text
xml:space="preserve"
style="font-size:3.38406372px;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:#f4d7d7;fill-opacity:1;stroke:none;display:inline;font-family:Sans;-inkscape-font-specification:Sans Bold"
x="-406.95456"
y="440.47641"
id="text4641-5-2-5"
sodipodi:linespacing="125%"
transform="matrix(0,-0.87458357,1.1434013,0,0,0)"><tspan
sodipodi:role="line"
id="tspan5424"
x="-406.95456"
y="440.47641">Auto</tspan></text>
<text
xml:space="preserve"
style="font-size:3.38406372px;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:#f4d7d7;fill-opacity:1;stroke:none;display:inline;font-family:Sans;-inkscape-font-specification:Sans Bold"
x="-447.34424"
y="464.44702"
id="text4641-5-2-1"
sodipodi:linespacing="125%"
transform="matrix(0,-0.87458357,1.1434013,0,0,0)"><tspan
sodipodi:role="line"
id="tspan5435"
x="-447.34424"
y="464.44702">Misc.</tspan></text>
<text
xml:space="preserve"
style="font-size:3.38406372px;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:#f4d7d7;fill-opacity:1;stroke:none;display:inline;font-family:Sans;-inkscape-font-specification:Sans Bold"
x="-462.94199"
y="464.46683"
id="text4641-5-2-11"
sodipodi:linespacing="125%"
transform="matrix(0,-0.87458357,1.1434013,0,0,0)"><tspan
sodipodi:role="line"
id="tspan5446"
x="-462.94199"
y="464.46683">Link</tspan></text>
<text
xml:space="preserve"
style="font-size:3.38406372px;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:#f4d7d7;fill-opacity:1;stroke:none;display:inline;font-family:Sans;-inkscape-font-specification:Sans Bold"
x="-464.57455"
y="486.72632"
id="text4641-5-2-2"
sodipodi:linespacing="125%"
transform="matrix(0,-0.87458357,1.1434013,0,0,0)"><tspan
sodipodi:role="line"
id="tspan5469"
x="-464.57455"
y="486.72632">Power</tspan></text>
<text
xml:space="preserve"
style="font-size:3.38406372px;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:#f4d7d7;fill-opacity:1;stroke:none;display:inline;font-family:Sans;-inkscape-font-specification:Sans Bold"
x="-478.51532"
y="464.46683"
id="text4641-5-2-6"
sodipodi:linespacing="125%"
transform="matrix(0,-0.87458357,1.1434013,0,0,0)"><tspan
sodipodi:role="line"
id="tspan4340"
x="-478.51532"
y="464.46683">Syst.</tspan></text>
<rect
style="fill:none;stroke:#ffffff;stroke-width:0.29055119;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
id="Telemetry"
width="23.347105"
height="5.6002355"
x="520.36267"
y="347.41809"
inkscape:label="#rect4552-27" />
<rect
style="fill:#332d2d;fill-opacity:1;stroke:#ffffff;stroke-width:0.53149605;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
id="Stabilization"
width="18.153212"
height="8.1216154"
x="535.7182"
y="395.55762"
inkscape:label="#rect6258" />
<rect
inkscape:label="#rect6260"
style="fill:#332d2d;fill-opacity:1;stroke:#ffffff;stroke-width:0.53149605;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
id="FlightTime"
width="18.153212"
height="8.1216154"
x="556.20465"
y="395.55762" />
<rect
inkscape:label="#rect4120"
style="fill:none;stroke:#ffffff;stroke-width:0.29055119;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
id="GPS"
width="23.347105"
height="5.6002355"
x="520.36267"
y="353.41809" />
<rect
y="375.55762"
x="556.20465"
height="8.1216154"
width="18.153212"
id="Attitude"
style="fill:#332d2d;fill-opacity:1;stroke:#ffffff;stroke-width:0.53149605;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
inkscape:label="#rect6260" />
<rect
style="fill:#332d2d;fill-opacity:1;stroke:#ffffff;stroke-width:0.53149605;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
id="Guidance"
width="18.153212"
height="8.1216154"
x="535.7182"
y="375.55762"
inkscape:label="#rect6258" />
<rect
y="375.55762"
x="515.23181"
height="8.1216154"
width="18.153212"
style="fill:#241c1c;fill-opacity:1;stroke:none;display:inline"
id="BootFault"
style="fill:#332d2d;fill-opacity:1;stroke:#ffffff;stroke-width:0.53149605;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
inkscape:label="#rect4000-7-6-7-1" />
</g>
<g
style="display:none"
inkscape:label="FlightTime-OK"
id="layer45"
inkscape:groupmode="layer">
width="13.310432"
height="10.308098"
x="546.92853"
y="382.58969"
ry="1"
inkscape:label="#rect4550-8-1-4-21-8" />
<rect
inkscape:label="#rect8374"
y="51.277248"
x="58.539021"
height="8.1216154"
width="18.153212"
id="FlightTime-OK"
style="fill:#04b629;fill-opacity:1;stroke:#ffffff;stroke-width:0.53149605;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
</g>
<g
style="display:none"
inkscape:label="FlightTime-Warning"
id="layer46"
inkscape:groupmode="layer">
style="fill:#241c1c;fill-opacity:1;stroke:none;display:inline"
id="rect4550-8-1-4-21-9"
width="13.310432"
height="10.308098"
x="561.6792"
y="382.58969"
ry="1" />
<rect
inkscape:label="#rect4073"
style="fill:#f1b907;fill-opacity:1;stroke:#ffffff;stroke-width:0.53149605;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
id="FlightTime-Warning"
width="18.153212"
height="8.1216154"
x="58.539021"
y="51.277248" />
</g>
<g
style="display:none"
inkscape:label="FlightTime-Error"
id="layer47"
inkscape:groupmode="layer">
<g
inkscape:label="#g4084"
transform="translate(20.488022,18.086644)"
id="FlightTime-Error"
style="stroke:#cf0e0e;stroke-width:2;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline">
<path
inkscape:connector-curvature="0"
id="path4086-8"
d="M 38.076545,33.292974 56.14311,41.28257"
style="fill:none;stroke:#cf0e0e;stroke-width:2;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
<path
inkscape:connector-curvature="0"
inkscape:label="#path4088-8"
id="FlightTime-Error2"
d="m 38.220502,41.354548 17.85063,-8.061574"
style="fill:none;stroke:#cf0e0e;stroke-width:2;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
</g>
</g>
<g
style="display:none"
inkscape:label="FlightTime-Critical"
id="layer48"
inkscape:groupmode="layer">
style="fill:#241c1c;fill-opacity:1;stroke:none;display:inline"
id="rect41234"
width="13.310432"
height="10.308098"
x="576.42981"
y="382.52267"
ry="1.3167187"
inkscape:label="#rect4550-8-1-4-21-2" />
<rect
inkscape:label="#rect4080"
y="51.277248"
x="58.539021"
height="8.1216154"
width="18.153212"
id="FlightTime-Critical"
style="fill:#cf0e0e;fill-opacity:1;stroke:#ffffff;stroke-width:0.53149605;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
style="fill:#241c1c;fill-opacity:1;stroke:none;display:inline"
id="FlightTime"
width="15.447426"
height="10.265867"
x="574.46124"
y="396.60678"
ry="1"
inkscape:label="#rect4550-8-1-4-21-2-9" />
<rect
style="fill:#241c1c;fill-opacity:1;stroke:none;display:inline"
id="Telemetry"
width="18.966711"
height="10.202584"
x="532.13593"
y="396.63843"
ry="1"
inkscape:label="#rect4550-8-1-4-21-5" />
<rect
style="fill:#241c1c;fill-opacity:1;stroke:none;display:inline"
id="Attitude"
width="18.966711"
height="10.202584"
x="505.26666"
y="347.495"
ry="1"
inkscape:label="#rect4550-8-1-4-21-5-4" />
<rect
style="fill:#241c1c;fill-opacity:1;stroke:none;display:inline"
id="Stabilization"
width="18.966711"
height="10.202584"
x="527.08551"
y="347.495"
ry="1"
inkscape:label="#rect4550-8-1-4-21-5-3" />
<rect
style="fill:#241c1c;fill-opacity:1;stroke:none;display:inline"
id="Guidance"
width="18.966711"
height="10.202584"
x="548.90442"
y="347.495"
ry="1"
inkscape:label="#rect4550-8-1-4-21-5-1" />
<rect
style="fill:#241c1c;fill-opacity:1;stroke:none;display:inline"
id="PathPlan"
width="18.966711"
height="10.202584"
x="570.72327"
y="347.495"
ry="1"
inkscape:label="#rect4550-8-1-4-21-5-2" />
<rect
style="fill:#241c1c;fill-opacity:1;stroke:none;display:inline"
id="GPS"
width="18.966711"
height="10.202584"
x="505.26666"
y="361.65591"
ry="1"
inkscape:label="#rect4550-8-1-4-21-5-33" />
<rect
style="fill:#241c1c;fill-opacity:1;stroke:none;display:inline"
id="Sensors"
width="18.966711"
height="10.202584"
x="527.08551"
y="361.65591"
ry="1"
inkscape:label="#rect4550-8-1-4-21-5-41" />
<rect
style="fill:#241c1c;fill-opacity:1;stroke:none;display:inline"
id="Airspeed"
width="18.966711"
height="10.202584"
x="548.90442"
y="361.65591"
ry="1"
inkscape:label="#rect4550-8-1-4-21-5-13" />
<rect
style="fill:#241c1c;fill-opacity:1;stroke:none;display:inline"
id="rect4550-8-1-4-21-5-8"
width="18.966711"
height="10.202584"
x="570.72327"
y="361.65591"
ry="1" />
<rect
style="fill:#241c1c;fill-opacity:1;stroke:none;display:inline"
id="Battery"
width="15.447426"
height="10.265867"
x="557.75928"
y="396.60678"
ry="1"
inkscape:label="#rect4550-8-1-4-21-2-9-8" />
<rect
style="fill:#241c1c;fill-opacity:1;stroke:none;display:inline"
id="SystemConfiguration"
width="13.310432"
height="10.308098"
x="532.17792"
y="382.58969"
ry="1"
inkscape:label="#rect4550-8-1-4-21" />
<rect
style="fill:#6c5d53;fill-opacity:1;stroke:none;display:inline"
id="rect1234-1"
width="26.147932"
height="27.124466"
x="500.06686"
y="381.38202"
ry="0" />
<text
xml:space="preserve"
style="font-size:3.38406372px;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:#f4d7d7;fill-opacity:1;stroke:none;display:inline;font-family:Sans;-inkscape-font-specification:Sans Bold"
x="-453.88235"
y="440.49704"
id="text4641-5-2-11-0"
sodipodi:linespacing="125%"
transform="matrix(0,-0.87458357,1.1434013,0,0,0)"><tspan
sodipodi:role="line"
id="tspan3467"
x="-453.88235"
y="440.49704">I/O</tspan></text>
<rect
style="fill:#6c5353;fill-opacity:1;stroke:#6c5d53;stroke-width:0.66968507;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
id="rect3510"
width="1.94293"
height="7.3697343"
x="12.260558"
y="54.383957"
transform="translate(497.66563,344.28037)" />
<rect
style="fill:#241c1c;fill-opacity:1;stroke:none;display:inline"
id="Receiver-OK-2"
width="19.129522"
height="10.639811"
x="505.12875"
y="382.42383"
ry="1.0787175"
inkscape:label="#rect4550"
rx="1.1054602" />
<rect
style="fill:#6c5d53;fill-opacity:1;stroke:none;display:inline"
id="rect1234-1-1"
width="26.147932"
height="12.217504"
x="500.06686"
y="409.64682"
ry="0" />
<rect
style="fill:#241c1c;fill-opacity:1;stroke:none;display:inline"
id="rect"
width="19.129522"
height="10.639811"
x="504.98425"
y="410.36182"
ry="1.0787175"
inkscape:label="#rect4550"
rx="1.1054602" />
<rect
inkscape:label="#rect4550-8-1-4-21-5-33"
ry="0.98606986"
y="396.92505"
x="505.28799"
height="10.060461"
width="18.729839"
id="Actuator"
style="fill:#241c1c;fill-opacity:1;stroke:none;display:inline" />
</g>
<g
inkscape:groupmode="layer"
id="g3164"
inkscape:label="I2C-OK"
style="display:none">
<rect
style="fill:#04b629;fill-opacity:1;stroke:#ffffff;stroke-width:0.53149605;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
id="I2C-OK"
width="18.153212"
height="8.1216154"
x="74.851883"
y="1.5189452"
inkscape:label="#rect8374" />
</g>
<g
inkscape:groupmode="layer"
id="g3160"
inkscape:label="I2C-Warning"
style="display:none">
<rect
y="1.5189452"
x="74.851883"
height="8.1216154"
width="18.153212"
id="I2C-Warning"
style="fill:#f1b907;fill-opacity:1;stroke:#ffffff;stroke-width:0.53149605;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
inkscape:label="#rect4073" />
</g>
<g
inkscape:groupmode="layer"
id="g3152"
inkscape:label="I2C-Error"
style="display:none">
<g
style="stroke:#cf0e0e;stroke-width:2;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
id="I2C-Error"
transform="translate(36.695254,-31.446948)"
inkscape:label="#g4084">
<path
style="fill:none;stroke:#cf0e0e;stroke-width:2;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
d="M 38.076545,33.292974 56.14311,41.28257"
id="path3156"
inkscape:connector-curvature="0" />
<path
style="fill:none;stroke:#cf0e0e;stroke-width:2;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
d="m 38.220502,41.354548 17.85063,-8.061574"
id="path3158"
inkscape:label="#path4088-8"
inkscape:connector-curvature="0" />
</g>
</g>
<g
inkscape:groupmode="layer"
id="g3148"
inkscape:label="I2C-Critical"
style="display:none">
<rect
style="fill:#cf0e0e;fill-opacity:1;stroke:#ffffff;stroke-width:0.53149605;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
id="I2C-Critical"
width="18.153212"
height="8.1216154"
x="74.851883"
y="1.5189452"
inkscape:label="#rect4080" />
</g>
<g
style="display:none"
id="layer1"
inkscape:label="GPS-OK"
id="g3184"
inkscape:groupmode="layer">
style="display:inline">
<rect
inkscape:label="#rect8374"
y="9.1076469"
x="22.798349"
height="5.6002355"
width="23.347105"
transform="translate(-497.66563,-344.28037)"
style="fill:#008000;fill-opacity:1;stroke:none;display:inline"
id="GPS-OK"
style="fill:#04b629;fill-opacity:1;stroke:#ffffff;stroke-width:0.30000001;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
</g>
<g
style="display:none"
inkscape:label="GPS-Warning"
id="g3180"
inkscape:groupmode="layer">
<rect
inkscape:label="#rect4073"
style="fill:#f1b907;fill-opacity:1;stroke:#ffffff;stroke-width:0.30000001;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
id="GPS-Warning"
width="23.347105"
height="5.6002355"
x="22.798349"
y="9.1076469" />
</g>
<g
style="display:none"
inkscape:label="GPS-Error"
id="g3172"
inkscape:groupmode="layer">
<g
inkscape:label="#g4084"
id="GPS-Error"
style="stroke:#cf0e0e;stroke-width:2;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
transform="matrix(1.2853162,0,0,0.64013573,-26.151312,-11.845582)">
<path
id="path3176"
d="m 38,33.292974 17.85,8"
style="fill:none;stroke:#cf0e0e;stroke-width:2;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
inkscape:connector-curvature="0" />
<path
inkscape:label="#path4088-8"
id="path3178"
d="m 38,41.354548 17.85,-8"
style="fill:none;stroke:#cf0e0e;stroke-width:2;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
inkscape:connector-curvature="0" />
</g>
</g>
<g
style="display:none"
inkscape:label="GPS-Critical"
id="g3168"
inkscape:groupmode="layer">
<rect
inkscape:label="#rect4080"
y="9.1076469"
x="22.798349"
height="5.6002355"
width="23.347105"
id="GPS-Critical"
style="fill:#cf0e0e;fill-opacity:1;stroke:#ffffff;stroke-width:0.30000001;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
</g>
<g
inkscape:groupmode="layer"
id="layer50"
inkscape:label="Airspeed-OK"
style="display:none">
<rect
style="fill:#04b629;fill-opacity:1;stroke:#ffffff;stroke-width:0.40371776;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
id="Airspeed-OK"
width="8"
height="20.241537"
x="64.72757"
y="1.6625173"
inkscape:label="#rect4552-27" />
</g>
<g
inkscape:groupmode="layer"
id="layer20"
inkscape:label="Airspeed-Warning"
style="display:none">
<rect
inkscape:label="#rect4552-27"
y="1.7688711"
x="64.727081"
height="20.135679"
width="8"
id="Airspeed-Warning"
style="fill:#f1b907;fill-opacity:1;stroke:#ffffff;stroke-width:0.4026823;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
width="18.966711"
height="10.202584"
x="505.26666"
y="361.65591"
ry="1"
inkscape:label="#rect4550-8-1-4-21-5-33" />
</g>
<g
inkscape:groupmode="layer"
id="layer11"
inkscape:label="Airspeed-Error"
style="display:none">
<g
inkscape:label="#g5707"
transform="matrix(0.98237131,0,0,1.3895115,61.95219,0.4046338)"
id="Airspeed-Error"
style="stroke:#cf0e0e;stroke-width:2;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline">
<path
sodipodi:nodetypes="cc"
id="path5709-4"
d="M 4.2641874,1.9700434 9.4,14.522849"
style="fill:none;stroke:#cf0e0e;stroke-width:2;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
inkscape:connector-curvature="0" />
<path
sodipodi:nodetypes="cc"
id="path5711-6"
d="M 4.5521007,14.319264 9.4,1.9402289"
style="fill:none;stroke:#cf0e0e;stroke-width:2;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
inkscape:connector-curvature="0" />
inkscape:label="Airspeed-OK"
style="display:inline">
<rect
style="fill:#008000;fill-opacity:1;stroke:none;display:inline"
id="Airspeed-OK"
width="18.966711"
height="10.202584"
x="51.238789"
y="17.375544"
ry="1"
inkscape:label="#rect4550-8-1-4-21-5-33" />
</g>
<g
inkscape:groupmode="layer"
id="layer10"
inkscape:label="Sensors-OK"
style="display:inline">
<rect
style="fill:#008000;fill-opacity:1;stroke:none;display:inline"
id="Sensors-OK"
width="18.966711"
height="10.202584"
x="29.41988"
y="17.375544"
ry="1"
inkscape:label="#rect4550-8-1-4-21-5-33" />
</g>
<g
inkscape:groupmode="layer"
id="layer9"
inkscape:label="PathPlan-OK"
style="display:inline">
<rect
style="fill:#008000;fill-opacity:1;stroke:none;display:inline"
id="PathPlan-OK"
width="18.966711"
height="10.202584"
x="73.05764"
y="3.2146251"
ry="1"
inkscape:label="#rect4550-8-1-4-21-5-33" />
</g>
<g
inkscape:groupmode="layer"
id="layer8"
inkscape:label="Guidance-OK"
style="display:inline">
<rect
style="fill:#008000;fill-opacity:1;stroke:none;display:inline"
id="Guidance-OK"
width="18.966711"
height="10.202584"
x="51.238789"
y="3.2146251"
ry="1"
inkscape:label="#rect4550-8-1-4-21-5-33" />
</g>
<g
inkscape:groupmode="layer"
id="layer7"
inkscape:label="Stabilization-OK"
style="display:inline">
<rect
style="fill:#008000;fill-opacity:1;stroke:none;display:inline"
id="Stabilization-OK"
width="18.966711"
height="10.202584"
x="29.41988"
y="3.2146251"
ry="1"
inkscape:label="#rect4550-8-1-4-21-5-33" />
</g>
<g
inkscape:groupmode="layer"
id="layer6"
inkscape:label="Airspeed-Critical"
style="display:none">
inkscape:label="Attitude-OK"
style="display:inline">
<rect
style="fill:#cf0e0e;fill-opacity:1;stroke:#ffffff;stroke-width:0.40371776;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
id="Airspeed-Critical"
width="8"
height="20.241537"
x="64.72757"
y="1.6625173"
inkscape:label="#rect4552-27" />
style="fill:#008000;fill-opacity:1;stroke:none;display:inline"
id="Attitude-OK"
width="18.966711"
height="10.202584"
x="7.6010327"
y="3.2146251"
ry="1"
inkscape:label="#rect4550-8-1-4-21-5-33" />
</g>
<g
style="display:none"
inkscape:label="Sensors-OK"
id="layer41"
inkscape:groupmode="layer">
<rect
style="fill:#04b629;fill-opacity:1;stroke:#ffffff;stroke-width:0.40371776;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
id="Sensors-OK"
width="8"
height="20.241537"
x="54.228596"
y="1.586597"
inkscape:label="#rect4552-27" />
</g>
<g
style="display:none"
inkscape:label="Sensors-Warning"
id="layer42"
inkscape:groupmode="layer">
<rect
inkscape:label="#rect4552-27"
y="1.6929722"
x="54.228077"
height="20.135679"
width="8"
id="Sensors-Warning"
style="fill:#f1b907;fill-opacity:1;stroke:#ffffff;stroke-width:0.4026823;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
</g>
<g
style="display:none"
inkscape:label="Sensors-Error"
id="layer43"
inkscape:groupmode="layer">
<g
inkscape:label="#g5707"
transform="matrix(0.98237131,0,0,1.3895115,51.453151,0.32873234)"
id="Sensors-Error"
style="stroke:#cf0e0e;stroke-width:2;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline">
<path
sodipodi:nodetypes="cc"
id="path5709"
d="M 4.2641874,1.9700434 9.4,14.522849"
style="fill:none;stroke:#cf0e0e;stroke-width:2;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
inkscape:connector-curvature="0" />
<path
sodipodi:nodetypes="cc"
id="path5711"
d="M 4.5521007,14.319264 9.4,1.9402289"
style="fill:none;stroke:#cf0e0e;stroke-width:2;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
inkscape:connector-curvature="0" />
</g>
</g>
<g
style="display:none"
inkscape:label="Sensors-Critical"
id="layer44"
inkscape:groupmode="layer">
<rect
style="fill:#cf0e0e;fill-opacity:1;stroke:#ffffff;stroke-width:0.40371776;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
id="Sensors-Critical"
width="8"
height="20.241537"
x="54.228596"
y="1.586597"
inkscape:label="#rect4552-27" />
</g>
<g
style="display:none"
inkscape:label="Receiver-OK"
id="layer36"
inkscape:groupmode="layer">
<rect
y="365.44907"
x="576.71594"
height="56.637238"
width="13.893178"
id="Receiver-OK"
style="fill:#04b629;fill-opacity:1;stroke:#ffffff;stroke-width:0.53149605;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
inkscape:label="#rect4000-8-0-9"
transform="translate(-497.66563,-344.28037)" />
</g>
<g
style="display:none"
inkscape:label="Receiver-Warning"
id="layer33"
inkscape:groupmode="layer">
<rect
y="365.44907"
x="576.71594"
height="56.637238"
width="13.893178"
id="Receiver-Warning"
style="fill:#f1b907;fill-opacity:1;stroke:#ffffff;stroke-width:0.53149605;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
inkscape:label="#rect4000-8-0-9"
transform="translate(-497.66563,-344.28037)" />
</g>
<g
style="display:none"
inkscape:label="Receiver-Error"
id="layer34"
inkscape:groupmode="layer">
<g
transform="translate(78,0)"
id="Receiver-Error"
style="stroke:#cf0e0e;stroke-opacity:1;display:inline"
inkscape:label="#g3878">
<path
id="path5066"
d="M 2.0153937,22.13633 14.539626,77.127787"
style="fill:none;stroke:#cf0e0e;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" />
<path
style="fill:none;stroke:#cf0e0e;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
d="M 14.539626,22.13633 2.0153937,77.127787"
id="path5068" />
</g>
</g>
<g
style="display:none"
inkscape:label="Receiver-Critical"
id="layer35"
inkscape:groupmode="layer">
<rect
transform="translate(-497.66563,-344.28037)"
inkscape:label="#rect4000-8-0-9"
style="fill:#cf0e0e;fill-opacity:1;stroke:#ffffff;stroke-width:0.53149605;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
id="Receiver-Critical"
width="13.893178"
height="56.637238"
x="576.71594"
y="365.44907" />
</g>
<g
style="display:none"
inkscape:label="Actuator-OK"
id="layer29"
inkscape:groupmode="layer">
<rect
y="365.44907"
x="499.10913"
height="56.637238"
width="13.893178"
id="Actuator-OK"
style="fill:#04b629;fill-opacity:1;stroke:#ffffff;stroke-width:0.53149605;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
inkscape:label="#rect4000-8-5"
transform="translate(-497.66563,-344.28037)" />
</g>
<g
style="display:none"
inkscape:label="Actuator-Warning"
id="layer30"
inkscape:groupmode="layer">
<rect
transform="translate(-497.66563,-344.28037)"
inkscape:label="#rect4000-8-5"
style="fill:#f1b907;fill-opacity:1;stroke:#ffffff;stroke-width:0.53149605;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
id="Actuator-Warning"
width="13.893178"
height="56.637238"
x="499.10913"
y="365.44907" />
</g>
<g
style="display:none"
inkscape:label="Actuator-Error"
id="layer31"
inkscape:groupmode="layer">
<g
inkscape:label="#g3878"
style="stroke:#cf0e0e;stroke-opacity:1"
id="Actuator-Error">
<path
style="fill:none;stroke:#cf0e0e;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
d="M 2.0153937,22.13633 14.539626,77.127787"
id="path3874" />
<path
id="path3876"
d="M 14.539626,22.13633 2.0153937,77.127787"
style="fill:none;stroke:#cf0e0e;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" />
</g>
</g>
<g
style="display:none"
inkscape:label="Actuator-Critical"
id="layer32"
inkscape:groupmode="layer">
<rect
y="365.44907"
x="499.10913"
height="56.637238"
width="13.893178"
id="Actuator-Critical"
style="fill:#cf0e0e;fill-opacity:1;stroke:#ffffff;stroke-width:0.53149605;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
inkscape:label="#rect4000-8-5"
transform="translate(-497.66563,-344.28037)" />
</g>
<g
style="display:none"
inkscape:label="EventSystem-OK"
id="layer21"
inkscape:groupmode="layer">
<rect
inkscape:label="#rect4000-7-6-7-1"
style="fill:#04b629;fill-opacity:1;stroke:#ffffff;stroke-width:0.53149605;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
id="EventSystem-OK"
width="18.153212"
height="8.1216154"
x="17.566181"
y="51.277248" />
</g>
<g
style="display:none"
inkscape:label="EventSystem-Warning"
id="layer22"
inkscape:groupmode="layer">
<rect
y="51.277248"
x="17.566181"
height="8.1216154"
width="18.153212"
id="EventSystem-Warning"
style="fill:#f1b907;fill-opacity:1;stroke:#ffffff;stroke-width:0.53149605;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
inkscape:label="#rect4000-7-6-7-1" />
</g>
<g
style="display:none"
inkscape:label="EventSystem-Error"
id="layer23"
inkscape:groupmode="layer">
<g
transform="translate(-20.405861,18.143957)"
id="EventSystem-Error"
style="stroke:#cf0e0e;stroke-width:2;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
inkscape:label="#g4040-1">
<path
id="path4161"
d="M 38.076545,33.292974 56.14311,41.28257"
style="fill:none;stroke:#cf0e0e;stroke-width:2;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
<path
id="path4163"
d="m 38.220502,41.354548 17.85063,-8.061574"
style="fill:none;stroke:#cf0e0e;stroke-width:2;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
</g>
</g>
<g
style="display:none"
inkscape:label="EventSystem-Critical"
id="layer24"
inkscape:groupmode="layer">
<rect
style="fill:#cf0e0e;fill-opacity:1;stroke:#ffffff;stroke-width:0.53149605;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
id="EventSystem-Critical"
width="18.153212"
height="8.1216154"
x="17.566181"
y="51.277248"
inkscape:label="#rect8365" />
</g>
<g
style="display:none"
inkscape:label="Telemetry-OK"
id="layer25"
inkscape:groupmode="layer">
<rect
inkscape:label="#rect4552-27"
y="3.1377156"
x="22.697004"
height="5.6002355"
width="23.347105"
id="Telemetry-OK"
style="fill:#04b629;fill-opacity:1;stroke:#ffffff;stroke-width:0.29055119;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
</g>
<g
style="display:none"
inkscape:label="Telemetry-Warning"
id="layer26"
inkscape:groupmode="layer">
<rect
style="fill:#f1b907;fill-opacity:1;stroke:#ffffff;stroke-width:0.29055119;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
id="Telemetry-Warning"
width="23.347105"
height="5.6002355"
x="22.697004"
y="3.1377156"
inkscape:label="#rect4552-27" />
</g>
<g
style="display:none"
inkscape:label="Telemetry-Error"
id="layer27"
inkscape:groupmode="layer">
<g
inkscape:label="#g4357"
style="stroke:#cf0e0e;stroke-opacity:1;display:inline"
id="Telemetry-Error"
transform="translate(-3.4013125,0)">
<path
style="fill:none;stroke:#cf0e0e;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
d="M 26.488031,3.4219598 49.017254,8.3164874"
id="path4353"
inkscape:connector-curvature="0" />
<path
style="fill:none;stroke:#cf0e0e;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
d="M 49.089232,3.3499815 26.56001,8.3884657"
id="path4355"
inkscape:connector-curvature="0" />
</g>
</g>
<g
style="display:none"
inkscape:label="Telemetry-Critical"
id="layer28"
inkscape:groupmode="layer">
<rect
inkscape:label="#rect4552-27"
y="3.1377156"
x="22.697004"
height="5.6002355"
width="23.347105"
id="Telemetry-Critical"
style="fill:#cf0e0e;fill-opacity:1;stroke:#ffffff;stroke-width:0.29055119;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
</g>
<g
style="display:none"
inkscape:label="Memory-OK"
id="layer9"
inkscape:groupmode="layer">
<rect
inkscape:label="#rect8374"
y="41.277248"
x="58.539021"
height="8.1216154"
width="18.153212"
id="OutOfMemory-OK"
style="fill:#04b629;fill-opacity:1;stroke:#ffffff;stroke-width:0.53149605;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
</g>
<g
style="display:none"
inkscape:label="Memory-Warning"
id="layer17"
inkscape:groupmode="layer">
<rect
inkscape:label="#rect4073"
style="fill:#f1b907;fill-opacity:1;stroke:#ffffff;stroke-width:0.53149605;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
id="OutOfMemory-Warning"
width="18.153212"
height="8.1216154"
x="58.539021"
y="41.277248" />
</g>
<g
style="display:none"
inkscape:label="Memory-Error"
id="layer18"
inkscape:groupmode="layer">
<g
inkscape:label="#g4084"
transform="translate(20.503848,8)"
id="OutOfMemory-Error"
style="stroke:#cf0e0e;stroke-width:2;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline">
<path
id="path4086"
d="M 38.076545,33.292974 56.14311,41.28257"
style="fill:none;stroke:#cf0e0e;stroke-width:2;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
<path
id="path4088"
d="m 38.220502,41.354548 17.85063,-8.061574"
style="fill:none;stroke:#cf0e0e;stroke-width:2;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
</g>
</g>
<g
style="display:none"
inkscape:label="Memory-Critical"
id="layer19"
inkscape:groupmode="layer">
<rect
inkscape:label="#rect4080"
y="41.277248"
x="58.539021"
height="8.1216154"
width="18.153212"
id="OutOfMemory-Critical"
style="fill:#cf0e0e;fill-opacity:1;stroke:#ffffff;stroke-width:0.53149605;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
</g>
<g
style="display:none"
inkscape:label="StackOverflow-OK"
id="layer8"
inkscape:groupmode="layer">
<rect
inkscape:label="#rect8370"
style="fill:#04b629;fill-opacity:1;stroke:#ffffff;stroke-width:0.53149605;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
id="StackOverflow-OK"
width="18.153212"
height="8.1216154"
x="38.05257"
y="41.277248" />
</g>
<g
style="display:none"
inkscape:label="StackOverflow-Warning"
id="layer10"
inkscape:groupmode="layer">
<rect
inkscape:label="#rect8540"
y="41.277248"
x="38.05257"
height="8.1216154"
width="18.153212"
id="StackOverflow-Warning"
style="fill:#f1b907;fill-opacity:1;stroke:#ffffff;stroke-width:0.53149605;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
</g>
<g
style="display:none"
inkscape:label="StackOverflow-Error"
id="layer15"
inkscape:groupmode="layer">
<g
transform="translate(0,8)"
style="stroke:#cf0e0e;stroke-width:2;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
id="g4040">
<path
style="fill:none;stroke:#cf0e0e;stroke-width:2;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
d="M 38.076545,33.292974 56.14311,41.28257"
id="path4036" />
<path
style="fill:none;stroke:#cf0e0e;stroke-width:2;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
d="m 38.220502,41.354548 17.85063,-8.061574"
id="path4038" />
</g>
<g
transform="translate(0,8)"
inkscape:label="#g4102"
id="StackOverflow-Error"
style="stroke:#cf0e0e;stroke-width:2;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline">
<path
id="path4104"
d="M 38.076545,33.292974 56.14311,41.28257"
style="fill:none;stroke:#cf0e0e;stroke-width:2;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
<path
id="path4106"
d="m 38.220502,41.354548 17.85063,-8.061574"
style="fill:none;stroke:#cf0e0e;stroke-width:2;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
</g>
</g>
<g
style="display:none"
inkscape:label="StackOverflow-Critical"
id="layer16"
inkscape:groupmode="layer">
<rect
inkscape:label="#rect4032"
style="fill:#cf0e0e;fill-opacity:1;stroke:#ffffff;stroke-width:0.53149605;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
id="StackOverflow-Critical"
width="18.153212"
height="8.1216154"
x="38.05257"
y="41.277248" />
</g>
<g
style="display:none"
inkscape:label="CPUOverload-OK"
id="layer7"
inkscape:groupmode="layer">
<rect
inkscape:label="#rect8365"
y="41.277248"
x="17.566181"
height="8.1216154"
width="18.153212"
id="CPUOverload-OK"
style="fill:#04b629;fill-opacity:1;stroke:#ffffff;stroke-width:0.53149605;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
</g>
<g
style="display:none"
inkscape:label="CPUOverload-Warning"
inkscape:groupmode="layer"
id="layer12"
inkscape:groupmode="layer">
inkscape:label="SystemConfiguration-OK"
style="display:inline">
<rect
style="fill:#f1b907;fill-opacity:1;stroke:#ffffff;stroke-width:0.53149605;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
id="CPUOverload-Warning"
width="18.153212"
height="8.1216154"
x="17.566181"
y="41.277248"
inkscape:label="#rect8365" />
style="fill:#008000;fill-opacity:1;stroke:none;display:inline"
id="SystemConfiguration-OK"
width="13.310432"
height="10.308098"
x="34.512287"
y="38.309322"
ry="1"
inkscape:label="#rect4550-8-1-4-21-1" />
</g>
<g
style="display:none"
inkscape:label="CPUOverload-Error"
inkscape:groupmode="layer"
id="layer13"
inkscape:groupmode="layer">
<g
inkscape:label="#g4040-1"
style="stroke:#cf0e0e;stroke-width:2;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
id="CPUOverload-Error"
transform="translate(-20.405861,8.1439567)">
<path
style="fill:none;stroke:#cf0e0e;stroke-width:2;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
d="M 38.076545,33.292974 56.14311,41.28257"
id="path4036-7" />
<path
style="fill:none;stroke:#cf0e0e;stroke-width:2;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
d="m 38.220502,41.354548 17.85063,-8.061574"
id="path4038-4" />
</g>
</g>
<g
style="display:none"
inkscape:label="CPUOverload-Critical"
id="layer14"
inkscape:groupmode="layer">
inkscape:label="BootFault-OK"
style="display:inline">
<rect
inkscape:label="#rect8365"
y="41.277248"
x="17.566181"
height="8.1216154"
width="18.153212"
id="CPUOverload-Critical"
style="fill:#cf0e0e;fill-opacity:1;stroke:#ffffff;stroke-width:0.53149605;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
</g>
<g
style="display:none"
inkscape:label="Power-OK"
id="layer2"
inkscape:groupmode="layer">
<rect
inkscape:label="#rect7370"
y="1.8212841"
x="1.5801588"
height="8.2846708"
width="18.023544"
id="Power-OK"
style="fill:#04b629;fill-opacity:1;stroke:#ffffff;stroke-width:0.53149605;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
</g>
<g
style="display:none"
inkscape:label="Power-Warning"
id="layer3"
inkscape:groupmode="layer">
<rect
inkscape:label="#rect7397"
style="fill:#f1b907;fill-opacity:1;stroke:#ffffff;stroke-width:0.53149605;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
id="Power-Warning"
width="18.023544"
height="8.2846708"
x="1.5801588"
y="1.8212841" />
</g>
<g
style="display:none"
inkscape:label="Power-Error"
id="layer4"
inkscape:groupmode="layer">
<g
inkscape:label="#g4026"
style="stroke:#cf0e0e;stroke-width:2;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
id="Power-Error"
transform="translate(-1.9500095,0)">
<path
style="fill:none;stroke:#cf0e0e;stroke-width:2;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
d="M 3.9588091,1.7664579 22.097352,10.043968"
id="path4022"
inkscape:connector-curvature="0" />
<path
style="fill:none;stroke:#cf0e0e;stroke-width:2;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
d="M 4.2467224,10.043968 22.025374,1.8384362"
id="path4024"
inkscape:connector-curvature="0" />
</g>
</g>
<g
style="display:none"
inkscape:label="Power-Critical"
id="layer5"
inkscape:groupmode="layer">
<rect
inkscape:label="#rect7437"
y="1.8212841"
x="1.5801588"
height="8.2846708"
width="18.023544"
id="Power-Critical"
style="fill:#cf0e0e;fill-opacity:1;stroke:#f9f9f9;stroke-width:0.53149605;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
style="fill:#008000;fill-opacity:1;stroke:none;display:inline"
id="BootFault-OK"
width="13.310432"
height="10.308098"
x="49.262897"
y="38.309322"
ry="1" />
</g>
<g
inkscape:groupmode="layer"
id="g471999"
id="layer15"
inkscape:label="Battery-OK"
style="display:none">
style="display:inline">
<rect
style="fill:#04b629;fill-opacity:1;stroke:#ffffff;stroke-width:0.53149605;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
style="fill:#008000;fill-opacity:1;stroke:none;display:inline"
id="Battery-OK"
width="18.023544"
height="8.2846708"
x="1.4732658"
y="11.334756"
inkscape:label="#rect7370" />
width="15.447426"
height="10.265867"
x="60.093647"
y="52.326412"
ry="1"
inkscape:label="#rect4550-8-1-4-21-2-9-8" />
</g>
<g
inkscape:groupmode="layer"
id="g4712"
id="layer14"
inkscape:label="Telemetry-OK"
style="display:inline">
<rect
style="fill:#008000;fill-opacity:1;stroke:none;display:inline"
id="Telemetry-OK"
width="18.966711"
height="10.202584"
x="34.470295"
y="52.358059"
ry="1"
inkscape:label="#rect4550-8-1-4-21-5" />
</g>
<g
inkscape:groupmode="layer"
id="layer16"
inkscape:label="FlightTime-OK"
style="display:inline">
<rect
style="fill:#008000;fill-opacity:1;stroke:none;display:inline"
id="FlightTime-OK"
width="15.447426"
height="10.265867"
x="76.795616"
y="52.326412"
ry="1"
inkscape:label="#rect4550-8-1-4-21-2-9-8" />
</g>
<g
inkscape:groupmode="layer"
id="layer21"
inkscape:label="I2C-OK"
style="display:inline">
<rect
style="fill:#008000;fill-opacity:1;stroke:none;display:inline"
id="I2C-OK"
width="10.470912"
height="8.5405388"
x="82.190269"
y="67.18853"
ry="1"
inkscape:label="#rect4550-8" />
</g>
<g
inkscape:groupmode="layer"
id="layer20"
inkscape:label="EventSystem-OK"
style="display:inline">
<rect
style="fill:#008000;fill-opacity:1;stroke:none;display:inline"
id="EventSystem-OK"
width="10.470912"
height="8.5405388"
x="70.423416"
y="67.18853"
ry="1"
inkscape:label="#rect4550-8" />
</g>
<g
inkscape:groupmode="layer"
id="layer19"
inkscape:label="StackOverflow-OK"
style="display:inline">
<rect
style="fill:#008000;fill-opacity:1;stroke:none;display:inline"
id="StackOverflow-OK"
width="10.470912"
height="8.5405388"
x="58.656513"
y="67.18853"
ry="1"
inkscape:label="#rect4550-8" />
</g>
<g
inkscape:groupmode="layer"
id="layer18"
inkscape:label="OutOfMemory-OK"
style="display:inline">
<rect
style="fill:#008000;fill-opacity:1;stroke:none;display:inline"
id="OutOfMemory-OK"
width="10.470912"
height="8.5405388"
x="46.889668"
y="67.18853"
ry="1"
inkscape:label="#rect4550-8" />
</g>
<g
inkscape:groupmode="layer"
id="layer17"
inkscape:label="CPUOverload-OK"
style="display:inline">
<rect
style="fill:#008000;fill-opacity:1;stroke:none;display:inline"
id="CPUOverload-OK"
width="10.470912"
height="8.5405388"
x="35.122761"
y="67.18853"
ry="1"
inkscape:label="#rect4550-8" />
</g>
<g
inkscape:groupmode="layer"
id="layer22"
inkscape:label="Receiver-OK"
style="display:inline">
<rect
style="fill:#008000;fill-opacity:1;stroke:none;display:inline"
id="Receiver-OK"
width="18.963711"
height="10.260815"
x="7.6226416"
y="38.370422"
ry="0.99888694"
inkscape:label="#rect4550"
rx="0.88121402" />
</g>
<g
inkscape:groupmode="layer"
id="layer23"
inkscape:label="Actuator-OK"
style="display:inline">
<rect
style="fill:#008000;fill-opacity:1;stroke:none;display:inline"
id="Actuator-OK"
width="18.905607"
height="10.044919"
x="7.6230011"
y="52.617489"
ry="1.112498"
inkscape:label="#rect4550"
rx="0.86747229" />
</g>
<g
inkscape:groupmode="layer"
id="g5041"
inkscape:label="GPS-Warning"
style="display:inline">
<rect
transform="translate(-497.66563,-344.28037)"
style="fill:#ff6600;fill-opacity:1;stroke:none;display:inline"
id="GPS-Warning"
width="18.966711"
height="10.202584"
x="505.26666"
y="361.65591"
ry="1"
inkscape:label="#rect4550-8-1-4-21-5-33" />
</g>
<g
inkscape:groupmode="layer"
id="g5044"
inkscape:label="Airspeed-Warning"
style="display:inline">
<rect
style="fill:#ff6600;fill-opacity:1;stroke:none;display:inline"
id="Airspeed-Warning"
width="18.966711"
height="10.202584"
x="51.238789"
y="17.375544"
ry="1"
inkscape:label="#rect4550-8-1-4-21-5-33" />
</g>
<g
inkscape:groupmode="layer"
id="g5047"
inkscape:label="Sensors-Warning"
style="display:inline">
<rect
style="fill:#ff6600;fill-opacity:1;stroke:none;display:inline"
id="Sensors-Warning"
width="18.966711"
height="10.202584"
x="29.41988"
y="17.375544"
ry="1"
inkscape:label="#rect4550-8-1-4-21-5-33" />
</g>
<g
inkscape:groupmode="layer"
id="g5050"
inkscape:label="PathPlan-Warning"
style="display:inline">
<rect
style="fill:#ff6600;fill-opacity:1;stroke:none;display:inline"
id="PathPlan-Warning"
width="18.966711"
height="10.202584"
x="73.05764"
y="3.2146251"
ry="1"
inkscape:label="#rect4550-8-1-4-21-5-33" />
</g>
<g
inkscape:groupmode="layer"
id="g5053"
inkscape:label="Guidance-Warning"
style="display:inline">
<rect
style="fill:#ff6600;fill-opacity:1;stroke:none;display:inline"
id="Guidance-Warning"
width="18.966711"
height="10.202584"
x="51.238789"
y="3.2146251"
ry="1"
inkscape:label="#rect4550-8-1-4-21-5-33" />
</g>
<g
inkscape:groupmode="layer"
id="g5056"
inkscape:label="Stabilization-Warning"
style="display:inline">
<rect
style="fill:#ff6600;fill-opacity:1;stroke:none;display:inline"
id="Stabilization-Warning"
width="18.966711"
height="10.202584"
x="29.41988"
y="3.2146251"
ry="1"
inkscape:label="#rect4550-8-1-4-21-5-33" />
</g>
<g
inkscape:groupmode="layer"
id="g5059"
inkscape:label="Attitude-Warning"
style="display:inline">
<rect
style="fill:#ff6600;fill-opacity:1;stroke:none;display:inline"
id="Attitude-Warning"
width="18.966711"
height="10.202584"
x="7.6010327"
y="3.2146251"
ry="1"
inkscape:label="#rect4550-8-1-4-21-5-33" />
</g>
<g
inkscape:groupmode="layer"
id="g5062"
inkscape:label="SystemConfiguration-Warning"
style="display:inline">
<rect
style="fill:#ff6600;fill-opacity:1;stroke:none;display:inline"
id="SystemConfiguration-Warning"
width="13.310432"
height="10.308098"
x="34.512287"
y="38.309322"
ry="1"
inkscape:label="#rect4550-8-1-4-21-1" />
</g>
<g
inkscape:groupmode="layer"
id="g5065"
inkscape:label="BootFault-Warning"
style="display:inline">
<rect
style="fill:#ff6600;fill-opacity:1;stroke:none;display:inline"
id="BootFault-Warning"
width="13.310432"
height="10.308098"
x="49.262897"
y="38.309322"
ry="1" />
</g>
<g
inkscape:groupmode="layer"
id="g5069"
inkscape:label="Battery-Warning"
style="display:none">
style="display:inline">
<rect
y="11.334756"
x="1.4732658"
height="8.2846708"
width="18.023544"
style="fill:#ff6600;fill-opacity:1;stroke:none;display:inline"
id="Battery-Warning"
style="fill:#f1b907;fill-opacity:1;stroke:#ffffff;stroke-width:0.53149605;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
inkscape:label="#rect7397" />
width="15.447426"
height="10.265867"
x="60.093647"
y="52.326412"
ry="1"
inkscape:label="#rect4550-8-1-4-21-2-9-8" />
</g>
<g
inkscape:groupmode="layer"
id="g4700"
inkscape:label="Battery-Critical"
id="g5072"
inkscape:label="Telemetry-Warning"
style="display:inline">
<rect
style="fill:#ff6600;fill-opacity:1;stroke:none;display:inline"
id="Telemetry-Warning"
width="18.966711"
height="10.202584"
x="34.470295"
y="52.358059"
ry="1"
inkscape:label="#rect4550-8-1-4-21-5" />
</g>
<g
inkscape:groupmode="layer"
id="g5075"
inkscape:label="FlightTime-Warning"
style="display:inline">
<rect
style="fill:#ff6600;fill-opacity:1;stroke:none;display:inline"
id="FlightTime-Warning"
width="15.447426"
height="10.265867"
x="76.795616"
y="52.326412"
ry="1"
inkscape:label="#rect4550-8-1-4-21-2-9-8" />
</g>
<g
inkscape:groupmode="layer"
id="g5078"
inkscape:label="I2C-Warning"
style="display:inline">
<rect
style="fill:#ff6600;fill-opacity:1;stroke:none;display:inline"
id="I2C-Warning"
width="10.470912"
height="8.5405388"
x="82.190269"
y="67.18853"
ry="1"
inkscape:label="#rect4550-8" />
</g>
<g
inkscape:groupmode="layer"
id="g5081"
inkscape:label="EventSystem-Warning"
style="display:inline">
<rect
style="fill:#ff6600;fill-opacity:1;stroke:none;display:inline"
id="EventSystem-Warning"
width="10.470912"
height="8.5405388"
x="70.423416"
y="67.18853"
ry="1"
inkscape:label="#rect4550-8" />
</g>
<g
inkscape:groupmode="layer"
id="g5084"
inkscape:label="StackOverflow-Warning"
style="display:inline">
<rect
style="fill:#ff6600;fill-opacity:1;stroke:none;display:inline"
id="StackOverflow-Warning"
width="10.470912"
height="8.5405388"
x="58.656513"
y="67.18853"
ry="1"
inkscape:label="#rect4550-8" />
</g>
<g
inkscape:groupmode="layer"
id="g5087"
inkscape:label="OutOfMemory-Warning"
style="display:inline">
<rect
style="fill:#ff6600;fill-opacity:1;stroke:none;display:inline"
id="OutOfMemory-Warning"
width="10.470912"
height="8.5405388"
x="46.889668"
y="67.18853"
ry="1"
inkscape:label="#rect4550-8" />
</g>
<g
inkscape:groupmode="layer"
id="g5090"
inkscape:label="CPUOverload-Warning"
style="display:inline">
<rect
style="fill:#ff6600;fill-opacity:1;stroke:none;display:inline"
id="CPUOverload-Warning"
width="10.470912"
height="8.5405388"
x="35.122761"
y="67.18853"
ry="1"
inkscape:label="#rect4550-8" />
</g>
<g
inkscape:groupmode="layer"
id="g5093"
inkscape:label="Receiver-Warning"
style="display:inline">
<rect
style="fill:#ff6600;fill-opacity:1;stroke:none;display:inline"
id="Receiver-Warning"
width="18.821587"
height="10.21344"
x="7.7214546"
y="38.403919"
ry="0.79517722"
inkscape:label="#rect4550"
rx="0.8158862" />
</g>
<g
inkscape:groupmode="layer"
id="g5096"
inkscape:label="Actuator-Warning"
style="display:none">
<rect
style="fill:#cf0e0e;fill-opacity:1;stroke:#f9f9f9;stroke-width:0.53149605;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
id="Battery-Critical"
width="18.023544"
height="8.2846708"
x="1.5801588"
y="11.344959"
inkscape:label="#rect7437" />
style="fill:#ff6600;fill-opacity:1;stroke:none;display:inline"
id="Actuator-Warning"
width="18.91176"
height="10.037488"
x="7.6274734"
y="52.645531"
ry="0.92773163"
inkscape:label="#rect4550"
rx="0.9812547" />
</g>
<g
inkscape:groupmode="layer"
id="g4704"
inkscape:label="Battery-Error"
id="g5417"
inkscape:label="GPS-Critical"
style="display:inline">
<rect
transform="translate(-497.66563,-344.28037)"
style="fill:#d40000;fill-opacity:1;stroke:none;display:inline"
id="GPS-Critical"
width="18.966711"
height="10.202584"
x="505.26666"
y="361.65591"
ry="1"
inkscape:label="#rect4550-8-1-4-21-5-33" />
</g>
<g
inkscape:groupmode="layer"
id="g5420"
inkscape:label="Airspeed-Critical"
style="display:inline">
<rect
style="fill:#d40000;fill-opacity:1;stroke:none;display:inline"
id="Airspeed-Critical"
width="18.966711"
height="10.202584"
x="51.238789"
y="17.375544"
ry="1"
inkscape:label="#rect4550-8-1-4-21-5-33" />
</g>
<g
inkscape:groupmode="layer"
id="g5423"
inkscape:label="Sensors-Critical"
style="display:inline">
<rect
style="fill:#d40000;fill-opacity:1;stroke:none;display:inline"
id="Sensors-Critical"
width="18.966711"
height="10.202584"
x="29.41988"
y="17.375544"
ry="1"
inkscape:label="#rect4550-8-1-4-21-5-33" />
</g>
<g
inkscape:groupmode="layer"
id="g5426"
inkscape:label="PathPlan-Critical"
style="display:inline">
<rect
style="fill:#d40000;fill-opacity:1;stroke:none;display:inline"
id="PathPlan-Critical"
width="18.966711"
height="10.202584"
x="73.05764"
y="3.2146251"
ry="1"
inkscape:label="#rect4550-8-1-4-21-5-33" />
</g>
<g
inkscape:groupmode="layer"
id="g5429"
inkscape:label="Guidance-Critical"
style="display:inline">
<rect
style="fill:#d40000;fill-opacity:1;stroke:none;display:inline"
id="Guidance-Critical"
width="18.966711"
height="10.202584"
x="51.238789"
y="3.2146251"
ry="1"
inkscape:label="#rect4550-8-1-4-21-5-33" />
</g>
<g
inkscape:groupmode="layer"
id="g5432"
inkscape:label="Stabilization-Critical"
style="display:inline">
<rect
style="fill:#d40000;fill-opacity:1;stroke:none;display:inline"
id="Stabilization-Critical"
width="18.966711"
height="10.202584"
x="29.41988"
y="3.2146251"
ry="1"
inkscape:label="#rect4550-8-1-4-21-5-33" />
</g>
<g
inkscape:groupmode="layer"
id="g5435"
inkscape:label="Attitude-Critical"
style="display:inline">
<rect
style="fill:#d40000;fill-opacity:1;stroke:none;display:inline"
id="Attitude-Critical"
width="18.966711"
height="10.202584"
x="7.6010327"
y="3.2146251"
ry="1"
inkscape:label="#rect4550-8-1-4-21-5-33" />
</g>
<g
inkscape:groupmode="layer"
id="g5438"
inkscape:label="SystemConfiguration-Critical"
style="display:inline">
<rect
style="fill:#d40000;fill-opacity:1;stroke:none;display:inline"
id="SystemConfiguration-Critical"
width="13.310432"
height="10.308098"
x="34.512287"
y="38.309322"
ry="1"
inkscape:label="#rect4550-8-1-4-21-1" />
</g>
<g
inkscape:groupmode="layer"
id="g5441"
inkscape:label="BootFault-Critical"
style="display:inline">
<rect
style="fill:#d40000;fill-opacity:1;stroke:none;display:inline"
id="BootFault-Critical"
width="13.310432"
height="10.308098"
x="49.262897"
y="38.309322"
ry="1" />
</g>
<g
inkscape:groupmode="layer"
id="g5445"
inkscape:label="Battery-Critical"
style="display:inline">
<rect
style="fill:#d40000;fill-opacity:1;stroke:none;display:inline"
id="Battery-Critical"
width="15.447426"
height="10.265867"
x="60.093647"
y="52.326412"
ry="1"
inkscape:label="#rect4550-8-1-4-21-2-9-8" />
</g>
<g
inkscape:groupmode="layer"
id="g5448"
inkscape:label="Telemetry-Critical"
style="display:inline">
<rect
style="fill:#d40000;fill-opacity:1;stroke:none;display:inline"
id="Telemetry-Critical"
width="18.966711"
height="10.202584"
x="34.470295"
y="52.358059"
ry="1"
inkscape:label="#rect4550-8-1-4-21-5" />
</g>
<g
inkscape:groupmode="layer"
id="g5451"
inkscape:label="FlightTime-Critical"
style="display:inline">
<rect
style="fill:#d40000;fill-opacity:1;stroke:none;display:inline"
id="FlightTime-Critical"
width="15.447426"
height="10.265867"
x="76.795616"
y="52.326412"
ry="1"
inkscape:label="#rect4550-8-1-4-21-2-9-8" />
</g>
<g
inkscape:groupmode="layer"
id="g5454"
inkscape:label="I2C-Critical"
style="display:inline">
<rect
style="fill:#d40000;fill-opacity:1;stroke:none;display:inline"
id="I2C-Critical"
width="10.470912"
height="8.5405388"
x="82.190269"
y="67.18853"
ry="1"
inkscape:label="#rect4550-8" />
</g>
<g
inkscape:groupmode="layer"
id="g5457"
inkscape:label="EventSystem-Critical"
style="display:inline">
<rect
style="fill:#d40000;fill-opacity:1;stroke:none;display:inline"
id="EventSystem-Critical"
width="10.470912"
height="8.5405388"
x="70.423416"
y="67.18853"
ry="1"
inkscape:label="#rect4550-8" />
</g>
<g
inkscape:groupmode="layer"
id="g5460"
inkscape:label="StackOverflow-Critical"
style="display:inline">
<rect
style="fill:#d40000;fill-opacity:1;stroke:none;display:inline"
id="StackOverflow-Critical"
width="10.470912"
height="8.5405388"
x="58.656513"
y="67.18853"
ry="1"
inkscape:label="#rect4550-8" />
</g>
<g
inkscape:groupmode="layer"
id="g5463"
inkscape:label="OutOfMemory-Critical"
style="display:inline">
<rect
style="fill:#d40000;fill-opacity:1;stroke:none;display:inline"
id="OutOfMemory-Critical"
width="10.470912"
height="8.5405388"
x="46.889668"
y="67.18853"
ry="1"
inkscape:label="#rect4550-8" />
</g>
<g
inkscape:groupmode="layer"
id="g5466"
inkscape:label="CPUOverload-Critical"
style="display:inline">
<rect
style="fill:#d40000;fill-opacity:1;stroke:none;display:inline"
id="CPUOverload-Critical"
width="10.470912"
height="8.5405388"
x="35.122761"
y="67.18853"
ry="1"
inkscape:label="#rect4550-8" />
</g>
<g
inkscape:groupmode="layer"
id="g5469"
inkscape:label="Receiver-Critical"
style="display:inline">
<rect
style="fill:#d40000;fill-opacity:1;stroke:none;display:inline"
id="Receiver-Critical"
width="18.940025"
height="10.213441"
x="7.6267047"
y="38.417793"
ry="1.1877477"
inkscape:label="#rect4550"
rx="1.2082177" />
</g>
<g
inkscape:groupmode="layer"
id="g5472"
inkscape:label="Actuator-Critical"
style="display:none">
<rect
style="fill:#d40000;fill-opacity:1;stroke:none;display:inline"
id="Actuator-Critical"
width="18.874826"
height="10.081664"
x="7.663065"
y="52.603611"
ry="0.77868479"
inkscape:label="#rect4550"
rx="0.79499185" />
</g>
<g
inkscape:groupmode="layer"
id="layer5"
inkscape:label="GPS-Error"
style="display:inline">
<g
id="GPS-Error"
inkscape:label="#g3406"
transform="matrix(1.0377771,0,0,1,-0.27728602,0)">
<path
inkscape:connector-curvature="0"
id="path6233-9-9"
d="M 7.9615204,18.056455 26.210275,26.874464"
style="fill:#ff0000;stroke:#ff0000;stroke-width:1.19737208;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
<path
inkscape:connector-curvature="0"
id="path6233-9-9-4"
d="M 7.9364397,26.848957 26.252147,18.055286"
style="fill:#ff0000;stroke:#ff0000;stroke-width:1.19791019;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
</g>
</g>
<g
inkscape:groupmode="layer"
id="layer39"
inkscape:label="PathPlan-Error"
style="display:inline">
<g
id="PathPlan-Error"
inkscape:label="#g3394">
<path
inkscape:connector-curvature="0"
id="path6233-9-9-34"
d="M 73.398615,3.9044559 91.633186,12.691532"
style="fill:#ff0000;stroke:#ff0000;stroke-width:1.19480562;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
<path
inkscape:connector-curvature="0"
id="path6233-9-9-4-11"
d="M 73.388721,12.684336 91.693369,3.968722"
style="fill:#ff0000;stroke:#ff0000;stroke-width:1.19222152;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
</g>
</g>
<g
inkscape:groupmode="layer"
id="layer38"
inkscape:label="Guidance-Error"
style="display:inline">
<g
id="Guidance-Error"
inkscape:label="#g3390">
<path
inkscape:connector-curvature="0"
id="path6233-9-9-3"
d="M 51.597094,3.9170519 69.869527,12.712435"
style="fill:#ff0000;stroke:#ff0000;stroke-width:1.19661069;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
<path
inkscape:connector-curvature="0"
id="path6233-9-9-4-1"
d="M 51.571412,12.7076 69.859775,3.9449701"
style="fill:#ff0000;stroke:#ff0000;stroke-width:1.19490099;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
</g>
</g>
<g
inkscape:groupmode="layer"
id="layer37"
inkscape:label="Stabilization-Error"
style="display:inline">
<g
id="Stabilization-Error"
inkscape:label="#g3386">
<path
inkscape:connector-curvature="0"
id="path6233-9-9-7"
d="M 29.767185,3.9554513 48.050511,12.741033"
style="fill:#ff0000;stroke:#ff0000;stroke-width:1.19630003;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
<path
inkscape:connector-curvature="0"
id="path6233-9-9-4-95"
d="M 29.774605,12.683025 48.059882,3.919784"
style="fill:#ff0000;stroke:#ff0000;stroke-width:1.19484198;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
</g>
</g>
<g
inkscape:groupmode="layer"
id="layer3"
inkscape:label="Airspeed-Error"
style="display:inline">
<g
id="Airspeed-Error"
inkscape:label="#g3398"
transform="matrix(1.0309004,0,0,1,-1.5754528,0)">
<path
inkscape:connector-curvature="0"
id="path6233-9-9-79"
d="m 51.59088,18.071902 18.268111,8.770366"
style="fill:#ff0000;stroke:#ff0000;stroke-width:1.19476616;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
<path
inkscape:connector-curvature="0"
id="path6233-9-9-4-3"
d="M 51.580734,26.818576 69.902677,18.119165"
style="fill:#ff0000;stroke:#ff0000;stroke-width:1.19167542;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
</g>
</g>
<g
inkscape:groupmode="layer"
id="layer2"
inkscape:label="Sensors-Error"
style="display:inline">
<g
id="Sensors-Error"
inkscape:label="#g3402">
<path
inkscape:connector-curvature="0"
id="path6233-9-9-86"
d="m 29.801735,18.056972 18.247723,8.833725"
style="fill:#ff0000;stroke:#ff0000;stroke-width:1.19840479;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
<path
inkscape:connector-curvature="0"
id="path6233-9-9-4-5"
d="M 29.739026,26.85257 48.02846,18.152169"
style="fill:#ff0000;stroke:#ff0000;stroke-width:1.19068551;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
</g>
</g>
<g
inkscape:groupmode="layer"
id="layer33"
inkscape:label="Telemetry-Error"
style="display:inline">
<g
id="Telemetry-Error"
inkscape:label="#g3422"
transform="matrix(1.0343732,0,0,1,13.305779,0)">
<path
inkscape:connector-curvature="0"
id="path6233-9-9-86-4"
d="M 20.794895,53.039633 39.08945,61.825066"
style="fill:#ff0000;stroke:#ff0000;stroke-width:1.1966573;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
<path
inkscape:connector-curvature="0"
id="path6233-9-9-4-5-4"
d="M 20.83573,61.847333 39.066764,53.07372"
style="fill:#ff0000;stroke:#ff0000;stroke-width:1.19377422;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
</g>
</g>
<g
inkscape:groupmode="layer"
id="layer35"
inkscape:label="Receiver-Error"
style="display:inline">
<g
style="display:inline"
id="Receiver-Error"
inkscape:label="#g3406"
transform="matrix(1.0487144,0,0,1,-0.57430778,21.097426)">
<path
inkscape:connector-curvature="0"
id="path6233-9-9-2"
d="M 7.9615204,18.056455 26.210275,26.874464"
style="fill:#ff0000;stroke:#ff0000;stroke-width:1.19737208;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
<path
inkscape:connector-curvature="0"
id="path6233-9-9-4-7"
d="M 7.9364397,26.848957 26.252147,18.055286"
style="fill:#ff0000;stroke:#ff0000;stroke-width:1.19791019;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
</g>
</g>
<g
inkscape:groupmode="layer"
id="layer34"
inkscape:label="Actuator-Error"
style="display:inline">
<g
style="display:inline"
id="Actuator-Error"
inkscape:label="#g3406"
transform="matrix(1.0377771,0,0,1,-0.32069392,35.147296)">
<path
inkscape:connector-curvature="0"
id="path6233-9-9-1"
d="M 7.9615204,18.056455 26.210275,26.874464"
style="fill:#ff0000;stroke:#ff0000;stroke-width:1.19737208;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
<path
inkscape:connector-curvature="0"
id="path6233-9-9-4-4"
d="M 7.9364397,26.848957 26.252147,18.055286"
style="fill:#ff0000;stroke:#ff0000;stroke-width:1.19791019;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
</g>
</g>
<g
inkscape:groupmode="layer"
id="layer32"
inkscape:label="Battery-Error"
style="display:inline">
<g
id="Battery-Error"
style="stroke:#cf0e0e;stroke-width:2;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
inkscape:label="#g4026"
transform="translate(-1.9500095,9.5134715)">
inkscape:label="#g3426"
transform="translate(14,0)">
<path
inkscape:connector-curvature="0"
id="path4708"
d="M 3.9588091,1.7664579 22.097352,10.043968"
style="fill:none;stroke:#cf0e0e;stroke-width:2;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
id="path6233-9-9-86-0"
d="m 46.502131,52.910887 14.610607,9.14342"
style="fill:#ff0000;stroke:#ff0000;stroke-width:1.09097731;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
<path
inkscape:connector-curvature="0"
id="path4710"
d="M 4.2467224,10.043968 22.025374,1.8384362"
style="fill:none;stroke:#cf0e0e;stroke-width:2;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
id="path6233-9-9-4-5-6"
d="M 46.442675,61.953487 61.145921,52.934252"
style="fill:#ff0000;stroke:#ff0000;stroke-width:1.08697307;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
</g>
</g>
<g
style="display:none"
inkscape:label="Stabilization-OK"
id="layer37"
inkscape:groupmode="layer">
<rect
style="fill:#04b629;fill-opacity:1;stroke:#ffffff;stroke-width:0.53149605;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
id="Stabilization-OK"
width="18.153212"
height="8.1216154"
x="37.998051"
y="51.277248"
inkscape:label="#rect8365" />
</g>
inkscape:groupmode="layer"
id="layer31"
inkscape:label="FlightTime-Error"
style="display:inline">
<g
style="display:none"
inkscape:label="Stabilization-Warning"
id="layer38"
inkscape:groupmode="layer">
<rect
inkscape:label="#rect3132"
y="51.261425"
x="38.015614"
height="8.2846708"
width="18.023544"
id="Stabilization-Warning"
style="fill:#f1b907;fill-opacity:1;stroke:#ffffff;stroke-width:0.53149605;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
</g>
<g
style="display:none"
inkscape:label="Stabilization-Error"
id="layer39"
inkscape:groupmode="layer">
<g
inkscape:label="#g3114"
transform="translate(34,49.56813)"
id="Stabilization-Error"
style="stroke:#cf0e0e;stroke-width:2;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline">
id="FlightTime-Error"
inkscape:label="#g3430"
transform="translate(14,0)">
<path
inkscape:connector-curvature="0"
id="path3116"
d="M 3.9588091,1.7664579 22.097352,10.043968"
style="fill:none;stroke:#cf0e0e;stroke-width:2;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
id="path6233-9-9-86-0-3"
d="m 63.233236,52.875846 14.63044,9.079506"
style="fill:#ff0000;stroke:#ff0000;stroke-width:1.08789504;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
<path
inkscape:connector-curvature="0"
id="path3118"
d="M 4.2467224,10.043968 22.025374,1.8384362"
style="fill:none;stroke:#cf0e0e;stroke-width:2;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
id="path6233-9-9-4-5-6-7"
d="m 63.192544,61.969763 14.647987,-9.06903"
style="fill:#ff0000;stroke:#ff0000;stroke-width:1.08791935;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
</g>
</g>
<g
style="display:none"
inkscape:label="Stabilization-Critical"
id="layer40"
inkscape:groupmode="layer">
<rect
inkscape:label="#rect3108"
style="fill:#cf0e0e;fill-opacity:1;stroke:#f9f9f9;stroke-width:0.53149605;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
id="Stabilization-Critical"
width="18.023544"
height="8.2846708"
x="38.134846"
y="51.101501" />
</g>
<g
inkscape:groupmode="layer"
id="g3357"
inkscape:label="Attitude-OK"
style="display:none">
<rect
style="fill:#04b629;fill-opacity:1;stroke:#ffffff;stroke-width:0.53149605;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
id="Attitude-OK"
width="18.153212"
height="8.1216154"
x="58.539021"
y="31.277248"
inkscape:label="#rect8374" />
</g>
id="layer30"
inkscape:label="SystemConfiguration-Error"
style="display:inline">
<g
inkscape:groupmode="layer"
id="g3361"
inkscape:label="Attitude-Warning"
style="display:none">
<rect
y="31.277248"
x="58.539021"
height="8.1216154"
width="18.153212"
id="Attitude-Warning"
style="fill:#f1b907;fill-opacity:1;stroke:#ffffff;stroke-width:0.53149605;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
inkscape:label="#rect4073" />
</g>
<g
inkscape:groupmode="layer"
id="g3365"
inkscape:label="Attitude-Error"
style="display:none">
<g
style="stroke:#cf0e0e;stroke-width:2;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
id="Attitude-Error"
transform="translate(20.488022,-1.913356)"
inkscape:label="#g4084">
id="SystemConfiguration-Error"
inkscape:label="#g3414"
transform="translate(14,0)">
<path
style="fill:none;stroke:#cf0e0e;stroke-width:2;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
d="M 38.076545,33.292974 56.14311,41.28257"
id="path3369"
inkscape:connector-curvature="0" />
inkscape:connector-curvature="0"
id="path6233-9-9-86-6"
d="m 20.93643,38.821072 12.493301,9.22163"
style="fill:#ff0000;stroke:#ff0000;stroke-width:1.01262045;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
<path
style="fill:none;stroke:#cf0e0e;stroke-width:2;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
d="m 38.220502,41.354548 17.85063,-8.061574"
id="path3371"
inkscape:label="#path4088-8"
inkscape:connector-curvature="0" />
inkscape:connector-curvature="0"
id="path6233-9-9-4-5-1"
d="M 20.937064,48.026792 33.498002,38.872801"
style="fill:#ff0000;stroke:#ff0000;stroke-width:1.01214695;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
</g>
</g>
<g
inkscape:groupmode="layer"
id="g3373"
inkscape:label="Attitude-Critical"
style="display:none">
<rect
style="fill:#cf0e0e;fill-opacity:1;stroke:#ffffff;stroke-width:0.53149605;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
id="Attitude-Critical"
width="18.153212"
height="8.1216154"
x="58.539021"
y="31.277248"
inkscape:label="#rect4080" />
</g>
<g
style="display:none"
inkscape:label="BootFault-OK"
id="g4794"
inkscape:groupmode="layer">
<rect
style="fill:#04b629;fill-opacity:1;stroke:#ffffff;stroke-width:0.53149605;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
id="BootFault-OK"
width="18.153212"
height="8.1216154"
x="17.567717"
y="31.277248"
inkscape:label="#rect4080" />
</g>
<g
inkscape:groupmode="layer"
id="g3546"
inkscape:label="BootFault-Warning"
style="display:none">
<rect
inkscape:label="#rect4080"
y="31.277248"
x="17.567717"
height="8.1216154"
width="18.153212"
id="BootFault-Warning"
style="fill:#f1b907;fill-opacity:1;stroke:#ffffff;stroke-width:0.53149605;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
</g>
<g
style="display:none"
id="layer29"
inkscape:label="BootFault-Error"
id="g3550"
inkscape:groupmode="layer">
<rect
style="fill:#cf0e0e;fill-opacity:1;stroke:#ffffff;stroke-width:0.53149605;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
style="display:inline">
<g
id="BootFault-Error"
width="18.153212"
height="8.1216154"
x="17.567717"
y="31.277248"
inkscape:label="#rect4080" />
</g>
<g
inkscape:groupmode="layer"
id="g3554"
inkscape:label="BootFault-Critical"
style="display:none">
<rect
inkscape:label="#rect4080"
y="31.277248"
x="17.567717"
height="8.1216154"
width="18.153212"
id="BootFault-Critical"
style="fill:#cf0e0e;fill-opacity:1;stroke:#ffffff;stroke-width:0.53149605;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
</g>
<g
inkscape:groupmode="layer"
id="g3377"
inkscape:label="Guidance-OK"
style="display:none">
<rect
inkscape:label="#rect8365"
y="31.277248"
x="37.998051"
height="8.1216154"
width="18.153212"
id="Guidance-OK"
style="fill:#04b629;fill-opacity:1;stroke:#ffffff;stroke-width:0.53149605;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
</g>
<g
inkscape:groupmode="layer"
id="g3381"
inkscape:label="Guidance-Warning"
style="display:none">
<rect
style="fill:#f1b907;fill-opacity:1;stroke:#ffffff;stroke-width:0.53149605;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
id="Guidance-Warning"
width="18.023544"
height="8.2846708"
x="38.015614"
y="31.261425"
inkscape:label="#rect3132" />
</g>
<g
inkscape:groupmode="layer"
id="g3385"
inkscape:label="Guidance-Error"
style="display:none">
<g
style="stroke:#cf0e0e;stroke-width:2;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
id="Guidance-Error"
transform="translate(34,29.56813)"
inkscape:label="#g3114">
inkscape:label="#g3418"
transform="translate(14,0)">
<path
style="fill:none;stroke:#cf0e0e;stroke-width:2;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
d="M 3.9588091,1.7664579 22.097352,10.043968"
id="path3389"
inkscape:connector-curvature="0" />
inkscape:connector-curvature="0"
id="path6233-9-9-86-6-8"
d="m 35.705761,38.803039 12.45607,9.277316"
style="fill:#ff0000;stroke:#ff0000;stroke-width:1.01467943;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
<path
style="fill:none;stroke:#cf0e0e;stroke-width:2;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
d="M 4.2467224,10.043968 22.025374,1.8384362"
id="path3391"
inkscape:connector-curvature="0" />
inkscape:connector-curvature="0"
id="path6233-9-9-4-5-1-9"
d="M 35.66424,48.062824 48.169858,38.865363"
style="fill:#ff0000;stroke:#ff0000;stroke-width:1.01231074;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
</g>
</g>
<g
inkscape:groupmode="layer"
id="g3393"
inkscape:label="Guidance-Critical"
style="display:none">
<rect
y="31.101501"
x="38.134846"
height="8.2846708"
width="18.023544"
id="Guidance-Critical"
style="fill:#cf0e0e;fill-opacity:1;stroke:#f9f9f9;stroke-width:0.53149605;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
inkscape:label="#rect3108" />
id="layer24"
inkscape:label="Attitude-Error"
style="display:inline">
<g
id="Attitude-Error"
inkscape:label="#g3382"
transform="matrix(1.0376867,0,0,1,-0.27616141,0)">
<path
inkscape:connector-curvature="0"
id="path6233-9-9-8"
d="M 7.9267385,3.9562181 26.225281,12.757016"
style="fill:#ff0000;stroke:#ff0000;stroke-width:1.19783366;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
<path
inkscape:connector-curvature="0"
id="path6233-9-9-4-9"
d="M 7.9328239,12.666843 26.286235,3.9527152"
style="fill:#ff0000;stroke:#ff0000;stroke-width:1.19370687;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
</g>
</g>
<g
inkscape:groupmode="layer"
id="g3109"
inkscape:label="OutOfMemory-Error"
style="display:inline">
<g
id="OutOfMemory-Error"
inkscape:label="#g3442"
transform="translate(14,0)">
<path
inkscape:connector-curvature="0"
id="path6233"
d="M 33.20487,75.243494 43.009818,67.67709"
style="fill:#ff0000;stroke:#ff0000;stroke-width:0.80505109;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
<path
inkscape:connector-curvature="0"
id="path6233-9"
d="m 33.214298,67.65316 9.826498,7.608655"
style="fill:#ff0000;stroke:#ff0000;stroke-width:0.81616998;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
</g>
</g>
<g
inkscape:groupmode="layer"
id="layer28"
inkscape:label="I2C-Error"
style="display:inline">
<g
id="I2C-Error"
inkscape:label="#g3454">
<path
inkscape:connector-curvature="0"
id="path6233-09"
d="m 68.473832,75.266428 9.874503,-7.54121"
style="fill:#ff0000;stroke:#ff0000;stroke-width:0.80655557;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
<path
inkscape:connector-curvature="0"
id="path6233-9-0"
d="m 68.55267,67.640417 9.780922,7.610454"
style="fill:#ff0000;stroke:#ff0000;stroke-width:0.81437129;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
</g>
</g>
<g
inkscape:groupmode="layer"
id="layer27"
inkscape:label="EventSystem-Error"
style="display:inline">
<g
id="EventSystem-Error"
inkscape:label="#g3450"
transform="translate(14,0)">
<path
inkscape:connector-curvature="0"
id="path6233-8"
d="m 56.728611,75.196387 9.852857,-7.519565"
style="fill:#ff0000;stroke:#ff0000;stroke-width:0.80451399;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
<path
inkscape:connector-curvature="0"
id="path6233-9-6"
d="m 56.761123,67.664132 9.82824,7.574867"
style="fill:#ff0000;stroke:#ff0000;stroke-width:0.81442791;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
</g>
</g>
<g
inkscape:groupmode="layer"
id="layer26"
inkscape:label="StackOverflow-Error"
style="display:inline">
<g
id="StackOverflow-Error"
inkscape:label="#g3446"
transform="translate(14,0)">
<path
inkscape:connector-curvature="0"
id="path6233-0"
d="m 45.020244,75.290833 9.74566,-7.613709"
style="fill:#ff0000;stroke:#ff0000;stroke-width:0.80511868;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
<path
inkscape:connector-curvature="0"
id="path6233-9-2"
d="m 45.015735,67.662945 9.78324,7.565398"
style="fill:#ff0000;stroke:#ff0000;stroke-width:0.81205326;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
</g>
</g>
<g
inkscape:groupmode="layer"
id="layer25"
inkscape:label="CPUOverload-Error"
style="display:inline">
<g
id="CPUOverload-Error"
inkscape:label="#g3438"
transform="translate(14,0)">
<path
inkscape:connector-curvature="0"
id="path6233-2"
d="m 21.425298,75.227504 9.844871,-7.557269"
style="fill:#ff0000;stroke:#ff0000;stroke-width:0.8062014;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
<path
inkscape:connector-curvature="0"
id="path6233-9-8"
d="M 21.451681,67.664449 31.2556,75.243937"
style="fill:#ff0000;stroke:#ff0000;stroke-width:0.8136676;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
</g>
</g>
<g
style="display:inline"
inkscape:label="Foreground"
id="foreground"
inkscape:groupmode="layer">
<g
id="text4522-4"
style="font-size:40px;font-style:normal;font-weight:normal;fill:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Bitstream Vera Sans"
transform="translate(-2.3409014,-0.20358251)">
<path
inkscape:connector-curvature="0"
id="path3980"
style="font-size:4px;fill:#ffffff"
d="m 7.6886106,4.8015099 0,1.0957031 0.4960937,0 C 8.3682966,5.8972145 8.5102235,5.8496885 8.6104856,5.7546349 8.7107442,5.6595845 8.7608743,5.524168 8.7608762,5.3483849 8.7608743,5.1739079 8.7107442,5.0391424 8.6104856,4.944088 8.5102235,4.8490384 8.3682966,4.8015124 8.1847043,4.8015099 l -0.4960937,0 m -0.3945313,-0.3242188 0.890625,0 c 0.3268213,2.9e-6 0.5735659,0.074222 0.7402344,0.2226563 C 9.0929052,4.8470853 9.1768895,5.0632309 9.1768918,5.3483849 9.1768895,5.636147 9.0929052,5.8535947 8.9249387,6.0007286 8.7582702,6.1478653 8.5115256,6.2214329 8.1847043,6.2214317 l -0.4960937,0 0,1.171875 -0.3945313,0 0,-2.9160156" />
<path
inkscape:connector-curvature="0"
id="path3982"
style="font-size:4px;fill:#ffffff"
d="m 10.399548,5.4577599 c -0.192709,1.9e-6 -0.345053,0.075523 -0.4570312,0.2265625 -0.1119798,0.1497411 -0.1679693,0.3554701 -0.1679687,0.6171875 -6e-7,0.2617195 0.055338,0.4680995 0.1660156,0.6191406 0.1119783,0.1497399 0.2649733,0.2246096 0.4589843,0.2246094 0.191405,2e-7 0.343097,-0.075521 0.455078,-0.2265625 0.111978,-0.1510411 0.167967,-0.35677 0.167969,-0.6171875 -2e-6,-0.2591133 -0.05599,-0.4641912 -0.167969,-0.6152344 C 10.742645,5.5339336 10.590953,5.4577618 10.399548,5.4577599 m 0,-0.3046875 c 0.312499,2.2e-6 0.557941,0.1015646 0.736328,0.3046875 0.178383,0.2031267 0.267576,0.4843764 0.267578,0.84375 -2e-6,0.3580736 -0.0892,0.6393233 -0.267578,0.84375 -0.178387,0.203125 -0.423829,0.3046874 -0.736328,0.3046875 -0.313803,-1e-7 -0.5598964,-0.1015625 -0.7382812,-0.3046875 -0.1770836,-0.2044267 -0.2656252,-0.4856764 -0.265625,-0.84375 -2e-7,-0.3593736 0.088541,-0.6406233 0.265625,-0.84375 C 9.8396516,5.254637 10.085745,5.1530746 10.399548,5.1530724" />
<path
inkscape:connector-curvature="0"
id="path3984"
style="font-size:4px;fill:#ffffff"
d="m 11.78822,5.2058067 0.359375,0 0.449219,1.7070313 0.447265,-1.7070313 0.423828,0 0.449219,1.7070313 0.447266,-1.7070313 0.359375,0 -0.572266,2.1875 -0.423828,0 -0.470703,-1.7929687 -0.472656,1.7929687 -0.423828,0 -0.572266,-2.1875" />
<path
inkscape:connector-curvature="0"
id="path3986"
style="font-size:4px;fill:#ffffff"
d="m 17.141736,6.209713 0,0.1757812 -1.652344,0 c 0.01562,0.2473966 0.08984,0.4361985 0.222656,0.5664063 0.134114,0.1289065 0.320311,0.1933596 0.558594,0.1933594 0.138019,2e-7 0.271483,-0.016927 0.40039,-0.050781 0.130207,-0.033854 0.259113,-0.084635 0.386719,-0.1523437 l 0,0.3398437 c -0.128908,0.054688 -0.261069,0.096354 -0.396484,0.125 -0.135418,0.028646 -0.272788,0.042969 -0.41211,0.042969 -0.348959,-10e-8 -0.625651,-0.1015625 -0.830078,-0.3046875 -0.203125,-0.2031246 -0.304687,-0.4778639 -0.304687,-0.8242188 0,-0.3580715 0.09635,-0.6419254 0.289062,-0.8515625 0.19401,-0.2109354 0.455077,-0.316404 0.783203,-0.3164062 0.29427,2.2e-6 0.526691,0.095054 0.697266,0.2851562 0.171873,0.1888039 0.25781,0.4459651 0.257813,0.7714844 M 16.782361,6.1042442 c -0.0026,-0.1966131 -0.05795,-0.353514 -0.166016,-0.4707031 -0.106773,-0.1171856 -0.248699,-0.1757793 -0.425781,-0.1757812 -0.200522,1.9e-6 -0.361329,0.056642 -0.482422,0.1699218 -0.119793,0.1132829 -0.188803,0.272788 -0.207031,0.4785157 l 1.28125,-0.00195" />
<path
inkscape:connector-curvature="0"
id="path3988"
style="font-size:4px;fill:#ffffff"
d="m 18.999157,5.5417442 c -0.04037,-0.023436 -0.08464,-0.040363 -0.132812,-0.050781 -0.04688,-0.011717 -0.09896,-0.017576 -0.15625,-0.017578 -0.203126,1.9e-6 -0.359376,0.066408 -0.46875,0.1992187 -0.108074,0.131512 -0.16211,0.3209649 -0.162109,0.5683594 l 0,1.1523437 -0.361329,0 0,-2.1875 0.361329,0 0,0.3398438 c 0.07552,-0.1328105 0.173827,-0.2311177 0.294921,-0.2949219 0.121093,-0.065102 0.268228,-0.097654 0.441407,-0.097656 0.02474,2.2e-6 0.05208,0.00196 0.08203,0.00586 0.02995,0.00261 0.06315,0.00716 0.09961,0.013672 l 0.002,0.3691406" />
</g>
<g
id="I2C-Text"
style="font-size:40px;font-style:normal;font-weight:normal;fill:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Bitstream Vera Sans"
transform="translate(2.8817153,-0.30233889)">
<path
inkscape:connector-curvature="0"
id="path3924"
style="font-size:4px;fill:#ffffff"
d="m 78.026871,4.3897209 0.394531,0 0,2.9160156 -0.394531,0 0,-2.9160156" />
<path
inkscape:connector-curvature="0"
id="path3926"
style="font-size:4px;fill:#ffffff"
d="m 79.581558,6.9737053 1.376953,0 0,0.3320312 -1.851562,0 0,-0.3320312 C 79.256688,6.8187579 79.460464,6.6110758 79.718277,6.3506584 79.97739,6.0889409 80.140151,5.9203213 80.206558,5.844799 80.332859,5.7028736 80.420749,5.583082 80.47023,5.485424 80.52101,5.386468 80.5464,5.2894625 80.5464,5.1944084 c -2e-6,-0.1549456 -0.05469,-0.2812476 -0.164063,-0.3789062 -0.108074,-0.097654 -0.24935,-0.1464818 -0.423828,-0.1464844 -0.123699,2.6e-6 -0.254558,0.021487 -0.392578,0.064453 -0.136719,0.042971 -0.283203,0.1080754 -0.439453,0.1953125 l 0,-0.3984375 c 0.158854,-0.063799 0.307291,-0.1119763 0.445313,-0.1445312 0.13802,-0.032549 0.264321,-0.048825 0.378906,-0.048828 0.302082,3e-6 0.542967,0.075524 0.722656,0.2265625 0.179686,0.1510443 0.269529,0.352867 0.269531,0.6054688 -2e-6,0.1197937 -0.02279,0.2337259 -0.06836,0.3417969 -0.04427,0.1067725 -0.125653,0.2330744 -0.244141,0.3789062 -0.03255,0.037762 -0.136069,0.1471367 -0.310547,0.328125 -0.17448,0.1796884 -0.420574,0.4316413 -0.738281,0.7558594" />
<path
inkscape:connector-curvature="0"
id="path3928"
style="font-size:4px;fill:#ffffff"
d="m 83.937027,4.6143303 0,0.4160156 C 83.804212,4.9066504 83.662285,4.8142026 83.511246,4.7530022 83.361504,4.6918069 83.201999,4.6612079 83.03273,4.6612053 c -0.333335,2.6e-6 -0.588543,0.1022161 -0.765625,0.3066406 -0.177084,0.2031272 -0.265626,0.4973977 -0.265625,0.8828125 -10e-7,0.3841157 0.08854,0.6783862 0.265625,0.8828125 0.177082,0.2031254 0.43229,0.3046878 0.765625,0.3046875 0.169269,3e-7 0.328774,-0.030599 0.478516,-0.091797 0.151039,-0.061198 0.292966,-0.1536453 0.425781,-0.2773437 l 0,0.4121094 c -0.138023,0.09375 -0.284508,0.1640625 -0.439453,0.2109375 -0.153648,0.046875 -0.316408,0.070312 -0.488281,0.070312 -0.441408,-1e-7 -0.789064,-0.1347656 -1.042969,-0.4042969 -0.253907,-0.2708327 -0.38086,-0.639973 -0.38086,-1.1074219 0,-0.4687481 0.126953,-0.8378883 0.38086,-1.1074219 0.253905,-0.2708305 0.601561,-0.406247 1.042969,-0.40625 0.174477,3e-6 0.338539,0.02344 0.492187,0.070312 0.154946,0.045576 0.300128,0.1145862 0.435547,0.2070313" />
</g>
<g
id="text4647-0-2-6"
style="font-size:40px;font-style:normal;font-weight:normal;text-align:center;text-anchor:middle;fill:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Bitstream Vera Sans"
transform="translate(2.9776741,0)">
<path
inkscape:connector-curvature="0"
id="path3905"
style="font-size:3px;fill:#ffffff"
d="m 73.102684,13.569345 1.850098,0 0,0.249024 -0.776368,0 0,1.937988 -0.297363,0 0,-1.937988 -0.776367,0 0,-0.249024" />
<path
inkscape:connector-curvature="0"
id="path3907"
style="font-size:3px;fill:#ffffff"
d="m 76.121727,14.868662 0,0.131836 -1.239258,0 c 0.01172,0.185547 0.06738,0.327149 0.166992,0.424805 0.100586,0.09668 0.240234,0.145019 0.418946,0.145019 0.103514,0 0.203612,-0.0127 0.300293,-0.03809 0.09765,-0.02539 0.194334,-0.06348 0.290039,-0.114258 l 0,0.254883 c -0.09668,0.04102 -0.195802,0.07227 -0.297364,0.09375 -0.101563,0.02148 -0.204591,0.03223 -0.309082,0.03223 -0.261719,0 -0.469238,-0.07617 -0.622558,-0.228516 -0.152344,-0.152343 -0.228516,-0.358398 -0.228516,-0.618164 0,-0.268554 0.07227,-0.481444 0.216797,-0.638672 0.145507,-0.158201 0.341308,-0.237303 0.587402,-0.237305 0.220702,2e-6 0.395019,0.07129 0.52295,0.213868 0.128904,0.141602 0.193357,0.334473 0.193359,0.578613 m -0.269531,-0.0791 c -0.002,-0.14746 -0.04346,-0.265135 -0.124512,-0.353027 -0.08008,-0.08789 -0.186525,-0.131835 -0.319336,-0.131836 -0.150391,10e-7 -0.270997,0.04248 -0.361816,0.127441 -0.08984,0.08496 -0.141602,0.204591 -0.155274,0.358887 l 0.960938,-0.0015" />
<path
inkscape:connector-curvature="0"
id="path3909"
style="font-size:3px;fill:#ffffff"
d="m 77.841454,14.430674 c 0.06738,-0.121093 0.147947,-0.210448 0.241699,-0.268067 0.09375,-0.05762 0.204099,-0.08642 0.331054,-0.08643 0.170897,2e-6 0.302732,0.06006 0.395508,0.180176 0.09277,0.119142 0.139158,0.289064 0.13916,0.509766 l 0,0.990234 -0.270996,0 0,-0.981445 c -2e-6,-0.157226 -0.02783,-0.273925 -0.0835,-0.350098 -0.05567,-0.07617 -0.140627,-0.114256 -0.254883,-0.114258 -0.13965,2e-6 -0.250001,0.04639 -0.331054,0.139161 -0.08106,0.09277 -0.121584,0.219239 -0.121582,0.379394 l 0,0.927246 -0.270996,0 0,-0.981445 c -2e-6,-0.158202 -0.02783,-0.274901 -0.0835,-0.350098 -0.05567,-0.07617 -0.141603,-0.114256 -0.257813,-0.114258 -0.137696,2e-6 -0.247071,0.04688 -0.328125,0.140625 -0.08105,0.09277 -0.121583,0.218751 -0.121582,0.37793 l 0,0.927246 -0.270996,0 0,-1.640625 0.270996,0 0,0.254883 c 0.06152,-0.100584 0.135253,-0.174803 0.221191,-0.222656 0.08594,-0.04785 0.187988,-0.07178 0.306153,-0.07178 0.119139,2e-6 0.220213,0.03027 0.303222,0.09082 0.08398,0.06055 0.145995,0.148439 0.186036,0.263672" />
<path
inkscape:connector-curvature="0"
id="path3911"
style="font-size:3px;fill:#ffffff"
d="m 79.74868,15.510263 0,0.870118 -0.270996,0 0,-2.264649 0.270996,0 0,0.249024 c 0.05664,-0.09765 0.127929,-0.169921 0.213867,-0.216797 0.08691,-0.04785 0.190429,-0.07178 0.310547,-0.07178 0.199218,2e-6 0.360839,0.0791 0.484863,0.237305 0.124999,0.158205 0.187499,0.366212 0.1875,0.624024 -1e-6,0.257813 -0.0625,0.46582 -0.1875,0.624023 -0.124024,0.158203 -0.285645,0.237305 -0.484863,0.237305 -0.120118,0 -0.223633,-0.02344 -0.310547,-0.07031 -0.08594,-0.04785 -0.157227,-0.120605 -0.213867,-0.218262 m 0.916992,-0.572753 c -10e-7,-0.198242 -0.04102,-0.353515 -0.123047,-0.465821 -0.08106,-0.11328 -0.192872,-0.16992 -0.335449,-0.169922 -0.142579,2e-6 -0.254883,0.05664 -0.336914,0.169922 -0.08105,0.112306 -0.121582,0.267579 -0.121582,0.465821 0,0.198242 0.04053,0.354004 0.121582,0.467285 0.08203,0.112305 0.194335,0.168457 0.336914,0.168457 0.142577,0 0.254393,-0.05615 0.335449,-0.168457 0.08203,-0.113281 0.123046,-0.269043 0.123047,-0.467285" />
<path
inkscape:connector-curvature="0"
id="path3913"
style="font-size:3px;fill:#ffffff"
d="m 81.871239,13.569345 0.249023,0 -0.761719,2.465333 -0.249023,0 0.761719,-2.465333" />
<path
inkscape:connector-curvature="0"
id="path3915"
style="font-size:3px;fill:#ffffff"
d="m 82.713524,14.711924 0,0.801269 0.474609,0 c 0.159179,0 0.276854,-0.03271 0.353028,-0.09814 0.07715,-0.06641 0.115721,-0.16748 0.115722,-0.303223 -10e-7,-0.136718 -0.03857,-0.237304 -0.115722,-0.301758 -0.07617,-0.06543 -0.193849,-0.09814 -0.353028,-0.09814 l -0.474609,0 m 0,-0.899414 0,0.659179 0.437988,0 c 0.14453,2e-6 0.251952,-0.02685 0.322266,-0.08057 0.07129,-0.05469 0.106932,-0.137694 0.106933,-0.249024 -10e-7,-0.110349 -0.03565,-0.192869 -0.106933,-0.247558 -0.07031,-0.05469 -0.177736,-0.08203 -0.322266,-0.08203 l -0.437988,0 m -0.295899,-0.243165 0.75586,0 c 0.225584,3e-6 0.399412,0.04688 0.521484,0.140625 0.122069,0.09375 0.183104,0.227053 0.183106,0.399903 -2e-6,0.13379 -0.03125,0.240236 -0.09375,0.319336 -0.0625,0.0791 -0.154299,0.128419 -0.275391,0.147949 0.145506,0.03125 0.258299,0.09668 0.338379,0.196289 0.08105,0.09863 0.12158,0.222169 0.121582,0.370606 -2e-6,0.195312 -0.06641,0.346191 -0.199219,0.452636 -0.132814,0.106446 -0.321778,0.159668 -0.566894,0.159668 l -0.785157,0 0,-2.187012" />
<path
inkscape:connector-curvature="0"
id="path3917"
style="font-size:3px;fill:#ffffff"
d="m 85.208153,14.93165 c -0.217774,1e-6 -0.368653,0.0249 -0.452637,0.07471 -0.08398,0.04981 -0.125977,0.134766 -0.125977,0.254883 0,0.0957 0.03125,0.171875 0.09375,0.228516 0.06348,0.05566 0.149414,0.0835 0.257813,0.0835 0.149413,0 0.269042,-0.05273 0.358887,-0.158203 0.09082,-0.106445 0.136229,-0.247558 0.13623,-0.42334 l 0,-0.06006 -0.268066,0 m 0.537597,-0.111328 0,0.936035 -0.269531,0 0,-0.249023 c -0.06152,0.09961 -0.138185,0.17334 -0.22998,0.221191 -0.0918,0.04687 -0.204103,0.07031 -0.336914,0.07031 -0.16797,0 -0.301759,-0.04687 -0.401368,-0.140625 -0.09863,-0.09473 -0.147949,-0.221191 -0.147949,-0.379395 0,-0.18457 0.06152,-0.32373 0.184571,-0.41748 0.124023,-0.09375 0.308593,-0.140624 0.55371,-0.140625 l 0.37793,0 0,-0.02637 c -10e-7,-0.124022 -0.04102,-0.219725 -0.123047,-0.287109 -0.08106,-0.06836 -0.195313,-0.102538 -0.342773,-0.102539 -0.09375,10e-7 -0.185059,0.01123 -0.273926,0.03369 -0.08887,0.02246 -0.174317,0.05615 -0.256348,0.101075 l 0,-0.249024 c 0.09863,-0.03808 0.194336,-0.0664 0.28711,-0.08496 0.09277,-0.01953 0.183105,-0.02929 0.270996,-0.0293 0.237303,2e-6 0.414549,0.06152 0.531738,0.184571 0.117186,0.123048 0.17578,0.309571 0.175781,0.55957" />
<path
inkscape:connector-curvature="0"
id="path3919"
style="font-size:3px;fill:#ffffff"
d="m 87.253075,14.367685 c -0.03027,-0.01758 -0.06348,-0.03027 -0.09961,-0.03809 -0.03516,-0.0088 -0.07422,-0.01318 -0.117187,-0.01318 -0.152345,1e-6 -0.269532,0.04981 -0.351563,0.149414 -0.08105,0.09863 -0.121582,0.240724 -0.121582,0.426269 l 0,0.864258 -0.270996,0 0,-1.640625 0.270996,0 0,0.254883 c 0.05664,-0.09961 0.130371,-0.173338 0.221192,-0.221191 0.09082,-0.04883 0.201171,-0.07324 0.331054,-0.07324 0.01855,2e-6 0.03906,0.0015 0.06152,0.0044 0.02246,0.002 0.04736,0.0054 0.07471,0.01025 l 0.0015,0.276855" />
<path
inkscape:connector-curvature="0"
id="path3921"
style="font-size:3px;fill:#ffffff"
d="m 88.110008,14.304697 c -0.144532,10e-7 -0.258789,0.05664 -0.342773,0.169922 -0.08398,0.112306 -0.125977,0.266602 -0.125977,0.462891 0,0.196289 0.0415,0.351074 0.124512,0.464355 0.08398,0.112305 0.19873,0.168457 0.344238,0.168457 0.143554,0 0.257323,-0.05664 0.341309,-0.169922 0.08398,-0.113281 0.125975,-0.267577 0.125976,-0.46289 -10e-7,-0.194335 -0.04199,-0.348144 -0.125976,-0.461426 -0.08399,-0.114257 -0.197755,-0.171386 -0.341309,-0.171387 m 0,-0.228516 c 0.234374,2e-6 0.418456,0.07617 0.552246,0.228516 0.133788,0.152345 0.200682,0.363282 0.200684,0.632813 -2e-6,0.268555 -0.0669,0.479492 -0.200684,0.632812 -0.13379,0.152344 -0.317872,0.228516 -0.552246,0.228516 -0.235352,0 -0.419922,-0.07617 -0.553711,-0.228516 -0.132812,-0.15332 -0.199219,-0.364257 -0.199218,-0.632812 -10e-7,-0.269531 0.06641,-0.480468 0.199218,-0.632813 0.133789,-0.152342 0.318359,-0.228514 0.553711,-0.228516" />
</g>
<g
id="text6268"
style="font-size:40px;font-style:normal;font-weight:normal;fill:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Bitstream Vera Sans">
<path
inkscape:connector-curvature="0"
id="path4194"
style="font-size:4px;fill:#ffffff"
d="m 25.05489,44.078304 0,0.416016 c -0.132815,-0.123696 -0.274742,-0.216143 -0.425782,-0.277344 -0.149741,-0.0612 -0.309246,-0.09179 -0.478515,-0.0918 -0.333335,3e-6 -0.588543,0.102216 -0.765625,0.306641 -0.177084,0.203127 -0.265626,0.497398 -0.265625,0.882812 -1e-6,0.384116 0.08854,0.678387 0.265625,0.882813 0.177082,0.203125 0.43229,0.304688 0.765625,0.304687 0.169269,1e-6 0.328774,-0.0306 0.478515,-0.0918 0.15104,-0.0612 0.292967,-0.153646 0.425782,-0.277344 l 0,0.412109 c -0.138024,0.09375 -0.284508,0.164063 -0.439453,0.210938 -0.153648,0.04687 -0.316409,0.07031 -0.488282,0.07031 -0.441407,0 -0.789063,-0.134765 -1.042968,-0.404297 -0.253907,-0.270832 -0.38086,-0.639973 -0.38086,-1.107422 0,-0.468748 0.126953,-0.837888 0.38086,-1.107421 0.253905,-0.270831 0.601561,-0.406247 1.042968,-0.40625 0.174478,3e-6 0.33854,0.02344 0.492188,0.07031 0.154945,0.04558 0.300128,0.114586 0.435547,0.207031" />
<path
inkscape:connector-curvature="0"
id="path4196"
style="font-size:4px;fill:#ffffff"
d="m 26.062702,44.177914 0,1.095703 0.496094,0 c 0.183592,10e-7 0.325519,-0.04753 0.425781,-0.142578 0.100259,-0.09505 0.150389,-0.230467 0.150391,-0.40625 -2e-6,-0.174477 -0.05013,-0.309243 -0.150391,-0.404297 -0.100262,-0.09505 -0.242189,-0.142576 -0.425781,-0.142578 l -0.496094,0 m -0.394531,-0.324219 0.890625,0 c 0.326821,3e-6 0.573566,0.07422 0.740234,0.222656 0.167967,0.147138 0.251951,0.363284 0.251953,0.648438 -2e-6,0.287762 -0.08399,0.50521 -0.251953,0.652343 -0.166668,0.147137 -0.413413,0.220705 -0.740234,0.220704 l -0.496094,0 0,1.171875 -0.394531,0 0,-2.916016" />
<path
inkscape:connector-curvature="0"
id="path4198"
style="font-size:4px;fill:#ffffff"
d="m 28.037312,43.853695 0.396484,0 0,1.771484 c -1e-6,0.312501 0.05664,0.537761 0.169922,0.675782 0.11328,0.136719 0.296874,0.205078 0.550781,0.205078 0.252603,0 0.435545,-0.06836 0.548828,-0.205078 0.113279,-0.138021 0.16992,-0.363281 0.169922,-0.675782 l 0,-1.771484 0.396484,0 0,1.820312 c -2e-6,0.380209 -0.0944,0.667319 -0.283203,0.861329 -0.187502,0.19401 -0.464845,0.291015 -0.832031,0.291015 -0.368491,0 -0.647136,-0.09701 -0.835937,-0.291015 -0.187501,-0.19401 -0.281251,-0.48112 -0.28125,-0.861329 l 0,-1.820312" />
</g>
<g
id="text6272"
style="font-size:40px;font-style:normal;font-weight:normal;fill:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Bitstream Vera Sans">
<path
inkscape:connector-curvature="0"
id="path4201"
style="font-size:4px;fill:#ffffff"
d="m 43.60281,44.008953 0,0.384766 c -0.149742,-0.07161 -0.291018,-0.124998 -0.423828,-0.160157 -0.132814,-0.03515 -0.261069,-0.05273 -0.384766,-0.05273 -0.214845,3e-6 -0.38086,0.04167 -0.498047,0.125 -0.115886,0.08334 -0.173829,0.201825 -0.173828,0.355469 -10e-7,0.128908 0.03841,0.226564 0.115235,0.292969 0.07812,0.06511 0.225259,0.11784 0.441406,0.158203 l 0.238281,0.04883 c 0.294269,0.05599 0.511066,0.154949 0.650391,0.296875 0.140622,0.140626 0.210935,0.329428 0.210937,0.566406 -2e-6,0.282553 -0.09505,0.496745 -0.285156,0.642578 -0.188804,0.145834 -0.466147,0.21875 -0.832031,0.21875 -0.138022,0 -0.285158,-0.01563 -0.441407,-0.04687 -0.154948,-0.03125 -0.315755,-0.07747 -0.482421,-0.138672 l 0,-0.40625 c 0.160155,0.08985 0.317056,0.157553 0.470703,0.203125 0.153645,0.04557 0.304686,0.06836 0.453125,0.06836 0.225259,0 0.399087,-0.04427 0.521484,-0.132813 0.122394,-0.08854 0.183592,-0.214843 0.183594,-0.378906 -2e-6,-0.143228 -0.04427,-0.255207 -0.132813,-0.335938 -0.08724,-0.08073 -0.231121,-0.141274 -0.43164,-0.18164 l -0.240235,-0.04687 c -0.294271,-0.05859 -0.507162,-0.150389 -0.638672,-0.275391 -0.13151,-0.124998 -0.197265,-0.298826 -0.197265,-0.521484 0,-0.25781 0.09049,-0.460935 0.271484,-0.609375 0.182291,-0.148435 0.432942,-0.222653 0.751953,-0.222656 0.136718,3e-6 0.27604,0.01237 0.417969,0.03711 0.141925,0.02474 0.287107,0.06185 0.435547,0.111328" />
<path
inkscape:connector-curvature="0"
id="path4203"
style="font-size:4px;fill:#ffffff"
d="m 44.733669,44.020672 0,0.621094 0.740235,0 0,0.279296 -0.740235,0 0,1.1875 c 0,0.178386 0.02409,0.29297 0.07227,0.34375 0.04948,0.05078 0.149087,0.07617 0.298828,0.07617 l 0.369141,0 0,0.300782 -0.369141,0 c -0.277345,0 -0.468751,-0.05143 -0.574219,-0.154297 C 44.425075,46.570802 44.372341,46.382 44.372341,46.108562 l 0,-1.1875 -0.263672,0 0,-0.279296 0.263672,0 0,-0.621094 0.361328,0" />
<path
inkscape:connector-curvature="0"
id="path4205"
style="font-size:4px;fill:#ffffff"
d="m 46.942654,45.729656 c -0.290366,1e-6 -0.491538,0.0332 -0.603516,0.09961 -0.11198,0.06641 -0.167969,0.179688 -0.167969,0.339843 0,0.127605 0.04167,0.229167 0.125,0.304688 0.08463,0.07422 0.199218,0.111328 0.34375,0.111328 0.199218,0 0.358723,-0.07031 0.478516,-0.210938 0.121092,-0.141926 0.181639,-0.330077 0.181641,-0.564453 l 0,-0.08008 -0.357422,0 m 0.716797,-0.148437 0,1.248047 -0.359375,0 0,-0.332032 c -0.08203,0.132813 -0.184247,0.23112 -0.306641,0.294922 -0.122397,0.0625 -0.272137,0.09375 -0.449219,0.09375 -0.223959,0 -0.402344,-0.0625 -0.535156,-0.1875 -0.131511,-0.126302 -0.197266,-0.294921 -0.197266,-0.505859 0,-0.246093 0.08203,-0.43164 0.246094,-0.556641 0.165364,-0.124998 0.411457,-0.187498 0.738281,-0.1875 l 0.503907,0 0,-0.03516 c -2e-6,-0.165363 -0.05469,-0.292967 -0.164063,-0.382813 -0.108074,-0.09114 -0.260418,-0.136716 -0.457031,-0.136718 -0.125001,2e-6 -0.246746,0.01498 -0.365235,0.04492 -0.11849,0.02995 -0.232422,0.07487 -0.341796,0.134765 l 0,-0.332031 c 0.131509,-0.05078 0.259113,-0.08854 0.382812,-0.113281 0.123697,-0.02604 0.24414,-0.03906 0.361328,-0.03906 0.316405,2e-6 0.552733,0.08203 0.708985,0.246094 0.156248,0.164064 0.234372,0.412762 0.234375,0.746094" />
<path
inkscape:connector-curvature="0"
id="path4207"
style="font-size:4px;fill:#ffffff"
d="m 49.975857,44.72575 0,0.335937 c -0.101565,-0.05599 -0.203778,-0.09765 -0.306641,-0.125 -0.101564,-0.02864 -0.204428,-0.04297 -0.308594,-0.04297 -0.233074,2e-6 -0.414063,0.07422 -0.542968,0.222656 -0.128907,0.147137 -0.19336,0.354168 -0.19336,0.621094 0,0.266928 0.06445,0.47461 0.19336,0.623047 0.128905,0.147135 0.309894,0.220703 0.542968,0.220703 0.104166,0 0.20703,-0.01367 0.308594,-0.04102 0.102863,-0.02864 0.205076,-0.07096 0.306641,-0.126953 l 0,0.332031 c -0.100262,0.04687 -0.204429,0.08203 -0.3125,0.105469 -0.106773,0.02344 -0.220705,0.03516 -0.341797,0.03516 -0.329428,0 -0.591147,-0.103515 -0.785156,-0.310547 -0.194011,-0.20703 -0.291016,-0.486327 -0.291016,-0.83789 0,-0.35677 0.09766,-0.637368 0.292969,-0.841797 0.196614,-0.204425 0.465494,-0.306639 0.80664,-0.306641 0.110676,2e-6 0.218749,0.01172 0.324219,0.03516 0.105467,0.02214 0.207681,0.05599 0.306641,0.101563" />
<path
inkscape:connector-curvature="0"
id="path4209"
style="font-size:4px;fill:#ffffff"
d="m 50.591091,43.790203 0.361328,0 0,1.794922 1.072266,-0.943359 0.458984,0 -1.160156,1.023437 1.208984,1.164063 -0.46875,0 -1.111328,-1.06836 0,1.06836 -0.361328,0 0,-3.039063" />
</g>
<g
id="Mem"
style="font-size:40px;font-style:normal;font-weight:normal;fill:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Bitstream Vera Sans">
<path
inkscape:connector-curvature="0"
id="path4212"
style="font-size:4px;fill:#ffffff"
d="m 59.734768,43.432796 0.587891,0 0.74414,1.984375 0.748047,-1.984375 0.587891,0 0,2.916016 -0.384766,0 0,-2.560547 -0.751953,2 -0.396484,0 -0.751954,-2 0,2.560547 -0.382812,0 0,-2.916016" />
<path
inkscape:connector-curvature="0"
id="path4214"
style="font-size:4px;fill:#ffffff"
d="m 65.043362,45.165218 0,0.175782 -1.652344,0 c 0.01562,0.247396 0.08984,0.436198 0.222656,0.566406 0.134114,0.128906 0.320312,0.193359 0.558594,0.193359 0.138019,0 0.271483,-0.01693 0.400391,-0.05078 0.130206,-0.03385 0.259112,-0.08463 0.386718,-0.152344 l 0,0.339844 c -0.128908,0.05469 -0.261069,0.09635 -0.396484,0.125 -0.135418,0.02865 -0.272788,0.04297 -0.412109,0.04297 -0.34896,0 -0.625652,-0.101563 -0.830079,-0.304688 -0.203125,-0.203124 -0.304687,-0.477864 -0.304687,-0.824219 0,-0.358071 0.09635,-0.641925 0.289062,-0.851562 0.19401,-0.210935 0.455078,-0.316404 0.783204,-0.316406 0.294269,2e-6 0.52669,0.09505 0.697265,0.285156 0.171873,0.188804 0.25781,0.445965 0.257813,0.771484 m -0.359375,-0.10547 c -0.0026,-0.196613 -0.05795,-0.353514 -0.166016,-0.470704 -0.106772,-0.117185 -0.248699,-0.175779 -0.425781,-0.175781 -0.200522,2e-6 -0.361329,0.05664 -0.482422,0.169922 -0.119792,0.113283 -0.188803,0.272788 -0.207031,0.478516 l 1.28125,-0.002" />
<path
inkscape:connector-curvature="0"
id="path4216"
style="font-size:4px;fill:#ffffff"
d="m 67.33633,44.581234 c 0.08984,-0.161456 0.197264,-0.280597 0.322266,-0.357422 0.124998,-0.07682 0.272133,-0.115232 0.441406,-0.115234 0.227862,2e-6 0.403643,0.08008 0.527344,0.240234 0.123694,0.158856 0.185543,0.385418 0.185547,0.679688 l 0,1.320312 -0.361328,0 0,-1.308594 c -3e-6,-0.209634 -0.03711,-0.365232 -0.111328,-0.466797 -0.07422,-0.10156 -0.187503,-0.152341 -0.339844,-0.152343 -0.186201,2e-6 -0.333336,0.06185 -0.441406,0.185547 -0.108075,0.123699 -0.162112,0.292319 -0.16211,0.505859 l 0,1.236328 -0.361328,0 0,-1.308594 c -2e-6,-0.210936 -0.03711,-0.366534 -0.111328,-0.466797 -0.07422,-0.10156 -0.188804,-0.152341 -0.34375,-0.152343 -0.183595,2e-6 -0.329428,0.0625 -0.4375,0.1875 -0.108074,0.123699 -0.16211,0.291668 -0.162109,0.503906 l 0,1.236328 -0.361328,0 0,-2.1875 0.361328,0 0,0.339844 c 0.08203,-0.134113 0.180337,-0.233071 0.294922,-0.296875 0.114582,-0.0638 0.250649,-0.0957 0.408203,-0.0957 0.158852,2e-6 0.293618,0.04037 0.404297,0.121093 0.111977,0.08073 0.194659,0.197919 0.248046,0.351563" />
<path
inkscape:connector-curvature="0"
id="path4218"
style="font-size:4px;fill:#ffffff"
d="m 70.379299,44.413265 c -0.192709,2e-6 -0.345053,0.07552 -0.457031,0.226563 -0.11198,0.149741 -0.167969,0.35547 -0.167969,0.617187 0,0.26172 0.05534,0.4681 0.166016,0.619141 0.111978,0.14974 0.264973,0.224609 0.458984,0.224609 0.191405,0 0.343098,-0.07552 0.455078,-0.226562 0.111978,-0.151041 0.167967,-0.35677 0.167969,-0.617188 -2e-6,-0.259113 -0.05599,-0.464191 -0.167969,-0.615234 -0.11198,-0.152342 -0.263673,-0.228514 -0.455078,-0.228516 m 0,-0.304687 c 0.312499,2e-6 0.557941,0.101564 0.736328,0.304687 0.178384,0.203127 0.267576,0.484377 0.267578,0.84375 -2e-6,0.358074 -0.08919,0.639324 -0.267578,0.84375 -0.178387,0.203125 -0.423829,0.304688 -0.736328,0.304688 -0.313803,0 -0.559896,-0.101563 -0.738281,-0.304688 -0.177084,-0.204426 -0.265625,-0.485676 -0.265625,-0.84375 0,-0.359373 0.08854,-0.640623 0.265625,-0.84375 0.178385,-0.203123 0.424478,-0.304685 0.738281,-0.304687" />
<path
inkscape:connector-curvature="0"
id="path4220"
style="font-size:4px;fill:#ffffff"
d="m 73.244534,44.49725 c -0.04037,-0.02344 -0.08464,-0.04036 -0.132813,-0.05078 -0.04688,-0.01172 -0.09896,-0.01758 -0.15625,-0.01758 -0.203126,2e-6 -0.359376,0.06641 -0.46875,0.199219 -0.108074,0.131512 -0.16211,0.320965 -0.162109,0.568359 l 0,1.152344 -0.361328,0 0,-2.1875 0.361328,0 0,0.339844 c 0.07552,-0.132811 0.173827,-0.231118 0.294922,-0.294922 0.121092,-0.0651 0.268227,-0.09765 0.441406,-0.09766 0.02474,2e-6 0.05208,0.002 0.08203,0.0059 0.02995,0.0026 0.06315,0.0072 0.09961,0.01367 l 0.002,0.369141" />
<path
inkscape:connector-curvature="0"
id="path4222"
style="font-size:4px;fill:#ffffff"
d="m 74.535549,46.551937 c -0.101564,0.260416 -0.200522,0.430338 -0.296875,0.509766 -0.09636,0.07943 -0.225261,0.11914 -0.386719,0.11914 l -0.287109,0 0,-0.300781 0.210938,0 c 0.09896,0 0.17578,-0.02344 0.230468,-0.07031 0.05469,-0.04688 0.115234,-0.157553 0.181641,-0.332032 l 0.06445,-0.164062 -0.884766,-2.152344 0.38086,0 0.683594,1.710938 0.683593,-1.710938 0.38086,0 -0.960938,2.390625" />
</g>
<rect
y="366.52393"
x="583.84381"
height="5.9022241"
width="5.3263974"
id="rect4552-0-7-4"
style="fill:none;stroke:#ffffff;stroke-width:0.29055119;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
transform="translate(-497.66563,-344.28037)" />
<g
id="text4554-2-3-4"
style="font-size:40px;font-style:normal;font-weight:normal;fill:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Bitstream Vera Sans"
transform="translate(-497.66563,-344.28037)">
<path
inkscape:connector-curvature="0"
id="path4118"
style="font-size:4px;fill:#ffffff"
d="m 585.62018,370.49521 0.64453,0 0,-2.22461 -0.70117,0.14062 0,-0.35937 0.69726,-0.14063 0.39453,0 0,2.58399 0.64454,0 0,0.33203 -1.67969,0 0,-0.33203" />
</g>
<rect
y="373.38257"
x="583.84381"
height="5.9022241"
width="5.3263974"
id="rect4552-09-6-6"
style="fill:none;stroke:#ffffff;stroke-width:0.29055119;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
transform="translate(-497.66563,-344.28037)" />
<g
id="text4554-0-0-6"
style="font-size:40px;font-style:normal;font-weight:normal;fill:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Bitstream Vera Sans"
transform="translate(-497.66563,-344.28037)">
<path
inkscape:connector-curvature="0"
id="path4099"
style="font-size:4px;fill:#ffffff"
d="m 585.89166,377.35385 1.37696,0 0,0.33203 -1.85157,0 0,-0.33203 c 0.14974,-0.15495 0.35352,-0.36263 0.61133,-0.62305 0.25911,-0.26171 0.42188,-0.43033 0.48828,-0.50585 0.1263,-0.14193 0.21419,-0.26172 0.26367,-0.35938 0.0508,-0.099 0.0762,-0.19596 0.0762,-0.29102 -10e-6,-0.15494 -0.0547,-0.28124 -0.16407,-0.3789 -0.10807,-0.0977 -0.24935,-0.14648 -0.42382,-0.14649 -0.1237,1e-5 -0.25456,0.0215 -0.39258,0.0645 -0.13672,0.043 -0.28321,0.10807 -0.43946,0.19531 l 0,-0.39844 c 0.15886,-0.0638 0.3073,-0.11197 0.44532,-0.14453 0.13802,-0.0326 0.26432,-0.0488 0.3789,-0.0488 0.30209,1e-5 0.54297,0.0755 0.72266,0.22657 0.17968,0.15104 0.26953,0.35286 0.26953,0.60546 0,0.1198 -0.0228,0.23373 -0.0684,0.3418 -0.0443,0.10677 -0.12565,0.23308 -0.24414,0.37891 -0.0325,0.0378 -0.13607,0.14713 -0.31055,0.32812 -0.17448,0.17969 -0.42057,0.43164 -0.73828,0.75586" />
</g>
<rect
y="380.24118"
x="583.84381"
height="5.9022241"
width="5.3263974"
id="rect4552-3-5-4"
style="fill:none;stroke:#ffffff;stroke-width:0.29055119;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
transform="translate(-497.66563,-344.28037)" />
<g
id="text4554-8-7-9"
style="font-size:40px;font-style:normal;font-weight:normal;fill:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Bitstream Vera Sans"
transform="translate(-497.66563,-344.28037)">
<path
inkscape:connector-curvature="0"
id="path4096"
style="font-size:4px;fill:#ffffff"
d="m 586.74713,382.97223 c 0.1888,0.0404 0.33594,0.12435 0.44141,0.25195 0.10677,0.12761 0.16015,0.28516 0.16015,0.47266 0,0.28776 -0.099,0.51042 -0.29687,0.66797 -0.19792,0.15755 -0.47917,0.23633 -0.84375,0.23633 -0.1224,0 -0.2487,-0.0124 -0.37891,-0.0371 -0.1289,-0.0234 -0.26237,-0.0593 -0.40039,-0.10743 l 0,-0.38086 c 0.10938,0.0638 0.22917,0.11198 0.35938,0.14454 0.1302,0.0326 0.26627,0.0488 0.4082,0.0488 0.24739,0 0.43555,-0.0488 0.56445,-0.14648 0.13021,-0.0977 0.19531,-0.23958 0.19532,-0.42578 -1e-5,-0.17188 -0.0606,-0.30599 -0.18164,-0.40235 -0.1198,-0.0976 -0.28712,-0.14648 -0.50196,-0.14648 l -0.33984,0 0,-0.32422 0.35547,0 c 0.19401,0 0.34244,-0.0384 0.44531,-0.11523 0.10286,-0.0781 0.15429,-0.19011 0.1543,-0.33594 -10e-6,-0.14974 -0.0534,-0.26432 -0.16016,-0.34375 -0.10547,-0.0807 -0.25716,-0.12109 -0.45508,-0.12109 -0.10807,0 -0.22396,0.0117 -0.34765,0.0351 -0.1237,0.0234 -0.25977,0.0599 -0.40821,0.10938 l 0,-0.35157 c 0.14974,-0.0417 0.28972,-0.0729 0.41992,-0.0937 0.13151,-0.0208 0.25521,-0.0312 0.3711,-0.0312 0.29948,10e-6 0.53645,0.0684 0.71094,0.20508 0.17447,0.13542 0.26171,0.31902 0.26171,0.55078 0,0.16146 -0.0462,0.29818 -0.13867,0.41016 -0.0924,0.11068 -0.22396,0.1875 -0.39453,0.23047" />
</g>
<rect
y="387.09979"
x="583.84381"
height="5.9022241"
width="5.3263974"
id="rect4552-6-1-7"
style="fill:none;stroke:#ffffff;stroke-width:0.29055119;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
transform="translate(-497.66563,-344.28037)" />
<g
id="text4554-06-2-8"
style="font-size:40px;font-style:normal;font-weight:normal;fill:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Bitstream Vera Sans"
transform="translate(-497.66563,-344.28037)">
<path
inkscape:connector-curvature="0"
id="path4093"
style="font-size:4px;fill:#ffffff"
d="m 586.6358,388.83084 -0.99609,1.55664 0.99609,0 0,-1.55664 m -0.10351,-0.34375 0.49609,0 0,1.90039 0.41602,0 0,0.32813 -0.41602,0 0,0.6875 -0.39258,0 0,-0.6875 -1.3164,0 0,-0.38086 1.21289,-1.84766" />
</g>
<rect
transform="translate(-497.66563,-344.28037)"
y="393.9584"
x="583.84381"
height="5.9022241"
width="5.3263974"
id="rect4552-49-1-9"
style="fill:none;stroke:#ffffff;stroke-width:0.29055119;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
<g
id="text4554-6-4-1"
style="font-size:40px;font-style:normal;font-weight:normal;fill:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Bitstream Vera Sans"
transform="translate(-497.66563,-344.28037)">
<path
inkscape:connector-curvature="0"
id="path4090"
style="font-size:4px;fill:#ffffff"
d="m 585.55573,395.3457 1.54882,0 0,0.33203 -1.1875,0 0,0.71485 c 0.0573,-0.0195 0.11459,-0.0339 0.17188,-0.043 0.0573,-0.0104 0.11458,-0.0156 0.17187,-0.0156 0.32552,10e-6 0.58333,0.0892 0.77344,0.26758 0.1901,0.17839 0.28515,0.41993 0.28516,0.72461 -10e-6,0.3138 -0.0977,0.55794 -0.29297,0.73242 -0.19532,0.17318 -0.47071,0.25977 -0.82617,0.25977 -0.1224,0 -0.2474,-0.0104 -0.375,-0.0312 -0.12631,-0.0208 -0.25717,-0.0521 -0.39258,-0.0937 l 0,-0.39649 c 0.11719,0.0638 0.23828,0.11133 0.36328,0.14258 0.125,0.0312 0.25716,0.0469 0.39648,0.0469 0.22526,0 0.40365,-0.0593 0.53516,-0.17774 0.13151,-0.11849 0.19726,-0.27929 0.19727,-0.48242 -1e-5,-0.20312 -0.0658,-0.36393 -0.19727,-0.48242 -0.13151,-0.11849 -0.3099,-0.17773 -0.53516,-0.17773 -0.10547,0 -0.21093,0.0117 -0.3164,0.0351 -0.10417,0.0234 -0.21094,0.0599 -0.32031,0.10938 l 0,-1.46485" />
</g>
<rect
y="400.81705"
x="583.84381"
height="5.9022241"
width="5.3263974"
id="rect4552-2-7-9"
style="fill:none;stroke:#ffffff;stroke-width:0.29055119;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
transform="translate(-497.66563,-344.28037)" />
<g
id="text4554-9-1-8"
style="font-size:40px;font-style:normal;font-weight:normal;fill:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Bitstream Vera Sans"
transform="translate(-497.66563,-344.28037)">
<path
inkscape:connector-curvature="0"
id="path4087"
style="font-size:4px;fill:#ffffff"
d="m 586.4444,403.50513 c -0.17709,0 -0.31771,0.0605 -0.42188,0.18164 -0.10286,0.12109 -0.1543,0.28711 -0.15429,0.49804 -1e-5,0.20964 0.0514,0.37566 0.15429,0.49805 0.10417,0.1211 0.24479,0.18164 0.42188,0.18164 0.17708,0 0.31705,-0.0605 0.41992,-0.18164 0.10416,-0.12239 0.15625,-0.28841 0.15625,-0.49805 0,-0.21093 -0.0521,-0.37695 -0.15625,-0.49804 -0.10287,-0.12109 -0.24284,-0.18164 -0.41992,-0.18164 m 0.7832,-1.23633 0,0.35937 c -0.099,-0.0469 -0.19922,-0.0827 -0.30078,-0.10742 -0.10026,-0.0247 -0.19987,-0.0371 -0.29883,-0.0371 -0.26042,10e-6 -0.45964,0.0879 -0.59766,0.26367 -0.13672,0.17579 -0.21484,0.44141 -0.23437,0.79688 0.0768,-0.11328 0.17318,-0.19987 0.28906,-0.25977 0.11589,-0.0612 0.24349,-0.0918 0.38281,-0.0918 0.29297,0 0.52409,0.0892 0.69336,0.26758 0.17057,0.17708 0.25586,0.41862 0.25586,0.7246 0,0.29948 -0.0885,0.53972 -0.26562,0.72071 -0.17709,0.18099 -0.41276,0.27148 -0.70703,0.27148 -0.33724,0 -0.59506,-0.1289 -0.77344,-0.38672 -0.17839,-0.25911 -0.26758,-0.63411 -0.26758,-1.125 0,-0.46093 0.10938,-0.82812 0.32813,-1.10156 0.21875,-0.27474 0.51237,-0.41211 0.88086,-0.41211 0.0989,0 0.19856,0.01 0.29882,0.0293 0.10156,0.0195 0.20703,0.0488 0.31641,0.0879" />
</g>
<rect
y="407.67563"
x="583.84381"
height="5.9022241"
width="5.3263974"
id="rect4552-9-7-7"
style="fill:none;stroke:#ffffff;stroke-width:0.29055119;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
transform="translate(-497.66563,-344.28037)" />
<g
id="text4554-84-7-6"
style="font-size:40px;font-style:normal;font-weight:normal;fill:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Bitstream Vera Sans"
transform="translate(-497.66563,-344.28037)">
<path
inkscape:connector-curvature="0"
id="path4083"
style="font-size:4px;fill:#ffffff"
d="m 585.45221,409.06293 1.875,0 0,0.16797 -1.05859,2.74804 -0.41211,0 0.99609,-2.58398 -1.40039,0 0,-0.33203" />
</g>
<rect
y="414.53427"
x="583.84381"
height="5.9022241"
width="5.3263974"
id="rect4552-5-5-1"
style="fill:none;stroke:#ffffff;stroke-width:0.29055119;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
transform="translate(-497.66563,-344.28037)" />
<g
id="text4554-4-9-5"
style="font-size:40px;font-style:normal;font-weight:normal;fill:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Bitstream Vera Sans"
transform="translate(-497.66563,-344.28037)">
<path
inkscape:connector-curvature="0"
id="path4080"
style="font-size:4px;fill:#ffffff"
d="m 586.39557,417.45282 c -0.1875,0 -0.33529,0.0501 -0.44336,0.15039 -0.10677,0.10026 -0.16016,0.23828 -0.16016,0.41406 0,0.17578 0.0534,0.31381 0.16016,0.41407 0.10807,0.10026 0.25586,0.15039 0.44336,0.15039 0.1875,0 0.33528,-0.0501 0.44336,-0.15039 0.10807,-0.10157 0.16211,-0.23959 0.16211,-0.41407 0,-0.17578 -0.054,-0.3138 -0.16211,-0.41406 -0.10677,-0.10026 -0.25456,-0.15039 -0.44336,-0.15039 m -0.39453,-0.16797 c -0.16927,-0.0417 -0.30144,-0.12044 -0.39649,-0.23633 -0.0937,-0.11588 -0.14062,-0.25716 -0.14062,-0.42383 0,-0.23307 0.0827,-0.41731 0.24805,-0.55273 0.16666,-0.13541 0.39453,-0.20312 0.68359,-0.20312 0.29036,0 0.51823,0.0677 0.68359,0.20312 0.16537,0.13542 0.24805,0.31966 0.24805,0.55273 0,0.16667 -0.0475,0.30795 -0.14258,0.42383 -0.0937,0.11589 -0.22461,0.19467 -0.39258,0.23633 0.19011,0.0443 0.33789,0.13086 0.44336,0.25977 0.10677,0.1289 0.16016,0.28646 0.16016,0.47265 0,0.28256 -0.0866,0.49935 -0.25977,0.65039 -0.17187,0.15105 -0.41862,0.22657 -0.74023,0.22657 -0.32162,0 -0.56901,-0.0755 -0.74219,-0.22657 -0.17187,-0.15104 -0.25781,-0.36783 -0.25781,-0.65039 0,-0.18619 0.0534,-0.34375 0.16016,-0.47265 0.10677,-0.12891 0.2552,-0.2155 0.44531,-0.25977 m -0.14453,-0.62305 c 0,0.15105 0.0469,0.26889 0.14062,0.35352 0.0951,0.0846 0.22786,0.12695 0.39844,0.12695 0.16927,0 0.30143,-0.0423 0.39648,-0.12695 0.0964,-0.0846 0.14453,-0.20247 0.14453,-0.35352 0,-0.15104 -0.0482,-0.26887 -0.14453,-0.35351 -0.0951,-0.0846 -0.22721,-0.12695 -0.39648,-0.12695 -0.17058,0 -0.30339,0.0423 -0.39844,0.12695 -0.0937,0.0846 -0.14062,0.20247 -0.14062,0.35351" />
</g>
<g
id="text4842-8-2"
style="font-size:40px;font-style:normal;font-weight:normal;fill:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Bitstream Vera Sans"
transform="translate(-497.66563,-344.28037)">
<path
inkscape:connector-curvature="0"
id="path4102"
style="font-size:4px;writing-mode:tb-rl;fill:#ffffff"
d="m 580.3844,377.1857 c 0.0846,0.0287 0.16666,0.0898 0.24609,0.18359 0.0807,0.0937 0.16146,0.22266 0.24219,0.38672 l 0.40039,0.79688 -0.42383,0 -0.37304,-0.74805 c -0.0964,-0.19531 -0.19011,-0.32487 -0.28125,-0.38867 -0.0898,-0.0638 -0.2129,-0.0957 -0.36914,-0.0957 l -0.42969,0 0,1.23242 -0.39453,0 0,-2.91602 0.89062,0 c 0.33333,0 0.58203,0.0697 0.7461,0.20899 0.16406,0.13932 0.24609,0.34961 0.24609,0.63086 0,0.18359 -0.043,0.33593 -0.12891,0.45703 -0.0846,0.12109 -0.20833,0.20508 -0.37109,0.25195 m -0.98828,-1.22461 0,1.03516 0.49609,0 c 0.1901,0 0.33333,-0.0436 0.42969,-0.13086 0.0976,-0.0885 0.14648,-0.2181 0.14648,-0.38867 0,-0.17058 -0.0488,-0.29883 -0.14648,-0.38477 -0.0964,-0.0872 -0.23959,-0.13086 -0.42969,-0.13086 l -0.49609,0" />
<path
inkscape:connector-curvature="0"
id="path4105"
style="font-size:4px;writing-mode:tb-rl;fill:#ffffff"
d="m 581.07971,380.51773 0,0.41602 c -0.13281,-0.1237 -0.27474,-0.21615 -0.42578,-0.27735 -0.14974,-0.0612 -0.30925,-0.0918 -0.47851,-0.0918 -0.33334,0 -0.58855,0.10221 -0.76563,0.30664 -0.17708,0.20312 -0.26563,0.49739 -0.26562,0.88281 -10e-6,0.38411 0.0885,0.67839 0.26562,0.88281 0.17708,0.20313 0.43229,0.30469 0.76563,0.30469 0.16926,0 0.32877,-0.0306 0.47851,-0.0918 0.15104,-0.0612 0.29297,-0.15364 0.42578,-0.27734 l 0,0.41211 c -0.13802,0.0937 -0.28451,0.16406 -0.43945,0.21094 -0.15365,0.0469 -0.31641,0.0703 -0.48828,0.0703 -0.44141,0 -0.78907,-0.13477 -1.04297,-0.4043 -0.25391,-0.27083 -0.38086,-0.63997 -0.38086,-1.10742 0,-0.46875 0.12695,-0.83789 0.38086,-1.10742 0.2539,-0.27083 0.60156,-0.40625 1.04297,-0.40625 0.17447,0 0.33854,0.0234 0.49219,0.0703 0.15494,0.0456 0.30012,0.11459 0.43554,0.20703" />
<path
inkscape:connector-curvature="0"
id="path4107"
style="font-size:4px;writing-mode:tb-rl;fill:#ffffff"
d="m 579.70471,389.60562 0.39453,0 0,2.91602 -0.39453,0 0,-2.91602" />
<path
inkscape:connector-curvature="0"
id="path4109"
style="font-size:4px;writing-mode:tb-rl;fill:#ffffff"
d="m 580.82776,395.85757 0,1.32032 -0.35938,0 0,-1.3086 c 0,-0.20703 -0.0404,-0.36197 -0.12109,-0.46484 -0.0807,-0.10286 -0.20182,-0.1543 -0.36328,-0.1543 -0.19401,0 -0.34701,0.0618 -0.45899,0.18555 -0.11198,0.1237 -0.16797,0.29232 -0.16796,0.50586 l 0,1.23633 -0.36133,0 0,-2.1875 0.36133,0 0,0.33984 c 0.0859,-0.13151 0.18684,-0.22981 0.30273,-0.29492 0.11719,-0.0651 0.25195,-0.0977 0.4043,-0.0977 0.2513,0 0.4414,0.0781 0.57031,0.23438 0.1289,0.15495 0.19336,0.38346 0.19336,0.68554" />
<path
inkscape:connector-curvature="0"
id="path4111"
style="font-size:4px;writing-mode:tb-rl;fill:#ffffff"
d="m 579.35706,401.50601 0,1.16016 -0.36133,0 0,-3.01953 0.36133,0 0,0.33203 c 0.0755,-0.13021 0.17057,-0.22656 0.28515,-0.28906 0.11589,-0.0638 0.25391,-0.0957 0.41406,-0.0957 0.26563,0 0.48112,0.10547 0.64649,0.31641 0.16666,0.21094 0.25,0.48828 0.25,0.83203 0,0.34375 -0.0833,0.62109 -0.25,0.83203 -0.16537,0.21094 -0.38086,0.31641 -0.64649,0.31641 -0.16015,0 -0.29817,-0.0312 -0.41406,-0.0937 -0.11458,-0.0638 -0.20963,-0.16081 -0.28515,-0.29102 m 1.22265,-0.76367 c 0,-0.26432 -0.0547,-0.47135 -0.16406,-0.62109 -0.10808,-0.15104 -0.25716,-0.22656 -0.44727,-0.22657 -0.1901,10e-6 -0.33984,0.0755 -0.44921,0.22657 -0.10808,0.14974 -0.16212,0.35677 -0.16211,0.62109 -1e-5,0.26432 0.054,0.47201 0.16211,0.62305 0.10937,0.14974 0.25911,0.22461 0.44921,0.22461 0.19011,0 0.33919,-0.0749 0.44727,-0.22461 0.10937,-0.15104 0.16406,-0.35873 0.16406,-0.62305" />
<path
inkscape:connector-curvature="0"
id="path4113"
style="font-size:4px;writing-mode:tb-rl;fill:#ffffff"
d="m 578.97229,405.62711 0,-1.32422 0.35938,0 0,1.31054 c -10e-6,0.20704 0.0404,0.36263 0.12109,0.4668 0.0807,0.10287 0.20182,0.1543 0.36328,0.1543 0.19401,0 0.347,-0.0618 0.45898,-0.18555 0.11328,-0.1237 0.16992,-0.29232 0.16993,-0.50586 l 0,-1.24023 0.35937,0 0,2.1875 -0.35937,0 0,-0.33594 c -0.0872,0.13281 -0.18881,0.23177 -0.30469,0.29687 -0.11459,0.0638 -0.24805,0.0957 -0.40039,0.0957 -0.2513,0 -0.44206,-0.0781 -0.57227,-0.23438 -0.13021,-0.15625 -0.19531,-0.38476 -0.19531,-0.68554 m 0.9043,-1.37696 0,0" />
<path
inkscape:connector-curvature="0"
id="path4115"
style="font-size:4px;writing-mode:tb-rl;fill:#ffffff"
d="m 579.84924,408.33804 0,0.6211 0.74024,0 0,0.27929 -0.74024,0 0,1.1875 c 0,0.17839 0.0241,0.29297 0.0723,0.34375 0.0495,0.0508 0.14909,0.0762 0.29883,0.0762 l 0.36914,0 0,0.30078 -0.36914,0 c -0.27735,0 -0.46875,-0.0514 -0.57422,-0.1543 -0.10547,-0.10417 -0.15821,-0.29297 -0.1582,-0.56641 l 0,-1.1875 -0.26368,0 0,-0.27929 0.26368,0 0,-0.6211 0.36132,0" />
</g>
<g
id="text5124-0-6"
style="font-size:40px;font-style:normal;font-weight:normal;fill:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Bitstream Vera Sans">
<path
inkscape:connector-curvature="0"
id="path4275"
style="font-size:3px;writing-mode:tb-rl;fill:#ffffff"
d="m 56.800373,65.694183 0.297363,0 0,1.328614 c 0,0.234375 0.04248,0.40332 0.127442,0.506836 0.08496,0.102539 0.222655,0.153808 0.413086,0.153808 0.189452,0 0.326658,-0.05127 0.411621,-0.153808 0.08496,-0.103516 0.12744,-0.272461 0.127441,-0.506836 l 0,-1.328614 0.297363,0 0,1.365235 c -10e-7,0.285157 -0.0708,0.500488 -0.212402,0.645996 -0.140626,0.145508 -0.348634,0.218261 -0.624023,0.218262 -0.276368,-10e-7 -0.485352,-0.07275 -0.626953,-0.218262 -0.140626,-0.145508 -0.210938,-0.360839 -0.210938,-0.645996 l 0,-1.365235" />
<path
inkscape:connector-curvature="0"
id="path4277"
style="font-size:3px;writing-mode:tb-rl;fill:#ffffff"
d="m 58.291584,69.258148 0,0.288574 c -0.112306,-0.05371 -0.218263,-0.09375 -0.317871,-0.120117 -0.09961,-0.02636 -0.195802,-0.03955 -0.288574,-0.03955 -0.161134,2e-6 -0.285646,0.03125 -0.373535,0.09375 -0.08692,0.0625 -0.130372,0.151369 -0.130372,0.266602 0,0.09668 0.02881,0.169923 0.08643,0.219727 0.05859,0.04883 0.168945,0.08838 0.331055,0.118652 l 0.178711,0.03662 c 0.220702,0.04199 0.383299,0.116212 0.487793,0.222656 0.105467,0.10547 0.158201,0.247071 0.158203,0.424805 -2e-6,0.211914 -0.07129,0.372559 -0.213867,0.481934 -0.141603,0.109375 -0.349611,0.164062 -0.624024,0.164062 -0.103516,0 -0.213868,-0.01172 -0.331054,-0.03516 -0.116212,-0.02344 -0.236817,-0.05811 -0.361817,-0.104004 l 0,-0.304688 c 0.120117,0.06738 0.237793,0.118165 0.353028,0.152344 0.115233,0.03418 0.228514,0.05127 0.339843,0.05127 0.168945,0 0.299316,-0.0332 0.391114,-0.09961 0.09179,-0.06641 0.137693,-0.161132 0.137695,-0.284179 -2e-6,-0.107422 -0.0332,-0.191406 -0.09961,-0.251954 -0.06543,-0.06055 -0.173341,-0.105956 -0.323731,-0.13623 L 57.510822,70.3685 c -0.220703,-0.04394 -0.380371,-0.112792 -0.479004,-0.206543 -0.09863,-0.09375 -0.147949,-0.22412 -0.147949,-0.391113 0,-0.193358 0.06787,-0.345702 0.203613,-0.457032 0.136719,-0.111326 0.324707,-0.16699 0.563965,-0.166992 0.102538,2e-6 0.20703,0.0093 0.313477,0.02783 0.106444,0.01856 0.21533,0.04639 0.32666,0.0835" />
<path
inkscape:connector-curvature="0"
id="path4279"
style="font-size:3px;writing-mode:tb-rl;fill:#ffffff"
d="m 57.200275,73.821136 0,0.80127 0.47461,0 c 0.159178,0 0.276854,-0.03271 0.353027,-0.09815 0.07715,-0.0664 0.115721,-0.167479 0.115723,-0.303222 -2e-6,-0.136718 -0.03858,-0.237304 -0.115723,-0.301758 -0.07617,-0.06543 -0.193849,-0.09814 -0.353027,-0.09815 l -0.47461,0 m 0,-0.899414 0,0.65918 0.437989,0 c 0.14453,10e-7 0.251952,-0.02685 0.322265,-0.08057 0.07129,-0.05469 0.106932,-0.137694 0.106934,-0.249024 -2e-6,-0.11035 -0.03565,-0.192869 -0.106934,-0.247558 -0.07031,-0.05469 -0.177735,-0.08203 -0.322265,-0.08203 l -0.437989,0 m -0.295898,-0.243164 0.755859,0 c 0.225585,3e-6 0.399413,0.04688 0.521485,0.140625 0.122068,0.09375 0.183103,0.227053 0.183105,0.399903 -2e-6,0.13379 -0.03125,0.240235 -0.09375,0.319336 -0.0625,0.0791 -0.154298,0.128419 -0.27539,0.147949 0.145506,0.03125 0.258299,0.09668 0.338378,0.196289 0.08105,0.09863 0.121581,0.222169 0.121583,0.370605 -2e-6,0.195313 -0.06641,0.346192 -0.199219,0.452637 -0.132814,0.106445 -0.321779,0.159668 -0.566895,0.159668 l -0.785156,0 0,-2.187012" />
</g>
<g
id="text5124-0-1"
style="font-size:40px;font-style:normal;font-weight:normal;fill:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Bitstream Vera Sans">
<path
inkscape:connector-curvature="0"
id="path4266"
style="font-size:3px;writing-mode:tb-rl;fill:#ffffff"
d="m 65.825645,63.926846 0.295899,0 0,2.034668 c -10e-7,0.263671 -0.05029,0.455077 -0.150879,0.574218 -0.09961,0.11914 -0.260254,0.178711 -0.481934,0.178711 l -0.112793,0 0,-0.249023 0.09229,0 c 0.130859,-10e-7 0.223144,-0.03662 0.276855,-0.109864 0.05371,-0.07324 0.08057,-0.204589 0.08057,-0.394042 l 0,-2.034668" />
<path
inkscape:connector-curvature="0"
id="path4268"
style="font-size:3px;writing-mode:tb-rl;fill:#ffffff"
d="m 65.165001,67.419033 1.850098,0 0,0.249023 -0.776368,0 0,1.937989 -0.297363,0 0,-1.937989 -0.776367,0 0,-0.249023" />
<path
inkscape:connector-curvature="0"
id="path4270"
style="font-size:3px;writing-mode:tb-rl;fill:#ffffff"
d="m 65.999962,71.202724 -0.401367,1.088379 0.804199,0 -0.402832,-1.088379 m -0.166992,-0.291503 0.335449,0 0.833496,2.187011 -0.307617,0 -0.199219,-0.561035 -0.98584,0 -0.199219,0.561035 -0.312011,0 0.834961,-2.187011" />
<path
inkscape:connector-curvature="0"
id="path4272"
style="font-size:3px;writing-mode:tb-rl;fill:#ffffff"
d="m 66.596153,76.278408 0,-0.587402 -0.483398,0 0,-0.243164 0.776367,0 0,0.938964 c -0.11426,0.08105 -0.240236,0.142579 -0.37793,0.184571 -0.137697,0.04102 -0.284669,0.06152 -0.440918,0.06152 -0.341797,0 -0.609375,-0.09961 -0.802734,-0.298828 -0.192383,-0.200195 -0.288574,-0.478515 -0.288574,-0.834961 0,-0.35742 0.09619,-0.63574 0.288574,-0.834961 0.193359,-0.200193 0.460937,-0.300291 0.802734,-0.300293 0.142577,2e-6 0.277831,0.01758 0.405762,0.05273 0.128905,0.03516 0.247557,0.08692 0.355957,0.155273 l 0,0.314941 c -0.109377,-0.09277 -0.225588,-0.162595 -0.348633,-0.209472 -0.123048,-0.04687 -0.252443,-0.07031 -0.388183,-0.07031 -0.267579,2e-6 -0.468751,0.07471 -0.603516,0.224121 -0.13379,0.149416 -0.200684,0.372072 -0.200684,0.667969 0,0.294923 0.06689,0.517091 0.200684,0.666504 0.134765,0.149414 0.335937,0.224121 0.603516,0.224121 0.10449,0 0.197752,-0.0088 0.279785,-0.02637 0.08203,-0.01855 0.15576,-0.04687 0.221191,-0.08496" />
</g>
<g
id="text5124-0"
style="font-size:40px;font-style:normal;font-weight:normal;fill:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Bitstream Vera Sans"
transform="translate(-497.66563,-344.28037)">
<path
inkscape:connector-curvature="0"
id="path4285"
style="font-size:2px;writing-mode:tb-rl;fill:#ffffff"
d="m 547.35425,409.21243 0,-0.3916 -0.32227,0 0,-0.16211 0.51758,0 0,0.62598 c -0.0762,0.054 -0.16016,0.0951 -0.25195,0.12305 -0.0918,0.0273 -0.18978,0.041 -0.29395,0.041 -0.22786,0 -0.40625,-0.0664 -0.53515,-0.19922 -0.12826,-0.13346 -0.19239,-0.31901 -0.19239,-0.55664 0,-0.23828 0.0641,-0.42383 0.19239,-0.55664 0.1289,-0.13346 0.30729,-0.20019 0.53515,-0.20019 0.0951,0 0.18522,0.0117 0.27051,0.0352 0.0859,0.0234 0.16504,0.058 0.2373,0.10352 l 0,0.20996 c -0.0729,-0.0618 -0.15039,-0.1084 -0.23242,-0.13965 -0.082,-0.0312 -0.16829,-0.0469 -0.25879,-0.0469 -0.17838,0 -0.3125,0.0498 -0.40234,0.14941 -0.0892,0.0996 -0.13379,0.24805 -0.13379,0.44531 0,0.19662 0.0446,0.34473 0.13379,0.44434 0.0898,0.0996 0.22396,0.14941 0.40234,0.14941 0.0697,0 0.13184,-0.006 0.18653,-0.0176 0.0547,-0.0124 0.10384,-0.0312 0.14746,-0.0566" />
<path
inkscape:connector-curvature="0"
id="path4287"
style="font-size:2px;writing-mode:tb-rl;fill:#ffffff"
d="m 546.72925,410.45267 0,0.54785 0.24804,0 c 0.0918,0 0.16276,-0.0238 0.2129,-0.0713 0.0501,-0.0475 0.0752,-0.11523 0.0752,-0.20313 0,-0.0872 -0.0251,-0.15462 -0.0752,-0.20214 -0.0501,-0.0475 -0.1211,-0.0713 -0.2129,-0.0713 l -0.24804,0 m -0.19727,-0.16211 0.44531,0 c 0.16342,0 0.28679,0.0371 0.37012,0.11133 0.084,0.0736 0.12598,0.18164 0.12598,0.32421 0,0.14389 -0.042,0.25261 -0.12598,0.32618 -0.0833,0.0736 -0.2067,0.11035 -0.37012,0.11035 l -0.24804,0 0,0.58594 -0.19727,0 0,-1.45801" />
<path
inkscape:connector-curvature="0"
id="path4289"
style="font-size:2px;writing-mode:tb-rl;fill:#ffffff"
d="m 546.84058,412.61868 0.19726,0 0,1.45801 -0.19726,0 0,-1.45801" />
<path
inkscape:connector-curvature="0"
id="path4291"
style="font-size:2px;writing-mode:tb-rl;fill:#ffffff"
d="m 546.94019,415.0806 c -0.14323,0 -0.25717,0.0534 -0.3418,0.16015 -0.084,0.10678 -0.12598,0.25228 -0.12598,0.43653 0,0.18359 0.042,0.32877 0.12598,0.43554 0.0846,0.10677 0.19857,0.16016 0.3418,0.16016 0.14322,0 0.2565,-0.0534 0.33984,-0.16016 0.084,-0.10677 0.12597,-0.25195 0.12598,-0.43554 -1e-5,-0.18425 -0.042,-0.32975 -0.12598,-0.43653 -0.0833,-0.10677 -0.19662,-0.16015 -0.33984,-0.16015 m 0,-0.16016 c 0.20442,0 0.36783,0.0687 0.49023,0.20606 0.12239,0.13672 0.18359,0.32031 0.18359,0.55078 0,0.22981 -0.0612,0.41341 -0.18359,0.55078 -0.1224,0.13672 -0.28581,0.20508 -0.49023,0.20508 -0.20508,0 -0.36915,-0.0684 -0.49219,-0.20508 -0.1224,-0.13672 -0.1836,-0.32031 -0.1836,-0.55078 0,-0.23047 0.0612,-0.41406 0.1836,-0.55078 0.12304,-0.13737 0.28711,-0.20606 0.49219,-0.20606" />
</g>
<g
id="text5124-0-5"
style="font-size:40px;font-style:normal;font-weight:normal;fill:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Bitstream Vera Sans"
transform="translate(-497.66563,-344.28037)">
<path
inkscape:connector-curvature="0"
id="path4320"
style="font-size:3px;writing-mode:lr-tb;fill:#ffffff"
d="m 516.10529,408.09613 0,0.82178 0.37207,0 c 0.13769,0 0.24414,-0.0357 0.31933,-0.10694 0.0752,-0.0713 0.11279,-0.17285 0.11279,-0.30468 0,-0.13086 -0.0376,-0.23194 -0.11279,-0.30323 -0.0752,-0.0713 -0.18164,-0.10693 -0.31933,-0.10693 l -0.37207,0 m -0.2959,-0.24316 0.66797,0 c 0.24511,0 0.43017,0.0557 0.55517,0.16699 0.12598,0.11035 0.18896,0.27246 0.18897,0.48633 -10e-6,0.21582 -0.063,0.3789 -0.18897,0.48925 -0.125,0.11036 -0.31006,0.16553 -0.55517,0.16553 l -0.37207,0 0,0.87891 -0.2959,0 0,-2.18701" />
<path
inkscape:connector-curvature="0"
id="path4322"
style="font-size:3px;writing-mode:lr-tb;fill:#ffffff"
d="m 517.42511,407.85297 0.29883,0 0.45996,1.84863 0.4585,-1.84863 0.33251,0 0.45997,1.84863 0.45849,-1.84863 0.30029,0 -0.54931,2.18701 -0.37207,0 -0.46143,-1.89844 -0.46582,1.89844 -0.37207,0 -0.54785,-2.18701" />
<path
inkscape:connector-curvature="0"
id="path4324"
style="font-size:3px;writing-mode:lr-tb;fill:#ffffff"
d="m 521.62189,409.01459 c 0.0635,0.0215 0.125,0.0674 0.18457,0.13769 0.0605,0.0703 0.12109,0.167 0.18164,0.29004 l 0.30029,0.59766 -0.31787,0 -0.27979,-0.56104 c -0.0723,-0.14648 -0.14257,-0.24365 -0.21093,-0.2915 -0.0674,-0.0478 -0.15967,-0.0718 -0.27686,-0.0718 l -0.32226,0 0,0.92432 -0.2959,0 0,-2.18701 0.66797,0 c 0.25,0 0.43652,0.0522 0.55957,0.15673 0.12304,0.1045 0.18457,0.26221 0.18457,0.47315 0,0.1377 -0.0322,0.25195 -0.0967,0.34277 -0.0635,0.0908 -0.15625,0.15381 -0.27832,0.18897 m -0.74121,-0.91846 0,0.77637 0.37207,0 c 0.14257,0 0.25,-0.0327 0.32226,-0.0981 0.0732,-0.0664 0.10986,-0.16357 0.10987,-0.2915 -10e-6,-0.12793 -0.0366,-0.22412 -0.10987,-0.28858 -0.0723,-0.0654 -0.17969,-0.0981 -0.32226,-0.0981 l -0.37207,0" />
<path
inkscape:connector-curvature="0"
id="path4326"
style="font-size:3px;writing-mode:lr-tb;fill:#ffffff"
d="m 517.12042,411.67474 0,0.28858 c -0.1123,-0.0537 -0.21826,-0.0937 -0.31787,-0.12012 -0.0996,-0.0264 -0.1958,-0.0396 -0.28857,-0.0396 -0.16114,0 -0.28565,0.0312 -0.37354,0.0937 -0.0869,0.0625 -0.13037,0.15137 -0.13037,0.2666 0,0.0967 0.0288,0.16992 0.0864,0.21973 0.0586,0.0488 0.16894,0.0884 0.33105,0.11865 l 0.17871,0.0366 c 0.2207,0.042 0.3833,0.11621 0.4878,0.22266 0.10546,0.10547 0.1582,0.24707 0.1582,0.4248 0,0.21192 -0.0713,0.37256 -0.21387,0.48194 -0.1416,0.10937 -0.34961,0.16406 -0.62402,0.16406 -0.10352,0 -0.21387,-0.0117 -0.33106,-0.0352 -0.11621,-0.0234 -0.23681,-0.0581 -0.36181,-0.104 l 0,-0.30469 c 0.12011,0.0674 0.23779,0.11817 0.35302,0.15234 0.11524,0.0342 0.22852,0.0513 0.33985,0.0513 0.16894,0 0.29931,-0.0332 0.39111,-0.0996 0.0918,-0.0664 0.13769,-0.16113 0.1377,-0.28417 -10e-6,-0.10743 -0.0332,-0.19141 -0.0996,-0.25196 -0.0654,-0.0605 -0.17334,-0.10595 -0.32373,-0.13623 l -0.18018,-0.0351 c -0.2207,-0.0439 -0.38037,-0.1128 -0.479,-0.20655 -0.0986,-0.0937 -0.14795,-0.22412 -0.14795,-0.39111 0,-0.19336 0.0679,-0.3457 0.20361,-0.45703 0.13672,-0.11133 0.32471,-0.16699 0.56397,-0.16699 0.10253,0 0.20703,0.009 0.31347,0.0278 0.10645,0.0186 0.21533,0.0464 0.32666,0.0835" />
<path
inkscape:connector-curvature="0"
id="path4328"
style="font-size:3px;writing-mode:lr-tb;fill:#ffffff"
d="m 519.10529,412.90228 0,0.13184 -1.23926,0 c 0.0117,0.18555 0.0674,0.32715 0.16699,0.4248 0.10059,0.0967 0.24023,0.14502 0.41895,0.14502 0.10351,0 0.20361,-0.0127 0.30029,-0.0381 0.0977,-0.0254 0.19433,-0.0635 0.29004,-0.11426 l 0,0.25488 c -0.0967,0.041 -0.1958,0.0723 -0.29737,0.0937 -0.10156,0.0215 -0.20459,0.0322 -0.30908,0.0322 -0.26172,0 -0.46924,-0.0762 -0.62256,-0.22852 -0.15234,-0.15234 -0.22851,-0.3584 -0.22851,-0.61816 0,-0.26855 0.0723,-0.48145 0.21679,-0.63867 0.14551,-0.1582 0.34131,-0.23731 0.58741,-0.23731 0.2207,0 0.39502,0.0713 0.52295,0.21387 0.1289,0.1416 0.19335,0.33447 0.19336,0.57861 m -0.26954,-0.0791 c -0.002,-0.14746 -0.0435,-0.26513 -0.12451,-0.35303 -0.0801,-0.0879 -0.18652,-0.13183 -0.31933,-0.13183 -0.15039,0 -0.271,0.0425 -0.36182,0.12744 -0.0898,0.085 -0.1416,0.20459 -0.15527,0.35889 l 0.96093,-10e-4" />
<path
inkscape:connector-curvature="0"
id="path4330"
style="font-size:3px;writing-mode:lr-tb;fill:#ffffff"
d="m 520.91144,412.79974 0,0.99024 -0.26953,0 0,-0.98145 c 0,-0.15527 -0.0303,-0.27148 -0.0908,-0.34863 -0.0606,-0.0772 -0.15137,-0.11572 -0.27246,-0.11572 -0.14551,0 -0.26026,0.0464 -0.34424,0.13916 -0.084,0.0928 -0.12598,0.21924 -0.12598,0.37939 l 0,0.92725 -0.271,0 0,-1.64063 0.271,0 0,0.25489 c 0.0644,-0.0986 0.14014,-0.17237 0.22705,-0.2212 0.0879,-0.0488 0.18897,-0.0732 0.30322,-0.0732 0.18848,0 0.33106,0.0586 0.42774,0.17578 0.0967,0.11622 0.14502,0.2876 0.14502,0.51416" />
<path
inkscape:connector-curvature="0"
id="path4332"
style="font-size:3px;writing-mode:lr-tb;fill:#ffffff"
d="m 522.49786,412.19769 0,0.25489 c -0.0762,-0.0391 -0.15527,-0.0684 -0.2373,-0.0879 -0.082,-0.0195 -0.16699,-0.0293 -0.25488,-0.0293 -0.13379,0 -0.23438,0.0205 -0.30176,0.0615 -0.0664,0.041 -0.0996,0.10254 -0.0996,0.18457 0,0.0625 0.0239,0.11182 0.0718,0.14795 0.0478,0.0352 0.14404,0.0688 0.28857,0.10108 l 0.0923,0.0205 c 0.1914,0.041 0.32714,0.0991 0.40722,0.17432 0.0811,0.0742 0.12158,0.17822 0.12158,0.31201 0,0.15235 -0.0605,0.27295 -0.18164,0.36182 -0.12011,0.0889 -0.28564,0.1333 -0.49658,0.1333 -0.0879,0 -0.17969,-0.009 -0.27539,-0.0264 -0.0947,-0.0166 -0.19482,-0.042 -0.30029,-0.0762 l 0,-0.27832 c 0.0996,0.0518 0.19775,0.0908 0.29443,0.11719 0.0967,0.0254 0.19238,0.0381 0.28711,0.0381 0.12695,0 0.22461,-0.0215 0.29297,-0.0645 0.0684,-0.0439 0.10254,-0.10547 0.10254,-0.18457 0,-0.0732 -0.0249,-0.12939 -0.0747,-0.16846 -0.0488,-0.0391 -0.15674,-0.0767 -0.32373,-0.11279 l -0.0937,-0.022 c -0.16699,-0.0352 -0.2876,-0.0889 -0.36181,-0.16114 -0.0742,-0.0732 -0.11133,-0.17334 -0.11133,-0.30029 0,-0.15429 0.0547,-0.27344 0.16406,-0.35742 0.10937,-0.084 0.26465,-0.12598 0.46582,-0.12598 0.0996,0 0.19336,0.007 0.28125,0.022 0.0879,0.0146 0.16894,0.0366 0.24316,0.0659" />
<path
inkscape:connector-curvature="0"
id="path4334"
style="font-size:3px;writing-mode:lr-tb;fill:#ffffff"
d="m 524.41974,412.90228 0,0.13184 -1.23926,0 c 0.0117,0.18555 0.0674,0.32715 0.16699,0.4248 0.10059,0.0967 0.24024,0.14502 0.41895,0.14502 0.10351,0 0.20361,-0.0127 0.30029,-0.0381 0.0977,-0.0254 0.19434,-0.0635 0.29004,-0.11426 l 0,0.25488 c -0.0967,0.041 -0.1958,0.0723 -0.29736,0.0937 -0.10157,0.0215 -0.20459,0.0322 -0.30908,0.0322 -0.26172,0 -0.46924,-0.0762 -0.62256,-0.22852 -0.15235,-0.15234 -0.22852,-0.3584 -0.22852,-0.61816 0,-0.26855 0.0723,-0.48145 0.2168,-0.63867 0.14551,-0.1582 0.34131,-0.23731 0.5874,-0.23731 0.2207,0 0.39502,0.0713 0.52295,0.21387 0.1289,0.1416 0.19336,0.33447 0.19336,0.57861 m -0.26953,-0.0791 c -0.002,-0.14746 -0.0435,-0.26513 -0.12451,-0.35303 -0.0801,-0.0879 -0.18653,-0.13183 -0.31934,-0.13183 -0.15039,0 -0.271,0.0425 -0.36182,0.12744 -0.0898,0.085 -0.1416,0.20459 -0.15527,0.35889 l 0.96094,-10e-4" />
</g>
<g
id="text4548-2-7"
style="font-size:40px;font-style:normal;font-weight:normal;fill:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Bitstream Vera Sans">
<path
inkscape:connector-curvature="0"
id="path4303"
style="font-size:4px;fill:#ffffff"
d="m 31.543343,65.534691 -0.535157,1.451172 1.072266,0 -0.537109,-1.451172 m -0.222657,-0.388672 0.447266,0 1.111328,2.916016 -0.410156,0 -0.265625,-0.748047 -1.314453,0 -0.265625,0.748047 -0.416016,0 1.113281,-2.916016" />
<path
inkscape:connector-curvature="0"
id="path4305"
style="font-size:4px;fill:#ffffff"
d="m 33.697639,65.470238 0,2.267578 0.476563,0 c 0.402342,0 0.696613,-0.09115 0.882812,-0.273438 0.187498,-0.182291 0.281248,-0.470051 0.28125,-0.863281 -2e-6,-0.390623 -0.09375,-0.67643 -0.28125,-0.857422 -0.186199,-0.182289 -0.48047,-0.273435 -0.882812,-0.273437 l -0.476563,0 m -0.394531,-0.324219 0.810547,0 c 0.565102,3e-6 0.979816,0.117841 1.244141,0.353516 0.26432,0.234377 0.396481,0.601564 0.396484,1.101562 -3e-6,0.502605 -0.132815,0.871745 -0.398437,1.107422 -0.265628,0.235677 -0.67969,0.353516 -1.242188,0.353516 l -0.810547,0 0,-2.916016" />
<path
inkscape:connector-curvature="0"
id="path4307"
style="font-size:4px;fill:#ffffff"
d="m 38.564827,65.370628 0,0.416016 C 38.432012,65.662948 38.290085,65.570501 38.139046,65.5093 37.989304,65.44811 37.829799,65.41751 37.66053,65.4175 c -0.333335,3e-6 -0.588543,0.102216 -0.765625,0.306641 -0.177084,0.203127 -0.265626,0.497398 -0.265625,0.882812 -1e-6,0.384116 0.08854,0.678387 0.265625,0.882813 0.177082,0.203125 0.43229,0.304688 0.765625,0.304687 0.169269,10e-7 0.328774,-0.0306 0.478516,-0.0918 0.151039,-0.0612 0.292966,-0.153646 0.425781,-0.277344 l 0,0.412109 c -0.138023,0.09375 -0.284508,0.164063 -0.439453,0.210938 -0.153648,0.04687 -0.316408,0.07031 -0.488281,0.07031 -0.441408,0 -0.789064,-0.134765 -1.042969,-0.404297 -0.253907,-0.270832 -0.38086,-0.639973 -0.38086,-1.107422 0,-0.468748 0.126953,-0.837888 0.38086,-1.107421 0.253905,-0.270831 0.601561,-0.406247 1.042969,-0.40625 0.174477,3e-6 0.338539,0.02344 0.492187,0.07031 0.154946,0.04558 0.300128,0.114586 0.435547,0.207031" />
<path
inkscape:connector-curvature="0"
id="path4309"
style="font-size:4px;fill:#ffffff"
d="m 40.451546,65.146019 0.394531,0 0,2.916016 -0.394531,0 0,-2.916016" />
<path
inkscape:connector-curvature="0"
id="path4311"
style="font-size:4px;fill:#ffffff"
d="m 43.433968,66.741722 0,1.320313 -0.359375,0 0,-1.308594 c -2e-6,-0.20703 -0.04037,-0.361978 -0.121094,-0.464844 -0.08073,-0.102863 -0.201825,-0.154295 -0.363281,-0.154297 -0.194012,2e-6 -0.347007,0.06185 -0.458985,0.185547 -0.11198,0.1237 -0.167969,0.292319 -0.167969,0.505859 l 0,1.236329 -0.361328,0 0,-2.1875 0.361328,0 0,0.339843 c 0.08594,-0.131508 0.186849,-0.229815 0.302735,-0.294922 0.117186,-0.0651 0.251952,-0.09765 0.404297,-0.09766 0.2513,2e-6 0.441404,0.07813 0.570312,0.234375 0.128904,0.15495 0.193357,0.383465 0.19336,0.685547" />
</g>
<g
id="text4842-6"
style="font-size:39.24139404px;font-style:normal;font-weight:normal;fill:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Bitstream Vera Sans"
transform="scale(1.0193318,0.98103488)">
<path
inkscape:connector-curvature="0"
id="path4035"
style="font-size:3.9241395px;writing-mode:tb-rl;fill:#ffffff"
d="m 11.282518,23.899893 0,0.377468 c -0.146901,-0.07025 -0.285498,-0.122627 -0.41579,-0.157119 -0.130295,-0.03449 -0.256118,-0.05173 -0.377468,-0.05173 -0.21077,3e-6 -0.373637,0.04088 -0.488602,0.122629 -0.1136879,0.08176 -0.1705316,0.197998 -0.170531,0.348728 -6e-7,0.126463 0.037682,0.222267 0.113049,0.287412 0.076642,0.06387 0.220987,0.115606 0.433035,0.155203 l 0.233762,0.0479 c 0.288688,0.05493 0.501373,0.152011 0.638056,0.291245 0.137956,0.137959 0.206935,0.32318 0.206937,0.555664 -2e-6,0.277194 -0.09325,0.487324 -0.279748,0.630392 -0.185223,0.143067 -0.457307,0.214601 -0.816252,0.214601 -0.135404,0 -0.279749,-0.01533 -0.4330348,-0.04599 -0.1520099,-0.03066 -0.3097673,-0.076 -0.4732727,-0.136042 l 0,-0.398545 c 0.1571185,0.08814 0.3110437,0.154564 0.4617762,0.199272 0.1507313,0.04471 0.2989083,0.06706 0.4445313,0.06706 0.220987,0 0.391518,-0.04343 0.511594,-0.130293 0.120073,-0.08686 0.18011,-0.210769 0.180112,-0.371721 -2e-6,-0.140512 -0.04343,-0.250367 -0.130293,-0.329566 -0.08559,-0.0792 -0.226738,-0.138596 -0.423455,-0.178196 l -0.235678,-0.04599 C 9.9725551,25.294803 9.7637022,25.204747 9.6346865,25.082116 9.5056698,24.959489 9.4411618,24.788957 9.441162,24.570522 c -2e-7,-0.252921 0.088778,-0.452193 0.2663357,-0.597818 0.1788337,-0.14562 0.4247313,-0.218431 0.7376923,-0.218434 0.134124,3e-6 0.270805,0.01214 0.410042,0.03641 0.139233,0.02427 0.281662,0.06068 0.427286,0.109217" />
<path
inkscape:connector-curvature="0"
id="path4037"
style="font-size:3.9241395px;writing-mode:tb-rl;fill:#ffffff"
d="m 11.426225,30.073514 0,0.172448 -1.621007,0 c 0.015328,0.242705 0.088139,0.427926 0.218434,0.555664 0.13157,0.126462 0.314236,0.189693 0.547999,0.189692 0.135402,1e-6 0.266334,-0.0166 0.392798,-0.04982 0.127737,-0.03321 0.254198,-0.08303 0.379384,-0.149454 l 0,0.333398 c -0.126463,0.05365 -0.256118,0.09453 -0.388965,0.12263 -0.13285,0.0281 -0.267614,0.04215 -0.404293,0.04215 -0.342342,-1e-6 -0.6137867,-0.09964 -0.814336,-0.29891 -0.1992731,-0.199272 -0.2989093,-0.468801 -0.2989091,-0.808587 -2e-7,-0.35128 0.094527,-0.629751 0.2835804,-0.835412 0.1903303,-0.206935 0.4464467,-0.310404 0.7683497,-0.310406 0.288688,2e-6 0.516702,0.09325 0.684042,0.279748 0.168613,0.185223 0.252921,0.437508 0.252923,0.756853 m -0.35256,-0.103468 c -0.0026,-0.192884 -0.05685,-0.34681 -0.162867,-0.461776 -0.104747,-0.114964 -0.243982,-0.172446 -0.417706,-0.172448 -0.196719,2e-6 -0.354476,0.05557 -0.473273,0.166699 -0.1175201,0.111135 -0.1852217,0.267615 -0.2031045,0.469441 l 1.2569505,-0.0019" />
<path
inkscape:connector-curvature="0"
id="path4039"
style="font-size:3.9241395px;writing-mode:tb-rl;fill:#ffffff"
d="m 11.2327,33.986157 c -0.0396,-0.02299 -0.08303,-0.0396 -0.130293,-0.04982 -0.04599,-0.01149 -0.09708,-0.01724 -0.153287,-0.01724 -0.199274,2e-6 -0.35256,0.06515 -0.45986,0.195441 -0.106024,0.129018 -0.159036,0.314878 -0.159035,0.55758 l 0,1.13049 -0.3544756,0 0,-2.146014 0.3544756,0 0,0.333398 c 0.07409,-0.130291 0.17053,-0.226734 0.289329,-0.289328 0.118796,-0.06387 0.26314,-0.0958 0.433034,-0.0958 0.02427,2e-6 0.0511,0.0019 0.08048,0.0057 0.02938,0.0026 0.06195,0.007 0.09772,0.01341 l 0.0019,0.36214" />
<path
inkscape:connector-curvature="0"
id="path4041"
style="font-size:3.9241395px;writing-mode:tb-rl;fill:#ffffff"
d="m 9.3836795,38.224534 0.3736363,0 0.6706292,1.801119 0.670629,-1.801119 0.373637,0 -0.804755,2.146014 -0.479021,0 -0.8047555,-2.146014" />
<path
inkscape:connector-curvature="0"
id="path4043"
style="font-size:3.9241395px;writing-mode:tb-rl;fill:#ffffff"
d="m 10.429861,43.039653 c -0.189054,2e-6 -0.338509,0.07409 -0.4483633,0.222266 -0.1098561,0.146901 -0.1647838,0.348728 -0.1647832,0.605482 -6e-7,0.256756 0.054288,0.459222 0.1628671,0.607399 0.1098544,0.1469 0.2599474,0.220349 0.4502794,0.220349 0.187775,0 0.336591,-0.07409 0.446448,-0.222266 0.109853,-0.148176 0.164781,-0.350003 0.164783,-0.605482 -2e-6,-0.254199 -0.05493,-0.455388 -0.164783,-0.603566 -0.109857,-0.149453 -0.258673,-0.22418 -0.446448,-0.224182 m 0,-0.298909 c 0.306572,2e-6 0.54736,0.09964 0.722364,0.298909 0.175,0.199274 0.262501,0.47519 0.262503,0.827748 -2e-6,0.351283 -0.0875,0.627199 -0.262503,0.827748 -0.175004,0.199273 -0.415792,0.298909 -0.722364,0.298909 -0.307851,0 -0.5492777,-0.09964 -0.7242794,-0.298909 C 9.5318564,44.4946 9.444994,44.218684 9.4449942,43.867401 c -2e-7,-0.352558 0.086862,-0.628474 0.2605874,-0.827748 0.1750017,-0.199271 0.4164284,-0.298907 0.7242794,-0.298909" />
<path
inkscape:connector-curvature="0"
id="path4045"
style="font-size:3.9241395px;writing-mode:tb-rl;fill:#ffffff"
d="m 10.429861,51.476169 c -0.281027,3e-6 -0.5045695,0.104749 -0.6706291,0.314238 -0.1647839,0.209494 -0.2471754,0.49499 -0.2471748,0.85649 -6e-7,0.360224 0.082391,0.645082 0.2471748,0.854573 0.1660596,0.209492 0.3896021,0.314238 0.6706291,0.314238 0.281024,0 0.503289,-0.104746 0.666797,-0.314238 0.164781,-0.209491 0.247173,-0.494349 0.247175,-0.854573 -2e-6,-0.3615 -0.08239,-0.646996 -0.247175,-0.85649 -0.163508,-0.209489 -0.385773,-0.314235 -0.666797,-0.314238 m 0,-0.314237 c 0.401098,3e-6 0.721723,0.134767 0.961874,0.404293 0.240147,0.268254 0.360221,0.628478 0.360224,1.080672 -3e-6,0.450919 -0.120077,0.811142 -0.360224,1.080671 -0.240151,0.268252 -0.560776,0.402377 -0.961874,0.402377 -0.402379,0 -0.7242803,-0.134125 -0.965706,-0.402377 -0.2401495,-0.268251 -0.360224,-0.628475 -0.3602237,-1.080671 -3e-7,-0.452194 0.1200742,-0.812418 0.3602237,-1.080672 0.2414257,-0.269526 0.563327,-0.40429 0.965706,-0.404293" />
<path
inkscape:connector-curvature="0"
id="path4047"
style="font-size:3.9241395px;writing-mode:tb-rl;fill:#ffffff"
d="m 9.5158893,57.795414 0,-1.299105 0.3525594,0 0,1.285692 c -7e-7,0.203105 0.039598,0.355753 0.1187972,0.457944 0.079197,0.100914 0.1979941,0.151371 0.3563911,0.151371 0.19033,0 0.340423,-0.06068 0.45028,-0.182028 0.111131,-0.121352 0.166698,-0.286774 0.166699,-0.496266 l 0,-1.216713 0.35256,0 0,2.146014 -0.35256,0 0,-0.329567 c -0.08559,0.130294 -0.185223,0.227376 -0.298909,0.291245 -0.112411,0.06259 -0.243344,0.09389 -0.392797,0.09389 -0.246537,0 -0.4336741,-0.07664 -0.5614123,-0.22993 -0.1277394,-0.153288 -0.1916088,-0.37747 -0.1916084,-0.672547 m 0.8871467,-1.35084 0,0" />
<path
inkscape:connector-curvature="0"
id="path4049"
style="font-size:3.9241395px;writing-mode:tb-rl;fill:#ffffff"
d="m 10.376211,60.454938 0,0.609314 0.726196,0 0,0.274 -0.726196,0 0,1.164979 c -10e-7,0.175003 0.02363,0.287413 0.0709,0.337231 0.04854,0.04982 0.14626,0.07473 0.293161,0.07473 l 0.36214,0 0,0.295077 -0.36214,0 c -0.272085,0 -0.459861,-0.05046 -0.563329,-0.151371 -0.103469,-0.10219 -0.155203,-0.287412 -0.155203,-0.555664 l 0,-1.164979 -0.2586709,0 0,-0.274 0.2586709,0 0,-0.609314 0.354476,0" />
<path
inkscape:connector-curvature="0"
id="path4051"
style="font-size:3.9241395px;writing-mode:tb-rl;fill:#ffffff"
d="m 9.8933578,67.456308 0,1.138153 -0.3544755,0 0,-2.962265 0.3544755,0 0,0.325734 c 0.074088,-0.127737 0.1673372,-0.222264 0.2797482,-0.28358 0.113687,-0.06259 0.24909,-0.09389 0.40621,-0.09389 0.260585,2e-6 0.471993,0.10347 0.634223,0.310405 0.163504,0.206939 0.245257,0.479023 0.245259,0.816252 -2e-6,0.337231 -0.08175,0.609315 -0.245259,0.816252 -0.16223,0.206937 -0.373638,0.310405 -0.634223,0.310405 -0.15712,0 -0.292523,-0.03066 -0.40621,-0.09197 -0.112411,-0.06259 -0.2056604,-0.157757 -0.2797482,-0.285496 m 1.1994682,-0.749189 c -2e-6,-0.259309 -0.05365,-0.462413 -0.160951,-0.609315 -0.106025,-0.148175 -0.252286,-0.222264 -0.438783,-0.222265 -0.1865,10e-7 -0.3334,0.07409 -0.440699,0.222265 -0.1060243,0.146902 -0.1590359,0.350006 -0.1590352,0.609315 -7e-7,0.259311 0.053011,0.463054 0.1590352,0.611231 0.107299,0.1469 0.254199,0.220349 0.440699,0.220349 0.186497,0 0.332758,-0.07345 0.438783,-0.220349 0.107299,-0.148177 0.160949,-0.35192 0.160951,-0.611231" />
<path
inkscape:connector-curvature="0"
id="path4053"
style="font-size:3.9241395px;writing-mode:tb-rl;fill:#ffffff"
d="m 9.5158893,71.499244 0,-1.299105 0.3525594,0 0,1.285693 c -7e-7,0.203105 0.039598,0.355753 0.1187972,0.457944 0.079197,0.100914 0.1979941,0.151371 0.3563911,0.15137 0.19033,10e-7 0.340423,-0.06068 0.45028,-0.182028 0.111131,-0.121351 0.166698,-0.286773 0.166699,-0.496265 l 0,-1.216714 0.35256,0 0,2.146014 -0.35256,0 0,-0.329566 c -0.08559,0.130294 -0.185223,0.227375 -0.298909,0.291245 -0.112411,0.06259 -0.243344,0.09389 -0.392797,0.09389 -0.246537,0 -0.4336741,-0.07664 -0.5614123,-0.22993 -0.1277394,-0.153289 -0.1916088,-0.37747 -0.1916084,-0.672548 m 0.8871467,-1.350839 0,0" />
<path
inkscape:connector-curvature="0"
id="path4055"
style="font-size:3.9241395px;writing-mode:tb-rl;fill:#ffffff"
d="m 10.376211,74.158768 0,0.609315 0.726196,0 0,0.274 -0.726196,0 0,1.164979 c -10e-7,0.175003 0.02363,0.287413 0.0709,0.337231 0.04854,0.04982 0.14626,0.07473 0.293161,0.07473 l 0.36214,0 0,0.295077 -0.36214,0 c -0.272085,0 -0.459861,-0.05046 -0.563329,-0.151371 -0.103469,-0.102191 -0.155203,-0.287412 -0.155203,-0.555664 l 0,-1.164979 -0.2586709,0 0,-0.274 0.2586709,0 0,-0.609315 0.354476,0" />
</g>
<rect
y="366.52393"
x="500.23694"
height="5.9022241"
width="5.3263974"
id="rect4552-0-3"
style="fill:none;stroke:#ffffff;stroke-width:0.29055119;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
transform="translate(-497.66563,-344.28037)" />
<g
id="text4554-2-1"
style="font-size:40px;font-style:normal;font-weight:normal;fill:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Bitstream Vera Sans"
transform="translate(-497.66563,-344.28037)">
<path
inkscape:connector-curvature="0"
id="path4058"
style="font-size:4px;fill:#ffffff"
d="m 502.01331,370.49521 0.64453,0 0,-2.22461 -0.70117,0.14062 0,-0.35937 0.69726,-0.14063 0.39453,0 0,2.58399 0.64453,0 0,0.33203 -1.67968,0 0,-0.33203" />
</g>
<rect
y="373.38257"
x="500.23694"
height="5.9022241"
width="5.3263974"
id="rect4552-09-3"
style="fill:none;stroke:#ffffff;stroke-width:0.29055119;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
transform="translate(-497.66563,-344.28037)" />
<g
id="text4554-0-4"
style="font-size:40px;font-style:normal;font-weight:normal;fill:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Bitstream Vera Sans"
transform="translate(-497.66563,-344.28037)">
<path
inkscape:connector-curvature="0"
id="path4032"
style="font-size:4px;fill:#ffffff"
d="m 502.28479,377.35385 1.37695,0 0,0.33203 -1.85156,0 0,-0.33203 c 0.14974,-0.15495 0.35352,-0.36263 0.61133,-0.62305 0.25911,-0.26171 0.42187,-0.43033 0.48828,-0.50585 0.1263,-0.14193 0.21419,-0.26172 0.26367,-0.35938 0.0508,-0.099 0.0762,-0.19596 0.0762,-0.29102 0,-0.15494 -0.0547,-0.28124 -0.16406,-0.3789 -0.10807,-0.0977 -0.24935,-0.14648 -0.42383,-0.14649 -0.1237,1e-5 -0.25456,0.0215 -0.39257,0.0645 -0.13672,0.043 -0.28321,0.10807 -0.43946,0.19531 l 0,-0.39844 c 0.15886,-0.0638 0.30729,-0.11197 0.44531,-0.14453 0.13802,-0.0326 0.26433,-0.0488 0.37891,-0.0488 0.30208,1e-5 0.54297,0.0755 0.72266,0.22657 0.17968,0.15104 0.26953,0.35286 0.26953,0.60546 0,0.1198 -0.0228,0.23373 -0.0684,0.3418 -0.0443,0.10677 -0.12565,0.23308 -0.24414,0.37891 -0.0326,0.0378 -0.13607,0.14713 -0.31055,0.32812 -0.17448,0.17969 -0.42057,0.43164 -0.73828,0.75586" />
</g>
<rect
y="380.24118"
x="500.23694"
height="5.9022241"
width="5.3263974"
id="rect4552-3-8"
style="fill:none;stroke:#ffffff;stroke-width:0.29055119;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
transform="translate(-497.66563,-344.28037)" />
<g
id="text4554-8-74"
style="font-size:40px;font-style:normal;font-weight:normal;fill:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Bitstream Vera Sans"
transform="translate(-497.66563,-344.28037)">
<path
inkscape:connector-curvature="0"
id="path4029"
style="font-size:4px;fill:#ffffff"
d="m 503.14026,382.97223 c 0.1888,0.0404 0.33593,0.12435 0.44141,0.25195 0.10676,0.12761 0.16015,0.28516 0.16015,0.47266 0,0.28776 -0.099,0.51042 -0.29687,0.66797 -0.19792,0.15755 -0.47917,0.23633 -0.84375,0.23633 -0.1224,0 -0.2487,-0.0124 -0.37891,-0.0371 -0.12891,-0.0234 -0.26237,-0.0593 -0.40039,-0.10743 l 0,-0.38086 c 0.10937,0.0638 0.22917,0.11198 0.35937,0.14454 0.13021,0.0326 0.26628,0.0488 0.40821,0.0488 0.24739,0 0.43554,-0.0488 0.56445,-0.14648 0.13021,-0.0977 0.19531,-0.23958 0.19531,-0.42578 0,-0.17188 -0.0606,-0.30599 -0.18164,-0.40235 -0.11979,-0.0976 -0.28711,-0.14648 -0.50195,-0.14648 l -0.33984,0 0,-0.32422 0.35546,0 c 0.19401,0 0.34245,-0.0384 0.44532,-0.11523 0.10286,-0.0781 0.15429,-0.19011 0.15429,-0.33594 0,-0.14974 -0.0534,-0.26432 -0.16015,-0.34375 -0.10547,-0.0807 -0.25717,-0.12109 -0.45508,-0.12109 -0.10807,0 -0.22396,0.0117 -0.34766,0.0351 -0.1237,0.0234 -0.25976,0.0599 -0.4082,0.10938 l 0,-0.35157 c 0.14974,-0.0417 0.28971,-0.0729 0.41992,-0.0937 0.13151,-0.0208 0.25521,-0.0312 0.3711,-0.0312 0.29947,10e-6 0.53645,0.0684 0.71093,0.20508 0.17448,0.13542 0.26172,0.31902 0.26172,0.55078 0,0.16146 -0.0462,0.29818 -0.13867,0.41016 -0.0924,0.11068 -0.22396,0.1875 -0.39453,0.23047" />
</g>
<rect
y="387.09979"
x="500.23694"
height="5.9022241"
width="5.3263974"
id="rect4552-6-7"
style="fill:none;stroke:#ffffff;stroke-width:0.29055119;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
transform="translate(-497.66563,-344.28037)" />
<g
id="text4554-06-9"
style="font-size:40px;font-style:normal;font-weight:normal;fill:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Bitstream Vera Sans"
transform="translate(-497.66563,-344.28037)">
<path
inkscape:connector-curvature="0"
id="path4026"
style="font-size:4px;fill:#ffffff"
d="m 503.02893,388.83084 -0.99609,1.55664 0.99609,0 0,-1.55664 m -0.10351,-0.34375 0.49609,0 0,1.90039 0.41601,0 0,0.32813 -0.41601,0 0,0.6875 -0.39258,0 0,-0.6875 -1.31641,0 0,-0.38086 1.2129,-1.84766" />
</g>
<rect
y="393.9584"
x="500.23694"
height="5.9022241"
width="5.3263974"
id="rect4552-49-9"
style="fill:none;stroke:#ffffff;stroke-width:0.29055119;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
transform="translate(-497.66563,-344.28037)" />
<g
id="text4554-6-8"
style="font-size:40px;font-style:normal;font-weight:normal;fill:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Bitstream Vera Sans"
transform="translate(-497.66563,-344.28037)">
<path
inkscape:connector-curvature="0"
id="path4023"
style="font-size:4px;fill:#ffffff"
d="m 501.94885,395.3457 1.54883,0 0,0.33203 -1.1875,0 0,0.71485 c 0.0573,-0.0195 0.11458,-0.0339 0.17188,-0.043 0.0573,-0.0104 0.11458,-0.0156 0.17187,-0.0156 0.32552,10e-6 0.58333,0.0892 0.77344,0.26758 0.1901,0.17839 0.28515,0.41993 0.28515,0.72461 0,0.3138 -0.0976,0.55794 -0.29296,0.73242 -0.19532,0.17318 -0.47071,0.25977 -0.82618,0.25977 -0.12239,0 -0.24739,-0.0104 -0.375,-0.0312 -0.1263,-0.0208 -0.25716,-0.0521 -0.39257,-0.0937 l 0,-0.39649 c 0.11718,0.0638 0.23828,0.11133 0.36328,0.14258 0.125,0.0312 0.25716,0.0469 0.39648,0.0469 0.22526,0 0.40365,-0.0593 0.53516,-0.17774 0.13151,-0.11849 0.19726,-0.27929 0.19726,-0.48242 0,-0.20312 -0.0658,-0.36393 -0.19726,-0.48242 -0.13151,-0.11849 -0.3099,-0.17773 -0.53516,-0.17773 -0.10547,0 -0.21094,0.0117 -0.3164,0.0351 -0.10417,0.0234 -0.21094,0.0599 -0.32032,0.10938 l 0,-1.46485" />
</g>
<rect
y="400.81705"
x="500.23694"
height="5.9022241"
width="5.3263974"
id="rect4552-2-8"
style="fill:none;stroke:#ffffff;stroke-width:0.29055119;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
transform="translate(-497.66563,-344.28037)" />
<g
id="text4554-9-6"
style="font-size:40px;font-style:normal;font-weight:normal;fill:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Bitstream Vera Sans"
transform="translate(-497.66563,-344.28037)">
<path
inkscape:connector-curvature="0"
id="path4020"
style="font-size:4px;fill:#ffffff"
d="m 502.83752,403.50513 c -0.17708,0 -0.3177,0.0605 -0.42187,0.18164 -0.10287,0.12109 -0.1543,0.28711 -0.1543,0.49804 0,0.20964 0.0514,0.37566 0.1543,0.49805 0.10417,0.1211 0.24479,0.18164 0.42187,0.18164 0.17709,0 0.31706,-0.0605 0.41993,-0.18164 0.10416,-0.12239 0.15624,-0.28841 0.15625,-0.49805 -1e-5,-0.21093 -0.0521,-0.37695 -0.15625,-0.49804 -0.10287,-0.12109 -0.24284,-0.18164 -0.41993,-0.18164 m 0.78321,-1.23633 0,0.35937 c -0.099,-0.0469 -0.19922,-0.0827 -0.30078,-0.10742 -0.10027,-0.0247 -0.19988,-0.0371 -0.29883,-0.0371 -0.26042,10e-6 -0.45964,0.0879 -0.59766,0.26367 -0.13672,0.17579 -0.21484,0.44141 -0.23437,0.79688 0.0768,-0.11328 0.17317,-0.19987 0.28906,-0.25977 0.11588,-0.0612 0.24349,-0.0918 0.38281,-0.0918 0.29297,0 0.52409,0.0892 0.69336,0.26758 0.17057,0.17708 0.25586,0.41862 0.25586,0.7246 0,0.29948 -0.0885,0.53972 -0.26562,0.72071 -0.17709,0.18099 -0.41277,0.27148 -0.70704,0.27148 -0.33724,0 -0.59505,-0.1289 -0.77343,-0.38672 -0.17839,-0.25911 -0.26758,-0.63411 -0.26758,-1.125 0,-0.46093 0.10937,-0.82812 0.32812,-1.10156 0.21875,-0.27474 0.51237,-0.41211 0.88086,-0.41211 0.099,0 0.19857,0.01 0.29883,0.0293 0.10156,0.0195 0.20703,0.0488 0.31641,0.0879" />
</g>
<rect
y="407.67563"
x="500.23694"
height="5.9022241"
width="5.3263974"
id="rect4552-9-4"
style="fill:none;stroke:#ffffff;stroke-width:0.29055119;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
transform="translate(-497.66563,-344.28037)" />
<g
id="text4554-84-8"
style="font-size:40px;font-style:normal;font-weight:normal;fill:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Bitstream Vera Sans"
transform="translate(-497.66563,-344.28037)">
<path
inkscape:connector-curvature="0"
id="path4017"
style="font-size:4px;fill:#ffffff"
d="m 501.84534,409.06293 1.875,0 0,0.16797 -1.0586,2.74804 -0.41211,0 0.9961,-2.58398 -1.40039,0 0,-0.33203" />
</g>
<rect
y="414.53427"
x="500.23694"
height="5.9022241"
width="5.3263974"
id="rect4552-5-0"
style="fill:none;stroke:#ffffff;stroke-width:0.29055119;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
transform="translate(-497.66563,-344.28037)" />
<g
id="text4554-4-90"
style="font-size:40px;font-style:normal;font-weight:normal;fill:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Bitstream Vera Sans"
transform="translate(-497.66563,-344.28037)">
<path
inkscape:connector-curvature="0"
id="path4014"
style="font-size:4px;fill:#ffffff"
d="m 502.7887,417.45282 c -0.1875,0 -0.33529,0.0501 -0.44336,0.15039 -0.10677,0.10026 -0.16016,0.23828 -0.16016,0.41406 0,0.17578 0.0534,0.31381 0.16016,0.41407 0.10807,0.10026 0.25586,0.15039 0.44336,0.15039 0.18749,0 0.33528,-0.0501 0.44336,-0.15039 0.10807,-0.10157 0.1621,-0.23959 0.16211,-0.41407 -10e-6,-0.17578 -0.054,-0.3138 -0.16211,-0.41406 -0.10678,-0.10026 -0.25456,-0.15039 -0.44336,-0.15039 m -0.39453,-0.16797 c -0.16928,-0.0417 -0.30144,-0.12044 -0.39649,-0.23633 -0.0937,-0.11588 -0.14062,-0.25716 -0.14062,-0.42383 0,-0.23307 0.0827,-0.41731 0.24804,-0.55273 0.16667,-0.13541 0.39453,-0.20312 0.6836,-0.20312 0.29036,0 0.51822,0.0677 0.68359,0.20312 0.16536,0.13542 0.24804,0.31966 0.24805,0.55273 -1e-5,0.16667 -0.0475,0.30795 -0.14258,0.42383 -0.0937,0.11589 -0.22461,0.19467 -0.39258,0.23633 0.1901,0.0443 0.33789,0.13086 0.44336,0.25977 0.10677,0.1289 0.16015,0.28646 0.16016,0.47265 -1e-5,0.28256 -0.0866,0.49935 -0.25977,0.65039 -0.17188,0.15105 -0.41862,0.22657 -0.74023,0.22657 -0.32162,0 -0.56901,-0.0755 -0.74219,-0.22657 -0.17188,-0.15104 -0.25781,-0.36783 -0.25781,-0.65039 0,-0.18619 0.0534,-0.34375 0.16015,-0.47265 0.10677,-0.12891 0.25521,-0.2155 0.44532,-0.25977 m -0.14454,-0.62305 c 0,0.15105 0.0469,0.26889 0.14063,0.35352 0.0951,0.0846 0.22786,0.12695 0.39844,0.12695 0.16927,0 0.30143,-0.0423 0.39648,-0.12695 0.0963,-0.0846 0.14453,-0.20247 0.14453,-0.35352 0,-0.15104 -0.0482,-0.26887 -0.14453,-0.35351 -0.0951,-0.0846 -0.22721,-0.12695 -0.39648,-0.12695 -0.17058,0 -0.30339,0.0423 -0.39844,0.12695 -0.0937,0.0846 -0.14063,0.20247 -0.14063,0.35351" />
</g>
<rect
y="417.05634"
x="544.98993"
height="4.2557931"
width="3.8405941"
id="rect4552-38-2-7"
style="fill:none;stroke:#ffffff;stroke-width:0.20950167;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
transform="translate(-497.66563,-344.28037)" />
<g
id="text4554-01-6-4"
style="font-size:28.84196281px;font-style:normal;font-weight:normal;fill:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Bitstream Vera Sans"
transform="translate(-497.66563,-344.28037)">
<path
inkscape:connector-curvature="0"
id="path4282"
style="font-size:2.88419628px;fill:#ffffff"
d="m 546.27079,419.91983 0.46474,0 0,-1.60405 -0.50558,0.10139 0,-0.25912 0.50277,-0.1014 0.28447,0 0,1.86318 0.46474,0 0,0.23941 -1.21114,0 0,-0.23941" />
</g>
<rect
y="416.46304"
x="537.50421"
height="4.2557931"
width="3.8405941"
id="rect4552-38-2-7-7-5"
style="fill:none;stroke:#ffffff;stroke-width:0.20950167;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
transform="translate(-497.66563,-344.28037)" />
<g
id="text4554-01-6-4-1-76"
style="font-size:28.84196281px;font-style:normal;font-weight:normal;fill:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Bitstream Vera Sans"
transform="translate(-497.66563,-344.28037)">
<path
inkscape:connector-curvature="0"
id="path4294"
style="font-size:2.88419628px;fill:#ffffff"
d="m 539.59766,418.43227 c 0.13614,0.0291 0.24223,0.0897 0.31828,0.18167 0.077,0.092 0.11548,0.20561 0.11548,0.34081 0,0.20749 -0.0714,0.36803 -0.21406,0.48163 -0.14271,0.11361 -0.3455,0.17041 -0.60839,0.17041 -0.0883,0 -0.17932,-0.009 -0.27321,-0.0268 -0.0929,-0.0169 -0.18918,-0.0427 -0.2887,-0.0774 l 0,-0.27462 c 0.0789,0.046 0.16524,0.0807 0.25913,0.10421 0.0939,0.0235 0.192,0.0352 0.29433,0.0352 0.17839,0 0.31405,-0.0352 0.407,-0.10562 0.0939,-0.0704 0.14083,-0.17275 0.14083,-0.30701 0,-0.12393 -0.0437,-0.22064 -0.13097,-0.29011 -0.0864,-0.0704 -0.20702,-0.10562 -0.36193,-0.10563 l -0.24505,0 0,-0.23377 0.25631,0 c 0.13989,0 0.24693,-0.0277 0.3211,-0.0831 0.0742,-0.0563 0.11125,-0.13708 0.11125,-0.24223 0,-0.10797 -0.0385,-0.19059 -0.11548,-0.24786 -0.0761,-0.0582 -0.18543,-0.0873 -0.32813,-0.0873 -0.0779,10e-6 -0.16149,0.008 -0.25068,0.0254 -0.0892,0.0169 -0.1873,0.0432 -0.29433,0.0789 l 0,-0.25349 c 0.10797,-0.0301 0.20889,-0.0526 0.30278,-0.0676 0.0948,-0.015 0.18402,-0.0225 0.26758,-0.0225 0.21594,1e-5 0.38681,0.0493 0.51262,0.14788 0.1258,0.0976 0.18871,0.23002 0.18871,0.39714 0,0.11642 -0.0333,0.215 -0.1,0.29574 -0.0667,0.0798 -0.16149,0.1352 -0.28448,0.16618" />
</g>
<rect
y="416.46304"
x="532.56604"
height="4.2557931"
width="3.8405941"
id="rect4552-38-2-7-7-23"
style="fill:none;stroke:#ffffff;stroke-width:0.20950167;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
transform="translate(-497.66563,-344.28037)" />
<g
id="text4554-01-6-4-1-2"
style="font-size:28.84196281px;font-style:normal;font-weight:normal;fill:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Bitstream Vera Sans"
transform="translate(-497.66563,-344.28037)">
<path
inkscape:connector-curvature="0"
id="path4297"
style="font-size:2.88419628px;fill:#ffffff"
d="m 534.0426,419.32654 0.99285,0 0,0.23941 -1.33507,0 0,-0.23941 c 0.10797,-0.11173 0.2549,-0.26148 0.4408,-0.44925 0.18683,-0.18871 0.30419,-0.31029 0.35207,-0.36475 0.0911,-0.10233 0.15445,-0.18871 0.19012,-0.25913 0.0366,-0.0713 0.0549,-0.14129 0.0549,-0.20983 0,-0.11173 -0.0394,-0.2028 -0.1183,-0.27321 -0.0779,-0.0704 -0.17979,-0.10562 -0.3056,-0.10563 -0.0892,1e-5 -0.18355,0.0155 -0.28307,0.0465 -0.0986,0.031 -0.2042,0.0779 -0.31687,0.14083 l 0,-0.28729 c 0.11454,-0.046 0.22158,-0.0807 0.3211,-0.10422 0.0995,-0.0235 0.19058,-0.0352 0.27321,-0.0352 0.21781,10e-6 0.3915,0.0545 0.52107,0.16337 0.12956,0.10891 0.19434,0.25443 0.19434,0.43657 0,0.0864 -0.0164,0.16853 -0.0493,0.24645 -0.0319,0.077 -0.0906,0.16806 -0.17604,0.27321 -0.0235,0.0272 -0.0981,0.10609 -0.22392,0.2366 -0.1258,0.12956 -0.30325,0.31123 -0.53233,0.54501" />
</g>
<rect
y="416.46304"
x="527.62781"
height="4.2557931"
width="3.8405941"
id="rect4552-38-2-7-7-2"
style="fill:none;stroke:#ffffff;stroke-width:0.20950167;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
transform="translate(-497.66563,-344.28037)" />
<g
id="text4554-01-6-4-1-7"
style="font-size:28.84196281px;font-style:normal;font-weight:normal;fill:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Bitstream Vera Sans"
transform="translate(-497.66563,-344.28037)">
<path
inkscape:connector-curvature="0"
id="path4300"
style="font-size:2.88419628px;fill:#ffffff"
d="m 528.90867,419.32654 0.46474,0 0,-1.60405 -0.50558,0.10139 0,-0.25912 0.50276,-0.1014 0.28448,0 0,1.86318 0.46474,0 0,0.23941 -1.21114,0 0,-0.23941" />
</g>
<rect
y="416.40854"
x="515.29425"
height="4.2557931"
width="3.8405941"
id="rect4552-38-2-7-7-2-9"
style="fill:none;stroke:#ffffff;stroke-width:0.20950167;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
transform="translate(-497.66563,-344.28037)" />
<g
id="text4554-01-6-4-1-7-2"
style="font-size:28.84196281px;font-style:normal;font-weight:normal;fill:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Bitstream Vera Sans"
transform="translate(-497.66563,-344.28037)">
<path
inkscape:connector-curvature="0"
id="path4317"
style="font-size:2.88419628px;fill:#ffffff"
d="m 516.57512,419.272 0.46473,0 0,-1.60405 -0.50558,0.1014 0,-0.25913 0.50277,-0.1014 0.28447,0 0,1.86318 0.46474,0 0,0.23941 -1.21113,0 0,-0.23941" />
</g>
<rect
y="416.40851"
x="520.23248"
height="4.2557931"
width="3.8405941"
id="rect4552-38-2-7-7-23-5"
style="fill:none;stroke:#ffffff;stroke-width:0.20950167;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
transform="translate(-497.66563,-344.28037)" />
<g
id="text4554-01-6-4-1-2-4"
style="font-size:28.84196281px;font-style:normal;font-weight:normal;fill:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Bitstream Vera Sans"
transform="translate(-497.66563,-344.28037)">
<path
inkscape:connector-curvature="0"
id="path4314"
style="font-size:2.88419628px;fill:#ffffff"
d="m 521.70904,419.272 0.99285,0 0,0.23941 -1.33507,0 0,-0.23941 c 0.10797,-0.11172 0.25491,-0.26147 0.4408,-0.44924 0.18683,-0.18872 0.30419,-0.3103 0.35208,-0.36475 0.0911,-0.10234 0.15444,-0.18871 0.19012,-0.25913 0.0366,-0.0713 0.0549,-0.1413 0.0549,-0.20984 0,-0.11172 -0.0394,-0.20279 -0.1183,-0.27321 -0.0779,-0.0704 -0.17979,-0.10562 -0.3056,-0.10562 -0.0892,0 -0.18355,0.0155 -0.28307,0.0465 -0.0986,0.031 -0.2042,0.0779 -0.31686,0.14083 l 0,-0.28729 c 0.11454,-0.046 0.22157,-0.0807 0.32109,-0.10421 0.0995,-0.0235 0.19059,-0.0352 0.27321,-0.0352 0.21781,0 0.3915,0.0545 0.52107,0.16336 0.12956,0.10891 0.19434,0.25444 0.19434,0.43657 0,0.0864 -0.0164,0.16853 -0.0493,0.24646 -0.0319,0.077 -0.0906,0.16805 -0.17603,0.27321 -0.0235,0.0272 -0.0981,0.10609 -0.22392,0.23659 -0.12581,0.12957 -0.30326,0.31124 -0.53234,0.54501" />
</g>
<rect
transform="translate(-497.66563,-344.28037)"
inkscape:label="#rect3054"
style="fill:none;stroke:#000000;stroke-width:0.99921262;stroke-linecap:butt;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
id="outline"
width="93.746948"
height="79.063599"
x="497.92136"
y="344.5361"
ry="1.628684" />
<g
id="text3316"
style="font-size:40px;font-style:normal;font-weight:normal;fill:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Bitstream Vera Sans">
<path
inkscape:connector-curvature="0"
id="path4183"
style="font-size:3.5px;fill:#ffffff"
d="m 21.839687,52.218197 1.613282,0 0,0.290527 -1.268067,0 0,0.755371 1.215088,0 0,0.290528 -1.215088,0 0,0.92456 1.298828,0 0,0.290528 -1.644043,0 0,-2.551514" />
<path
inkscape:connector-curvature="0"
id="path4185"
style="font-size:3.5px;fill:#ffffff"
d="m 23.815273,52.855648 0.333252,0 0.598145,1.606445 0.598144,-1.606445 0.333252,0 -0.717773,1.914063 -0.427246,0 -0.717774,-1.914063" />
<path
inkscape:connector-curvature="0"
id="path4187"
style="font-size:3.5px;fill:#ffffff"
d="m 27.749355,53.734066 0,0.153809 -1.4458,0 c 0.01367,0.216472 0.07861,0.381673 0.194824,0.495605 0.117349,0.112793 0.280272,0.16919 0.488769,0.16919 0.120767,0 0.237548,-0.01481 0.350342,-0.04443 0.113931,-0.02962 0.226724,-0.07406 0.338379,-0.133301 l 0,0.297363 c -0.112795,0.04785 -0.228436,0.08431 -0.346924,0.109375 -0.118491,0.02507 -0.238689,0.0376 -0.360596,0.0376 -0.305339,0 -0.547445,-0.08887 -0.726318,-0.266601 -0.177735,-0.177734 -0.266602,-0.418131 -0.266601,-0.721192 -1e-6,-0.313312 0.08431,-0.561685 0.252929,-0.745117 0.169759,-0.184569 0.398193,-0.276854 0.685303,-0.276856 0.257486,2e-6 0.460854,0.08317 0.610107,0.249512 0.150389,0.165204 0.225584,0.39022 0.225586,0.675049 m -0.314453,-0.09228 c -0.0023,-0.172037 -0.0507,-0.309325 -0.145263,-0.411865 -0.09343,-0.102538 -0.217612,-0.153807 -0.372559,-0.153809 -0.175457,2e-6 -0.316163,0.04956 -0.422119,0.148682 -0.104819,0.09912 -0.165203,0.238689 -0.181153,0.418701 l 1.121094,-0.0017" />
<path
inkscape:connector-curvature="0"
id="path4189"
style="font-size:3.5px;fill:#ffffff"
d="m 29.856533,53.614437 0,1.155274 -0.314453,0 0,-1.14502 c -2e-6,-0.181151 -0.03532,-0.31673 -0.105957,-0.406738 -0.07064,-0.09 -0.176596,-0.135008 -0.317871,-0.13501 -0.16976,2e-6 -0.303631,0.05412 -0.401612,0.162353 -0.09798,0.108238 -0.146973,0.25578 -0.146972,0.442627 l 0,1.081788 -0.316162,0 0,-1.914063 0.316162,0 0,0.297363 c 0.07519,-0.11507 0.163492,-0.201088 0.264892,-0.258056 0.102538,-0.05697 0.220458,-0.08545 0.35376,-0.08545 0.219888,2e-6 0.386229,0.06836 0.499024,0.205079 0.112791,0.135581 0.169187,0.335532 0.169189,0.599853" />
<path
inkscape:connector-curvature="0"
id="path4191"
style="font-size:3.5px;fill:#ffffff"
d="m 30.798183,52.312191 0,0.543457 0.647706,0 0,0.244385 -0.647706,0 0,1.039062 c 0,0.156088 0.02108,0.256348 0.06323,0.300782 0.04329,0.04443 0.130452,0.06665 0.261474,0.06665 l 0.322999,0 0,0.263184 -0.322999,0 c -0.242676,0 -0.410156,-0.045 -0.502441,-0.13501 -0.09229,-0.09115 -0.138428,-0.256347 -0.138428,-0.495606 l 0,-1.039062 -0.230713,0 0,-0.244385 0.230713,0 0,-0.543457 0.316162,0" />
</g>
<g
id="text3320"
style="font-size:40px;font-style:normal;font-weight:normal;fill:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Bitstream Vera Sans">
<path
inkscape:connector-curvature="0"
id="path4143"
style="font-size:3.5px;fill:#ffffff"
d="m 22.021694,55.589386 0,0.33667 c -0.131024,-0.06266 -0.25464,-0.109373 -0.370849,-0.140137 -0.116213,-0.03076 -0.228436,-0.04614 -0.33667,-0.04614 -0.18799,2e-6 -0.333253,0.03646 -0.435791,0.109375 -0.101401,0.07292 -0.152101,0.176597 -0.1521,0.311035 -1e-6,0.112795 0.03361,0.198244 0.10083,0.256347 0.06836,0.05697 0.197102,0.103111 0.386231,0.138428 l 0.208496,0.04272 c 0.257485,0.04899 0.447182,0.135581 0.569091,0.259765 0.123045,0.123048 0.184569,0.28825 0.184571,0.495606 -2e-6,0.247233 -0.08317,0.434652 -0.249512,0.562256 -0.165203,0.127604 -0.407879,0.191406 -0.728027,0.191406 -0.120769,0 -0.249513,-0.01367 -0.386231,-0.04102 -0.13558,-0.02734 -0.276286,-0.06779 -0.422119,-0.121338 l 0,-0.355468 c 0.140136,0.07861 0.277425,0.137858 0.411865,0.177734 0.13444,0.03988 0.266601,0.05982 0.396485,0.05982 0.197101,0 0.349201,-0.03874 0.456299,-0.116211 0.107094,-0.07747 0.160642,-0.187988 0.160644,-0.331543 -2e-6,-0.125325 -0.03874,-0.223307 -0.116211,-0.293946 -0.07634,-0.07064 -0.202231,-0.123615 -0.377685,-0.158935 L 21.110806,56.88479 C 20.853318,56.83352 20.667039,56.7532 20.551968,56.643823 20.436896,56.53445 20.37936,56.38235 20.37936,56.187525 c 0,-0.225584 0.07918,-0.403319 0.237549,-0.533204 0.159505,-0.12988 0.378824,-0.194821 0.657959,-0.194824 0.119628,3e-6 0.241535,0.01083 0.365723,0.03247 0.124184,0.02165 0.251219,0.05412 0.381103,0.09741" />
<path
inkscape:connector-curvature="0"
id="path4145"
style="font-size:3.5px;fill:#ffffff"
d="m 23.496548,58.234894 c -0.08887,0.227864 -0.175457,0.376545 -0.259766,0.446045 -0.08431,0.0695 -0.197103,0.104247 -0.338379,0.104248 l -0.251221,0 0,-0.263184 0.184571,0 c 0.08659,0 0.153808,-0.02051 0.20166,-0.06152 0.04785,-0.04102 0.100829,-0.137859 0.158935,-0.290528 l 0.0564,-0.143554 -0.77417,-1.883301 0.333252,0 0.598145,1.49707 0.598144,-1.49707 0.333252,0 -0.84082,2.091797" />
<path
inkscape:connector-curvature="0"
id="path4147"
style="font-size:3.5px;fill:#ffffff"
d="m 25.991665,56.199493 0,0.297364 c -0.08887,-0.04557 -0.181154,-0.07975 -0.276856,-0.102539 -0.0957,-0.02278 -0.194825,-0.03418 -0.297363,-0.03418 -0.156088,2e-6 -0.273438,0.02393 -0.352051,0.07178 -0.07747,0.04785 -0.116211,0.119631 -0.116211,0.215332 0,0.07292 0.02791,0.130454 0.08374,0.172608 0.05583,0.04102 0.168049,0.08032 0.33667,0.11792 l 0.107666,0.02392 c 0.223306,0.04785 0.381671,0.115643 0.475097,0.20337 0.09456,0.08659 0.141844,0.207927 0.141846,0.364013 -2e-6,0.177735 -0.07064,0.318441 -0.211914,0.422119 -0.140138,0.103679 -0.333253,0.155518 -0.579346,0.155518 -0.10254,0 -0.209636,-0.01025 -0.321289,-0.03076 -0.110515,-0.01937 -0.227295,-0.04899 -0.350342,-0.08887 l 0,-0.324707 c 0.116211,0.06038 0.230713,0.105957 0.343506,0.136719 0.112793,0.02962 0.224446,0.04443 0.334961,0.04443 0.148111,10e-7 0.262043,-0.02506 0.341797,-0.0752 0.07975,-0.05127 0.119628,-0.123046 0.119629,-0.215332 -10e-7,-0.08545 -0.02905,-0.15096 -0.08716,-0.196533 -0.05697,-0.04557 -0.182863,-0.08944 -0.377686,-0.131592 l -0.109375,-0.02564 c -0.194825,-0.04101 -0.335531,-0.103677 -0.422119,-0.187988 -0.08659,-0.08545 -0.129883,-0.202229 -0.129883,-0.350342 0,-0.180011 0.0638,-0.319009 0.191406,-0.416992 0.127604,-0.09798 0.308756,-0.146971 0.543457,-0.146973 0.11621,2e-6 0.225585,0.0085 0.328125,0.02564 0.102538,0.01709 0.197102,0.04273 0.283692,0.0769" />
<path
inkscape:connector-curvature="0"
id="path4149"
style="font-size:3.5px;fill:#ffffff"
d="m 26.907681,55.59964 0,0.543457 0.647705,0 0,0.244385 -0.647705,0 0,1.039062 c -1e-6,0.156088 0.02108,0.256348 0.06323,0.300781 0.04329,0.04443 0.130452,0.06665 0.261475,0.06665 l 0.322998,0 0,0.263183 -0.322998,0 c -0.242677,0 -0.410157,-0.045 -0.502442,-0.135009 -0.09229,-0.09115 -0.138428,-0.256348 -0.138428,-0.495606 l 0,-1.039062 -0.230712,0 0,-0.244385 0.230712,0 0,-0.543457 0.316163,0" />
<path
inkscape:connector-curvature="0"
id="path4151"
style="font-size:3.5px;fill:#ffffff"
d="m 29.607876,57.021515 0,0.153808 -1.445801,0 c 0.01367,0.216473 0.07861,0.381674 0.194824,0.495606 0.11735,0.112793 0.280273,0.16919 0.48877,0.169189 0.120767,1e-6 0.237547,-0.01481 0.350342,-0.04443 0.11393,-0.02962 0.226723,-0.07406 0.338378,-0.133301 l 0,0.297363 c -0.112794,0.04785 -0.228435,0.08431 -0.346923,0.109375 -0.118491,0.02506 -0.23869,0.0376 -0.360596,0.0376 -0.305339,0 -0.547445,-0.08887 -0.726318,-0.266602 -0.177735,-0.177734 -0.266602,-0.41813 -0.266602,-0.721191 0,-0.313313 0.08431,-0.561685 0.25293,-0.745117 0.169758,-0.184569 0.398192,-0.276854 0.685302,-0.276856 0.257486,2e-6 0.460855,0.08317 0.610108,0.249512 0.150389,0.165203 0.225584,0.390219 0.225586,0.675049 m -0.314453,-0.09229 c -0.0023,-0.172037 -0.0507,-0.309325 -0.145264,-0.411865 -0.09343,-0.102538 -0.217612,-0.153807 -0.372559,-0.153809 -0.175456,2e-6 -0.316162,0.04956 -0.422119,0.148682 -0.104818,0.09912 -0.165202,0.238689 -0.181152,0.418701 l 1.121094,-0.0017" />
<path
inkscape:connector-curvature="0"
id="path4153"
style="font-size:3.5px;fill:#ffffff"
d="m 31.614223,56.510529 c 0.07861,-0.141275 0.172606,-0.245523 0.281983,-0.312745 0.109373,-0.06722 0.238116,-0.100828 0.38623,-0.10083 0.199379,2e-6 0.353188,0.07007 0.461426,0.210205 0.108233,0.138999 0.162351,0.337241 0.162354,0.594727 l 0,1.155273 -0.316162,0 0,-1.145019 c -3e-6,-0.18343 -0.03247,-0.319579 -0.09741,-0.408447 -0.06494,-0.08887 -0.164065,-0.133299 -0.297363,-0.133301 -0.162925,2e-6 -0.291669,0.05412 -0.38623,0.162353 -0.09457,0.108237 -0.141848,0.25578 -0.141846,0.442627 l 0,1.081787 -0.316162,0 0,-1.145019 c -2e-6,-0.184569 -0.03247,-0.320718 -0.09741,-0.408447 -0.06494,-0.08887 -0.165203,-0.133299 -0.300781,-0.133301 -0.160646,2e-6 -0.28825,0.05469 -0.382813,0.164062 -0.09456,0.108237 -0.141846,0.25521 -0.141846,0.440918 l 0,1.081787 -0.316162,0 0,-1.914062 0.316162,0 0,0.297363 c 0.07178,-0.117348 0.157796,-0.203937 0.258057,-0.259765 0.100259,-0.05582 0.219319,-0.08374 0.357178,-0.08374 0.138996,2e-6 0.256916,0.03532 0.353759,0.105957 0.09798,0.07064 0.170327,0.173179 0.217041,0.307618" />
</g>
<g
id="text4548-7"
style="font-size:40px;font-style:normal;font-weight:normal;fill:#ffffff;fill-opacity:1;stroke:none;font-family:Bitstream Vera Sans"
transform="translate(-3.4013125,0)">
<path
inkscape:connector-curvature="0"
id="path3947"
style="font-size:3px;writing-mode:tb-rl;fill:#ffffff"
d="m 51.41621,4.7088294 0.297363,0 0,1.3286133 c 0,0.2343756 0.04248,0.4033208 0.127442,0.5068359 0.08496,0.1025393 0.222655,0.1538088 0.413086,0.1538086 0.189452,2e-7 0.326659,-0.051269 0.411621,-0.1538086 0.08496,-0.1035151 0.12744,-0.2724603 0.127441,-0.5068359 l 0,-1.3286133 0.297364,0 0,1.3652344 c -2e-6,0.2851568 -0.0708,0.5004886 -0.212403,0.6459961 -0.140626,0.1455078 -0.348634,0.2182616 -0.624023,0.2182617 -0.276368,-1e-7 -0.485352,-0.072754 -0.626953,-0.2182617 C 51.486522,6.5745524 51.41621,6.3592206 51.41621,6.0740638 l 0,-1.3652344" />
<path
inkscape:connector-curvature="0"
id="path3949"
style="font-size:3px;writing-mode:tb-rl;fill:#ffffff"
d="m 52.878124,8.2727942 0,0.2885743 c -0.112306,-0.053709 -0.218263,-0.093748 -0.317871,-0.1201172 -0.09961,-0.026365 -0.195802,-0.039549 -0.288574,-0.039551 -0.161134,2e-6 -0.285645,0.031252 -0.373535,0.09375 -0.08692,0.062502 -0.130372,0.1513689 -0.130371,0.2666016 -10e-7,0.096681 0.02881,0.1699233 0.08642,0.2197265 0.05859,0.04883 0.168945,0.08838 0.331055,0.1186524 l 0.178711,0.036621 c 0.220702,0.041993 0.383299,0.116212 0.487793,0.2226562 0.105467,0.1054697 0.158201,0.2470711 0.158203,0.4248047 -2e-6,0.2119145 -0.07129,0.3725593 -0.213867,0.4819343 -0.141603,0.109375 -0.349611,0.164062 -0.624023,0.164062 -0.103517,0 -0.213868,-0.01172 -0.331055,-0.03516 -0.116212,-0.02344 -0.236817,-0.05811 -0.361817,-0.104004 l 0,-0.3046879 c 0.120117,0.067384 0.237793,0.1181649 0.353028,0.1523439 0.115233,0.03418 0.228515,0.05127 0.339844,0.05127 0.168944,0 0.299315,-0.0332 0.391113,-0.09961 0.09179,-0.06641 0.137694,-0.1611323 0.137695,-0.2841796 -1e-6,-0.1074212 -0.0332,-0.1914055 -0.09961,-0.2519532 -0.06543,-0.060546 -0.173341,-0.1059561 -0.323731,-0.1362304 L 52.097357,9.3831418 C 51.876653,9.3391978 51.716985,9.27035 51.618353,9.1765988 c -0.09863,-0.093749 -0.14795,-0.2241196 -0.14795,-0.3911132 0,-0.1933576 0.06787,-0.3457012 0.203614,-0.4570313 0.136718,-0.1113259 0.324706,-0.16699 0.563965,-0.1669922 0.102538,2.2e-6 0.20703,0.00928 0.313476,0.027832 0.106444,0.018557 0.215331,0.046389 0.32666,0.083496" />
<path
inkscape:connector-curvature="0"
id="path3951"
style="font-size:3px;writing-mode:tb-rl;fill:#ffffff"
d="m 52.254101,11.984708 -0.401367,1.088379 0.804199,0 -0.402832,-1.088379 m -0.166992,-0.291504 0.335449,0 0.833496,2.187012 -0.307617,0 -0.199219,-0.561035 -0.98584,0 -0.199219,0.561035 -0.312011,0 0.834961,-2.187012" />
<path
inkscape:connector-curvature="0"
id="path3953"
style="font-size:3px;writing-mode:tb-rl;fill:#ffffff"
d="m 52.651073,16.347013 c 0.06348,0.02148 0.124999,0.06738 0.184571,0.137695 0.06054,0.07031 0.121092,0.166993 0.18164,0.290039 l 0.300293,0.597657 -0.317871,0 -0.279785,-0.561036 c -0.07227,-0.146483 -0.142579,-0.243651 -0.210937,-0.291503 -0.06738,-0.04785 -0.159669,-0.07178 -0.276856,-0.07178 l -0.322265,0 0,0.924317 -0.295899,0 0,-2.187012 0.667969,0 c 0.249999,2e-6 0.436522,0.05225 0.55957,0.156738 0.123045,0.104494 0.184569,0.262209 0.18457,0.473145 -10e-7,0.137696 -0.03223,0.251954 -0.09668,0.342773 -0.06348,0.09082 -0.156252,0.15381 -0.278321,0.188965 m -0.74121,-0.918457 0,0.776367 0.37207,0 c 0.142577,1e-6 0.249999,-0.03271 0.322265,-0.09814 0.07324,-0.0664 0.109862,-0.163573 0.109864,-0.291504 -2e-6,-0.127928 -0.03662,-0.22412 -0.109864,-0.288575 -0.07227,-0.06543 -0.179688,-0.09814 -0.322265,-0.09814 l -0.37207,0" />
<path
inkscape:connector-curvature="0"
id="path3955"
style="font-size:3px;writing-mode:tb-rl;fill:#ffffff"
d="m 51.32832,18.677579 1.850097,0 0,0.249024 -0.776367,0 0,1.937988 -0.297363,0 0,-1.937988 -0.776367,0 0,-0.249024" />
</g>
<g
id="text4554-61"
style="font-size:35.79270172px;font-style:normal;font-weight:normal;fill:#ffffff;fill-opacity:1;stroke:none;font-family:Bitstream Vera Sans"
transform="translate(-3.4013125,0)">
<path
inkscape:connector-curvature="0"
id="path3991"
style="font-size:3.57927036px;fill:#ffffff"
d="m 27.717732,6.5908392 0.576738,0 0,-1.9906196 -0.627421,0.1258337 0,-0.321575 0.623926,-0.1258338 0.353033,0 0,2.3121947 0.576738,0 0,0.2971074 -1.503014,0 0,-0.2971074" />
<path
inkscape:connector-curvature="0"
id="path3993"
style="font-size:3.57927036px;fill:#ffffff"
d="m 29.972253,6.4440332 0.368763,0 0,0.4439134 -0.368763,0 0,-0.4439134 m 0,-1.4068909 0.368763,0 0,0.4439134 -0.368763,0 0,-0.4439134" />
<path
inkscape:connector-curvature="0"
id="path3995"
style="font-size:3.57927036px;fill:#ffffff"
d="m 30.751723,4.2786445 2.207334,0 0,0.2971074 -0.926277,0 0,2.3121947 -0.354781,0 0,-2.3121947 -0.926276,0 0,-0.2971074" />
<path
inkscape:connector-curvature="0"
id="path3997"
style="font-size:3.57927036px;fill:#ffffff"
d="m 34.353713,5.8288461 0,0.1572922 -1.478546,0 c 0.01398,0.2213748 0.08039,0.390318 0.199237,0.5068302 0.120007,0.1153479 0.28662,0.1730216 0.499839,0.1730214 0.123503,2e-7 0.242928,-0.015146 0.358277,-0.04544 0.116511,-0.030293 0.231859,-0.075733 0.346043,-0.1363198 l 0,0.3040981 c -0.11535,0.048935 -0.23361,0.08622 -0.354781,0.1118522 -0.121175,0.025633 -0.244096,0.038449 -0.368763,0.038449 -0.312255,0 -0.559844,-0.09088 -0.742769,-0.2726397 -0.18176,-0.1817594 -0.27264,-0.427601 -0.272639,-0.7375254 -10e-7,-0.3204087 0.08622,-0.5744061 0.258658,-0.7619931 0.173603,-0.1887487 0.407211,-0.2831239 0.700824,-0.2831259 0.263317,2e-6 0.471292,0.085056 0.623925,0.2551628 0.153795,0.168945 0.230693,0.3990574 0.230695,0.6903378 M 34.032138,5.7344709 C 34.029838,5.558538 33.980288,5.4181404 33.883585,5.3132775 33.788045,5.2084177 33.661044,5.155987 33.502588,5.1559853 c -0.17943,1.7e-6 -0.323323,0.050685 -0.431679,0.1520491 -0.107193,0.1013675 -0.168944,0.2440955 -0.185256,0.4281842 l 1.146485,-0.00175" />
<path
inkscape:connector-curvature="0"
id="path3999"
style="font-size:3.57927036px;fill:#ffffff"
d="m 34.881516,4.16854 0.321575,0 0,2.7194066 -0.321575,0 0,-2.7194066" />
<path
inkscape:connector-curvature="0"
id="path4001"
style="font-size:3.57927036px;fill:#ffffff"
d="m 37.548492,5.8288461 0,0.1572922 -1.478546,0 c 0.01398,0.2213748 0.08039,0.390318 0.199237,0.5068302 0.120007,0.1153479 0.28662,0.1730216 0.499839,0.1730214 0.123503,2e-7 0.242928,-0.015146 0.358277,-0.04544 0.116511,-0.030293 0.231858,-0.075733 0.346043,-0.1363198 l 0,0.3040981 c -0.11535,0.048935 -0.23361,0.08622 -0.354781,0.1118522 -0.121175,0.025633 -0.244096,0.038449 -0.368763,0.038449 -0.312255,0 -0.559844,-0.09088 -0.742769,-0.2726397 -0.18176,-0.1817594 -0.27264,-0.427601 -0.272639,-0.7375254 -10e-7,-0.3204087 0.08622,-0.5744061 0.258658,-0.7619931 0.173603,-0.1887487 0.407211,-0.2831239 0.700824,-0.2831259 0.263317,2e-6 0.471292,0.085056 0.623925,0.2551628 0.153795,0.168945 0.230693,0.3990574 0.230695,0.6903378 M 37.226917,5.7344709 C 37.224617,5.558538 37.175067,5.4181404 37.078364,5.3132775 36.982824,5.2084177 36.855823,5.155987 36.697367,5.1559853 c -0.17943,1.7e-6 -0.323324,0.050685 -0.431679,0.1520491 -0.107193,0.1013675 -0.168944,0.2440955 -0.185256,0.4281842 l 1.146485,-0.00175" />
<path
inkscape:connector-curvature="0"
id="path4003"
style="font-size:3.57927036px;fill:#ffffff"
d="m 39.600281,5.3062866 c 0.08039,-0.144474 0.176515,-0.251083 0.288369,-0.3198274 0.11185,-0.06874 0.243509,-0.1031117 0.394978,-0.1031137 0.203895,2e-6 0.361187,0.071657 0.471877,0.2149659 0.110684,0.1421472 0.166027,0.3448791 0.16603,0.6081964 l 0,1.1814388 -0.323322,0 0,-1.1709527 c -3e-6,-0.1875841 -0.03321,-0.3268166 -0.09962,-0.4176981 -0.06641,-0.090878 -0.167781,-0.1363181 -0.304098,-0.1363198 -0.166615,1.7e-6 -0.298275,0.055345 -0.394978,0.1660306 -0.09671,0.1106885 -0.14506,0.2615723 -0.145058,0.4526519 l 0,1.1062881 -0.323323,0 0,-1.1709527 c -2e-6,-0.1887492 -0.03321,-0.3279818 -0.09962,-0.4176981 -0.06641,-0.090878 -0.168945,-0.1363181 -0.307594,-0.1363198 -0.164284,1.7e-6 -0.294778,0.055928 -0.391483,0.1677783 -0.09671,0.1106885 -0.145059,0.2609897 -0.145058,0.4509042 l 0,1.1062881 -0.323323,0 0,-1.9574135 0.323323,0 0,0.3040982 c 0.0734,-0.1200063 0.161369,-0.2085559 0.263901,-0.265649 0.10253,-0.057089 0.224286,-0.085635 0.365268,-0.085637 0.142144,2e-6 0.262734,0.036121 0.361772,0.1083568 0.100199,0.07224 0.174184,0.177101 0.221956,0.3145843" />
<path
inkscape:connector-curvature="0"
id="path4005"
style="font-size:3.57927036px;fill:#ffffff"
d="m 43.238973,5.8288461 0,0.1572922 -1.478547,0 c 0.01398,0.2213748 0.08039,0.390318 0.199237,0.5068302 0.120007,0.1153479 0.28662,0.1730216 0.49984,0.1730214 0.123502,2e-7 0.242927,-0.015146 0.358276,-0.04544 0.116511,-0.030293 0.231859,-0.075733 0.346043,-0.1363198 l 0,0.3040981 c -0.115349,0.048935 -0.23361,0.08622 -0.354781,0.1118522 -0.121175,0.025633 -0.244096,0.038449 -0.368763,0.038449 -0.312255,0 -0.559844,-0.09088 -0.742768,-0.2726397 -0.181761,-0.1817594 -0.27264,-0.427601 -0.27264,-0.7375254 0,-0.3204087 0.08622,-0.5744061 0.258658,-0.7619931 0.173603,-0.1887487 0.407211,-0.2831239 0.700824,-0.2831259 0.263317,2e-6 0.471292,0.085056 0.623925,0.2551628 0.153795,0.168945 0.230694,0.3990574 0.230696,0.6903378 M 42.917398,5.7344709 C 42.915098,5.558538 42.865548,5.4181404 42.768844,5.3132775 42.673304,5.2084177 42.546303,5.155987 42.387847,5.1559853 c -0.17943,1.7e-6 -0.323323,0.050685 -0.431679,0.1520491 -0.107193,0.1013675 -0.168944,0.2440955 -0.185255,0.4281842 l 1.146485,-0.00175" />
<path
inkscape:connector-curvature="0"
id="path4007"
style="font-size:3.57927036px;fill:#ffffff"
d="m 44.084856,4.3747675 0,0.5557656 0.662375,0 0,0.2499198 -0.662375,0 0,1.0625959 c -1e-6,0.1596229 0.02155,0.2621539 0.06466,0.3075935 0.04427,0.04544 0.133407,0.06816 0.267397,0.06816 l 0.330314,0 0,0.2691443 -0.330314,0 c -0.248173,0 -0.419446,-0.046023 -0.513821,-0.1380676 -0.09438,-0.09321 -0.141563,-0.2621531 -0.141563,-0.5068302 l 0,-1.0625959 -0.235938,0 0,-0.2499198 0.235938,0 0,-0.5557656 0.323323,0" />
<path
inkscape:connector-curvature="0"
id="path4009"
style="font-size:3.57927036px;fill:#ffffff"
d="m 46.306169,5.2311359 c -0.03612,-0.020971 -0.07573,-0.036117 -0.118843,-0.04544 -0.04195,-0.010485 -0.08855,-0.015727 -0.139815,-0.015729 -0.181761,1.8e-6 -0.321576,0.059423 -0.419446,0.1782645 -0.09671,0.1176792 -0.145059,0.2872051 -0.145058,0.5085779 l 0,1.0311375 -0.323323,0 0,-1.9574135 0.323323,0 0,0.3040982 c 0.06758,-0.1188412 0.155544,-0.2068082 0.263901,-0.2639013 0.108356,-0.058254 0.240015,-0.087382 0.394978,-0.087384 0.02214,2e-6 0.0466,0.00175 0.0734,0.00524 0.0268,0.00233 0.05651,0.00641 0.08913,0.012234 l 0.0017,0.3303135" />
<path
inkscape:connector-curvature="0"
id="path4011"
style="font-size:3.57927036px;fill:#ffffff"
d="m 47.461394,7.0697064 c -0.09088,0.233025 -0.179431,0.385074 -0.265649,0.4561473 -0.08622,0.071072 -0.201568,0.1066084 -0.346043,0.1066091 l -0.25691,0 0,-0.2691443 0.18875,0 c 0.08855,-5e-7 0.157292,-0.020973 0.206228,-0.062917 0.04893,-0.041945 0.103113,-0.1409807 0.162535,-0.2971074 l 0.05767,-0.146806 -0.791704,-1.9259551 0.340799,0 0.611692,1.530977 0.611692,-1.530977 0.3408,0 -0.859864,2.1391733" />
</g>
<g
id="text4554-7-2"
style="font-size:40px;font-style:normal;font-weight:normal;fill:#ffffff;fill-opacity:1;stroke:none;font-family:Bitstream Vera Sans"
transform="translate(-3.4013125,0)">
<path
inkscape:connector-curvature="0"
id="path3969"
style="font-size:4px;fill:#ffffff"
d="m 28.610962,13.043303 1.376953,0 0,0.332031 -1.851562,0 0,-0.332031 c 0.149739,-0.154948 0.353515,-0.36263 0.611328,-0.623047 0.259113,-0.261718 0.421873,-0.430337 0.488281,-0.50586 0.1263,-0.141925 0.214191,-0.261717 0.263672,-0.359375 0.05078,-0.09896 0.07617,-0.195961 0.07617,-0.291015 -2e-6,-0.154946 -0.05469,-0.281248 -0.164063,-0.378907 -0.108074,-0.09765 -0.24935,-0.146481 -0.423828,-0.146484 -0.123699,3e-6 -0.254558,0.02149 -0.392578,0.06445 -0.136719,0.04297 -0.283204,0.108076 -0.439453,0.195313 l 0,-0.398438 c 0.158853,-0.0638 0.307291,-0.111976 0.445312,-0.144531 0.13802,-0.03255 0.264322,-0.04883 0.378907,-0.04883 0.302081,3e-6 0.542967,0.07552 0.722656,0.226562 0.179685,0.151045 0.269529,0.352867 0.269531,0.605469 -2e-6,0.119794 -0.02279,0.233726 -0.06836,0.341797 -0.04427,0.106772 -0.125653,0.233074 -0.244141,0.378906 -0.03255,0.03776 -0.136069,0.147137 -0.310547,0.328125 -0.17448,0.179689 -0.420574,0.431641 -0.738281,0.75586" />
<path
inkscape:connector-curvature="0"
id="path3971"
style="font-size:4px;fill:#ffffff"
d="m 30.859009,12.87924 0.412109,0 0,0.496094 -0.412109,0 0,-0.496094 m 0,-1.572266 0.412109,0 0,0.496094 -0.412109,0 0,-0.496094" />
<path
inkscape:connector-curvature="0"
id="path3973"
style="font-size:4px;fill:#ffffff"
d="m 34.122681,12.959318 0,-0.783203 -0.644532,0 0,-0.324219 1.035157,0 0,1.251953 c -0.152347,0.108073 -0.320315,0.190105 -0.503907,0.246094 -0.183595,0.05469 -0.379559,0.08203 -0.58789,0.08203 -0.455731,0 -0.812501,-0.132812 -1.070313,-0.398437 -0.25651,-0.266927 -0.384766,-0.63802 -0.384765,-1.113281 -1e-6,-0.476561 0.128255,-0.847654 0.384765,-1.113282 0.257812,-0.266924 0.614582,-0.400387 1.070313,-0.40039 0.190102,3e-6 0.37044,0.02344 0.541015,0.07031 0.171873,0.04688 0.330076,0.115888 0.47461,0.207032 l 0,0.419921 C 34.291298,10.980151 34.13635,10.887052 33.97229,10.82455 33.808225,10.76205 33.6357,10.7308 33.454712,10.7308 c -0.356772,2e-6 -0.625001,0.09961 -0.804688,0.298828 -0.178386,0.199221 -0.267578,0.496095 -0.267578,0.890625 0,0.39323 0.08919,0.689454 0.267578,0.888672 0.179687,0.199219 0.447916,0.298828 0.804688,0.298828 0.139321,0 0.26367,-0.01172 0.373047,-0.03516 0.109373,-0.02474 0.20768,-0.0625 0.294922,-0.113281" />
<path
inkscape:connector-curvature="0"
id="path3975"
style="font-size:4px;fill:#ffffff"
d="m 35.630493,10.783537 0,1.095703 0.496094,0 c 0.183592,2e-6 0.325519,-0.04752 0.425781,-0.142578 0.100259,-0.09505 0.150389,-0.230467 0.150391,-0.40625 -2e-6,-0.174477 -0.05013,-0.309243 -0.150391,-0.404297 -0.100262,-0.09505 -0.242189,-0.142575 -0.425781,-0.142578 l -0.496094,0 m -0.394531,-0.324219 0.890625,0 c 0.326821,3e-6 0.573566,0.07422 0.740234,0.222656 0.167967,0.147138 0.251951,0.363284 0.251953,0.648438 -2e-6,0.287762 -0.08399,0.50521 -0.251953,0.652344 -0.166668,0.147136 -0.413413,0.220704 -0.740234,0.220703 l -0.496094,0 0,1.171875 -0.394531,0 0,-2.916016" />
<path
inkscape:connector-curvature="0"
id="path3977"
style="font-size:4px;fill:#ffffff"
d="m 39.398071,10.555021 0,0.384766 c -0.149741,-0.07161 -0.291017,-0.124998 -0.423828,-0.160156 -0.132814,-0.03515 -0.261069,-0.05273 -0.384765,-0.05274 -0.214845,3e-6 -0.380861,0.04167 -0.498047,0.125 -0.115886,0.08334 -0.173829,0.201826 -0.173828,0.355469 -10e-7,0.128908 0.03841,0.226564 0.115234,0.292969 0.07812,0.06511 0.225259,0.11784 0.441406,0.158203 l 0.238281,0.04883 c 0.294269,0.05599 0.511066,0.154949 0.650391,0.296875 0.140623,0.140626 0.210935,0.329428 0.210938,0.566406 -3e-6,0.282553 -0.09506,0.496745 -0.285157,0.642578 -0.188804,0.145834 -0.466147,0.21875 -0.832031,0.21875 -0.138022,0 -0.285157,-0.01563 -0.441406,-0.04687 -0.154949,-0.03125 -0.315756,-0.07747 -0.482422,-0.138671 l 0,-0.40625 c 0.160156,0.08984 0.317057,0.157552 0.470703,0.203125 0.153645,0.04557 0.304686,0.06836 0.453125,0.06836 0.225259,0 0.399087,-0.04427 0.521484,-0.132813 0.122394,-0.08854 0.183592,-0.214843 0.183594,-0.378906 -2e-6,-0.143228 -0.04427,-0.255207 -0.132812,-0.335937 -0.08724,-0.08073 -0.231122,-0.141275 -0.431641,-0.181641 l -0.240234,-0.04687 c -0.294272,-0.05859 -0.507162,-0.150389 -0.638672,-0.275391 -0.131511,-0.124998 -0.197266,-0.298826 -0.197266,-0.521484 0,-0.25781 0.09049,-0.460935 0.271485,-0.609375 0.18229,-0.148435 0.432941,-0.222653 0.751953,-0.222656 0.136717,3e-6 0.27604,0.01237 0.417968,0.03711 0.141926,0.02474 0.287108,0.06185 0.435547,0.111328" />
</g>
<rect
y="15.137716"
x="22.697004"
height="5.6002355"
width="23.347105"
id="rect4122"
style="fill:none;stroke:#ffffff;stroke-width:0.29055119;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
<g
id="text4124"
style="font-size:40px;font-style:normal;font-weight:normal;fill:#ffffff;fill-opacity:1;stroke:none;font-family:Bitstream Vera Sans"
transform="translate(-3.4013125,0)">
<path
inkscape:connector-curvature="0"
id="path3958"
style="font-size:4px;fill:#ffffff"
d="m 29.466431,17.803068 c 0.1888,0.04037 0.335935,0.124351 0.441406,0.251953 0.106769,0.127606 0.160154,0.285158 0.160156,0.472657 -2e-6,0.287761 -0.09896,0.510417 -0.296875,0.667968 -0.197918,0.157552 -0.479168,0.236328 -0.84375,0.236328 -0.122397,0 -0.248699,-0.01237 -0.378906,-0.03711 -0.128907,-0.02344 -0.26237,-0.05925 -0.400391,-0.107422 l 0,-0.380859 c 0.109375,0.0638 0.229166,0.111979 0.359375,0.144531 0.130208,0.03255 0.266275,0.04883 0.408203,0.04883 0.247395,0 0.435546,-0.04883 0.564454,-0.146484 0.130206,-0.09766 0.19531,-0.239583 0.195312,-0.425781 -2e-6,-0.171874 -0.06055,-0.305989 -0.181641,-0.402344 -0.119793,-0.09765 -0.28711,-0.146483 -0.501953,-0.146485 l -0.339843,0 0,-0.324218 0.355468,0 c 0.194009,1e-6 0.342447,-0.03841 0.445313,-0.115235 0.102863,-0.07812 0.154295,-0.190102 0.154297,-0.335937 -2e-6,-0.149737 -0.05339,-0.264321 -0.160157,-0.34375 -0.10547,-0.08073 -0.257162,-0.121091 -0.455078,-0.121094 -0.108074,3e-6 -0.223959,0.01172 -0.347656,0.03516 -0.123699,0.02344 -0.259766,0.0599 -0.408203,0.109375 l 0,-0.351562 c 0.149739,-0.04166 0.289713,-0.07291 0.419922,-0.09375 0.131509,-0.02083 0.255207,-0.03125 0.371094,-0.03125 0.299477,3e-6 0.536456,0.06836 0.710937,0.205078 0.174477,0.135419 0.261717,0.319013 0.261719,0.550781 -2e-6,0.161461 -0.04623,0.298179 -0.138672,0.410156 -0.09245,0.110679 -0.22396,0.187502 -0.394531,0.230469" />
<path
inkscape:connector-curvature="0"
id="path3960"
style="font-size:4px;fill:#ffffff"
d="m 30.859009,18.87924 0.412109,0 0,0.496094 -0.412109,0 0,-0.496094 m 0,-1.572266 0.412109,0 0,0.496094 -0.412109,0 0,-0.496094" />
<path
inkscape:connector-curvature="0"
id="path3962"
style="font-size:4px;fill:#ffffff"
d="m 33.109009,16.84799 -0.535156,1.451172 1.072265,0 -0.537109,-1.451172 m -0.222656,-0.388672 0.447265,0 1.111328,2.916016 -0.410156,0 -0.265625,-0.748047 -1.314453,0 -0.265625,0.748047 -0.416016,0 1.113282,-2.916016" />
<path
inkscape:connector-curvature="0"
id="path3964"
style="font-size:4px;fill:#ffffff"
d="m 34.823853,16.459318 0.396484,0 0,1.771485 c -10e-7,0.3125 0.05664,0.537761 0.169922,0.675781 0.11328,0.136719 0.296874,0.205078 0.550781,0.205078 0.252602,0 0.435545,-0.06836 0.548828,-0.205078 0.113279,-0.13802 0.16992,-0.363281 0.169922,-0.675781 l 0,-1.771485 0.396484,0 0,1.820313 c -2e-6,0.380209 -0.0944,0.667318 -0.283203,0.861328 -0.187502,0.19401 -0.464845,0.291015 -0.832031,0.291015 -0.368491,0 -0.647136,-0.097 -0.835937,-0.291015 -0.187501,-0.19401 -0.281251,-0.481119 -0.28125,-0.861328 l 0,-1.820313" />
<path
inkscape:connector-curvature="0"
id="path3966"
style="font-size:4px;fill:#ffffff"
d="m 37.657837,16.459318 0.423828,0 0.724609,1.083985 0.728516,-1.083985 0.423828,0 -0.9375,1.400391 1,1.515625 -0.423828,0 -0.820312,-1.240235 -0.826172,1.240235 -0.425782,0 1.041016,-1.556641 -0.908203,-1.359375" />
</g>
<g
id="text3100"
style="font-size:26.84721947px;font-style:normal;font-weight:normal;fill:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Bitstream Vera Sans">
<path
inkscape:connector-curvature="0"
id="path4156"
style="font-size:2.68472195px;fill:#ffffff"
d="m 40.321019,54.44599 0,0.258247 c -0.100503,-0.04807 -0.195325,-0.0839 -0.284465,-0.107494 -0.08914,-0.02359 -0.175224,-0.03539 -0.258247,-0.03539 -0.1442,1e-6 -0.255626,0.02797 -0.334279,0.0839 -0.07778,0.05593 -0.116671,0.135461 -0.11667,0.238584 -10e-7,0.08652 0.02578,0.152066 0.07734,0.196635 0.05243,0.0437 0.151189,0.07909 0.296263,0.106183 l 0.15993,0.03277 c 0.197507,0.03758 0.343017,0.103999 0.436529,0.199257 0.09438,0.09438 0.141576,0.221106 0.141577,0.380161 -10e-7,0.189643 -0.0638,0.333405 -0.191391,0.431286 -0.126722,0.09788 -0.312869,0.14682 -0.558443,0.14682 -0.09264,0 -0.191392,-0.01049 -0.296264,-0.03146 -0.103998,-0.02097 -0.211929,-0.052 -0.323792,-0.09307 l 0,-0.272667 c 0.107494,0.0603 0.212803,0.105746 0.315927,0.136333 0.103124,0.03059 0.2045,0.04588 0.304129,0.04588 0.151189,0 0.267859,-0.02971 0.35001,-0.08914 0.08215,-0.05943 0.123223,-0.144199 0.123224,-0.254315 -10e-7,-0.09613 -0.02971,-0.17129 -0.08914,-0.225475 -0.05855,-0.05418 -0.155124,-0.09482 -0.289708,-0.121913 l -0.161241,-0.03146 c -0.197509,-0.03933 -0.340397,-0.100938 -0.428664,-0.184837 -0.08827,-0.0839 -0.132401,-0.200566 -0.132401,-0.35001 0,-0.173037 0.06074,-0.30937 0.182215,-0.409 0.12235,-0.09963 0.290582,-0.149441 0.504696,-0.149443 0.09176,2e-6 0.185273,0.0083 0.280533,0.02491 0.09526,0.01661 0.192701,0.04151 0.29233,0.07472" />
<path
inkscape:connector-curvature="0"
id="path4158"
style="font-size:2.68472195px;fill:#ffffff"
d="m 41.08003,54.453855 0,0.416866 0.496831,0 0,0.187459 -0.496831,0 0,0.797026 c -10e-7,0.11973 0.01617,0.196636 0.0485,0.230719 0.03321,0.03408 0.100065,0.05112 0.200568,0.05112 l 0.24776,0 0,0.201878 -0.24776,0 c -0.186148,0 -0.314616,-0.03452 -0.385405,-0.103561 -0.07079,-0.06991 -0.106183,-0.196634 -0.106182,-0.380161 l 0,-0.797026 -0.176972,0 0,-0.187459 0.176972,0 0,-0.416866 0.242516,0" />
<path
inkscape:connector-curvature="0"
id="path4160"
style="font-size:2.68472195px;fill:#ffffff"
d="m 42.562657,55.600892 c -0.194888,10e-7 -0.32991,0.02229 -0.405068,0.06686 -0.07516,0.04457 -0.112738,0.120603 -0.112737,0.228096 -10e-7,0.08565 0.02797,0.153813 0.0839,0.204501 0.05681,0.04981 0.133712,0.07472 0.230719,0.07472 0.133711,0 0.240767,-0.04719 0.32117,-0.141577 0.08127,-0.09526 0.121913,-0.221542 0.121914,-0.37885 l 0,-0.05375 -0.239895,0 m 0.4811,-0.09963 0,0.837664 -0.241205,0 0,-0.222853 c -0.05506,0.08914 -0.123663,0.155123 -0.205811,0.197946 -0.08215,0.04195 -0.182653,0.06292 -0.301507,0.06292 -0.150317,0 -0.270046,-0.04195 -0.359187,-0.125846 -0.08827,-0.08477 -0.132401,-0.197946 -0.132401,-0.339523 0,-0.165173 0.05506,-0.289708 0.165174,-0.373606 0.110989,-0.0839 0.276162,-0.125846 0.49552,-0.125847 l 0.338212,0 0,-0.0236 c -10e-7,-0.110988 -0.03671,-0.196634 -0.110116,-0.256936 -0.07254,-0.06117 -0.174787,-0.09176 -0.30675,-0.09176 -0.0839,10e-7 -0.165611,0.01005 -0.245138,0.03015 -0.07953,0.0201 -0.155998,0.05025 -0.229408,0.09045 l 0,-0.222853 c 0.08827,-0.03408 0.173912,-0.05943 0.256936,-0.07603 0.08302,-0.01748 0.163862,-0.02622 0.242517,-0.02622 0.212365,10e-7 0.370983,0.05506 0.475856,0.165173 0.104871,0.110117 0.157307,0.277038 0.157308,0.500764" />
<path
inkscape:connector-curvature="0"
id="path4162"
style="font-size:2.68472195px;fill:#ffffff"
d="m 44.595862,55.606135 c -10e-7,-0.177407 -0.03671,-0.316362 -0.110115,-0.416866 -0.07254,-0.101375 -0.172603,-0.152063 -0.300196,-0.152064 -0.127595,10e-7 -0.228097,0.05069 -0.301507,0.152064 -0.07254,0.100504 -0.108805,0.239459 -0.108805,0.416866 0,0.177409 0.03627,0.316802 0.108805,0.418177 0.07341,0.100503 0.173912,0.150754 0.301507,0.150754 0.127593,0 0.227658,-0.05025 0.300196,-0.150754 0.07341,-0.101375 0.110114,-0.240768 0.110115,-0.418177 m -0.820623,-0.512561 c 0.05069,-0.08739 0.114485,-0.152063 0.191392,-0.194013 0.07778,-0.04282 0.170416,-0.06423 0.27791,-0.06423 0.178281,1e-6 0.322917,0.07079 0.433908,0.212365 0.111862,0.141579 0.167794,0.327726 0.167795,0.558443 -10e-7,0.230719 -0.05593,0.416867 -0.167795,0.558444 -0.110991,0.141577 -0.255627,0.212365 -0.433908,0.212365 -0.107494,0 -0.200131,-0.02097 -0.27791,-0.06292 -0.07691,-0.04282 -0.140704,-0.10793 -0.191392,-0.195324 l 0,0.220231 -0.242516,0 0,-2.039759 0.242516,0 0,0.794405" />
<path
inkscape:connector-curvature="0"
id="path4164"
style="font-size:2.68472195px;fill:#ffffff"
d="m 45.246068,54.870721 0.241205,0 0,1.468207 -0.241205,0 0,-1.468207 m 0,-0.571552 0.241205,0 0,0.305439 -0.241205,0 0,-0.305439" />
<path
inkscape:connector-curvature="0"
id="path4166"
style="font-size:2.68472195px;fill:#ffffff"
d="m 45.990659,54.299169 0.241206,0 0,2.039759 -0.241206,0 0,-2.039759" />
<path
inkscape:connector-curvature="0"
id="path4168"
style="font-size:2.68472195px;fill:#ffffff"
d="m 46.73525,54.870721 0.241205,0 0,1.468207 -0.241205,0 0,-1.468207 m 0,-0.571552 0.241205,0 0,0.305439 -0.241205,0 0,-0.305439" />
<path
inkscape:connector-curvature="0"
id="path4170"
style="font-size:2.68472195px;fill:#ffffff"
d="m 47.374969,54.870721 1.145726,0 0,0.220231 -0.907143,1.055274 0.907143,0 0,0.192702 -1.178499,0 0,-0.220231 0.907143,-1.055274 -0.87437,0 0,-0.192702" />
<path
inkscape:connector-curvature="0"
id="path4172"
style="font-size:2.68472195px;fill:#ffffff"
d="m 49.557617,55.600892 c -0.194888,10e-7 -0.329911,0.02229 -0.405068,0.06686 -0.07516,0.04457 -0.112738,0.120603 -0.112738,0.228096 0,0.08565 0.02797,0.153813 0.0839,0.204501 0.05681,0.04981 0.133711,0.07472 0.230718,0.07472 0.133711,0 0.240768,-0.04719 0.321171,-0.141577 0.08127,-0.09526 0.121912,-0.221542 0.121913,-0.37885 l 0,-0.05375 -0.239894,0 m 0.4811,-0.09963 0,0.837664 -0.241206,0 0,-0.222853 c -0.05506,0.08914 -0.123662,0.155123 -0.205811,0.197946 -0.08215,0.04195 -0.182653,0.06292 -0.301507,0.06292 -0.150317,0 -0.270045,-0.04195 -0.359186,-0.125846 -0.08827,-0.08477 -0.132401,-0.197946 -0.132401,-0.339523 0,-0.165173 0.05506,-0.289708 0.165173,-0.373606 0.110989,-0.0839 0.276162,-0.125846 0.49552,-0.125847 l 0.338212,0 0,-0.0236 c -1e-6,-0.110988 -0.03671,-0.196634 -0.110115,-0.256936 -0.07254,-0.06117 -0.174788,-0.09176 -0.306751,-0.09176 -0.0839,10e-7 -0.165611,0.01005 -0.245138,0.03015 -0.07953,0.0201 -0.155997,0.05025 -0.229407,0.09045 l 0,-0.222853 c 0.08827,-0.03408 0.173912,-0.05943 0.256936,-0.07603 0.08302,-0.01748 0.163862,-0.02622 0.242516,-0.02622 0.212365,10e-7 0.370984,0.05506 0.475857,0.165173 0.10487,0.110117 0.157306,0.277038 0.157308,0.500764" />
<path
inkscape:connector-curvature="0"
id="path4174"
style="font-size:2.68472195px;fill:#ffffff"
d="m 50.775442,54.453855 0,0.416866 0.496831,0 0,0.187459 -0.496831,0 0,0.797026 c -10e-7,0.11973 0.01617,0.196636 0.0485,0.230719 0.03321,0.03408 0.100065,0.05112 0.200568,0.05112 l 0.24776,0 0,0.201878 -0.24776,0 c -0.186149,0 -0.314617,-0.03452 -0.385405,-0.103561 -0.07079,-0.06991 -0.106183,-0.196634 -0.106183,-0.380161 l 0,-0.797026 -0.176971,0 0,-0.187459 0.176971,0 0,-0.416866 0.242517,0" />
<path
inkscape:connector-curvature="0"
id="path4176"
style="font-size:2.68472195px;fill:#ffffff"
d="m 51.590821,54.870721 0.241205,0 0,1.468207 -0.241205,0 0,-1.468207 m 0,-0.571552 0.241205,0 0,0.305439 -0.241205,0 0,-0.305439" />
<path
inkscape:connector-curvature="0"
id="path4178"
style="font-size:2.68472195px;fill:#ffffff"
d="m 52.904343,55.039827 c -0.129343,10e-7 -0.231593,0.05069 -0.306751,0.152064 -0.07516,0.100504 -0.112737,0.238585 -0.112737,0.414244 0,0.175662 0.03714,0.31418 0.111426,0.415556 0.07516,0.100502 0.177845,0.150753 0.308062,0.150753 0.128467,0 0.23028,-0.05069 0.305439,-0.152064 0.07516,-0.101376 0.112736,-0.239457 0.112738,-0.414245 -2e-6,-0.173911 -0.03758,-0.311556 -0.112738,-0.412933 -0.07516,-0.102249 -0.176972,-0.153374 -0.305439,-0.153375 m 0,-0.2045 c 0.209743,10e-7 0.374479,0.06817 0.494209,0.2045 0.119727,0.136335 0.179592,0.325104 0.179593,0.566308 -10e-7,0.240333 -0.05987,0.429102 -0.179593,0.566309 -0.11973,0.136334 -0.284466,0.2045 -0.494209,0.2045 -0.210619,0 -0.375792,-0.06817 -0.49552,-0.2045 -0.118855,-0.137207 -0.178283,-0.325976 -0.178282,-0.566309 -1e-6,-0.241204 0.05943,-0.429973 0.178282,-0.566308 0.119728,-0.136332 0.284901,-0.204499 0.49552,-0.2045" />
<path
inkscape:connector-curvature="0"
id="path4180"
style="font-size:2.68472195px;fill:#ffffff"
d="m 55.197106,55.45276 0,0.886168 -0.241206,0 0,-0.878302 c -10e-7,-0.138955 -0.02709,-0.242953 -0.08128,-0.311994 -0.05418,-0.06904 -0.13546,-0.10356 -0.243827,-0.103561 -0.130217,10e-7 -0.232904,0.04151 -0.308061,0.124535 -0.07516,0.08302 -0.112738,0.196199 -0.112738,0.339523 l 0,0.829799 -0.242516,0 0,-1.468207 0.242516,0 0,0.228096 c 0.05768,-0.08826 0.125409,-0.154247 0.20319,-0.197945 0.07865,-0.0437 0.169105,-0.06554 0.271356,-0.06555 0.168668,1e-6 0.296262,0.05244 0.382783,0.157308 0.08652,0.103999 0.129777,0.257374 0.129779,0.460125" />
</g>
<g
id="text3316-4"
style="font-size:40px;font-style:normal;font-weight:normal;fill:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Bitstream Vera Sans">
<path
inkscape:connector-curvature="0"
id="path4130"
style="font-size:3.5px;fill:#ffffff"
d="m 62.94241,52.192474 1.466308,0 0,0.290528 -1.121094,0 0,0.751953 1.011719,0 0,0.290527 -1.011719,0 0,1.218506 -0.345214,0 0,-2.551514" />
<path
inkscape:connector-curvature="0"
id="path4132"
style="font-size:3.5px;fill:#ffffff"
d="m 64.945339,52.084808 0.314453,0 0,2.65918 -0.314453,0 0,-2.65918" />
<path
inkscape:connector-curvature="0"
id="path4134"
style="font-size:3.5px;fill:#ffffff"
d="m 65.916042,52.829926 0.314453,0 0,1.914062 -0.314453,0 0,-1.914062 m 0,-0.745118 0.314453,0 0,0.398194 -0.314453,0 0,-0.398194" />
<path
inkscape:connector-curvature="0"
id="path4136"
style="font-size:3.5px;fill:#ffffff"
d="m 68.146267,53.76474 c -2e-6,-0.227863 -0.04728,-0.404458 -0.141846,-0.529785 -0.09343,-0.125324 -0.225017,-0.187987 -0.394775,-0.187988 -0.168621,10e-7 -0.300212,0.06266 -0.394776,0.187988 -0.09343,0.125327 -0.140137,0.301922 -0.140136,0.529785 -1e-6,0.226726 0.04671,0.402751 0.140136,0.528076 0.09456,0.125326 0.226155,0.187989 0.394776,0.187988 0.169758,10e-7 0.301349,-0.06266 0.394775,-0.187988 0.09456,-0.125325 0.141844,-0.30135 0.141846,-0.528076 m 0.314453,0.741699 c -2e-6,0.325846 -0.07235,0.567952 -0.217041,0.726319 -0.144696,0.159504 -0.366294,0.239257 -0.664795,0.239257 -0.110515,0 -0.214763,-0.0085 -0.312744,-0.02563 -0.09798,-0.01595 -0.193116,-0.04102 -0.2854,-0.0752 l 0,-0.305908 c 0.09228,0.05013 0.18343,0.08716 0.273437,0.111084 0.09001,0.02392 0.181721,0.03589 0.275147,0.03589 0.206216,-1e-6 0.360594,-0.05412 0.463134,-0.162354 0.102538,-0.107096 0.153807,-0.26945 0.153809,-0.48706 l 0,-0.155518 c -0.06494,0.112793 -0.148113,0.197103 -0.249512,0.25293 -0.101401,0.05583 -0.222739,0.08374 -0.364013,0.08374 -0.234702,0 -0.423829,-0.08944 -0.567383,-0.268311 -0.143555,-0.178873 -0.215332,-0.415852 -0.215332,-0.710937 0,-0.296223 0.07178,-0.533771 0.215332,-0.712646 0.143554,-0.178872 0.332681,-0.268309 0.567383,-0.268311 0.141274,2e-6 0.262612,0.02792 0.364013,0.08374 0.101399,0.05583 0.184569,0.140139 0.249512,0.25293 l 0,-0.290527 0.314453,0 0,1.676513" />
<path
inkscape:connector-curvature="0"
id="path4138"
style="font-size:3.5px;fill:#ffffff"
d="m 70.69949,53.588715 0,1.155273 -0.314454,0 0,-1.145019 c -10e-7,-0.181152 -0.03532,-0.316731 -0.105957,-0.406739 -0.07064,-0.09001 -0.176596,-0.135008 -0.317871,-0.13501 -0.16976,2e-6 -0.30363,0.05412 -0.401611,0.162354 -0.09798,0.108237 -0.146973,0.255779 -0.146973,0.442627 l 0,1.081787 -0.316162,0 0,-2.65918 0.316162,0 0,1.042481 c 0.0752,-0.11507 0.163492,-0.201089 0.264893,-0.258057 0.102538,-0.05696 0.220458,-0.08545 0.35376,-0.08545 0.219888,2e-6 0.386229,0.06836 0.499023,0.205078 0.112791,0.135581 0.169188,0.335532 0.16919,0.599854" />
<path
inkscape:connector-curvature="0"
id="path4140"
style="font-size:3.5px;fill:#ffffff"
d="m 71.64114,52.286469 0,0.543457 0.647705,0 0,0.244384 -0.647705,0 0,1.039063 c -10e-7,0.156088 0.02108,0.256348 0.06323,0.300781 0.04329,0.04443 0.130452,0.06665 0.261475,0.06665 l 0.322998,0 0,0.263184 -0.322998,0 c -0.242676,0 -0.410157,-0.045 -0.502441,-0.13501 -0.09229,-0.09114 -0.138428,-0.256347 -0.138428,-0.495605 l 0,-1.039063 -0.230713,0 0,-0.244384 0.230713,0 0,-0.543457 0.316162,0" />
</g>
<g
id="text3316-4-1"
style="font-size:40px;font-style:normal;font-weight:normal;fill:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Bitstream Vera Sans">
<path
inkscape:connector-curvature="0"
id="path4121"
style="font-size:3.5px;fill:#ffffff"
d="m 63.420925,55.506077 2.158447,0 0,0.290527 -0.905761,0 0,2.260986 -0.346924,0 0,-2.260986 -0.905762,0 0,-0.290527" />
<path
inkscape:connector-curvature="0"
id="path4123"
style="font-size:3.5px;fill:#ffffff"
d="m 65.791286,56.143528 0.314454,0 0,1.914062 -0.314454,0 0,-1.914062 m 0,-0.745117 0.314454,0 0,0.398193 -0.314454,0 0,-0.398193" />
<path
inkscape:connector-curvature="0"
id="path4125"
style="font-size:3.5px;fill:#ffffff"
d="m 68.252224,56.51096 c 0.07861,-0.141275 0.172605,-0.245523 0.281982,-0.312745 0.109373,-0.06722 0.238117,-0.100828 0.386231,-0.10083 0.199379,2e-6 0.353187,0.07007 0.461426,0.210205 0.108232,0.138999 0.16235,0.337241 0.162353,0.594727 l 0,1.155273 -0.316162,0 0,-1.145019 c -3e-6,-0.18343 -0.03247,-0.319579 -0.09741,-0.408447 -0.06494,-0.08887 -0.164065,-0.133299 -0.297363,-0.133301 -0.162926,2e-6 -0.291669,0.05412 -0.386231,0.162353 -0.09457,0.108238 -0.141847,0.25578 -0.141846,0.442627 l 0,1.081787 -0.316162,0 0,-1.145019 c -10e-7,-0.184569 -0.03247,-0.320718 -0.09741,-0.408447 -0.06494,-0.08887 -0.165203,-0.133299 -0.300781,-0.133301 -0.160646,2e-6 -0.28825,0.05469 -0.382812,0.164062 -0.09456,0.108237 -0.141847,0.25521 -0.141846,0.440918 l 0,1.081787 -0.316162,0 0,-1.914062 0.316162,0 0,0.297363 c 0.07178,-0.117348 0.157795,-0.203937 0.258056,-0.259765 0.10026,-0.05582 0.219319,-0.08374 0.357178,-0.08374 0.138996,2e-6 0.256916,0.03532 0.35376,0.105957 0.09798,0.07064 0.170327,0.173179 0.217041,0.307618" />
<path
inkscape:connector-curvature="0"
id="path4127"
style="font-size:3.5px;fill:#ffffff"
d="m 71.810329,57.021946 0,0.153809 -1.4458,0 c 0.01367,0.216472 0.07861,0.381673 0.194824,0.495605 0.117349,0.112793 0.280272,0.16919 0.488769,0.169189 0.120767,10e-7 0.237548,-0.01481 0.350342,-0.04443 0.113931,-0.02962 0.226724,-0.07406 0.338379,-0.133301 l 0,0.297363 c -0.112795,0.04785 -0.228436,0.08431 -0.346924,0.109375 -0.118491,0.02506 -0.238689,0.0376 -0.360595,0.0376 -0.30534,0 -0.547446,-0.08887 -0.726319,-0.266602 -0.177734,-0.177734 -0.266602,-0.41813 -0.266601,-0.721191 -10e-7,-0.313312 0.08431,-0.561685 0.252929,-0.745117 0.169759,-0.184569 0.398193,-0.276854 0.685303,-0.276856 0.257486,2e-6 0.460855,0.08317 0.610107,0.249512 0.150389,0.165203 0.225584,0.39022 0.225586,0.675049 m -0.314453,-0.09228 c -0.0023,-0.172037 -0.0507,-0.309325 -0.145263,-0.411865 -0.09343,-0.102538 -0.217612,-0.153807 -0.372559,-0.153809 -0.175457,2e-6 -0.316163,0.04956 -0.422119,0.148682 -0.104818,0.09912 -0.165202,0.238689 -0.181152,0.418701 l 1.121093,-0.0017" />
</g>
<g
id="text3349"
style="font-size:40px;font-style:normal;font-weight:normal;fill:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Bitstream Vera Sans">
<path
inkscape:connector-curvature="0"
id="path4225"
style="font-size:4px;fill:#ffffff"
d="m 61.061916,34.301922 -0.535156,1.451172 1.072266,0 -0.53711,-1.451172 m -0.222656,-0.388672 0.447266,0 1.111328,2.916016 -0.410156,0 -0.265625,-0.748047 -1.314454,0 -0.265625,0.748047 -0.416015,0 1.113281,-2.916016" />
<path
inkscape:connector-curvature="0"
id="path4227"
style="font-size:4px;fill:#ffffff"
d="m 63.091213,34.020672 0,0.621094 0.740235,0 0,0.279296 -0.740235,0 0,1.1875 c -1e-6,0.178386 0.02409,0.29297 0.07227,0.34375 0.04948,0.05078 0.149087,0.07617 0.298828,0.07617 l 0.369141,0 0,0.300782 -0.369141,0 c -0.277345,0 -0.468751,-0.05143 -0.574219,-0.154297 C 62.782619,36.570802 62.729885,36.382 62.729885,36.108562 l 0,-1.1875 -0.263672,0 0,-0.279296 0.263672,0 0,-0.621094 0.361328,0" />
<path
inkscape:connector-curvature="0"
id="path4229"
style="font-size:4px;fill:#ffffff"
d="m 64.661526,34.020672 0,0.621094 0.740234,0 0,0.279296 -0.740234,0 0,1.1875 c -10e-7,0.178386 0.02409,0.29297 0.07227,0.34375 0.04948,0.05078 0.149088,0.07617 0.298828,0.07617 l 0.369141,0 0,0.300782 -0.369141,0 c -0.277344,0 -0.46875,-0.05143 -0.574218,-0.154297 C 64.352932,36.570802 64.300197,36.382 64.300198,36.108562 l 0,-1.1875 -0.263672,0 0,-0.279296 0.263672,0 0,-0.621094 0.361328,0" />
<path
inkscape:connector-curvature="0"
id="path4231"
style="font-size:4px;fill:#ffffff"
d="m 65.876369,34.641766 0.359375,0 0,2.1875 -0.359375,0 0,-2.1875 m 0,-0.851563 0.359375,0 0,0.455078 -0.359375,0 0,-0.455078" />
<path
inkscape:connector-curvature="0"
id="path4233"
style="font-size:4px;fill:#ffffff"
d="m 67.341213,34.020672 0,0.621094 0.740235,0 0,0.279296 -0.740235,0 0,1.1875 c -10e-7,0.178386 0.02409,0.29297 0.07227,0.34375 0.04948,0.05078 0.149087,0.07617 0.298828,0.07617 l 0.369141,0 0,0.300782 -0.369141,0 c -0.277345,0 -0.468751,-0.05143 -0.574219,-0.154297 C 67.032619,36.570802 66.979885,36.382 66.979885,36.108562 l 0,-1.1875 -0.263672,0 0,-0.279296 0.263672,0 0,-0.621094 0.361328,0" />
<path
inkscape:connector-curvature="0"
id="path4235"
style="font-size:4px;fill:#ffffff"
d="m 68.518948,35.965984 0,-1.324218 0.359375,0 0,1.310546 c -10e-7,0.207032 0.04036,0.362631 0.121093,0.466797 0.08073,0.102865 0.201822,0.154297 0.363282,0.154297 0.194009,0 0.347003,-0.06185 0.458984,-0.185547 0.113279,-0.123697 0.16992,-0.292317 0.169922,-0.505859 l 0,-1.240234 0.359375,0 0,2.1875 -0.359375,0 0,-0.335938 c -0.08724,0.132813 -0.188804,0.231771 -0.304688,0.296875 -0.114584,0.0638 -0.248048,0.0957 -0.40039,0.0957 -0.251303,0 -0.442058,-0.07813 -0.572266,-0.234375 -0.130209,-0.156249 -0.195313,-0.384765 -0.195312,-0.685547 m 0.904296,-1.376953 0,0" />
<path
inkscape:connector-curvature="0"
id="path4237"
style="font-size:4px;fill:#ffffff"
d="m 72.534573,34.973797 0,-1.183594 0.359375,0 0,3.039063 -0.359375,0 0,-0.328125 c -0.07552,0.130208 -0.171226,0.227213 -0.28711,0.291015 -0.114585,0.0625 -0.252605,0.09375 -0.414062,0.09375 -0.264324,0 -0.479819,-0.105468 -0.646485,-0.316406 -0.165365,-0.210937 -0.248047,-0.488281 -0.248047,-0.832031 0,-0.343749 0.08268,-0.621092 0.248047,-0.832032 0.166666,-0.210935 0.382161,-0.316404 0.646485,-0.316406 0.161457,2e-6 0.299477,0.0319 0.414062,0.0957 0.115884,0.0625 0.211587,0.158856 0.28711,0.289063 m -1.22461,0.763672 c 0,0.264323 0.05404,0.472006 0.16211,0.623047 0.109374,0.149739 0.259113,0.224609 0.449218,0.224609 0.190103,0 0.339843,-0.07487 0.449219,-0.224609 0.109373,-0.151041 0.164061,-0.358724 0.164063,-0.623047 -2e-6,-0.264322 -0.05469,-0.471353 -0.164063,-0.621094 -0.109376,-0.15104 -0.259116,-0.226561 -0.449219,-0.226563 -0.190105,2e-6 -0.339844,0.07552 -0.449218,0.226563 -0.108074,0.149741 -0.16211,0.356772 -0.16211,0.621094" />
<path
inkscape:connector-curvature="0"
id="path4239"
style="font-size:4px;fill:#ffffff"
d="m 75.505276,35.645672 0,0.175781 -1.652344,0 c 0.01562,0.247397 0.08984,0.436199 0.222656,0.566406 0.134114,0.128907 0.320312,0.19336 0.558594,0.19336 0.138019,0 0.271483,-0.01693 0.400391,-0.05078 0.130206,-0.03385 0.259112,-0.08463 0.386718,-0.152343 l 0,0.339843 c -0.128908,0.05469 -0.261069,0.09636 -0.396484,0.125 -0.135418,0.02865 -0.272788,0.04297 -0.412109,0.04297 -0.34896,0 -0.625652,-0.101562 -0.830079,-0.304687 -0.203125,-0.203125 -0.304687,-0.477864 -0.304687,-0.824219 0,-0.358072 0.09635,-0.641925 0.289062,-0.851563 0.19401,-0.210935 0.455078,-0.316404 0.783204,-0.316406 0.294269,2e-6 0.52669,0.09505 0.697265,0.285156 0.171873,0.188804 0.25781,0.445966 0.257813,0.771485 m -0.359375,-0.105469 c -0.0026,-0.196613 -0.05794,-0.353514 -0.166016,-0.470703 -0.106772,-0.117186 -0.248699,-0.175779 -0.425781,-0.175781 -0.200522,2e-6 -0.361329,0.05664 -0.482422,0.169922 -0.119792,0.113282 -0.188803,0.272788 -0.207031,0.478515 l 1.28125,-0.002" />
</g>
<g
id="text3353"
style="font-size:33.09410858px;font-style:normal;font-weight:normal;fill:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Bitstream Vera Sans">
<path
inkscape:connector-curvature="0"
id="path4242"
style="font-size:3.30941081px;fill:#ffffff"
d="m 41.256912,36.22762 0,-0.647985 -0.533254,0 0,-0.268243 0.856439,0 0,1.035806 c -0.126044,0.08942 -0.265014,0.157284 -0.416908,0.203607 -0.151899,0.04525 -0.31403,0.06787 -0.486393,0.06787 -0.37705,0 -0.672225,-0.109882 -0.885526,-0.329648 -0.212225,-0.220842 -0.318337,-0.527867 -0.318337,-0.921076 0,-0.394284 0.106112,-0.701309 0.318337,-0.921076 0.213301,-0.220841 0.508476,-0.331262 0.885526,-0.331265 0.157281,3e-6 0.306485,0.01939 0.44761,0.05817 0.1422,0.03878 0.273089,0.09588 0.39267,0.171287 l 0,0.347424 c -0.120658,-0.10234 -0.248854,-0.179365 -0.38459,-0.231077 -0.135739,-0.05171 -0.278479,-0.07756 -0.42822,-0.07756 -0.295176,2e-6 -0.517096,0.08241 -0.66576,0.247236 -0.147588,0.164826 -0.221382,0.410446 -0.221381,0.736861 -10e-7,0.32534 0.07379,0.570421 0.221381,0.735245 0.148664,0.164824 0.370584,0.247236 0.66576,0.247236 0.115268,0 0.218148,-0.0097 0.308642,-0.02909 0.09049,-0.02047 0.171824,-0.05171 0.244004,-0.09372" />
<path
inkscape:connector-curvature="0"
id="path4244"
style="font-size:3.30941081px;fill:#ffffff"
d="m 42.134358,35.857574 0,-1.095596 0.29733,0 0,1.084284 c 0,0.171289 0.03339,0.300024 0.100188,0.386206 0.06679,0.08511 0.166977,0.127658 0.300561,0.127658 0.160514,0 0.287095,-0.05117 0.379742,-0.153513 0.09372,-0.102341 0.140584,-0.241849 0.140586,-0.418524 l 0,-1.026111 0.297329,0 0,1.809834 -0.297329,0 0,-0.277939 c -0.07218,0.109883 -0.156208,0.191756 -0.252084,0.24562 -0.0948,0.05279 -0.205224,0.07918 -0.331265,0.07918 -0.207916,0 -0.365738,-0.06464 -0.473465,-0.19391 -0.107729,-0.129274 -0.161593,-0.318337 -0.161593,-0.567189 m 0.748173,-1.139226 0,0" />
<path
inkscape:connector-curvature="0"
id="path4246"
style="font-size:3.30941081px;fill:#ffffff"
d="m 44.265761,34.761978 0.29733,0 0,1.809834 -0.29733,0 0,-1.809834 m 0,-0.704543 0.29733,0 0,0.37651 -0.29733,0 0,-0.37651" />
<path
inkscape:connector-curvature="0"
id="path4248"
style="font-size:3.30941081px;fill:#ffffff"
d="m 46.374541,35.036685 0,-0.97925 0.29733,0 0,2.514377 -0.29733,0 0,-0.271475 c -0.06248,0.107728 -0.141664,0.187985 -0.237541,0.240772 -0.0948,0.05171 -0.208994,0.07756 -0.342576,0.07756 -0.218689,0 -0.396979,-0.08726 -0.53487,-0.261779 -0.136815,-0.174519 -0.205223,-0.40398 -0.205222,-0.688383 -1e-6,-0.284402 0.06841,-0.513863 0.205222,-0.688384 0.137891,-0.174518 0.316181,-0.261777 0.53487,-0.261779 0.133582,2e-6 0.247774,0.0264 0.342576,0.07918 0.09588,0.05171 0.175057,0.13143 0.237541,0.239157 m -1.013184,0.631826 c -10e-7,0.218689 0.04471,0.390515 0.134122,0.515479 0.09049,0.123888 0.214378,0.185831 0.371662,0.185831 0.157282,0 0.281169,-0.06194 0.371662,-0.185831 0.09049,-0.124964 0.135736,-0.29679 0.135738,-0.515479 -2e-6,-0.218688 -0.04525,-0.389975 -0.135738,-0.513864 -0.09049,-0.124963 -0.21438,-0.187446 -0.371662,-0.187447 -0.157284,10e-7 -0.281171,0.06248 -0.371662,0.187447 -0.08942,0.123889 -0.134123,0.295176 -0.134122,0.513864" />
<path
inkscape:connector-curvature="0"
id="path4250"
style="font-size:3.30941081px;fill:#ffffff"
d="m 48.106811,35.662047 c -0.240235,10e-7 -0.406675,0.02747 -0.499321,0.08241 -0.09265,0.05494 -0.138969,0.148666 -0.138969,0.281171 0,0.105574 0.03447,0.189602 0.103419,0.252084 0.07002,0.0614 0.164824,0.09211 0.284403,0.09211 0.164823,0 0.29679,-0.05817 0.395901,-0.174519 0.100186,-0.117424 0.150279,-0.273091 0.150281,-0.467002 l 0,-0.06625 -0.295714,0 m 0.593044,-0.12281 0,1.032575 -0.29733,0 0,-0.274707 c -0.06787,0.109883 -0.152437,0.191217 -0.2537,0.244004 -0.101266,0.05171 -0.225153,0.07756 -0.371663,0.07756 -0.185293,0 -0.33288,-0.05171 -0.442763,-0.155128 -0.108805,-0.104496 -0.163208,-0.244004 -0.163208,-0.418524 0,-0.203606 0.06787,-0.357118 0.203607,-0.460538 0.136814,-0.103418 0.34042,-0.155128 0.610818,-0.155129 l 0.416909,0 0,-0.02909 c -2e-6,-0.136813 -0.04525,-0.242387 -0.135738,-0.316721 -0.08942,-0.07541 -0.215457,-0.113113 -0.378126,-0.113114 -0.10342,10e-7 -0.204146,0.01239 -0.302178,0.03717 -0.09803,0.02478 -0.192295,0.06195 -0.282786,0.111499 l 0,-0.274707 c 0.108805,-0.04201 0.214378,-0.07325 0.316721,-0.09372 0.102341,-0.02154 0.201989,-0.03232 0.298946,-0.03232 0.261778,2e-6 0.457305,0.06787 0.58658,0.203606 0.129272,0.135739 0.193909,0.3415 0.193911,0.617283" />
<path
inkscape:connector-curvature="0"
id="path4252"
style="font-size:3.30941081px;fill:#ffffff"
d="m 50.81833,35.479448 0,1.092364 -0.29733,0 0,-1.082669 c -10e-7,-0.171287 -0.0334,-0.299483 -0.100187,-0.38459 -0.06679,-0.0851 -0.16698,-0.127656 -0.300562,-0.127658 -0.160516,2e-6 -0.287096,0.05117 -0.379742,0.153513 -0.09265,0.102343 -0.13897,0.241851 -0.138969,0.418524 l 0,1.02288 -0.298946,0 0,-1.809834 0.298946,0 0,0.28117 c 0.0711,-0.108804 0.154589,-0.190138 0.250468,-0.244004 0.09695,-0.05386 0.208453,-0.08079 0.334496,-0.0808 0.207914,2e-6 0.365197,0.06464 0.47185,0.193911 0.106649,0.128198 0.159974,0.31726 0.159976,0.567189" />
<path
inkscape:connector-curvature="0"
id="path4254"
style="font-size:3.30941081px;fill:#ffffff"
d="m 52.71704,34.831462 0,0.277939 c -0.08403,-0.04632 -0.168596,-0.08079 -0.2537,-0.103419 -0.08403,-0.0237 -0.169134,-0.03555 -0.255316,-0.03555 -0.192834,10e-7 -0.342576,0.06141 -0.449227,0.184215 -0.106651,0.121734 -0.159976,0.293022 -0.159976,0.513864 0,0.220843 0.05333,0.392669 0.159976,0.515479 0.106651,0.121733 0.256393,0.1826 0.449227,0.182599 0.08618,1e-6 0.171287,-0.01131 0.255316,-0.03393 0.0851,-0.0237 0.16967,-0.05871 0.2537,-0.105035 l 0,0.274707 c -0.08295,0.03878 -0.169135,0.06787 -0.258548,0.08726 -0.08834,0.01939 -0.1826,0.02909 -0.282786,0.02909 -0.272553,0 -0.489087,-0.08564 -0.649601,-0.256931 -0.160516,-0.171288 -0.240773,-0.402365 -0.240773,-0.693231 0,-0.295175 0.0808,-0.527329 0.242388,-0.696463 0.162669,-0.169132 0.385128,-0.253698 0.667377,-0.2537 0.09157,2e-6 0.180982,0.0097 0.268243,0.02909 0.08726,0.01832 0.171825,0.04633 0.2537,0.08403" />
<path
inkscape:connector-curvature="0"
id="path4256"
style="font-size:3.30941081px;fill:#ffffff"
d="m 54.785421,35.592562 0,0.145433 -1.367071,0 c 0.01293,0.204685 0.07433,0.36089 0.184215,0.468618 0.110959,0.106651 0.265011,0.159977 0.462154,0.159976 0.114191,1e-6 0.224612,-0.014 0.331264,-0.04201 0.107727,-0.02801 0.214378,-0.07002 0.319953,-0.126042 l 0,0.281171 c -0.106652,0.04525 -0.215996,0.07972 -0.328032,0.103419 -0.112039,0.0237 -0.225692,0.03555 -0.34096,0.03555 -0.288712,0 -0.517635,-0.08403 -0.686767,-0.252084 -0.168057,-0.168055 -0.252085,-0.395362 -0.252084,-0.681919 -10e-7,-0.296252 0.07972,-0.531099 0.239156,-0.704543 0.160515,-0.174518 0.37651,-0.261777 0.647985,-0.261779 0.243465,2e-6 0.43576,0.07864 0.576885,0.235925 0.142199,0.156207 0.2133,0.36897 0.213302,0.638289 m -0.29733,-0.08726 c -0.0022,-0.162668 -0.04794,-0.29248 -0.137353,-0.389437 -0.08834,-0.09695 -0.205763,-0.145432 -0.352272,-0.145433 -0.165902,10e-7 -0.298946,0.04686 -0.399133,0.140585 -0.09911,0.09373 -0.156206,0.225692 -0.171288,0.395901 l 1.060046,-0.0016" />
</g>
style="fill:none;stroke:#000000;stroke-width:1.00617588;stroke-linecap:butt;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
id="rect4795"
width="95.066467"
height="79.056633"
x="0.25920519"
y="0.25921404"
ry="1" />
<text
xml:space="preserve"
style="font-size:4px;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:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Arial;-inkscape-font-specification:Arial Bold"
x="67.606667"
y="8.3444462"
id="text5330-7"
sodipodi:linespacing="125%"
id="text3554"
y="28.857702"
x="20.861383"
style="font-size:4px;font-style:normal;font-weight:normal;line-height:125%;letter-spacing:0px;word-spacing:0px;fill:#ffffff;fill-opacity:1;stroke:none;font-family:Sans"
xml:space="preserve"><tspan
y="28.857702"
x="20.861383"
id="tspan3556"
sodipodi:role="line" /></text>
transform="scale(0.83127393,1.2029729)"><tspan
sodipodi:role="line"
id="tspan4289"
x="67.606667"
y="8.3444462">PATH</tspan></text>
<text
xml:space="preserve"
style="font-size:33.09410858px;font-style:normal;font-weight:normal;fill:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Bitstream Vera Sans"
x="18.13113"
y="36.642929"
id="text3353-9"><tspan
id="tspan3381"
style="font-size:4px;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:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Arial;-inkscape-font-specification:Arial Bold"
x="93.860985"
y="8.3444462"
id="text5330-7-2"
sodipodi:linespacing="125%"
transform="scale(0.83127393,1.2029729)"><tspan
sodipodi:role="line"
x="18.13113"
y="36.642929"
style="font-size:3.30941081px;fill:#ffffff;fill-opacity:1">Boot Fault</tspan></text>
id="tspan4291"
x="93.860985"
y="8.3444462">PLAN</tspan></text>
<text
xml:space="preserve"
style="font-size:4px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#ffffff;fill-opacity:1;stroke:none;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
x="3.0869398"
y="16.60899"
id="text6573"
sodipodi:linespacing="125%"><tspan
id="tspan6575"
style="font-size:4px;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:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Arial;-inkscape-font-specification:Arial Bold"
x="10.759087"
y="8.3200321"
id="text5330-7-7"
sodipodi:linespacing="125%"
transform="scale(0.83127393,1.2029729)"><tspan
sodipodi:role="line"
x="3.0869398"
y="16.60899"
style="font-size:4px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#ffffff;fill-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans">Battery</tspan></text>
id="tspan3458"
x="10.759087"
y="8.3200321">ATTITUDE</tspan></text>
<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:80.00000119%;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="4.3751421"
y="-57.099613"
id="text3565"
sodipodi:linespacing="80.000001%"
transform="matrix(0,1,-1,0,0,0)"><tspan
style="font-size:4px;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:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Arial;-inkscape-font-specification:Arial Bold"
x="41.377663"
y="8.3434696"
id="text5330-7-3"
sodipodi:linespacing="125%"
transform="scale(0.83127393,1.2029729)"><tspan
sodipodi:role="line"
id="tspan3567"
x="4.3751421"
y="-57.099613"
style="font-size:4px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:80.00000119%;writing-mode:lr-tb;text-anchor:start;fill:#ffffff;font-family:Arial;-inkscape-font-specification:Arial">Sensors</tspan></text>
id="tspan4287"
x="41.377663"
y="8.3434696">STAB</tspan></text>
<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:80.00000119%;letter-spacing:0px;word-spacing:0px;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;display:inline;font-family:Arial;-inkscape-font-specification:Sans Bold"
x="4.1748462"
y="-67.598602"
id="text3565-9"
sodipodi:linespacing="80.000001%"
transform="matrix(0,1,-1,0,0,0)"><tspan
style="font-size:4px;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:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Arial;-inkscape-font-specification:Arial Bold"
x="16.329399"
y="20.115072"
id="text5330-7-7-9"
sodipodi:linespacing="125%"
transform="scale(0.83127393,1.2029729)"><tspan
sodipodi:role="line"
id="tspan3567-3"
x="4.1748462"
y="-67.598602"
style="font-size:4px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:80.00000119%;writing-mode:lr-tb;text-anchor:start;fill:#ffffff;font-family:Arial;-inkscape-font-specification:Arial">Airspeed</tspan></text>
id="tspan5866"
x="16.329399"
y="20.115072">GPS</tspan></text>
<text
xml:space="preserve"
style="font-size:4px;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:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Arial;-inkscape-font-specification:Arial Bold"
x="37.037819"
y="20.115072"
id="text5330-7-7-6"
sodipodi:linespacing="125%"
transform="scale(0.83127393,1.2029729)"><tspan
sodipodi:role="line"
id="tspan4319"
x="37.037819"
y="20.115072">SENSORS</tspan></text>
<text
xml:space="preserve"
style="font-size:4px;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:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Arial;-inkscape-font-specification:Arial Bold"
x="62.913303"
y="20.115072"
id="text5330-7-7-0"
sodipodi:linespacing="125%"
transform="scale(0.83127393,1.2029729)"><tspan
sodipodi:role="line"
id="tspan4321"
x="62.913303"
y="20.115072">AIRSPEED</tspan></text>
<text
xml:space="preserve"
style="font-size:4px;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:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Arial;-inkscape-font-specification:Arial Bold"
x="93.336571"
y="20.116049"
id="text5330-7-7-8"
sodipodi:linespacing="125%"
transform="scale(0.83127393,1.2029729)"><tspan
sodipodi:role="line"
id="tspan4295"
x="93.336571"
y="20.116049">BARO</tspan></text>
<text
xml:space="preserve"
style="font-size:3px;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:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Arial;-inkscape-font-specification:Arial Bold"
x="47.086681"
y="58.514309"
id="text5330-0"
sodipodi:linespacing="125%"
transform="scale(0.8038279,1.2440474)"><tspan
sodipodi:role="line"
id="tspan5951"
x="47.086681"
y="58.514309">CPU</tspan></text>
<text
xml:space="preserve"
style="font-size:3px;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:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Arial;-inkscape-font-specification:Arial Bold"
x="89.03878"
y="58.514309"
id="text5330-0-4"
sodipodi:linespacing="125%"
transform="scale(0.8038279,1.2440474)"><tspan
sodipodi:role="line"
id="tspan4311"
x="89.03878"
y="58.514309">EVENT</tspan></text>
<text
xml:space="preserve"
style="font-size:3px;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:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Arial;-inkscape-font-specification:Arial Bold"
x="60.922539"
y="58.514309"
id="text5330-0-6"
sodipodi:linespacing="125%"
transform="scale(0.8038279,1.2440474)"><tspan
sodipodi:role="line"
id="tspan3462"
x="60.922539"
y="58.514309">MEM.</tspan></text>
<text
xml:space="preserve"
style="font-size:3px;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:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Arial;-inkscape-font-specification:Arial Bold"
x="74.263214"
y="58.513577"
id="text5330-0-0"
sodipodi:linespacing="125%"
transform="scale(0.8038279,1.2440474)"><tspan
sodipodi:role="line"
id="tspan4309"
x="74.263214"
y="58.513577">STACK</tspan></text>
<text
xml:space="preserve"
style="font-size:3px;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:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Arial;-inkscape-font-specification:Arial Bold"
x="106.74649"
y="58.476372"
id="text5330-0-00"
sodipodi:linespacing="125%"
transform="scale(0.8038279,1.2440474)"><tspan
sodipodi:role="line"
id="tspan5947"
x="106.74649"
y="58.476372">I2C</tspan></text>
<text
xml:space="preserve"
style="font-size:4px;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:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Arial;-inkscape-font-specification:Arial Bold"
x="43.342724"
y="37.561607"
id="textconf"
sodipodi:linespacing="125%"
transform="scale(0.83127393,1.2029729)"
inkscape:label="#text5330-7-7-9-1"><tspan
sodipodi:role="line"
id="tspan4317"
x="43.342724"
y="37.561607">CONF.</tspan></text>
<text
xml:space="preserve"
style="font-size:4px;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:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Arial;-inkscape-font-specification:Arial Bold"
x="61.386131"
y="37.561607"
id="text5858"
sodipodi:linespacing="125%"
transform="scale(0.83127393,1.2029729)"
inkscape:label="#text5330-7-7-9-8"><tspan
sodipodi:role="line"
id="tspan4313"
x="61.386131"
y="37.561607">BOOT</tspan></text>
<text
xml:space="preserve"
style="font-size:4px;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:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Arial;-inkscape-font-specification:Arial Bold"
x="45.628952"
y="49.196098"
id="text5330-7-7-9-8-3"
sodipodi:linespacing="125%"
transform="scale(0.83127393,1.2029729)"><tspan
sodipodi:role="line"
id="tspan4315"
x="45.628952"
y="49.196098">TELEM.</tspan></text>
<text
xml:space="preserve"
style="font-size:4px;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:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Arial;-inkscape-font-specification:Arial Bold"
x="75.682053"
y="49.196095"
id="text5330-7-7-9-8-4"
sodipodi:linespacing="125%"
transform="scale(0.83127393,1.2029729)"><tspan
sodipodi:role="line"
id="tspan4303"
x="75.682053"
y="49.196095">BATT.</tspan></text>
<text
xml:space="preserve"
style="font-size:4px;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:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Arial;-inkscape-font-specification:Arial Bold"
x="96.951797"
y="49.196095"
id="text5330-7-7-9-8-0"
sodipodi:linespacing="125%"
transform="scale(0.83127393,1.2029729)"><tspan
sodipodi:role="line"
id="tspan4305"
x="96.951797"
y="49.196095">TIME</tspan></text>
<rect
style="fill:none;stroke:#ffffff;stroke-width:0.53149605;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
id="Actuator-7"
width="11.450287"
height="44.10326"
x="71.210968"
y="84.344215"
ry="1"
inkscape:label="#rect4550-4" />
<rect
inkscape:label="#rect4550-8"
ry="1"
y="67.18853"
x="35.122761"
height="8.5405388"
width="10.470912"
id="rect4780"
style="fill:none;stroke:#ffffff;stroke-width:0.45410183;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
<rect
inkscape:label="#rect4550-8-7"
ry="1"
y="67.18853"
x="46.889668"
height="8.5405388"
width="10.470912"
id="rect4782"
style="fill:none;stroke:#ffffff;stroke-width:0.45410183;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
<rect
inkscape:label="#rect4550-8-1"
ry="1"
y="67.18853"
x="58.656513"
height="8.5405388"
width="10.470912"
id="rect4784"
style="fill:none;stroke:#ffffff;stroke-width:0.45410183;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
<rect
inkscape:label="#rect4550-8-15"
ry="1"
y="67.18853"
x="70.423416"
height="8.5405388"
width="10.470912"
id="rect4786"
style="fill:none;stroke:#ffffff;stroke-width:0.45410183;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
<rect
inkscape:label="#rect4550-8-2"
ry="1"
y="67.18853"
x="82.190269"
height="8.5405388"
width="10.470912"
id="rect4788"
style="fill:none;stroke:#ffffff;stroke-width:0.45410183;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
<rect
inkscape:label="#rect4550-8-1-4-21-8"
ry="1"
y="38.309322"
x="49.262897"
height="10.308098"
width="13.310432"
id="rect4790"
style="fill:none;stroke:#ffffff;stroke-width:0.56247556;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
<rect
ry="1"
y="38.309322"
x="64.013565"
height="10.308098"
width="13.310432"
id="rect4792"
style="fill:none;stroke:#ffffff;stroke-width:0.56247556;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
<rect
ry="1"
y="38.242306"
x="78.764183"
height="10.308098"
width="13.310432"
id="rect4794"
style="fill:none;stroke:#ffffff;stroke-width:0.56247556;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
<rect
inkscape:label="#rect4550-8-1-4-21-2-9"
ry="1"
y="52.326412"
x="76.795616"
height="10.265867"
width="15.447426"
id="rect4796"
style="fill:none;stroke:#ffffff;stroke-width:0.60470587;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
<rect
inkscape:label="#rect4550-8-1-4-21-5"
ry="1"
y="52.358059"
x="34.470295"
height="10.202584"
width="18.966711"
id="rect4798"
style="fill:none;stroke:#ffffff;stroke-width:0.66798913;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
<rect
transform="translate(-497.66563,-344.28037)"
inkscape:label="#rect4550-8-1-4-21-5-4"
ry="1"
y="347.495"
x="505.26666"
height="10.202584"
width="18.966711"
id="rect4800"
style="fill:none;stroke:#ffffff;stroke-width:0.66798913;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
<rect
transform="translate(-497.66563,-344.28037)"
inkscape:label="#rect4550-8-1-4-21-5-3"
ry="1"
y="347.495"
x="527.08551"
height="10.202584"
width="18.966711"
id="rect4802"
style="fill:none;stroke:#ffffff;stroke-width:0.66798913;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
<rect
transform="translate(-497.66563,-344.28037)"
inkscape:label="#rect4550-8-1-4-21-5-1"
ry="1"
y="347.495"
x="548.90442"
height="10.202584"
width="18.966711"
id="rect4804"
style="fill:none;stroke:#ffffff;stroke-width:0.66798913;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
<rect
transform="translate(-497.66563,-344.28037)"
inkscape:label="#rect4550-8-1-4-21-5-2"
ry="1"
y="347.495"
x="570.72327"
height="10.202584"
width="18.966711"
id="rect4806"
style="fill:none;stroke:#ffffff;stroke-width:0.66798913;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
<rect
inkscape:label="#rect4550-8-1-4-21-5-33"
ry="1"
y="361.65591"
x="505.26666"
height="10.202584"
width="18.966711"
id="rect4808"
style="fill:none;stroke:#ffffff;stroke-width:0.66798913;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
transform="translate(-497.66563,-344.28037)" />
<rect
transform="translate(-497.66563,-344.28037)"
inkscape:label="#rect4550-8-1-4-21-5-41"
ry="1"
y="361.65591"
x="527.08551"
height="10.202584"
width="18.966711"
id="rect4810"
style="fill:none;stroke:#ffffff;stroke-width:0.66798913;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
<rect
transform="translate(-497.66563,-344.28037)"
inkscape:label="#rect4550-8-1-4-21-5-13"
ry="1"
y="361.65591"
x="548.90442"
height="10.202584"
width="18.966711"
id="rect4812"
style="fill:none;stroke:#ffffff;stroke-width:0.66798913;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
<rect
transform="translate(-497.66563,-344.28037)"
ry="1"
y="361.65591"
x="570.72327"
height="10.202584"
width="18.966711"
id="rect4814"
style="fill:none;stroke:#ffffff;stroke-width:0.66798913;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
<rect
inkscape:label="#rect4550-8-1-4-21-2-9-8"
ry="1"
y="52.326412"
x="60.093647"
height="10.265867"
width="15.447426"
id="rect4816"
style="fill:none;stroke:#ffffff;stroke-width:0.60470587;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
<rect
ry="1"
y="38.309322"
x="34.512287"
height="10.308098"
width="13.310432"
id="rect4818"
style="fill:none;stroke:#ffffff;stroke-width:0.56247556;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
<rect
inkscape:label="#rect4550-4"
ry="1"
y="84.344215"
x="71.210968"
height="44.10326"
width="11.450287"
id="rect4841"
style="fill:none;stroke:#ffffff;stroke-width:0.53149605;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
<rect
inkscape:label="#rect4550-8-1-4-21-5-33"
ry="1"
y="38.420193"
x="7.6010327"
height="10.202584"
width="18.966711"
id="rect4808-4"
style="fill:none;stroke:#ffffff;stroke-width:0.66798913;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
<text
xml:space="preserve"
style="font-size:4px;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:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Arial;-inkscape-font-specification:Arial Bold"
x="14.453424"
y="37.585503"
id="text5330-7-7-9-8"
sodipodi:linespacing="125%"
transform="scale(0.83127393,1.2029729)"><tspan
sodipodi:role="line"
id="tspan3410"
x="14.453424"
y="37.585503">INPUT</tspan></text>
<rect
inkscape:label="#rect4550-8-1-4-21-5-33"
ry="1"
y="52.358059"
x="7.6010327"
height="10.202584"
width="18.966711"
id="rect4808-4-4"
style="fill:none;stroke:#ffffff;stroke-width:0.66798913;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
<rect
inkscape:label="#rect4550-8-1-4-21-5-33"
ry="1"
y="66.372726"
x="7.6010327"
height="10.202584"
width="18.966711"
id="rect4808-4-4-7"
style="fill:none;stroke:#ffffff;stroke-width:0.66798913;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
<text
xml:space="preserve"
style="font-size:4px;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:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Arial;-inkscape-font-specification:Arial Bold"
x="12.280572"
y="49.196102"
id="text5330-7-7-9-8-1"
sodipodi:linespacing="125%"
transform="scale(0.83127393,1.2029729)"><tspan
sodipodi:role="line"
id="tspan3412"
x="12.280572"
y="49.196102">OUTPUT</tspan></text>
</g>
<g
style="display:none"
inkscape:groupmode="layer"
id="layer36"
inkscape:label="No Link"
id="layer49"
inkscape:groupmode="layer">
style="display:none">
<g
inkscape:label="#g10909"
id="nolink"
style="display:inline"
transform="translate(-497.66624,-344.27977)">
inkscape:label="#g4324">
<rect
ry="1.628684"
y="344.5361"
x="497.92136"
height="79.063599"
width="93.746948"
id="rect3370"
style="fill:#453e3e;fill-opacity:0.86363639;fill-rule:evenodd;stroke:#000000;stroke-width:0.99921262;stroke-linecap:butt;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
<g
id="g10888"
transform="translate(0.5633316,0)">
inkscape:label="#nolink"
style="opacity:0.51388891;fill:#483737;fill-opacity:1;fill-rule:evenodd;stroke:#000000;stroke-width:1.00617588;stroke-linecap:butt;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
id="opacity"
width="95.066467"
height="79.056633"
x="0.25920519"
y="0.2592113"
ry="1.6285406" />
<rect
y="367.34116"
x="514.73834"
height="7.2664709"
width="58.986313"
id="rect3347-3"
style="fill:#332d2d;fill-opacity:1;stroke:#ffffff;stroke-width:0.53149605;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
inkscape:label="#rect4000-7-6-7-1" />
ry="2.3865318"
y="29.358137"
x="18.381285"
height="7.3904138"
width="62.155273"
id="rect8557"
style="fill:#ffffff;fill-opacity:1;stroke:#800000;stroke-width:0.53149605;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
<text
transform="scale(1.0128485,0.98731448)"
sodipodi:linespacing="125%"
id="text8563"
y="36.071426"
x="33.608711"
style="font-size:7.27633667px;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:#800000;fill-opacity:1;stroke:none;font-family:Arial;-inkscape-font-specification:Arial Bold"
xml:space="preserve"><tspan
y="36.071426"
x="33.608711"
id="tspan8565"
sodipodi:role="line">NO LINK</tspan></text>
<g
id="text10783"
style="font-size:19.60106087px;font-style:normal;font-weight:normal;line-height:125%;letter-spacing:0px;word-spacing:0px;fill:#000000;fill-opacity:1;stroke:none;font-family:Bitstream Vera Sans">
transform="matrix(1.0659619,0,0,1.2030901,11.890962,-5.4421624)"
id="g4267">
<path
inkscape:connector-curvature="0"
id="path12765"
style="font-size:6.37034512px;fill:#ff0000"
d="m 532.6868,368.56211 0.84606,0 2.05916,3.88504 0,-3.88504 0.60967,0 0,4.64401 -0.84606,0 -2.05917,-3.88504 0,3.88504 -0.60966,0 0,-4.64401" />
<path
inkscape:connector-curvature="0"
id="path12767"
style="font-size:6.37034512px;fill:#ff0000"
d="m 538.7772,370.12359 c -0.30691,0 -0.54953,0.12028 -0.72786,0.36082 -0.17834,0.23848 -0.26751,0.56612 -0.26751,0.98293 0,0.41681 0.0881,0.74548 0.2644,0.98603 0.17833,0.23847 0.42199,0.35771 0.73097,0.35771 0.30483,0 0.54641,-0.12027 0.72475,-0.36082 0.17833,-0.24055 0.2675,-0.56819 0.2675,-0.98292 0,-0.41267 -0.0892,-0.73927 -0.2675,-0.97982 -0.17834,-0.24262 -0.41992,-0.36393 -0.72475,-0.36393 m 0,-0.48524 c 0.49768,0 0.88857,0.16175 1.17266,0.48524 0.28409,0.3235 0.42614,0.77141 0.42614,1.34375 0,0.57026 -0.14205,1.01817 -0.42614,1.34374 -0.28409,0.32349 -0.67498,0.48524 -1.17266,0.48524 -0.49976,0 -0.89169,-0.16175 -1.17578,-0.48524 -0.28202,-0.32557 -0.42303,-0.77348 -0.42303,-1.34374 0,-0.57234 0.14101,-1.02025 0.42303,-1.34375 0.28409,-0.32349 0.67602,-0.48524 1.17578,-0.48524" />
<path
inkscape:connector-curvature="0"
id="path12769"
style="font-size:6.37034512px;fill:#ff0000"
d="m 543.37455,368.56211 0.62832,0 0,4.11522 2.26135,0 0,0.52879 -2.88967,0 0,-4.64401" />
<path
inkscape:connector-curvature="0"
id="path12771"
style="font-size:6.37034512px;fill:#ff0000"
d="m 546.89565,369.72233 0.57234,0 0,3.48379 -0.57234,0 0,-3.48379 m 0,-1.35618 0.57234,0 0,0.72475 -0.57234,0 0,-0.72475" />
<path
inkscape:connector-curvature="0"
id="path12773"
style="font-size:6.37034512px;fill:#ff0000"
d="m 551.55832,371.1034 0,2.10272 -0.57233,0 0,-2.08405 c 0,-0.32972 -0.0643,-0.57648 -0.19285,-0.74031 -0.12857,-0.16381 -0.32143,-0.24572 -0.57856,-0.24573 -0.30898,10e-6 -0.55264,0.0985 -0.73097,0.2955 -0.17834,0.197 -0.26751,0.46555 -0.26751,0.80563 l 0,1.96896 -0.57544,0 0,-3.48379 0.57544,0 0,0.54123 c 0.13686,-0.20943 0.29757,-0.366 0.48213,-0.46968 0.18663,-0.10369 0.40126,-0.15553 0.64388,-0.15553 0.40022,0 0.70298,0.12442 0.90827,0.37326 0.20529,0.24677 0.30794,0.6107 0.30794,1.09179" />
<path
inkscape:connector-curvature="0"
id="path12775"
style="font-size:6.37034512px;fill:#ff0000"
d="m 552.68433,368.36615 0.57545,0 0,2.85856 1.70767,-1.50238 0.73098,0 -1.84765,1.62992 1.92541,1.85387 -0.74653,0 -1.76988,-1.70146 0,1.70146 -0.57545,0 0,-4.83997" />
</g>
<g
transform="matrix(0.44255352,0,0,0.44255352,312.84845,210.43308)"
id="g10867">
<path
inkscape:connector-curvature="0"
d="m 466.346,356.14361 c -3.62458,0 -6.56905,2.94447 -6.56905,6.56905 0,3.62458 2.94447,6.56906 6.56905,6.56905 3.62458,0 6.56906,-2.94447 6.56905,-6.56905 0,-3.62458 -2.94447,-6.56905 -6.56905,-6.56905 z"
id="path2555-8"
style="fill:url(#radialGradient10901);fill-opacity:1;stroke:url(#linearGradient10903);stroke-width:0.68692255;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;stroke-dashoffset:0;display:inline" />
<path
inkscape:connector-curvature="0"
d="m 464.17717,359.06987 -1.00019,1.00019 2.06355,2.05302 c 0.0634,0.0642 0.0634,0.16742 0,0.23162 l -2.06355,2.05302 1.00019,1.00019 2.05302,-2.05302 c 0.0642,-0.0634 0.16743,-0.0634 0.23162,0 l 2.05302,2.05302 1.00019,-1.00019 -2.05302,-2.05302 c -0.0634,-0.0642 -0.0634,-0.16743 0,-0.23162 l 2.05302,-2.05302 -1.00019,-1.00019 -2.05302,2.05302 c -0.0642,0.0634 -0.16743,0.0634 -0.23162,0 l -2.05302,-2.05302 z"
id="path3243-2"
style="opacity:0.2;fill:#000000;fill-opacity:1;fill-rule:evenodd;stroke:none;display:inline" />
<path
inkscape:connector-curvature="0"
d="m 464.17717,359.40677 -1.00019,1.00019 2.06355,2.05302 c 0.0634,0.0642 0.0634,0.16743 0,0.23162 l -2.06355,2.05302 1.00019,1.00019 2.05302,-2.05302 c 0.0642,-0.0634 0.16743,-0.0634 0.23162,0 l 2.05302,2.05302 1.00019,-1.00019 -2.05302,-2.05302 c -0.0634,-0.0642 -0.0634,-0.16742 0,-0.23162 l 2.05302,-2.05302 -1.00019,-1.00019 -2.05302,2.05302 c -0.0642,0.0634 -0.16743,0.0634 -0.23162,0 l -2.05302,-2.05302 z"
id="path3256-7"
style="fill:#ffffff;fill-opacity:1;fill-rule:evenodd;stroke:none;display:inline" />
</g>
<g
id="g10876"
transform="matrix(0.44255352,0,0,0.44255352,362.84845,210.43308)">
<path
style="fill:url(#radialGradient10905);fill-opacity:1;stroke:url(#linearGradient10907);stroke-width:0.68692255;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;stroke-dashoffset:0;display:inline"
id="path10878"
d="m 466.346,356.14361 c -3.62458,0 -6.56905,2.94447 -6.56905,6.56905 0,3.62458 2.94447,6.56906 6.56905,6.56905 3.62458,0 6.56906,-2.94447 6.56905,-6.56905 0,-3.62458 -2.94447,-6.56905 -6.56905,-6.56905 z"
style="fill:none;stroke:#000000;stroke-width:0.29055119;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
d="m 10,34.57505 3,-5 3,5 z"
id="path4256"
inkscape:connector-curvature="0" />
<path
style="opacity:0.2;fill:#000000;fill-opacity:1;fill-rule:evenodd;stroke:none;display:inline"
id="path10880"
d="m 464.17717,359.06987 -1.00019,1.00019 2.06355,2.05302 c 0.0634,0.0642 0.0634,0.16742 0,0.23162 l -2.06355,2.05302 1.00019,1.00019 2.05302,-2.05302 c 0.0642,-0.0634 0.16743,-0.0634 0.23162,0 l 2.05302,2.05302 1.00019,-1.00019 -2.05302,-2.05302 c -0.0634,-0.0642 -0.0634,-0.16743 0,-0.23162 l 2.05302,-2.05302 -1.00019,-1.00019 -2.05302,2.05302 c -0.0642,0.0634 -0.16743,0.0634 -0.23162,0 l -2.05302,-2.05302 z"
style="fill:#feff4e;fill-opacity:1;stroke:none"
d="m 10.290063,34.407528 c 0.0054,-0.0098 0.6154,-1.028176 1.355653,-2.263122 1.065577,-1.777675 1.351802,-2.238983 1.374175,-2.214756 0.034,0.03682 2.687605,4.461874 2.687605,4.481753 0,0.0076 -1.221113,0.01389 -2.713585,0.01389 -1.492472,0 -2.709203,-0.008 -2.703848,-0.01777 z"
id="path4258"
inkscape:connector-curvature="0" />
<path
style="fill:#ffffff;fill-opacity:1;fill-rule:evenodd;stroke:none;display:inline"
id="path10882"
d="m 464.17717,359.40677 -1.00019,1.00019 2.06355,2.05302 c 0.0634,0.0642 0.0634,0.16743 0,0.23162 l -2.06355,2.05302 1.00019,1.00019 2.05302,-2.05302 c 0.0642,-0.0634 0.16743,-0.0634 0.23162,0 l 2.05302,2.05302 1.00019,-1.00019 -2.05302,-2.05302 c -0.0634,-0.0642 -0.0634,-0.16742 0,-0.23162 l 2.05302,-2.05302 -1.00019,-1.00019 -2.05302,2.05302 c -0.0642,0.0634 -0.16743,0.0634 -0.23162,0 l -2.05302,-2.05302 z"
sodipodi:type="arc"
style="fill:#000000;fill-opacity:1;stroke:none"
id="path4260"
sodipodi:cx="13.5"
sodipodi:cy="35.07505"
sodipodi:rx="0.5"
sodipodi:ry="0.5"
d="m 14,35.07505 c 0,0.276143 -0.223858,0.5 -0.5,0.5 -0.276142,0 -0.5,-0.223857 -0.5,-0.5 0,-0.276142 0.223858,-0.5 0.5,-0.5 0.269688,0 0.490781,0.21388 0.499725,0.483419"
sodipodi:start="0"
sodipodi:end="6.2500167"
sodipodi:open="true"
transform="matrix(0.85787666,0,0,0.89340749,1.4093898,2.5721417)" />
<path
style="fill:none;stroke:#000000;stroke-width:0.78661418;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
d="m 13,30.727043 0,2.607972"
id="path4265"
inkscape:connector-curvature="0" />
</g>
<g
transform="matrix(1.0659619,0,0,1.2030901,59.303858,-5.5104487)"
id="g4267-4"
style="display:inline">
<path
style="fill:none;stroke:#000000;stroke-width:0.29055119;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
d="m 10,34.57505 3,-5 3,5 z"
id="path4256-0"
inkscape:connector-curvature="0" />
<path
style="fill:#feff4e;fill-opacity:1;stroke:none"
d="m 10.290063,34.407528 c 0.0054,-0.0098 0.6154,-1.028176 1.355653,-2.263122 1.065577,-1.777675 1.351802,-2.238983 1.374175,-2.214756 0.034,0.03682 2.687605,4.461874 2.687605,4.481753 0,0.0076 -1.221113,0.01389 -2.713585,0.01389 -1.492472,0 -2.709203,-0.008 -2.703848,-0.01777 z"
id="path4258-9"
inkscape:connector-curvature="0" />
<path
sodipodi:type="arc"
style="fill:#000000;fill-opacity:1;stroke:none"
id="path4260-4"
sodipodi:cx="13.5"
sodipodi:cy="35.07505"
sodipodi:rx="0.5"
sodipodi:ry="0.5"
d="m 14,35.07505 c 0,0.276143 -0.223858,0.5 -0.5,0.5 -0.276142,0 -0.5,-0.223857 -0.5,-0.5 0,-0.276142 0.223858,-0.5 0.5,-0.5 0.269688,0 0.490781,0.21388 0.499725,0.483419"
sodipodi:start="0"
sodipodi:end="6.2500167"
sodipodi:open="true"
transform="matrix(0.85787666,0,0,0.89340749,1.4093898,2.5721417)" />
<path
style="fill:none;stroke:#000000;stroke-width:0.78661418;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
d="m 13,30.727043 0,2.607972"
id="path4265-8"
inkscape:connector-curvature="0" />
</g>
</g>
</g>

Before

Width:  |  Height:  |  Size: 239 KiB

After

Width:  |  Height:  |  Size: 103 KiB

View File

@ -312,21 +312,15 @@ have to define channel output range using Output configuration tab.</string>
<property name="minimumSize">
<size>
<width>0</width>
<height>16</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>16</height>
<height>20</height>
</size>
</property>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font: bold 12px;
margin:1px;</string>
margin:1px;
font:bold;</string>
</property>
<property name="text">
<string>Yaw</string>
@ -341,21 +335,15 @@ margin:1px;</string>
<property name="minimumSize">
<size>
<width>0</width>
<height>16</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>16</height>
<height>20</height>
</size>
</property>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font: bold 12px;
margin:1px;</string>
margin:1px;
font:bold;</string>
</property>
<property name="text">
<string>Pitch Or Servo2</string>
@ -370,21 +358,15 @@ margin:1px;</string>
<property name="minimumSize">
<size>
<width>0</width>
<height>16</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>16</height>
<height>20</height>
</size>
</property>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font: bold 12px;
margin:1px;</string>
margin:1px;
font:bold;</string>
</property>
<property name="text">
<string>Roll Or Servo1</string>
@ -426,21 +408,15 @@ margin:1px;</string>
<property name="minimumSize">
<size>
<width>0</width>
<height>16</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>16</height>
<height>20</height>
</size>
</property>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font: bold 12px;
margin:1px;</string>
margin:1px;
font:bold;</string>
</property>
<property name="text">
<string>Yaw</string>
@ -455,21 +431,15 @@ margin:1px;</string>
<property name="minimumSize">
<size>
<width>0</width>
<height>16</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>16</height>
<height>20</height>
</size>
</property>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font: bold 12px;
margin:1px;</string>
margin:1px;
font:bold;</string>
</property>
<property name="text">
<string>Pitch</string>
@ -484,21 +454,15 @@ margin:1px;</string>
<property name="minimumSize">
<size>
<width>0</width>
<height>16</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>16</height>
<height>20</height>
</size>
</property>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font: bold 12px;
margin:1px;</string>
margin:1px;
font:bold;</string>
</property>
<property name="text">
<string>Roll</string>
@ -914,21 +878,15 @@ value.</string>
<property name="minimumSize">
<size>
<width>0</width>
<height>16</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>16</height>
<height>20</height>
</size>
</property>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font: bold 12px;
margin:1px;</string>
margin:1px;
font:bold;</string>
</property>
<property name="text">
<string>Roll</string>
@ -943,21 +901,15 @@ margin:1px;</string>
<property name="minimumSize">
<size>
<width>0</width>
<height>16</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>16</height>
<height>20</height>
</size>
</property>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font: bold 12px;
margin:1px;</string>
margin:1px;
font:bold;</string>
</property>
<property name="text">
<string>Pitch</string>
@ -972,21 +924,15 @@ margin:1px;</string>
<property name="minimumSize">
<size>
<width>0</width>
<height>16</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>16</height>
<height>20</height>
</size>
</property>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font: bold 12px;
margin:1px;</string>
margin:1px;
font:bold;</string>
</property>
<property name="text">
<string>Yaw</string>

View File

@ -145,8 +145,8 @@
<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>
margin:1px;
font:bold;</string>
</property>
<property name="text">
<string>Roll</string>
@ -195,8 +195,8 @@ margin:1px;</string>
<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>
margin:1px;
font:bold;</string>
</property>
<property name="text">
<string>Yaw</string>
@ -225,8 +225,8 @@ margin:1px;</string>
<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>
margin:1px;
font:bold;</string>
</property>
<property name="text">
<string>Pitch</string>

View File

@ -26,7 +26,6 @@
*/
#include "config_cc_hw_widget.h"
#include "hwsettings.h"
#include <QDebug>
#include <QStringList>
#include <QWidget>
@ -83,7 +82,16 @@ ConfigCCHWWidget::ConfigCCHWWidget(QWidget *parent) : ConfigTaskWidget(parent)
addWidgetBinding("HwSettings", "TelemetrySpeed", m_telemetry->telemetrySpeed);
addWidgetBinding("HwSettings", "GPSSpeed", m_telemetry->gpsSpeed);
// Add Gps protocol configuration
HwSettings *hwSettings = HwSettings::GetInstance(getObjectManager());
HwSettings::DataFields hwSettingsData = hwSettings->getData();
if (hwSettingsData.OptionalModules[HwSettings::OPTIONALMODULES_GPS] != HwSettings::OPTIONALMODULES_ENABLED) {
m_telemetry->gpsProtocol->setEnabled(false);
m_telemetry->gpsProtocol->setToolTip(tr("Enable GPS module and reboot the board to be able to select GPS protocol"));
} else {
addWidgetBinding("GPSSettings", "DataProtocol", m_telemetry->gpsProtocol);
}
addWidgetBinding("HwSettings", "ComUsbBridgeSpeed", m_telemetry->comUsbBridgeSpeed);
connect(m_telemetry->cchwHelp, SIGNAL(clicked()), this, SLOT(openHelp()));

View File

@ -44,7 +44,6 @@ ConfigCCAttitudeWidget::ConfigCCAttitudeWidget(QWidget *parent) :
ui(new Ui_ccattitude)
{
ui->setupUi(this);
forceConnectedState(); // dynamic widgets don't recieve the connected signal
connect(ui->zeroBias, SIGNAL(clicked()), this, SLOT(startAccelCalibration()));
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
@ -67,7 +66,9 @@ ConfigCCAttitudeWidget::ConfigCCAttitudeWidget(QWidget *parent) :
addWidgetBinding("AttitudeSettings", "BoardRotation", ui->pitchBias, AttitudeSettings::BOARDROTATION_PITCH);
addWidgetBinding("AttitudeSettings", "BoardRotation", ui->yawBias, AttitudeSettings::BOARDROTATION_YAW);
addWidget(ui->zeroBias);
populateWidgets();
refreshWidgetsValues();
forceConnectedState();
}
ConfigCCAttitudeWidget::~ConfigCCAttitudeWidget()

View File

@ -146,12 +146,27 @@ ConfigInputWidget::ConfigInputWidget(QWidget *parent) :
addWidgetBinding("FlightModeSettings", "Stabilization1Settings", ui->fmsSsPos1Roll, "Roll", 1, true);
addWidgetBinding("FlightModeSettings", "Stabilization2Settings", ui->fmsSsPos2Roll, "Roll", 1, true);
addWidgetBinding("FlightModeSettings", "Stabilization3Settings", ui->fmsSsPos3Roll, "Roll", 1, true);
addWidgetBinding("FlightModeSettings", "Stabilization4Settings", ui->fmsSsPos4Roll, "Roll", 1, true);
addWidgetBinding("FlightModeSettings", "Stabilization5Settings", ui->fmsSsPos5Roll, "Roll", 1, true);
addWidgetBinding("FlightModeSettings", "Stabilization6Settings", ui->fmsSsPos6Roll, "Roll", 1, true);
addWidgetBinding("FlightModeSettings", "Stabilization1Settings", ui->fmsSsPos1Pitch, "Pitch", 1, true);
addWidgetBinding("FlightModeSettings", "Stabilization2Settings", ui->fmsSsPos2Pitch, "Pitch", 1, true);
addWidgetBinding("FlightModeSettings", "Stabilization3Settings", ui->fmsSsPos3Pitch, "Pitch", 1, true);
addWidgetBinding("FlightModeSettings", "Stabilization4Settings", ui->fmsSsPos4Pitch, "Pitch", 1, true);
addWidgetBinding("FlightModeSettings", "Stabilization5Settings", ui->fmsSsPos5Pitch, "Pitch", 1, true);
addWidgetBinding("FlightModeSettings", "Stabilization6Settings", ui->fmsSsPos6Pitch, "Pitch", 1, true);
addWidgetBinding("FlightModeSettings", "Stabilization1Settings", ui->fmsSsPos1Yaw, "Yaw", 1, true);
addWidgetBinding("FlightModeSettings", "Stabilization2Settings", ui->fmsSsPos2Yaw, "Yaw", 1, true);
addWidgetBinding("FlightModeSettings", "Stabilization3Settings", ui->fmsSsPos3Yaw, "Yaw", 1, true);
addWidgetBinding("FlightModeSettings", "Stabilization4Settings", ui->fmsSsPos4Yaw, "Yaw", 1, true);
addWidgetBinding("FlightModeSettings", "Stabilization5Settings", ui->fmsSsPos5Yaw, "Yaw", 1, true);
addWidgetBinding("FlightModeSettings", "Stabilization6Settings", ui->fmsSsPos6Yaw, "Yaw", 1, true);
addWidgetBinding("FlightModeSettings", "Stabilization1Settings", ui->fmsSsPos1Thrust, "Thrust", 1, true);
addWidgetBinding("FlightModeSettings", "Stabilization2Settings", ui->fmsSsPos2Thrust, "Thrust", 1, true);
addWidgetBinding("FlightModeSettings", "Stabilization3Settings", ui->fmsSsPos3Thrust, "Thrust", 1, true);
addWidgetBinding("FlightModeSettings", "Stabilization4Settings", ui->fmsSsPos4Thrust, "Thrust", 1, true);
addWidgetBinding("FlightModeSettings", "Stabilization5Settings", ui->fmsSsPos5Thrust, "Thrust", 1, true);
addWidgetBinding("FlightModeSettings", "Stabilization6Settings", ui->fmsSsPos6Thrust, "Thrust", 1, true);
addWidgetBinding("FlightModeSettings", "Arming", ui->armControl);
addWidgetBinding("FlightModeSettings", "ArmedTimeout", ui->armTimeout, 0, 1000);
@ -1324,32 +1339,26 @@ void ConfigInputWidget::updatePositionSlider()
default:
case 6:
ui->fmsModePos6->setEnabled(true);
ui->cc_box_5->setEnabled(true);
ui->pidBankSs1_5->setEnabled(true);
// pass through
case 5:
ui->fmsModePos5->setEnabled(true);
ui->cc_box_4->setEnabled(true);
ui->pidBankSs1_4->setEnabled(true);
// pass through
case 4:
ui->fmsModePos4->setEnabled(true);
ui->cc_box_3->setEnabled(true);
ui->pidBankSs1_3->setEnabled(true);
// pass through
case 3:
ui->fmsModePos3->setEnabled(true);
ui->cc_box_2->setEnabled(true);
ui->pidBankSs1_2->setEnabled(true);
// pass through
case 2:
ui->fmsModePos2->setEnabled(true);
ui->cc_box_1->setEnabled(true);
ui->pidBankSs1_1->setEnabled(true);
// pass through
case 1:
ui->fmsModePos1->setEnabled(true);
ui->cc_box_0->setEnabled(true);
ui->pidBankSs1_0->setEnabled(true);
// pass through
case 0:
@ -1359,32 +1368,26 @@ void ConfigInputWidget::updatePositionSlider()
switch (manualSettingsDataPriv.FlightModeNumber) {
case 0:
ui->fmsModePos1->setEnabled(false);
ui->cc_box_0->setEnabled(false);
ui->pidBankSs1_0->setEnabled(false);
// pass through
case 1:
ui->fmsModePos2->setEnabled(false);
ui->cc_box_1->setEnabled(false);
ui->pidBankSs1_1->setEnabled(false);
// pass through
case 2:
ui->fmsModePos3->setEnabled(false);
ui->cc_box_2->setEnabled(false);
ui->pidBankSs1_2->setEnabled(false);
// pass through
case 3:
ui->fmsModePos4->setEnabled(false);
ui->cc_box_3->setEnabled(false);
ui->pidBankSs1_3->setEnabled(false);
// pass through
case 4:
ui->fmsModePos5->setEnabled(false);
ui->cc_box_4->setEnabled(false);
ui->pidBankSs1_4->setEnabled(false);
// pass through
case 5:
ui->fmsModePos6->setEnabled(false);
ui->cc_box_5->setEnabled(false);
ui->pidBankSs1_5->setEnabled(false);
// pass through
case 6:

View File

@ -546,8 +546,8 @@
<rect>
<x>0</x>
<y>0</y>
<width>768</width>
<height>742</height>
<width>774</width>
<height>748</height>
</rect>
</property>
<layout class="QGridLayout" name="gridLayout_7" rowstretch="1,0,0,0">
@ -587,7 +587,7 @@
<property name="title">
<string>Stabilization Modes Configuration</string>
</property>
<layout class="QGridLayout" name="gridLayout_2" columnstretch="0,0,0,0,0,0,0,0,0,0,0">
<layout class="QGridLayout" name="gridLayout_2" columnstretch="0,0,0,0,0,0,0,0,0,0,0,0,0">
<property name="leftMargin">
<number>9</number>
</property>
@ -626,6 +626,51 @@
</property>
</spacer>
</item>
<item row="1" column="10">
<spacer name="horizontalSpacer_15">
<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>20</height>
</size>
</property>
</spacer>
</item>
<item row="0" column="11">
<widget class="QLabel" name="label_11">
<property name="minimumSize">
<size>
<width>120</width>
<height>20</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>20</height>
</size>
</property>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
margin:1px;
font:bold;</string>
</property>
<property name="text">
<string>Thrust</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="0" column="9">
<widget class="QLabel" name="label_10">
<property name="minimumSize">
@ -644,8 +689,8 @@
<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>
margin:1px;
font:bold;</string>
</property>
<property name="text">
<string>Yaw</string>
@ -673,8 +718,8 @@ margin:1px;</string>
<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>
margin:1px;
font:bold;</string>
</property>
<property name="text">
<string>Pitch</string>
@ -684,7 +729,7 @@ margin:1px;</string>
</property>
</widget>
</item>
<item row="1" column="10">
<item row="1" column="12">
<spacer name="horizontalSpacer_11">
<property name="orientation">
<enum>Qt::Horizontal</enum>
@ -718,8 +763,8 @@ margin:1px;</string>
<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>
margin:1px;
font:bold;</string>
</property>
<property name="text">
<string>Roll</string>
@ -750,6 +795,18 @@ margin:1px;</string>
<enum>QFrame::Raised</enum>
</property>
<layout class="QVBoxLayout" name="verticalLayout_13">
<property name="leftMargin">
<number>1</number>
</property>
<property name="topMargin">
<number>1</number>
</property>
<property name="rightMargin">
<number>1</number>
</property>
<property name="bottomMargin">
<number>1</number>
</property>
<item>
<widget class="QLabel" name="label_14">
<property name="text">
@ -780,6 +837,36 @@ margin:1px;</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="label_114">
<property name="text">
<string>Stabilized 4</string>
</property>
<property name="alignment">
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="label_121">
<property name="text">
<string>Stabilized 5</string>
</property>
<property name="alignment">
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="label_122">
<property name="text">
<string>Stabilized 6</string>
</property>
<property name="alignment">
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
</property>
</widget>
</item>
</layout>
</widget>
</item>
@ -831,6 +918,27 @@ margin:1px;</string>
</property>
</widget>
</item>
<item>
<widget class="QComboBox" name="fmsSsPos4Roll">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
</widget>
</item>
<item>
<widget class="QComboBox" name="fmsSsPos5Roll">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
</widget>
</item>
<item>
<widget class="QComboBox" name="fmsSsPos6Roll">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
</widget>
</item>
</layout>
</widget>
</item>
@ -882,6 +990,27 @@ margin:1px;</string>
</property>
</widget>
</item>
<item>
<widget class="QComboBox" name="fmsSsPos4Pitch">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
</widget>
</item>
<item>
<widget class="QComboBox" name="fmsSsPos5Pitch">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
</widget>
</item>
<item>
<widget class="QComboBox" name="fmsSsPos6Pitch">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
</widget>
</item>
</layout>
</widget>
</item>
@ -933,6 +1062,99 @@ margin:1px;</string>
</property>
</widget>
</item>
<item>
<widget class="QComboBox" name="fmsSsPos4Yaw">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
</widget>
</item>
<item>
<widget class="QComboBox" name="fmsSsPos5Yaw">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
</widget>
</item>
<item>
<widget class="QComboBox" name="fmsSsPos6Yaw">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
</widget>
</item>
</layout>
</widget>
</item>
<item row="1" column="11">
<widget class="QFrame" name="frame_7">
<property name="frameShape">
<enum>QFrame::NoFrame</enum>
</property>
<property name="frameShadow">
<enum>QFrame::Raised</enum>
</property>
<layout class="QVBoxLayout" name="verticalLayout_16">
<property name="leftMargin">
<number>1</number>
</property>
<property name="topMargin">
<number>1</number>
</property>
<property name="rightMargin">
<number>1</number>
</property>
<property name="bottomMargin">
<number>1</number>
</property>
<item>
<widget class="QComboBox" name="fmsSsPos1Thrust">
<property name="minimumSize">
<size>
<width>0</width>
<height>0</height>
</size>
</property>
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
</widget>
</item>
<item>
<widget class="QComboBox" name="fmsSsPos2Thrust">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
</widget>
</item>
<item>
<widget class="QComboBox" name="fmsSsPos3Thrust">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
</widget>
</item>
<item>
<widget class="QComboBox" name="fmsSsPos4Thrust">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
</widget>
</item>
<item>
<widget class="QComboBox" name="fmsSsPos5Thrust">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
</widget>
</item>
<item>
<widget class="QComboBox" name="fmsSsPos6Thrust">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
</widget>
</item>
</layout>
</widget>
</item>
@ -989,7 +1211,7 @@ margin:1px;</string>
<number>6</number>
</property>
<item row="0" column="6">
<widget class="QLabel" name="label_11">
<widget class="QLabel" name="label_111">
<property name="minimumSize">
<size>
<width>80</width>
@ -1006,8 +1228,8 @@ margin:1px;</string>
<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>
margin:1px;
font:bold;</string>
</property>
<property name="text">
<string>PID Bank</string>
@ -1021,7 +1243,7 @@ margin:1px;</string>
<widget class="QLabel" name="label_16">
<property name="minimumSize">
<size>
<width>132</width>
<width>138</width>
<height>20</height>
</size>
</property>
@ -1035,8 +1257,8 @@ margin:1px;</string>
<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>
margin:1px;
font:bold;</string>
</property>
<property name="text">
<string>Flight Mode Count</string>
@ -1048,12 +1270,6 @@ margin:1px;</string>
</item>
<item row="1" column="10">
<widget class="QSpinBox" name="fmsPosNum">
<property name="maximumSize">
<size>
<width>151</width>
<height>16777215</height>
</size>
</property>
<property name="toolTip">
<string>Number of positions your FlightMode switch has.
@ -1078,19 +1294,20 @@ channel value for each flight mode.</string>
<item row="2" column="10">
<widget class="QLabel" name="label_15">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Preferred">
<sizepolicy hsizetype="Ignored" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="font">
<font>
<pointsize>10</pointsize>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="text">
<string>Avoid &quot;Manual&quot; for multirotors!</string>
<string>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;Avoid &amp;quot;Manual&amp;quot; for multirotors! Never select &amp;quot;ALtitude&amp;quot;, &amp;quot;VelocityControl&amp;quot; or &amp;quot;CruiseControl&amp;quot; on a fixed wing!&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
@ -1116,22 +1333,6 @@ channel value for each flight mode.</string>
</property>
</spacer>
</item>
<item row="1" column="5">
<spacer name="horizontalSpacer_15">
<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>20</height>
</size>
</property>
</spacer>
</item>
<item row="1" column="7">
<spacer name="horizontalSpacer_16">
<property name="orientation">
@ -1164,35 +1365,6 @@ channel value for each flight mode.</string>
</property>
</spacer>
</item>
<item row="0" column="4">
<widget class="QLabel" name="label_12">
<property name="minimumSize">
<size>
<width>105</width>
<height>20</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>20</height>
</size>
</property>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font: bold 12px;
margin:1px;</string>
</property>
<property name="text">
<string>Cruise Control</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="0" column="8" rowspan="3">
<widget class="Line" name="line">
<property name="orientation">
@ -1218,8 +1390,8 @@ margin:1px;</string>
<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>
margin:1px;
font:bold;</string>
</property>
<property name="text">
<string>Flight Mode</string>
@ -1229,294 +1401,6 @@ margin:1px;</string>
</property>
</widget>
</item>
<item row="1" column="4" rowspan="2">
<widget class="QFrame" name="frame_4">
<property name="minimumSize">
<size>
<width>30</width>
<height>0</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>16777215</height>
</size>
</property>
<layout class="QVBoxLayout" name="verticalLayout_4">
<property name="spacing">
<number>6</number>
</property>
<property name="leftMargin">
<number>1</number>
</property>
<property name="topMargin">
<number>1</number>
</property>
<property name="rightMargin">
<number>1</number>
</property>
<property name="bottomMargin">
<number>1</number>
</property>
<item alignment="Qt::AlignHCenter">
<widget class="QCheckBox" name="cc_box_0">
<property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Minimum">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>20</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>20</height>
</size>
</property>
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="toolTip">
<string>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;Enabling this checkbox will enable Cruise Control for Flight Mode Switch position #1.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</string>
</property>
<property name="layoutDirection">
<enum>Qt::RightToLeft</enum>
</property>
<property name="text">
<string/>
</property>
<property name="objrelation" stdset="0">
<stringlist>
<string>objname:StabilizationSettings</string>
<string>fieldname:CruiseControlFlightModeSwitchPosEnable</string>
<string>index:0</string>
<string>haslimits:no</string>
<string>scale:1</string>
</stringlist>
</property>
</widget>
</item>
<item alignment="Qt::AlignHCenter">
<widget class="QCheckBox" name="cc_box_1">
<property name="minimumSize">
<size>
<width>0</width>
<height>20</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>20</height>
</size>
</property>
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="toolTip">
<string>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;Enabling this checkbox will enable Cruise Control for Flight Mode Switch position #2.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</string>
</property>
<property name="layoutDirection">
<enum>Qt::RightToLeft</enum>
</property>
<property name="text">
<string/>
</property>
<property name="objrelation" stdset="0">
<stringlist>
<string>objname:StabilizationSettings</string>
<string>fieldname:CruiseControlFlightModeSwitchPosEnable</string>
<string>index:1</string>
<string>haslimits:no</string>
<string>scale:1</string>
</stringlist>
</property>
</widget>
</item>
<item alignment="Qt::AlignHCenter">
<widget class="QCheckBox" name="cc_box_2">
<property name="minimumSize">
<size>
<width>0</width>
<height>20</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>20</height>
</size>
</property>
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="toolTip">
<string>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;Enabling this checkbox will enable Cruise Control for Flight Mode Switch position #3.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</string>
</property>
<property name="layoutDirection">
<enum>Qt::RightToLeft</enum>
</property>
<property name="text">
<string/>
</property>
<property name="objrelation" stdset="0">
<stringlist>
<string>objname:StabilizationSettings</string>
<string>fieldname:CruiseControlFlightModeSwitchPosEnable</string>
<string>index:2</string>
<string>haslimits:no</string>
<string>scale:1</string>
</stringlist>
</property>
</widget>
</item>
<item alignment="Qt::AlignHCenter">
<widget class="QCheckBox" name="cc_box_3">
<property name="enabled">
<bool>false</bool>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>20</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>20</height>
</size>
</property>
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="toolTip">
<string>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;Enabling this checkbox will enable Cruise Control for Flight Mode Switch position #4.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</string>
</property>
<property name="layoutDirection">
<enum>Qt::RightToLeft</enum>
</property>
<property name="text">
<string/>
</property>
<property name="objrelation" stdset="0">
<stringlist>
<string>objname:StabilizationSettings</string>
<string>fieldname:CruiseControlFlightModeSwitchPosEnable</string>
<string>index:3</string>
<string>haslimits:no</string>
<string>scale:1</string>
</stringlist>
</property>
</widget>
</item>
<item alignment="Qt::AlignHCenter">
<widget class="QCheckBox" name="cc_box_4">
<property name="enabled">
<bool>false</bool>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>20</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>20</height>
</size>
</property>
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="toolTip">
<string>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;Enabling this checkbox will enable Cruise Control for Flight Mode Switch position #5.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</string>
</property>
<property name="layoutDirection">
<enum>Qt::RightToLeft</enum>
</property>
<property name="text">
<string/>
</property>
<property name="objrelation" stdset="0">
<stringlist>
<string>objname:StabilizationSettings</string>
<string>fieldname:CruiseControlFlightModeSwitchPosEnable</string>
<string>index:4</string>
<string>haslimits:no</string>
<string>scale:1</string>
</stringlist>
</property>
</widget>
</item>
<item alignment="Qt::AlignHCenter">
<widget class="QCheckBox" name="cc_box_5">
<property name="enabled">
<bool>false</bool>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>20</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>20</height>
</size>
</property>
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="toolTip">
<string>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;Enabling this checkbox will enable Cruise Control for Flight Mode Switch position #6.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</string>
</property>
<property name="layoutDirection">
<enum>Qt::RightToLeft</enum>
</property>
<property name="text">
<string/>
</property>
<property name="objrelation" stdset="0">
<stringlist>
<string>objname:StabilizationSettings</string>
<string>fieldname:CruiseControlFlightModeSwitchPosEnable</string>
<string>index:5</string>
<string>haslimits:no</string>
<string>scale:1</string>
</stringlist>
</property>
</widget>
</item>
</layout>
</widget>
</item>
<item row="1" column="0" rowspan="2">
<widget class="QFrame" name="frame">
<property name="minimumSize">
@ -1867,7 +1751,7 @@ Setup the flight mode channel on the RC Input tab if you have not done so alread
</widget>
</item>
<item row="1" column="6" rowspan="2">
<widget class="QFrame" name="frame_7">
<widget class="QFrame" name="frame_8">
<property name="minimumSize">
<size>
<width>75</width>
@ -2164,8 +2048,8 @@ Setup the flight mode channel on the RC Input tab if you have not done so alread
<rect>
<x>0</x>
<y>0</y>
<width>768</width>
<height>742</height>
<width>504</width>
<height>156</height>
</rect>
</property>
<layout class="QVBoxLayout" name="verticalLayout_2">

View File

@ -464,8 +464,8 @@ p, li { white-space: pre-wrap; }
<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>
margin:1px;
font:bold;</string>
</property>
<property name="text">
<string>Roll</string>
@ -487,8 +487,8 @@ margin:1px;</string>
<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>
margin:1px;
font:bold;</string>
</property>
<property name="text">
<string>Yaw</string>
@ -533,8 +533,8 @@ margin:1px;</string>
<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>
margin:1px;
font:bold;</string>
</property>
<property name="text">
<string>Pitch</string>
@ -572,8 +572,8 @@ margin:1px;</string>
<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>
margin:1px;
font:bold;</string>
</property>
<property name="text">
<string>Accelerometers</string>

View File

@ -7837,7 +7837,7 @@ border-radius: 5;</string>
<rect>
<x>0</x>
<y>0</y>
<width>784</width>
<width>565</width>
<height>733</height>
</rect>
</property>
@ -8444,7 +8444,7 @@ border-radius: 5;</string>
<string notr="true"/>
</property>
<property name="text">
<string>Max rate attitude (deg/s)</string>
<string>Max rate limit (all modes) (deg/s)</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
@ -13377,8 +13377,6 @@ border-radius: 5;</string>
</property>
<property name="decimals">
<number>5</number>
</property>
<property name="singleStep">
<double>0.000100000000000</double>
@ -15943,7 +15941,6 @@ border-radius: 5;</string>
<string>element:Kp</string>
<string>haslimits:no</string>
<string>scale:1</string>
<string>buttongroup:5,20</string>
</stringlist>
</property>
@ -16302,8 +16299,8 @@ border-radius: 5;</string>
<rect>
<x>0</x>
<y>0</y>
<width>798</width>
<height>705</height>
<width>829</width>
<height>691</height>
</rect>
</property>
<layout class="QVBoxLayout" name="verticalLayout_9">
@ -16737,7 +16734,7 @@ border-radius: 5;</string>
<property name="minimumSize">
<size>
<width>0</width>
<height>16</height>
<height>20</height>
</size>
</property>
<property name="palette">
@ -17266,7 +17263,9 @@ border-radius: 5;</string>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;</string>
border-radius: 5;
margin:1px;
font:bold;</string>
</property>
<property name="text">
<string>Roll</string>
@ -17287,7 +17286,7 @@ border-radius: 5;</string>
<property name="minimumSize">
<size>
<width>0</width>
<height>16</height>
<height>20</height>
</size>
</property>
<property name="palette">
@ -17355,7 +17354,6 @@ border-radius: 5;</string>
<red>26</red>
<green>26</green>
<blue>26</blue>
</color>
</brush>
</colorrole>
@ -17817,7 +17815,9 @@ border-radius: 5;</string>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;</string>
border-radius: 5;
margin:1px;
font:bold;</string>
</property>
<property name="text">
<string>Yaw</string>
@ -18092,7 +18092,7 @@ border-radius: 5;</string>
<property name="minimumSize">
<size>
<width>0</width>
<height>16</height>
<height>20</height>
</size>
</property>
<property name="palette">
@ -18621,7 +18621,9 @@ border-radius: 5;</string>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;</string>
border-radius: 5;
margin:1px;
font:bold;</string>
</property>
<property name="text">
<string>Pitch</string>
@ -18882,21 +18884,15 @@ border-radius: 5;</string>
<item row="0" column="1">
<widget class="QLabel" name="label_50">
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Fixed">
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>144</width>
<height>16</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>175</width>
<height>16777215</height>
<width>162</width>
<height>20</height>
</size>
</property>
<property name="palette">
@ -19421,12 +19417,13 @@ border-radius: 5;</string>
</property>
<property name="autoFillBackground">
<bool>false</bool>
</property>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;</string>
border-radius: 5;
margin:1px;
font:bold;</string>
</property>
<property name="text">
<string>Weak Leveling Kp </string>
@ -19439,21 +19436,15 @@ border-radius: 5;</string>
<item row="0" column="3">
<widget class="QLabel" name="label_49">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>144</width>
<height>16</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>175</width>
<height>16777215</height>
<width>179</width>
<height>20</height>
</size>
</property>
<property name="palette">
@ -19946,7 +19937,6 @@ border-radius: 5;</string>
<red>39</red>
<green>39</green>
<blue>39</blue>
</color>
</brush>
</colorrole>
@ -19983,7 +19973,9 @@ border-radius: 5;</string>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;</string>
border-radius: 5;
margin:1px;
font:bold;</string>
</property>
<property name="text">
<string>Weak Leveling Rate </string>
@ -19996,21 +19988,15 @@ border-radius: 5;</string>
<item row="0" column="5">
<widget class="QLabel" name="label_51">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>144</width>
<height>16</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>175</width>
<height>16777215</height>
<width>132</width>
<height>20</height>
</size>
</property>
<property name="palette">
@ -20539,7 +20525,9 @@ border-radius: 5;</string>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;</string>
border-radius: 5;
margin:1px;
font:bold;</string>
</property>
<property name="text">
<string>Max Axis Lock </string>
@ -20552,21 +20540,15 @@ border-radius: 5;</string>
<item row="0" column="7">
<widget class="QLabel" name="label_52">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>144</width>
<height>16</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>175</width>
<height>16777215</height>
<width>176</width>
<height>20</height>
</size>
</property>
<property name="palette">
@ -21095,7 +21077,9 @@ border-radius: 5;</string>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;</string>
border-radius: 5;
margin:1px;
font:bold;</string>
</property>
<property name="text">
<string>Max Axis Lock Rate </string>
@ -21131,7 +21115,7 @@ border-radius: 5;</string>
</property>
<property name="minimumSize">
<size>
<width>5</width>
<width>25</width>
<height>22</height>
</size>
</property>
@ -21981,7 +21965,6 @@ border-radius: 5;</string>
</size>
</property>
</spacer>
</item>
<item row="1" column="3">
<widget class="QDoubleSpinBox" name="AccelKp">
@ -22046,7 +22029,7 @@ border-radius: 5;</string>
<property name="minimumSize">
<size>
<width>0</width>
<height>16</height>
<height>20</height>
</size>
</property>
<property name="palette">
@ -22575,7 +22558,9 @@ border-radius: 5;</string>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;</string>
border-radius: 5;
margin:1px;
font:bold;</string>
</property>
<property name="text">
<string>GyroTau</string>
@ -22596,7 +22581,7 @@ border-radius: 5;</string>
<property name="minimumSize">
<size>
<width>0</width>
<height>16</height>
<height>20</height>
</size>
</property>
<property name="palette">
@ -23125,7 +23110,9 @@ border-radius: 5;</string>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;</string>
border-radius: 5;
margin:1px;
font:bold;</string>
</property>
<property name="text">
<string>AccelKp</string>
@ -23211,7 +23198,7 @@ border-radius: 5;</string>
<property name="minimumSize">
<size>
<width>90</width>
<height>16</height>
<height>20</height>
</size>
</property>
<property name="palette">
@ -23740,7 +23727,9 @@ border-radius: 5;</string>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;</string>
border-radius: 5;
margin:1px;
font:bold;</string>
</property>
<property name="text">
<string>AccelKi</string>
@ -23923,8 +23912,8 @@ border-radius: 5;</string>
<rect>
<x>0</x>
<y>0</y>
<width>798</width>
<height>705</height>
<width>665</width>
<height>435</height>
</rect>
</property>
<layout class="QVBoxLayout" name="verticalLayout_19">
@ -24186,6 +24175,12 @@ border-radius: 5;</string>
</item>
<item row="1" column="0" colspan="2">
<widget class="QFrame" name="gridFrame">
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<layout class="QGridLayout" name="gridLayout_25">
<property name="leftMargin">
<number>9</number>
@ -24200,30 +24195,23 @@ border-radius: 5;</string>
<number>9</number>
</property>
<item row="1" column="4">
<widget class="QDoubleSpinBox" name="doubleSpinBox_6">
<widget class="QComboBox" name="comboBox">
<property name="minimumSize">
<size>
<width>75</width>
<height>0</height>
</size>
</property>
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;-1, 0, or 1. Cruise Control multiplies the throttle/collective stick by this value if the bank angle is past MaxAngle. The default is 0 which says to turn the motors off (actually set them to MinThrust) when inverted. 1 says to use the unboosted stick value. -1 (DON'T USE, INCOMPLETE, UNTESTED, for use by CP helis using idle up) says to reverse the collective stick when inverted.
&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
<property name="accelerated">
<bool>true</bool>
</property>
<property name="decimals">
<number>0</number>
</property>
<property name="minimum">
<double>-1.000000000000000</double>
</property>
<property name="maximum">
<double>1.000000000000000</double>
<string>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;CP helis can set this to Reversed to automatically reverse the direction of thrust when inverted. Fixed pitch copters, including multicopters, should leave this set at Unreversed. Unreversed direction with Boosted power may be dangerous because it adds power and the thrust direction moves the aircraft towards the ground.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</string>
</property>
<property name="objrelation" stdset="0">
<stringlist>
<string>objname:StabilizationSettings</string>
<string>fieldname:CruiseControlInvertedPowerSwitch</string>
<string>fieldname:CruiseControlInvertedThrustReversing</string>
<string>haslimits:no</string>
<string>scale:1</string>
<string>buttongroup:16</string>
@ -24231,6 +24219,39 @@ border-radius: 5;</string>
</property>
</widget>
</item>
<item row="0" column="4">
<widget class="QLabel" name="label_10">
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>145</width>
<height>16</height>
</size>
</property>
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;</string>
</property>
<property name="text">
<string>InvrtdThrustRev</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="1" column="5">
<spacer name="horizontalSpacer_59">
<property name="orientation">
@ -24247,7 +24268,7 @@ border-radius: 5;</string>
<item row="1" column="2">
<widget class="QDoubleSpinBox" name="doubleSpinBox_3">
<property name="toolTip">
<string>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;This is the bank angle that CruiseControl goes into inverted / power disabled mode. The power for inverted mode is controlled by CruiseControlInvertedPowerSwitch&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</string>
<string>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;The bank angle where CruiseControl goes into inverted power mode. InvertedThrustReverse and InvertedPower control the direction and amount of power when in inverted mode.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
@ -24259,7 +24280,7 @@ border-radius: 5;</string>
<number>0</number>
</property>
<property name="maximum">
<double>180.000000000000000</double>
<double>255.000000000000000</double>
</property>
<property name="value">
<double>105.000000000000000</double>
@ -24278,7 +24299,7 @@ border-radius: 5;</string>
<item row="1" column="1">
<widget class="QDoubleSpinBox" name="doubleSpinBox">
<property name="toolTip">
<string>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;Really just a safety limit. 4.0 means it will not use more than 4 times the power the throttle/collective stick is requesting.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</string>
<string>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;Really just a safety limit. 3.0 means it will not use more than 3 times the power the throttle/collective stick is requesting.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
@ -24290,13 +24311,13 @@ border-radius: 5;</string>
<number>2</number>
</property>
<property name="minimum">
<double>0.000000000000000</double>
<double>1.000000000000000</double>
</property>
<property name="maximum">
<double>50.000000000000000</double>
</property>
<property name="singleStep">
<double>0.250000000000000</double>
<double>0.100000000000000</double>
</property>
<property name="value">
<double>3.000000000000000</double>
@ -24310,11 +24331,10 @@ border-radius: 5;</string>
<string>buttongroup:16</string>
</stringlist>
</property>
</widget>
</item>
<item row="2" column="1">
<widget class="QLabel" name="label_6">
<widget class="QLabel" name="label_11">
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Fixed">
<horstretch>0</horstretch>
@ -24323,7 +24343,7 @@ border-radius: 5;</string>
</property>
<property name="minimumSize">
<size>
<width>140</width>
<width>155</width>
<height>16</height>
</size>
</property>
@ -24339,75 +24359,13 @@ color: rgb(255, 255, 255);
border-radius: 5;</string>
</property>
<property name="text">
<string>PowerTrim</string>
<string>PowerDelayComp</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="3" column="4">
<widget class="QDoubleSpinBox" name="doubleSpinBox_7">
<property name="toolTip">
<string>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;This needs to be 0 for all copters except CP helis that are using idle up.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
<property name="accelerated">
<bool>true</bool>
</property>
<property name="decimals">
<number>0</number>
</property>
<property name="objrelation" stdset="0">
<stringlist>
<string>objname:StabilizationSettings</string>
<string>fieldname:CruiseControlNeutralThrust</string>
<string>haslimits:no</string>
<string>scale:1</string>
<string>buttongroup:16</string>
</stringlist>
</property>
</widget>
</item>
<item row="3" column="1">
<widget class="QDoubleSpinBox" name="doubleSpinBox_2">
<property name="toolTip">
<string>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;If you find that banging the stick around a lot makes the copter climb a bit, adjust this number down a little.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
<property name="accelerated">
<bool>true</bool>
</property>
<property name="decimals">
<number>2</number>
</property>
<property name="minimum">
<double>80.000000000000000</double>
</property>
<property name="maximum">
<double>120.000000000000000</double>
</property>
<property name="singleStep">
<double>0.250000000000000</double>
</property>
<property name="value">
<double>100.000000000000000</double>
</property>
<property name="objrelation" stdset="0">
<stringlist>
<string>objname:StabilizationSettings</string>
<string>fieldname:CruiseControlPowerTrim</string>
<string>haslimits:no</string>
<string>scale:1</string>
<string>buttongroup:16</string>
</stringlist>
</property>
</widget>
</item>
<item row="0" column="1">
<widget class="QLabel" name="label_4">
<property name="sizePolicy">
@ -24451,7 +24409,7 @@ border-radius: 5;</string>
</property>
<property name="minimumSize">
<size>
<width>140</width>
<width>90</width>
<height>16</height>
</size>
</property>
@ -24484,7 +24442,7 @@ border-radius: 5;</string>
</property>
<property name="minimumSize">
<size>
<width>140</width>
<width>92</width>
<height>16</height>
</size>
</property>
@ -24510,7 +24468,7 @@ border-radius: 5;</string>
<item row="1" column="3">
<widget class="QDoubleSpinBox" name="doubleSpinBox_4">
<property name="toolTip">
<string>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;Throttle/Collective stick below this disables Cruise Control. Also, by default Cruise Control forces the use of this value for thrust when the copter is inverted. For safety, never set this so low that the trimmed throttle/collective stick cannot get below it.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</string>
<string>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;Throttle/Collective stick below this amount disables Cruise Control. Also, by default Cruise Control forces the use of this value for thrust when InvertedPower setting is Zero and the copter is inverted. CP helis probably want this set to -100%. For safety with fixed pitch copters (including multicopters), never set this so low that the trimmed throttle stick cannot get below it or your motor(s) will still run with the throttle stick all the way down. Fixed pitch throttle sticks go from -100 to 0 in the first tiny bit of throttle stick (and then up to 100 using the rest of the throttle range), so for example, a lot of &amp;quot;high throttle trim&amp;quot; will keep the stick from ever commanding less than 5% so it won't be possible to stop the motors with the throttle stick. Banking the copter in your hand in this state will make the motors speed up.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
@ -24521,6 +24479,12 @@ border-radius: 5;</string>
<property name="decimals">
<number>0</number>
</property>
<property name="minimum">
<double>-100.000000000000000</double>
</property>
<property name="maximum">
<double>49.000000000000000</double>
</property>
<property name="value">
<double>5.000000000000000</double>
</property>
@ -24535,43 +24499,10 @@ border-radius: 5;</string>
</property>
</widget>
</item>
<item row="2" column="4">
<widget class="QLabel" name="label_11">
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>140</width>
<height>16</height>
</size>
</property>
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;</string>
</property>
<property name="text">
<string>NeutralThrust</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="3" column="3">
<widget class="QDoubleSpinBox" name="doubleSpinBox_5">
<property name="toolTip">
<string>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;Multi-copters should probably use 90% to 95% to leave some headroom for stabilization. CP helis can set this to 100%.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</string>
<string>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;Multi-copters should probably use 80% to 90% to leave some headroom for stabilization. CP helis can set this to 100%.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
@ -24582,6 +24513,9 @@ border-radius: 5;</string>
<property name="decimals">
<number>0</number>
</property>
<property name="minimum">
<double>51.000000000000000</double>
</property>
<property name="value">
<double>90.000000000000000</double>
</property>
@ -24606,7 +24540,7 @@ border-radius: 5;</string>
</property>
<property name="minimumSize">
<size>
<width>140</width>
<width>97</width>
<height>16</height>
</size>
</property>
@ -24629,8 +24563,24 @@ border-radius: 5;</string>
</property>
</widget>
</item>
<item row="0" column="4">
<widget class="QLabel" name="label_10">
<item row="1" column="0">
<spacer name="horizontalSpacer_60">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Fixed</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>90</width>
<height>11</height>
</size>
</property>
</spacer>
</item>
<item row="2" column="2">
<widget class="QLabel" name="label_6">
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Fixed">
<horstretch>0</horstretch>
@ -24639,7 +24589,68 @@ border-radius: 5;</string>
</property>
<property name="minimumSize">
<size>
<width>140</width>
<width>97</width>
<height>16</height>
</size>
</property>
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;</string>
</property>
<property name="text">
<string>PowerTrim</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="3" column="1">
<widget class="QDoubleSpinBox" name="doubleSpinBox_7">
<property name="toolTip">
<string>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;Moves the inverted mode power switching this fraction of a second into the future to compensate for slow responding power systems. Used to more accurately time the changing of power when entering/exiting inverted mode. Set this to equal the fraction of a second it takes for your vehicle to go from full negative thrust (10% positive thrust for multis, full negative thrust (-90%) for CP helis) to full positive thrust (+90%). Increase this if for example continuous left flips &amp;quot;walk off&amp;quot; to the left because power is changed too late.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
<property name="accelerated">
<bool>true</bool>
</property>
<property name="decimals">
<number>5</number>
</property>
<property name="maximum">
<double>2.000000000000000</double>
</property>
<property name="singleStep">
<double>0.001000000000000</double>
</property>
<property name="value">
<double>0.250000000000000</double>
</property>
<property name="objrelation" stdset="0">
<stringlist>
<string>objname:StabilizationSettings</string>
<string>fieldname:CruiseControlPowerDelayComp</string>
<string>haslimits:no</string>
<string>scale:1</string>
<string>buttongroup:16</string>
</stringlist>
</property>
</widget>
</item>
<item row="2" column="4">
<widget class="QLabel" name="label_12">
<property name="minimumSize">
<size>
<width>120</width>
<height>16</height>
</size>
</property>
@ -24662,21 +24673,58 @@ border-radius: 5;</string>
</property>
</widget>
</item>
<item row="1" column="0">
<spacer name="horizontalSpacer_60">
<property name="orientation">
<enum>Qt::Horizontal</enum>
<item row="3" column="2">
<widget class="QDoubleSpinBox" name="doubleSpinBox_2">
<property name="toolTip">
<string>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;If you find that quickly moving the stick around a lot makes the copter climb a bit, adjust this number down a little. It will be a compromise between climbing a little with lots of stick motion and descending a little with minimal stick motion.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</string>
</property>
<property name="sizeType">
<enum>QSizePolicy::Fixed</enum>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>90</width>
<height>11</height>
</size>
<property name="accelerated">
<bool>true</bool>
</property>
</spacer>
<property name="decimals">
<number>2</number>
</property>
<property name="minimum">
<double>50.000000000000000</double>
</property>
<property name="maximum">
<double>200.000000000000000</double>
</property>
<property name="singleStep">
<double>0.250000000000000</double>
</property>
<property name="value">
<double>100.000000000000000</double>
</property>
<property name="objrelation" stdset="0">
<stringlist>
<string>objname:StabilizationSettings</string>
<string>fieldname:CruiseControlPowerTrim</string>
<string>haslimits:no</string>
<string>scale:1</string>
<string>buttongroup:16</string>
</stringlist>
</property>
</widget>
</item>
<item row="3" column="4">
<widget class="QComboBox" name="comboBox_2">
<property name="toolTip">
<string>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;The amount of power used when in inverted mode. Zero (min throttle stick for fixed pitch copters includding multicopters, neutral collective for CP), Normal (uses stick value), or Boosted (boosted according to bank angle). Beginning multicopter pilots should leave this set to Zero to automatically reduce throttle during flips. Boosted power with Unreversed direction may be dangerous because it adds power and the thrust direction moves the aircraft towards the ground.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</string>
</property>
<property name="objrelation" stdset="0">
<stringlist>
<string>objname:StabilizationSettings</string>
<string>fieldname:CruiseControlInvertedPowerOutput</string>
<string>haslimits:no</string>
<string>scale:1</string>
<string>buttongroup:16</string>
</stringlist>
</property>
</widget>
</item>
</layout>
</widget>
@ -24770,8 +24818,8 @@ border-radius: 5;</string>
<rect>
<x>0</x>
<y>0</y>
<width>798</width>
<height>705</height>
<width>478</width>
<height>518</height>
</rect>
</property>
<layout class="QVBoxLayout" name="verticalLayout_18">
@ -26166,7 +26214,6 @@ border-radius: 5;</string>
</property>
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="styleSheet">
<string notr="true"/>

View File

@ -214,8 +214,8 @@ Up to 3 separate PID options (or option pairs) can be selected and updated.</str
<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>
margin:1px;
font:bold;</string>
</property>
<property name="text">
<string>PID option</string>
@ -243,8 +243,8 @@ margin:1px;</string>
<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>
margin:1px;
font:bold;</string>
</property>
<property name="text">
<string>Control Source</string>
@ -272,8 +272,8 @@ margin:1px;</string>
<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>
margin:1px;
font:bold;</string>
</property>
<property name="text">
<string>Min</string>
@ -301,8 +301,8 @@ margin:1px;</string>
<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>
margin:1px;
font:bold;</string>
</property>
<property name="text">
<string>Max</string>
@ -620,8 +620,8 @@ only when system is armed without disabling the module.</string>
<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>
margin:1px;
font:bold;</string>
</property>
<property name="text">
<string>Min</string>
@ -649,8 +649,8 @@ margin:1px;</string>
<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>
margin:1px;
font:bold;</string>
</property>
<property name="text">
<string>Max</string>

View File

@ -318,19 +318,34 @@ void VehicleConfigurationHelper::applyFlighModeConfiguration()
data.Stabilization1Settings[0] = FlightModeSettings::STABILIZATION1SETTINGS_ATTITUDE;
data.Stabilization1Settings[1] = FlightModeSettings::STABILIZATION1SETTINGS_ATTITUDE;
data.Stabilization1Settings[2] = FlightModeSettings::STABILIZATION1SETTINGS_AXISLOCK;
data.Stabilization1Settings[3] = FlightModeSettings::STABILIZATION1SETTINGS_MANUAL;
data.Stabilization2Settings[0] = FlightModeSettings::STABILIZATION2SETTINGS_ATTITUDE;
data.Stabilization2Settings[1] = FlightModeSettings::STABILIZATION2SETTINGS_ATTITUDE;
data.Stabilization2Settings[2] = FlightModeSettings::STABILIZATION2SETTINGS_RATE;
data.Stabilization2Settings[3] = FlightModeSettings::STABILIZATION2SETTINGS_MANUAL;
data.Stabilization3Settings[0] = FlightModeSettings::STABILIZATION3SETTINGS_RATE;
data.Stabilization3Settings[1] = FlightModeSettings::STABILIZATION3SETTINGS_RATE;
data.Stabilization3Settings[2] = FlightModeSettings::STABILIZATION3SETTINGS_RATE;
data.Stabilization3Settings[3] = FlightModeSettings::STABILIZATION3SETTINGS_MANUAL;
data.Stabilization4Settings[0] = FlightModeSettings::STABILIZATION4SETTINGS_ATTITUDE;
data.Stabilization4Settings[1] = FlightModeSettings::STABILIZATION4SETTINGS_ATTITUDE;
data.Stabilization4Settings[2] = FlightModeSettings::STABILIZATION4SETTINGS_AXISLOCK;
data.Stabilization4Settings[3] = FlightModeSettings::STABILIZATION4SETTINGS_CRUISECONTROL;
data.Stabilization5Settings[0] = FlightModeSettings::STABILIZATION5SETTINGS_ATTITUDE;
data.Stabilization5Settings[1] = FlightModeSettings::STABILIZATION5SETTINGS_ATTITUDE;
data.Stabilization5Settings[2] = FlightModeSettings::STABILIZATION5SETTINGS_RATE;
data.Stabilization5Settings[3] = FlightModeSettings::STABILIZATION5SETTINGS_CRUISECONTROL;
data.Stabilization6Settings[0] = FlightModeSettings::STABILIZATION6SETTINGS_RATE;
data.Stabilization6Settings[1] = FlightModeSettings::STABILIZATION6SETTINGS_RATE;
data.Stabilization6Settings[2] = FlightModeSettings::STABILIZATION6SETTINGS_RATE;
data.Stabilization6Settings[3] = FlightModeSettings::STABILIZATION6SETTINGS_CRUISECONTROL;
data2.FlightModeNumber = 3;
data.FlightModePosition[0] = FlightModeSettings::FLIGHTMODEPOSITION_STABILIZED1;
data.FlightModePosition[1] = FlightModeSettings::FLIGHTMODEPOSITION_STABILIZED2;
data.FlightModePosition[2] = FlightModeSettings::FLIGHTMODEPOSITION_STABILIZED3;
data.FlightModePosition[3] = FlightModeSettings::FLIGHTMODEPOSITION_ALTITUDEHOLD;
data.FlightModePosition[4] = FlightModeSettings::FLIGHTMODEPOSITION_POSITIONHOLD;
data.FlightModePosition[5] = FlightModeSettings::FLIGHTMODEPOSITION_MANUAL;
data.FlightModePosition[3] = FlightModeSettings::FLIGHTMODEPOSITION_STABILIZED4;
data.FlightModePosition[4] = FlightModeSettings::FLIGHTMODEPOSITION_STABILIZED5;
data.FlightModePosition[5] = FlightModeSettings::FLIGHTMODEPOSITION_STABILIZED6;
modeSettings->setData(data);
addModifiedObject(modeSettings, tr("Writing flight mode settings 1/2"));
controlSettings->setData(data2);

View File

@ -35,7 +35,6 @@ HEADERS += \
$$UAVOBJECT_SYNTHETICS/airspeedstate.h \
$$UAVOBJECT_SYNTHETICS/attitudestate.h \
$$UAVOBJECT_SYNTHETICS/attitudesimulated.h \
$$UAVOBJECT_SYNTHETICS/altitudeholddesired.h \
$$UAVOBJECT_SYNTHETICS/altitudeholdsettings.h \
$$UAVOBJECT_SYNTHETICS/altitudeholdstatus.h \
$$UAVOBJECT_SYNTHETICS/altitudefiltersettings.h \
@ -62,6 +61,7 @@ HEADERS += \
$$UAVOBJECT_SYNTHETICS/overosyncstats.h \
$$UAVOBJECT_SYNTHETICS/overosyncsettings.h \
$$UAVOBJECT_SYNTHETICS/systemsettings.h \
$$UAVOBJECT_SYNTHETICS/stabilizationstatus.h \
$$UAVOBJECT_SYNTHETICS/stabilizationsettings.h \
$$UAVOBJECT_SYNTHETICS/stabilizationsettingsbank1.h \
$$UAVOBJECT_SYNTHETICS/stabilizationsettingsbank2.h \
@ -136,7 +136,6 @@ SOURCES += \
$$UAVOBJECT_SYNTHETICS/airspeedstate.cpp \
$$UAVOBJECT_SYNTHETICS/attitudestate.cpp \
$$UAVOBJECT_SYNTHETICS/attitudesimulated.cpp \
$$UAVOBJECT_SYNTHETICS/altitudeholddesired.cpp \
$$UAVOBJECT_SYNTHETICS/altitudeholdsettings.cpp \
$$UAVOBJECT_SYNTHETICS/altitudeholdstatus.cpp \
$$UAVOBJECT_SYNTHETICS/debuglogsettings.cpp \
@ -163,6 +162,7 @@ SOURCES += \
$$UAVOBJECT_SYNTHETICS/overosyncstats.cpp \
$$UAVOBJECT_SYNTHETICS/overosyncsettings.cpp \
$$UAVOBJECT_SYNTHETICS/systemsettings.cpp \
$$UAVOBJECT_SYNTHETICS/stabilizationstatus.cpp \
$$UAVOBJECT_SYNTHETICS/stabilizationsettings.cpp \
$$UAVOBJECT_SYNTHETICS/stabilizationsettingsbank1.cpp \
$$UAVOBJECT_SYNTHETICS/stabilizationsettingsbank2.cpp \

View File

@ -106,6 +106,7 @@ SRC += $(FLIGHTLIB)/sanitycheck.c
SRC += $(FLIGHTLIB)/CoordinateConversions.c
SRC += $(MATHLIB)/sin_lookup.c
SRC += $(MATHLIB)/pid.c
SRC += $(MATHLIB)/mathmisc.c
SRC += $(FLIGHTLIB)/printf-stdarg.c
## Modules

View File

@ -3,6 +3,7 @@
<description>Settings for the @ref State Estimator module plugin altitudeFilter</description>
<field name="AccelLowPassKp" units="m/s^2" type="float" elements="1" defaultvalue="0.04"/>
<field name="AccelDriftKi" units="m/s^2" type="float" elements="1" defaultvalue="0.0005"/>
<field name="InitializationAccelDriftKi" units="m/s^2" type="float" elements="1" defaultvalue="0.2"/>
<field name="BaroKp" units="m" type="float" elements="1" defaultvalue="0.04"/>
<access gcs="readwrite" flight="readwrite"/>
<telemetrygcs acked="true" updatemode="onchange" period="0"/>

View File

@ -1,14 +0,0 @@
<xml>
<object name="AltitudeHoldDesired" singleinstance="true" settings="false" category="Control">
<description>Holds the desired altitude (from manual control) as well as the desired attitude to pass through</description>
<field name="SetPoint" units="" type="float" elements="1"/>
<field name="ControlMode" units="" type="enum" elements="1" options="Altitude,Velocity,Thrust" />
<field name="Roll" units="deg" type="float" elements="1"/>
<field name="Pitch" units="deg" type="float" elements="1"/>
<field name="Yaw" units="deg/s" type="float" elements="1"/>
<access gcs="readwrite" flight="readwrite"/>
<telemetrygcs acked="false" updatemode="manual" period="0"/>
<telemetryflight acked="false" updatemode="periodic" period="1000"/>
<logging updatemode="manual" period="0"/>
</object>
</xml>

View File

@ -6,6 +6,8 @@
<elementname>EventDispatcher</elementname>
<elementname>StateEstimation</elementname>
<elementname>AltitudeHold</elementname>
<elementname>Stabilization0</elementname>
<elementname>Stabilization1</elementname>
<elementname>PathPlanner0</elementname>
<elementname>PathPlanner1</elementname>
<elementname>ManualControl</elementname>
@ -16,6 +18,8 @@
<elementname>EventDispatcher</elementname>
<elementname>StateEstimation</elementname>
<elementname>AltitudeHold</elementname>
<elementname>Stabilization0</elementname>
<elementname>Stabilization1</elementname>
<elementname>PathPlanner0</elementname>
<elementname>PathPlanner1</elementname>
<elementname>ManualControl</elementname>
@ -30,6 +34,8 @@
<elementname>EventDispatcher</elementname>
<elementname>StateEstimation</elementname>
<elementname>AltitudeHold</elementname>
<elementname>Stabilization0</elementname>
<elementname>Stabilization1</elementname>
<elementname>PathPlanner0</elementname>
<elementname>PathPlanner1</elementname>
<elementname>ManualControl</elementname>

View File

@ -3,9 +3,8 @@
<description>Flight Battery configuration.</description>
<field name="Type" units="" type="enum" elements="1" options="LiPo,A123,LiCo,LiFeSO4,None" defaultvalue="LiPo"/>
<field name="NbCells" units="" type="uint8" elements="1" defaultvalue="3"/>
<field name="NbCells" units="" type="uint8" elements="1" defaultvalue="0"/>
<field name="Capacity" units="mAh" type="uint32" elements="1" defaultvalue="2200"/>
<field name="CellVoltageThresholds" units="V" type="float" elementnames="Warning, Alarm" defaultvalue="3.4,3.1"/>
<field name="SensorCalibrations" units="" type="float" elementnames="VoltageFactor, CurrentFactor, VoltageZero, CurrentZero" defaultvalue="1.0, 1.0, 0.0, 0.0"/>
<access gcs="readwrite" flight="readwrite"/>

View File

@ -8,6 +8,9 @@
<field name="AvgCurrent" units="A" type="float" elements="1" defaultvalue="0.0"/>
<field name="ConsumedEnergy" units="mAh" type="float" elements="1" defaultvalue="0.0"/>
<field name="EstimatedFlightTime" units="sec" type="float" elements="1" defaultvalue="0.0"/>
<field name="NbCells" units="" type="uint8" elements="1" defaultvalue="3"/>
<field name="NbCellsAutodetected" units="bool" type="enum" elements="1" options="False,True" defaultvalue="False"/>
<access gcs="readonly" flight="readwrite"/>
<telemetrygcs acked="false" updatemode="manual" period="0"/>
<telemetryflight acked="false" updatemode="periodic" period="1000"/>

View File

@ -6,20 +6,71 @@
<!-- 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,VirtualBar,Rattitude,RelayRate,RelayAttitude"
defaultvalue="Attitude,Attitude,AxisLock"
limits="%NE:RelayRate:RelayAttitude; %NE:RelayRate:RelayAttitude; %NE:RelayRate:RelayAttitude;"/>
elementnames="Roll,Pitch,Yaw,Thrust"
options="Manual,Rate,Attitude,AxisLock,WeakLeveling,VirtualBar,Rattitude,RelayRate,RelayAttitude,AltitudeHold,VerticalVelocity,CruiseControl"
defaultvalue="Attitude,Attitude,AxisLock,Manual"
limits="%NE:RelayRate:RelayAttitude:AltitudeHold:VerticalVelocity:CruiseControl; \
%NE:RelayRate:RelayAttitude:AltitudeHold:VerticalVelocity:CruiseControl; \
%NE:RelayRate:RelayAttitude:AltitudeHold:VerticalVelocity:CruiseControl; \
%NE:Rate:Attitude:AxisLock:WeakLeveling:VirtualBar:Rattitude:RelayRate:RelayAttitude,\
%0401NE:Rate:Attitude:AxisLock:WeakLeveling:VirtualBar:Rattitude:RelayRate:RelayAttitude:AltitudeHold:VerticalVelocity,\
%0402NE:Rate:Attitude:AxisLock:WeakLeveling:VirtualBar:Rattitude:RelayRate:RelayAttitude:AltitudeHold:VerticalVelocity;"
/>
<field name="Stabilization2Settings" units="" type="enum"
elementnames="Roll,Pitch,Yaw"
options="None,Rate,Attitude,AxisLock,WeakLeveling,VirtualBar,Rattitude,RelayRate,RelayAttitude"
defaultvalue="Attitude,Attitude,Rate"
limits="%NE:RelayRate:RelayAttitude; %NE:RelayRate:RelayAttitude; %NE:RelayRate:RelayAttitude;"/>
elementnames="Roll,Pitch,Yaw,Thrust"
options="Manual,Rate,Attitude,AxisLock,WeakLeveling,VirtualBar,Rattitude,RelayRate,RelayAttitude,AltitudeHold,VerticalVelocity,CruiseControl"
defaultvalue="Attitude,Attitude,Rate,Manual"
limits="%NE:RelayRate:RelayAttitude:AltitudeHold:VerticalVelocity:CruiseControl; \
%NE:RelayRate:RelayAttitude:AltitudeHold:VerticalVelocity:CruiseControl; \
%NE:RelayRate:RelayAttitude:AltitudeHold:VerticalVelocity:CruiseControl; \
%NE:Rate:Attitude:AxisLock:WeakLeveling:VirtualBar:Rattitude:RelayRate:RelayAttitude,\
%0401NE:Rate:Attitude:AxisLock:WeakLeveling:VirtualBar:Rattitude:RelayRate:RelayAttitude:AltitudeHold:VerticalVelocity,\
%0402NE:Rate:Attitude:AxisLock:WeakLeveling:VirtualBar:Rattitude:RelayRate:RelayAttitude:AltitudeHold:VerticalVelocity;"
/>
<field name="Stabilization3Settings" units="" type="enum"
elementnames="Roll,Pitch,Yaw"
options="None,Rate,Attitude,AxisLock,WeakLeveling,VirtualBar,Rattitude,RelayRate,RelayAttitude"
defaultvalue="Rate,Rate,Rate"
limits="%NE:RelayRate:RelayAttitude; %NE:RelayRate:RelayAttitude; %NE:RelayRate:RelayAttitude;"/>
elementnames="Roll,Pitch,Yaw,Thrust"
options="Manual,Rate,Attitude,AxisLock,WeakLeveling,VirtualBar,Rattitude,RelayRate,RelayAttitude,AltitudeHold,VerticalVelocity,CruiseControl"
defaultvalue="Rate,Rate,Rate,Manual"
limits="%NE:RelayRate:RelayAttitude:AltitudeHold:VerticalVelocity:CruiseControl; \
%NE:RelayRate:RelayAttitude:AltitudeHold:VerticalVelocity:CruiseControl; \
%NE:RelayRate:RelayAttitude:AltitudeHold:VerticalVelocity:CruiseControl; \
%NE:Rate:Attitude:AxisLock:WeakLeveling:VirtualBar:Rattitude:RelayRate:RelayAttitude,\
%0401NE:Rate:Attitude:AxisLock:WeakLeveling:VirtualBar:Rattitude:RelayRate:RelayAttitude:AltitudeHold:VerticalVelocity,\
%0402NE:Rate:Attitude:AxisLock:WeakLeveling:VirtualBar:Rattitude:RelayRate:RelayAttitude:AltitudeHold:VerticalVelocity;"
/>
<field name="Stabilization4Settings" units="" type="enum"
elementnames="Roll,Pitch,Yaw,Thrust"
options="Manual,Rate,Attitude,AxisLock,WeakLeveling,VirtualBar,Rattitude,RelayRate,RelayAttitude,AltitudeHold,VerticalVelocity,CruiseControl"
defaultvalue="Attitude,Attitude,AxisLock,CruiseControl"
limits="%NE:RelayRate:RelayAttitude:AltitudeHold:VerticalVelocity:CruiseControl; \
%NE:RelayRate:RelayAttitude:AltitudeHold:VerticalVelocity:CruiseControl; \
%NE:RelayRate:RelayAttitude:AltitudeHold:VerticalVelocity:CruiseControl; \
%NE:Rate:Attitude:AxisLock:WeakLeveling:VirtualBar:Rattitude:RelayRate:RelayAttitude,\
%0401NE:Rate:Attitude:AxisLock:WeakLeveling:VirtualBar:Rattitude:RelayRate:RelayAttitude:AltitudeHold:VerticalVelocity,\
%0402NE:Rate:Attitude:AxisLock:WeakLeveling:VirtualBar:Rattitude:RelayRate:RelayAttitude:AltitudeHold:VerticalVelocity;"
/>
<field name="Stabilization5Settings" units="" type="enum"
elementnames="Roll,Pitch,Yaw,Thrust"
options="Manual,Rate,Attitude,AxisLock,WeakLeveling,VirtualBar,Rattitude,RelayRate,RelayAttitude,AltitudeHold,VerticalVelocity,CruiseControl"
defaultvalue="Attitude,Attitude,Rate,CruiseControl"
limits="%NE:RelayRate:RelayAttitude:AltitudeHold:VerticalVelocity:CruiseControl; \
%NE:RelayRate:RelayAttitude:AltitudeHold:VerticalVelocity:CruiseControl; \
%NE:RelayRate:RelayAttitude:AltitudeHold:VerticalVelocity:CruiseControl; \
%NE:Rate:Attitude:AxisLock:WeakLeveling:VirtualBar:Rattitude:RelayRate:RelayAttitude,\
%0401NE:Rate:Attitude:AxisLock:WeakLeveling:VirtualBar:Rattitude:RelayRate:RelayAttitude:AltitudeHold:VerticalVelocity,\
%0402NE:Rate:Attitude:AxisLock:WeakLeveling:VirtualBar:Rattitude:RelayRate:RelayAttitude:AltitudeHold:VerticalVelocity;"
/>
<field name="Stabilization6Settings" units="" type="enum"
elementnames="Roll,Pitch,Yaw,Thrust"
options="Manual,Rate,Attitude,AxisLock,WeakLeveling,VirtualBar,Rattitude,RelayRate,RelayAttitude,AltitudeHold,VerticalVelocity,CruiseControl"
defaultvalue="Rate,Rate,Rate,CruiseControl"
limits="%NE:RelayRate:RelayAttitude:AltitudeHold:VerticalVelocity:CruiseControl; \
%NE:RelayRate:RelayAttitude:AltitudeHold:VerticalVelocity:CruiseControl; \
%NE:RelayRate:RelayAttitude:AltitudeHold:VerticalVelocity:CruiseControl; \
%NE:Rate:Attitude:AxisLock:WeakLeveling:VirtualBar:Rattitude:RelayRate:RelayAttitude,\
%0401NE:Rate:Attitude:AxisLock:WeakLeveling:VirtualBar:Rattitude:RelayRate:RelayAttitude:AltitudeHold:VerticalVelocity,\
%0402NE:Rate:Attitude:AxisLock:WeakLeveling:VirtualBar:Rattitude:RelayRate:RelayAttitude:AltitudeHold:VerticalVelocity;"
/>
<!-- Note these options values should be identical to those defined in FlightMode -->
<!-- Currently only some modes are enabled for UI using limits attribute per board. Update when more modes will be operational -->
@ -27,32 +78,32 @@
units=""
type="enum"
elements="6"
options="Manual,Stabilized1,Stabilized2,Stabilized3,Autotune,AltitudeHold,AltitudeVario,VelocityControl,PositionHold,ReturnToBase,Land,PathPlanner,POI"
defaultvalue="Stabilized1,Stabilized2,Stabilized3,AltitudeHold,AltitudeVario,Manual"
options="Manual,Stabilized1,Stabilized2,Stabilized3,Stabilized4,Stabilized5,Stabilized6,Autotune,PositionHold,ReturnToBase,Land,PathPlanner,POI"
defaultvalue="Stabilized1,Stabilized2,Stabilized3,Stabilized4,Stabilized5,Stabilized6"
limits="\
%0401NE:Autotune:AltitudeVario:AltitudeHold:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner:POI,\
%0402NE:Autotune:AltitudeVario:AltitudeHold:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner:POI,\
%0903NE:Autotune:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner:POI;\
%0401NE:Autotune:PositionHold:ReturnToBase:Land:PathPlanner:POI,\
%0402NE:Autotune:PositionHold:ReturnToBase:Land:PathPlanner:POI,\
%0903NE:Autotune:PositionHold:ReturnToBase:Land:PathPlanner:POI;\
\
%0401NE:Autotune:AltitudeVario:AltitudeHold:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner:POI,\
%0402NE:Autotune:AltitudeVario:AltitudeHold:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner:POI,\
%0903NE:Autotune:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner:POI;\
%0401NE:Autotune:PositionHold:ReturnToBase:Land:PathPlanner:POI,\
%0402NE:Autotune:PositionHold:ReturnToBase:Land:PathPlanner:POI,\
%0903NE:Autotune:PositionHold:ReturnToBase:Land:PathPlanner:POI;\
\
%0401NE:Autotune:AltitudeVario:AltitudeHold:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner:POI,\
%0402NE:Autotune:AltitudeVario:AltitudeHold:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner:POI,\
%0903NE:Autotune:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner:POI;\
%0401NE:Autotune:PositionHold:ReturnToBase:Land:PathPlanner:POI,\
%0402NE:Autotune:PositionHold:ReturnToBase:Land:PathPlanner:POI,\
%0903NE:Autotune:PositionHold:ReturnToBase:Land:PathPlanner:POI;\
\
%0401NE:Autotune:AltitudeVario:AltitudeHold:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner:POI,\
%0402NE:Autotune:AltitudeVario:AltitudeHold:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner:POI,\
%0903NE:Autotune:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner:POI;\
%0401NE:Autotune:PositionHold:ReturnToBase:Land:PathPlanner:POI,\
%0402NE:Autotune:PositionHold:ReturnToBase:Land:PathPlanner:POI,\
%0903NE:Autotune:PositionHold:ReturnToBase:Land:PathPlanner:POI;\
\
%0401NE:Autotune:AltitudeVario:AltitudeHold:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner:POI,\
%0402NE:Autotune:AltitudeVario:AltitudeHold:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner:POI,\
%0903NE:Autotune:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner:POI;\
%0401NE:Autotune:PositionHold:ReturnToBase:Land:PathPlanner:POI,\
%0402NE:Autotune:PositionHold:ReturnToBase:Land:PathPlanner:POI,\
%0903NE:Autotune:PositionHold:ReturnToBase:Land:PathPlanner:POI;\
\
%0401NE:Autotune:AltitudeVario:AltitudeHold:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner:POI,\
%0402NE:Autotune:AltitudeVario:AltitudeHold:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner:POI,\
%0903NE:Autotune:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner:POI"/>
%0401NE:Autotune:PositionHold:ReturnToBase:Land:PathPlanner:POI,\
%0402NE:Autotune:PositionHold:ReturnToBase:Land:PathPlanner:POI,\
%0903NE:Autotune:PositionHold:ReturnToBase:Land:PathPlanner:POI"/>
<field name="ArmedTimeout" units="ms" type="uint16" elements="1" defaultvalue="30000"/>
<field name="ArmingSequenceTime" units="ms" type="uint16" elements="1" defaultvalue="1000"/>

Some files were not shown because too many files have changed in this diff Show More