Merge remote branch 'origin/next' into os/TxPID-module
2
.gitignore
vendored
@ -1,3 +1,5 @@
|
||||
# Exclude temporary and system files
|
||||
.DS_Store
|
||||
|
||||
# /flight/
|
||||
/flight/*.pnproj
|
||||
|
@ -1,5 +1,9 @@
|
||||
Short summary of changes. For a complete list see the git log.
|
||||
|
||||
2011-12-10
|
||||
Merged a change that sorts the UAVO fields based on size. Because this changes
|
||||
all of the objects, erase all existing flash files based on this.
|
||||
|
||||
2011-11-04
|
||||
New Spektrum/JR satellite receiver driver implementation.
|
||||
It now provides explicit selection of DSM2 (and DSMJ), DSMX (10bit) and
|
||||
|
@ -149,9 +149,19 @@ V: http://www.youtube.com/watch?v=8SrfIS7OkB4
|
||||
|
||||
M: First CopterControl Return to Base Fixed Wing
|
||||
C: Eric Price (Corvus Corax)
|
||||
D: AUgust 2011
|
||||
D: August 2011
|
||||
V: http://www.youtube.com/watch?v=CugI0oBSQn8
|
||||
|
||||
M: First CopterControl flip on a Flybarless Heli
|
||||
C: Anders Johansson (dezent)
|
||||
D: November 2011
|
||||
V: http://www.youtube.com/watch?v=Xfas2TUhOPw
|
||||
|
||||
M: First OpenPilot over 1km FixedWing navigation flight
|
||||
C: Eric Price (Corvus Corax)
|
||||
D: December 2011
|
||||
V: http://www.youtube.com/watch?v=nWNWuUiUTNg
|
||||
|
||||
|
||||
M: First Altitude Hold using Sonar
|
||||
C:
|
||||
@ -168,11 +178,6 @@ C:
|
||||
D:
|
||||
V:
|
||||
|
||||
M: First CopterControl flip on a Flybarless Heli
|
||||
C:
|
||||
D:
|
||||
V:
|
||||
|
||||
|
||||
An incomplete list of some future Milestones is below:
|
||||
|
||||
@ -184,8 +189,6 @@ An incomplete list of some future Milestones is below:
|
||||
* First fixed wing navigation flight
|
||||
* First Multirotor navigation flight
|
||||
* First Helicopter navigation flight
|
||||
* First over 1km navigation flight
|
||||
* First over 5km navigation flight
|
||||
* First "Follow Me" navigation flight
|
||||
* First Channel Crossing with OpenPilot
|
||||
|
||||
|
BIN
artwork/3D Model/multi/ricoo/CC.PNG
Normal file
After Width: | Height: | Size: 96 KiB |
BIN
artwork/3D Model/multi/ricoo/TEXTURE.PNG
Normal file
After Width: | Height: | Size: 51 KiB |
BIN
artwork/3D Model/multi/ricoo/ricoo.3DS
Normal file
BIN
artwork/3D Model/multi/ricoo/ricoo.jpg
Normal file
After Width: | Height: | Size: 111 KiB |
@ -70,6 +70,12 @@ int main()
|
||||
* */
|
||||
PIOS_Board_Init();
|
||||
|
||||
#ifdef ERASE_FLASH
|
||||
PIOS_Flash_W25X_EraseChip();
|
||||
PIOS_LED_Off(LED1);
|
||||
while (1) ;
|
||||
#endif
|
||||
|
||||
/* Initialize modules */
|
||||
MODULE_INITIALISE_ALL
|
||||
|
||||
@ -82,11 +88,11 @@ int main()
|
||||
/* If all is well we will never reach here as the scheduler will now be running. */
|
||||
|
||||
/* Do some indication to user that something bad just happened */
|
||||
PIOS_LED_Off(LED1); \
|
||||
for(;;) { \
|
||||
PIOS_LED_Toggle(LED1); \
|
||||
PIOS_DELAY_WaitmS(100); \
|
||||
};
|
||||
PIOS_LED_Off(LED1);
|
||||
while (1) {
|
||||
PIOS_LED_Toggle(LED1);
|
||||
PIOS_DELAY_WaitmS(100);
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
@ -1365,7 +1365,7 @@ void PIOS_Board_Init(void) {
|
||||
#endif /* PIOS_INCLUDE_PWM */
|
||||
break;
|
||||
case HWSETTINGS_CC_RCVRPORT_PPM:
|
||||
case HWSETTINGS_CC_RCVRPORT_PPMSERVO:
|
||||
case HWSETTINGS_CC_RCVRPORT_PPMOUTPUTS:
|
||||
#if defined(PIOS_INCLUDE_PPM)
|
||||
{
|
||||
uint32_t pios_ppm_id;
|
||||
@ -1401,8 +1401,8 @@ void PIOS_Board_Init(void) {
|
||||
case HWSETTINGS_CC_RCVRPORT_PPM:
|
||||
PIOS_Servo_Init(&pios_servo_cfg);
|
||||
break;
|
||||
case HWSETTINGS_CC_RCVRPORT_PPMSERVO:
|
||||
case HWSETTINGS_CC_RCVRPORT_SERVO:
|
||||
case HWSETTINGS_CC_RCVRPORT_PPMOUTPUTS:
|
||||
case HWSETTINGS_CC_RCVRPORT_OUTPUTS:
|
||||
PIOS_Servo_Init(&pios_servo_rcvr_cfg);
|
||||
break;
|
||||
}
|
||||
@ -1430,7 +1430,9 @@ void PIOS_Board_Init(void) {
|
||||
#endif /* PIOS_INCLUDE_USB_HID */
|
||||
|
||||
PIOS_IAP_Init();
|
||||
#ifndef ERASE_FLASH
|
||||
PIOS_WDG_Init();
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
|
@ -207,7 +207,7 @@ static void actuatorTask(void* parameters)
|
||||
nMixers ++;
|
||||
}
|
||||
}
|
||||
if((nMixers < 2) && !ActuatorCommandReadOnly(dummy)) //Nothing can fly with less than two mixers.
|
||||
if((nMixers < 2) && !ActuatorCommandReadOnly()) //Nothing can fly with less than two mixers.
|
||||
{
|
||||
setFailsafe(); // So that channels like PWM buzzer keep working
|
||||
continue;
|
||||
|
@ -62,8 +62,6 @@
|
||||
|
||||
// Private variables
|
||||
|
||||
static uint8_t camerastabEnabled = 0;
|
||||
|
||||
// Private functions
|
||||
static void attitudeUpdated(UAVObjEvent* ev);
|
||||
static float bound(float val);
|
||||
@ -76,16 +74,18 @@ int32_t CameraStabInitialize(void)
|
||||
{
|
||||
static UAVObjEvent ev;
|
||||
|
||||
HwSettingsInitialize();
|
||||
bool cameraStabEnabled;
|
||||
uint8_t optionalModules[HWSETTINGS_OPTIONALMODULES_NUMELEM];
|
||||
HwSettingsOptionalModulesGet(optionalModules);
|
||||
if (optionalModules[HWSETTINGS_OPTIONALMODULES_CAMERASTAB] == HWSETTINGS_OPTIONALMODULES_ENABLED) {
|
||||
camerastabEnabled=1;
|
||||
} else {
|
||||
camerastabEnabled=0;
|
||||
}
|
||||
|
||||
if (camerastabEnabled) {
|
||||
HwSettingsInitialize();
|
||||
HwSettingsOptionalModulesGet(optionalModules);
|
||||
|
||||
if (optionalModules[HWSETTINGS_OPTIONALMODULES_CAMERASTAB] == HWSETTINGS_OPTIONALMODULES_ENABLED)
|
||||
cameraStabEnabled = true;
|
||||
else
|
||||
cameraStabEnabled = false;
|
||||
|
||||
if (cameraStabEnabled) {
|
||||
|
||||
AttitudeActualInitialize();
|
||||
|
||||
|
@ -120,14 +120,16 @@ int32_t GPSStart(void)
|
||||
int32_t GPSInitialize(void)
|
||||
{
|
||||
gpsPort = PIOS_COM_GPS;
|
||||
|
||||
HwSettingsInitialize();
|
||||
uint8_t optionalModules[HWSETTINGS_OPTIONALMODULES_NUMELEM];
|
||||
|
||||
HwSettingsOptionalModulesGet(optionalModules);
|
||||
if (optionalModules[HWSETTINGS_OPTIONALMODULES_GPS] == HWSETTINGS_OPTIONALMODULES_ENABLED) {
|
||||
|
||||
if (optionalModules[HWSETTINGS_OPTIONALMODULES_GPS] == HWSETTINGS_OPTIONALMODULES_ENABLED)
|
||||
gpsEnabled = true;
|
||||
} else {
|
||||
else
|
||||
gpsEnabled = false;
|
||||
}
|
||||
|
||||
if (gpsPort && gpsEnabled) {
|
||||
GPSPositionInitialize();
|
||||
@ -149,6 +151,7 @@ int32_t GPSInitialize(void)
|
||||
|
||||
return -1;
|
||||
}
|
||||
|
||||
MODULE_INITCALL(GPSInitialize, GPSStart)
|
||||
|
||||
// ****************
|
||||
|
@ -189,19 +189,19 @@ static void manualControlTask(void *parameters)
|
||||
lastActivityTime = lastSysTime;
|
||||
}
|
||||
|
||||
if (ManualControlCommandReadOnly(&cmd)) {
|
||||
if (ManualControlCommandReadOnly()) {
|
||||
FlightTelemetryStatsData flightTelemStats;
|
||||
FlightTelemetryStatsGet(&flightTelemStats);
|
||||
if(flightTelemStats.Status != FLIGHTTELEMETRYSTATS_STATUS_CONNECTED) {
|
||||
/* trying to fly via GCS and lost connection. fall back to transmitter */
|
||||
UAVObjMetadata metadata;
|
||||
UAVObjGetMetadata(&cmd, &metadata);
|
||||
ManualControlCommandGetMetadata(&metadata);
|
||||
metadata.access = ACCESS_READWRITE;
|
||||
UAVObjSetMetadata(&cmd, &metadata);
|
||||
ManualControlCommandSetMetadata(&metadata);
|
||||
}
|
||||
}
|
||||
|
||||
if (!ManualControlCommandReadOnly(&cmd)) {
|
||||
if (!ManualControlCommandReadOnly()) {
|
||||
|
||||
bool valid_input_detected = true;
|
||||
|
||||
|
@ -56,8 +56,8 @@ struct fileHeader {
|
||||
} __attribute__((packed));
|
||||
|
||||
|
||||
#define OBJECT_TABLE_MAGIC 0x85FB3C35
|
||||
#define OBJ_MAGIC 0x3015AE71
|
||||
#define OBJECT_TABLE_MAGIC 0x85FB3D35
|
||||
#define OBJ_MAGIC 0x3015A371
|
||||
#define OBJECT_TABLE_START 0x00000010
|
||||
#define OBJECT_TABLE_END 0x00001000
|
||||
#define SECTOR_SIZE 0x00001000
|
||||
|
@ -1,5 +1,5 @@
|
||||
/* This is the size of the stack for all FreeRTOS IRQs */
|
||||
_irq_stack_size = 0x1A0;
|
||||
_irq_stack_size = 0x1E6;
|
||||
/* This is the size of the stack for early init: life span is until scheduler starts */
|
||||
_init_stack_size = 0x100;
|
||||
|
||||
|
@ -91,12 +91,11 @@
|
||||
* if this receiver is a master (provides receiver capabilities info to
|
||||
* the transmitter to choose data format) or slave (does not respond to
|
||||
* the transmitter which falls back to the old DSM mode in that case).
|
||||
* Currently known are 3(4) pulses for low resolution (10 bit) mode, and
|
||||
* 5(6) pulses for high resolution (11 bit) mode. Thus only 3 or 5 pulses
|
||||
* should be used for stand-alone satellite receiver to be bound correctly
|
||||
* as the master. 5 pulses (high resolution) mode simulates high-end
|
||||
* receivers which should work in all cases except user explicitly wants
|
||||
* to bind in low resolution mode.
|
||||
* Currently known are 3(4) pulses for low resolution (10 bit) DSM2 mode,
|
||||
* 5(6) pulses for high resolution (11 bit) DSM2 mode, and also 7(8) and
|
||||
* 9(10) pulses for DSMX modes. Thus only 3, 5, 7 or 9 pulses should be
|
||||
* used for stand-alone satellite receiver to be bound correctly as the
|
||||
* master.
|
||||
*/
|
||||
|
||||
#define DSM_CHANNELS_PER_FRAME 7
|
||||
|
@ -3139,6 +3139,7 @@
|
||||
65F93D0712EE09290047DB36 /* uavtalk_comms.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = uavtalk_comms.c; sourceTree = "<group>"; };
|
||||
65F93D0812EE09290047DB36 /* watchdog.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = watchdog.c; sourceTree = "<group>"; };
|
||||
65FAA03F133B669400F6F5CD /* GTOP_BIN.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = GTOP_BIN.c; sourceTree = "<group>"; };
|
||||
65FAB8CF147FFD76000FF8B2 /* receiveractivity.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = receiveractivity.xml; sourceTree = "<group>"; };
|
||||
65FBE14412E7C98100176B5A /* pios_servo_priv.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_servo_priv.h; sourceTree = "<group>"; };
|
||||
65FC66AA123F30F100B04F74 /* ahrs_timer.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = ahrs_timer.c; path = ../../AHRS/ahrs_timer.c; sourceTree = SOURCE_ROOT; };
|
||||
65FC66AB123F312A00B04F74 /* ahrs_timer.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = ahrs_timer.h; sourceTree = "<group>"; };
|
||||
@ -7469,6 +7470,7 @@
|
||||
65C35E6E12EFB2F3004811C2 /* positionactual.xml */,
|
||||
65C35E6F12EFB2F3004811C2 /* positiondesired.xml */,
|
||||
65C35E7012EFB2F3004811C2 /* ratedesired.xml */,
|
||||
65FAB8CF147FFD76000FF8B2 /* receiveractivity.xml */,
|
||||
652C856A132B6EA600BFCC70 /* sonaraltitude.xml */,
|
||||
6536D47B1307962C0042A298 /* stabilizationdesired.xml */,
|
||||
65C35E7112EFB2F3004811C2 /* stabilizationsettings.xml */,
|
||||
|
@ -67,7 +67,7 @@
|
||||
#define $(NAME)InstUpdated(instId) UAVObjUpdated($(NAME)Handle(), instId)
|
||||
#define $(NAME)GetMetadata(dataOut) UAVObjGetMetadata($(NAME)Handle(), dataOut)
|
||||
#define $(NAME)SetMetadata(dataIn) UAVObjSetMetadata($(NAME)Handle(), dataIn)
|
||||
#define $(NAME)ReadOnly(dataIn) UAVObjReadOnly($(NAME)Handle())
|
||||
#define $(NAME)ReadOnly() UAVObjReadOnly($(NAME)Handle())
|
||||
|
||||
// Object data
|
||||
typedef struct {
|
||||
|
BIN
ground/openpilotgcs/share/openpilotgcs/models/multi/ricoo/CC.PNG
Normal file
After Width: | Height: | Size: 96 KiB |
After Width: | Height: | Size: 51 KiB |
After Width: | Height: | Size: 111 KiB |
@ -1,7 +1,6 @@
|
||||
TEMPLATE = lib
|
||||
TARGET = Config
|
||||
QT += svg
|
||||
|
||||
include(../../openpilotgcsplugin.pri)
|
||||
include(../../libs/utils/utils.pri)
|
||||
include(../../plugins/uavtalk/uavtalk.pri)
|
||||
@ -10,9 +9,7 @@ include(../../plugins/uavobjects/uavobjects.pri)
|
||||
include(../../plugins/uavobjectutil/uavobjectutil.pri)
|
||||
include(../../plugins/uavsettingsimportexport/uavsettingsimportexport.pri)
|
||||
INCLUDEPATH += ../../libs/eigen
|
||||
|
||||
OTHER_FILES += Config.pluginspec
|
||||
|
||||
HEADERS += configplugin.h \
|
||||
configgadgetconfiguration.h \
|
||||
configgadgetwidget.h \
|
||||
@ -39,8 +36,8 @@ HEADERS += configplugin.h \
|
||||
smartsavebutton.h \
|
||||
defaulthwsettingswidget.h \
|
||||
inputchannelform.h \
|
||||
configcamerastabilizationwidget.h
|
||||
|
||||
configcamerastabilizationwidget.h \
|
||||
outputchannelform.h
|
||||
SOURCES += configplugin.cpp \
|
||||
configgadgetconfiguration.cpp \
|
||||
configgadgetwidget.cpp \
|
||||
@ -69,10 +66,9 @@ SOURCES += configplugin.cpp \
|
||||
smartsavebutton.cpp \
|
||||
defaulthwsettingswidget.cpp \
|
||||
inputchannelform.cpp \
|
||||
configcamerastabilizationwidget.cpp
|
||||
|
||||
FORMS += \
|
||||
airframe.ui \
|
||||
configcamerastabilizationwidget.cpp \
|
||||
outputchannelform.cpp
|
||||
FORMS += airframe.ui \
|
||||
cc_hw_settings.ui \
|
||||
pro_hw_settings.ui \
|
||||
ahrs.ui \
|
||||
@ -84,10 +80,6 @@ FORMS += \
|
||||
defaultattitude.ui \
|
||||
defaulthwsettings.ui \
|
||||
inputchannelform.ui \
|
||||
camerastabilization.ui
|
||||
|
||||
camerastabilization.ui \
|
||||
outputchannelform.ui
|
||||
RESOURCES += configgadget.qrc
|
||||
|
||||
|
||||
|
||||
|
||||
|
@ -134,6 +134,7 @@ void ConfigGadgetWidget::onAutopilotDisconnect() {
|
||||
|
||||
void ConfigGadgetWidget::onAutopilotConnect() {
|
||||
|
||||
qDebug()<<"ConfigGadgetWidget onAutopilotConnect";
|
||||
// First of all, check what Board type we are talking to, and
|
||||
// if necessary, remove/add tabs in the config gadget:
|
||||
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
|
||||
|
@ -293,6 +293,7 @@ void ConfigInputWidget::wzCancel()
|
||||
if(wizardStep != wizardNone)
|
||||
wizardTearDownStep(wizardStep);
|
||||
wizardStep=wizardNone;
|
||||
m_config->stackedWidget->setCurrentIndex(0);
|
||||
|
||||
// Load settings back from beginning of wizard
|
||||
manualSettingsObj->setData(previousManualSettingsData);
|
||||
@ -334,23 +335,8 @@ void ConfigInputWidget::wzNext()
|
||||
wizardSetUpStep(wizardFinish);
|
||||
break;
|
||||
case wizardFinish:
|
||||
setTxMovement(nothing);
|
||||
manualCommandObj->setMetadata(manualCommandObj->getDefaultMetadata());
|
||||
disconnect(manualCommandObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(moveSticks()));
|
||||
manualSettingsData=manualSettingsObj->getData();
|
||||
manualSettingsData.ChannelNeutral[ManualControlSettings::CHANNELNEUTRAL_THROTTLE]=
|
||||
manualSettingsData.ChannelMin[ManualControlSettings::CHANNELMIN_THROTTLE]+
|
||||
((manualSettingsData.ChannelMax[ManualControlSettings::CHANNELMAX_THROTTLE]-
|
||||
manualSettingsData.ChannelMin[ManualControlSettings::CHANNELMIN_THROTTLE])*0.02);
|
||||
if((abs(manualSettingsData.ChannelMax[ManualControlSettings::CHANNELMAX_FLIGHTMODE]-manualSettingsData.ChannelNeutral[ManualControlSettings::CHANNELNEUTRAL_FLIGHTMODE])<100) ||
|
||||
(abs(manualSettingsData.ChannelMin[ManualControlSettings::CHANNELMIN_FLIGHTMODE]-manualSettingsData.ChannelNeutral[ManualControlSettings::CHANNELNEUTRAL_FLIGHTMODE])<100))
|
||||
{
|
||||
manualSettingsData.ChannelNeutral[ManualControlSettings::CHANNELNEUTRAL_FLIGHTMODE]=manualSettingsData.ChannelMin[ManualControlSettings::CHANNELMIN_FLIGHTMODE]+
|
||||
(manualSettingsData.ChannelMax[ManualControlSettings::CHANNELMAX_FLIGHTMODE]-manualSettingsData.ChannelMin[ManualControlSettings::CHANNELMIN_FLIGHTMODE])/2;
|
||||
}
|
||||
manualSettingsObj->setData(manualSettingsData);
|
||||
m_config->stackedWidget->setCurrentIndex(0);
|
||||
wizardStep=wizardNone;
|
||||
m_config->stackedWidget->setCurrentIndex(0);
|
||||
break;
|
||||
default:
|
||||
Q_ASSERT(0);
|
||||
@ -463,15 +449,21 @@ void ConfigInputWidget::wizardSetUpStep(enum wizardSteps step)
|
||||
break;
|
||||
case wizardIdentifyLimits:
|
||||
{
|
||||
dimOtherControls(false);
|
||||
setTxMovement(nothing);
|
||||
m_config->wzText->setText(QString(tr("Please move all controls to their maximum extents on both directions and press next when ready")));
|
||||
fastMdata();
|
||||
manualSettingsData=manualSettingsObj->getData();
|
||||
for(uint i=0;i<ManualControlSettings::CHANNELMAX_NUMELEM;++i)
|
||||
{
|
||||
manualSettingsData.ChannelMin[i]=manualSettingsData.ChannelNeutral[i];
|
||||
manualSettingsData.ChannelMax[i]=manualSettingsData.ChannelNeutral[i];
|
||||
// Preserve the inverted status
|
||||
if(manualSettingsData.ChannelMin[i] <= manualSettingsData.ChannelMax[i]) {
|
||||
manualSettingsData.ChannelMin[i]=manualSettingsData.ChannelNeutral[i];
|
||||
manualSettingsData.ChannelMax[i]=manualSettingsData.ChannelNeutral[i];
|
||||
} else {
|
||||
// Make this detect as still inverted
|
||||
manualSettingsData.ChannelMin[i]=manualSettingsData.ChannelNeutral[i] + 1;
|
||||
manualSettingsData.ChannelMax[i]=manualSettingsData.ChannelNeutral[i];
|
||||
}
|
||||
}
|
||||
connect(manualCommandObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(identifyLimits()));
|
||||
connect(manualCommandObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(moveSticks()));
|
||||
@ -481,13 +473,19 @@ void ConfigInputWidget::wizardSetUpStep(enum wizardSteps step)
|
||||
dimOtherControls(true);
|
||||
setTxMovement(nothing);
|
||||
extraWidgets.clear();
|
||||
foreach(QString name,manualSettingsObj->getFields().at(0)->getElementNames())
|
||||
|
||||
for (int index = 0; index < manualSettingsObj->getField("ChannelMax")->getElementNames().length(); index++)
|
||||
{
|
||||
QString name = manualSettingsObj->getField("ChannelMax")->getElementNames().at(index);
|
||||
if(!name.contains("Access") && !name.contains("Flight"))
|
||||
{
|
||||
QCheckBox * cb=new QCheckBox(name,this);
|
||||
// Make sure checked status matches current one
|
||||
cb->setChecked(manualSettingsData.ChannelMax[index] < manualSettingsData.ChannelMin[index]);
|
||||
|
||||
extraWidgets.append(cb);
|
||||
m_config->checkBoxesLayout->layout()->addWidget(cb);
|
||||
|
||||
connect(cb,SIGNAL(toggled(bool)),this,SLOT(invertControls()));
|
||||
}
|
||||
}
|
||||
@ -496,16 +494,7 @@ void ConfigInputWidget::wizardSetUpStep(enum wizardSteps step)
|
||||
fastMdata();
|
||||
break;
|
||||
case wizardFinish:
|
||||
foreach(QWidget * wd,extraWidgets)
|
||||
{
|
||||
QCheckBox * cb=qobject_cast<QCheckBox *>(wd);
|
||||
if(cb)
|
||||
{
|
||||
disconnect(cb,SIGNAL(toggled(bool)),this,SLOT(invertControls()));
|
||||
delete cb;
|
||||
}
|
||||
}
|
||||
extraWidgets.clear();
|
||||
dimOtherControls(true);
|
||||
connect(manualCommandObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(moveSticks()));
|
||||
m_config->wzText->setText(QString(tr("You have completed this wizard, please check below if the picture below mimics your sticks movement.\n"
|
||||
"This new settings aren't saved to the board yet, after pressing next you will go to the initial screen where you can do that.")));
|
||||
@ -559,6 +548,7 @@ void ConfigInputWidget::wizardTearDownStep(enum wizardSteps step)
|
||||
case wizardIdentifySticks:
|
||||
disconnect(receiverActivityObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(identifyControls()));
|
||||
m_config->wzNext->setEnabled(true);
|
||||
setTxMovement(nothing);
|
||||
break;
|
||||
case wizardIdentifyCenter:
|
||||
manualCommandData=manualCommandObj->getData();
|
||||
@ -568,14 +558,17 @@ void ConfigInputWidget::wizardTearDownStep(enum wizardSteps step)
|
||||
manualSettingsData.ChannelNeutral[i]=manualCommandData.Channel[i];
|
||||
}
|
||||
manualSettingsObj->setData(manualSettingsData);
|
||||
setTxMovement(nothing);
|
||||
break;
|
||||
case wizardIdentifyLimits:
|
||||
disconnect(manualCommandObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(identifyLimits()));
|
||||
disconnect(manualCommandObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(moveSticks()));
|
||||
manualSettingsObj->setData(manualSettingsData);
|
||||
restoreMdata();
|
||||
setTxMovement(nothing);
|
||||
break;
|
||||
case wizardIdentifyInverted:
|
||||
dimOtherControls(false);
|
||||
foreach(QWidget * wd,extraWidgets)
|
||||
{
|
||||
QCheckBox * cb=qobject_cast<QCheckBox *>(wd);
|
||||
@ -590,8 +583,8 @@ void ConfigInputWidget::wizardTearDownStep(enum wizardSteps step)
|
||||
restoreMdata();
|
||||
break;
|
||||
case wizardFinish:
|
||||
dimOtherControls(false);
|
||||
setTxMovement(nothing);
|
||||
m_config->stackedWidget->setCurrentIndex(0);
|
||||
disconnect(manualCommandObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(moveSticks()));
|
||||
restoreMdata();
|
||||
break;
|
||||
@ -731,10 +724,19 @@ void ConfigInputWidget::identifyLimits()
|
||||
manualCommandData=manualCommandObj->getData();
|
||||
for(uint i=0;i<ManualControlSettings::CHANNELMAX_NUMELEM;++i)
|
||||
{
|
||||
if(manualSettingsData.ChannelMin[i]>manualCommandData.Channel[i])
|
||||
manualSettingsData.ChannelMin[i]=manualCommandData.Channel[i];
|
||||
if(manualSettingsData.ChannelMax[i]<manualCommandData.Channel[i])
|
||||
manualSettingsData.ChannelMax[i]=manualCommandData.Channel[i];
|
||||
if(manualSettingsData.ChannelMin[i] <= manualSettingsData.ChannelMax[i]) {
|
||||
// Non inverted channel
|
||||
if(manualSettingsData.ChannelMin[i]>manualCommandData.Channel[i])
|
||||
manualSettingsData.ChannelMin[i]=manualCommandData.Channel[i];
|
||||
if(manualSettingsData.ChannelMax[i]<manualCommandData.Channel[i])
|
||||
manualSettingsData.ChannelMax[i]=manualCommandData.Channel[i];
|
||||
} else {
|
||||
// Inverted channel
|
||||
if(manualSettingsData.ChannelMax[i]>manualCommandData.Channel[i])
|
||||
manualSettingsData.ChannelMax[i]=manualCommandData.Channel[i];
|
||||
if(manualSettingsData.ChannelMin[i]<manualCommandData.Channel[i])
|
||||
manualSettingsData.ChannelMin[i]=manualCommandData.Channel[i];
|
||||
}
|
||||
}
|
||||
manualSettingsObj->setData(manualSettingsData);
|
||||
}
|
||||
|
@ -1,13 +1,13 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file configservowidget.cpp
|
||||
* @file configoutputwidget.cpp
|
||||
* @author E. Lafargue & The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @addtogroup GCSPlugins GCS Plugins
|
||||
* @{
|
||||
* @addtogroup ConfigPlugin Config Plugin
|
||||
* @{
|
||||
* @brief Servo input/output configuration panel for the config gadget
|
||||
* @brief Servo output configuration panel for the config gadget
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* This program is free software; you can redistribute it and/or modify
|
||||
@ -26,6 +26,7 @@
|
||||
*/
|
||||
|
||||
#include "configoutputwidget.h"
|
||||
#include "outputchannelform.h"
|
||||
|
||||
#include "uavtalk/telemetrymanager.h"
|
||||
|
||||
@ -39,6 +40,7 @@
|
||||
#include <QDesktopServices>
|
||||
#include <QUrl>
|
||||
#include "actuatorcommand.h"
|
||||
#include "actuatorsettings.h"
|
||||
#include "systemalarms.h"
|
||||
#include "uavsettingsimportexport/uavsettingsimportexportfactory.h"
|
||||
|
||||
@ -57,99 +59,20 @@ ConfigOutputWidget::ConfigOutputWidget(QWidget *parent) : ConfigTaskWidget(paren
|
||||
setupButtons(m_config->saveRCOutputToRAM,m_config->saveRCOutputToSD);
|
||||
addUAVObject("ActuatorSettings");
|
||||
|
||||
// First of all, put all the channel widgets into lists, so that we can
|
||||
// manipulate those:
|
||||
|
||||
// NOTE: for historical reasons, we have objects below called ch0 to ch7, but the convention for OP is Channel 1 to Channel 8.
|
||||
outLabels << m_config->ch0OutValue
|
||||
<< m_config->ch1OutValue
|
||||
<< m_config->ch2OutValue
|
||||
<< m_config->ch3OutValue
|
||||
<< m_config->ch4OutValue
|
||||
<< m_config->ch5OutValue
|
||||
<< m_config->ch6OutValue
|
||||
<< m_config->ch7OutValue
|
||||
<< m_config->ch8OutValue
|
||||
<< m_config->ch9OutValue;
|
||||
|
||||
outSliders << m_config->ch0OutSlider
|
||||
<< m_config->ch1OutSlider
|
||||
<< m_config->ch2OutSlider
|
||||
<< m_config->ch3OutSlider
|
||||
<< m_config->ch4OutSlider
|
||||
<< m_config->ch5OutSlider
|
||||
<< m_config->ch6OutSlider
|
||||
<< m_config->ch7OutSlider
|
||||
<< m_config->ch8OutSlider
|
||||
<< m_config->ch9OutSlider;
|
||||
|
||||
outMin << m_config->ch0OutMin
|
||||
<< m_config->ch1OutMin
|
||||
<< m_config->ch2OutMin
|
||||
<< m_config->ch3OutMin
|
||||
<< m_config->ch4OutMin
|
||||
<< m_config->ch5OutMin
|
||||
<< m_config->ch6OutMin
|
||||
<< m_config->ch7OutMin
|
||||
<< m_config->ch8OutMin
|
||||
<< m_config->ch9OutMin;
|
||||
|
||||
outMax << m_config->ch0OutMax
|
||||
<< m_config->ch1OutMax
|
||||
<< m_config->ch2OutMax
|
||||
<< m_config->ch3OutMax
|
||||
<< m_config->ch4OutMax
|
||||
<< m_config->ch5OutMax
|
||||
<< m_config->ch6OutMax
|
||||
<< m_config->ch7OutMax
|
||||
<< m_config->ch8OutMax
|
||||
<< m_config->ch9OutMax;
|
||||
|
||||
reversals << m_config->ch0Rev
|
||||
<< m_config->ch1Rev
|
||||
<< m_config->ch2Rev
|
||||
<< m_config->ch3Rev
|
||||
<< m_config->ch4Rev
|
||||
<< m_config->ch5Rev
|
||||
<< m_config->ch6Rev
|
||||
<< m_config->ch7Rev
|
||||
<< m_config->ch8Rev
|
||||
<< m_config->ch9Rev;
|
||||
|
||||
links << m_config->ch0Link
|
||||
<< m_config->ch1Link
|
||||
<< m_config->ch2Link
|
||||
<< m_config->ch3Link
|
||||
<< m_config->ch4Link
|
||||
<< m_config->ch5Link
|
||||
<< m_config->ch6Link
|
||||
<< m_config->ch7Link
|
||||
<< m_config->ch8Link
|
||||
<< m_config->ch9Link;
|
||||
|
||||
// NOTE: we have channel indices from 0 to 9, but the convention for OP is Channel 1 to Channel 10.
|
||||
// Register for ActuatorSettings changes:
|
||||
for (int i = 0; i < ActuatorCommand::CHANNEL_NUMELEM; i++) {
|
||||
connect(outMin[i], SIGNAL(editingFinished()), this, SLOT(setChOutRange()));
|
||||
connect(outMax[i], SIGNAL(editingFinished()), this, SLOT(setChOutRange()));
|
||||
connect(reversals[i], SIGNAL(toggled(bool)), this, SLOT(reverseChannel(bool)));
|
||||
// Now connect the channel out sliders to our signal to send updates in test mode
|
||||
connect(outSliders[i], SIGNAL(valueChanged(int)), this, SLOT(sendChannelTest(int)));
|
||||
|
||||
addWidget(outMin[i]);
|
||||
addWidget(outMax[i]);
|
||||
addWidget(reversals[i]);
|
||||
addWidget(outSliders[i]);
|
||||
addWidget(links[i]);
|
||||
for (unsigned int i = 0; i < ActuatorCommand::CHANNEL_NUMELEM; i++)
|
||||
{
|
||||
OutputChannelForm *form = new OutputChannelForm(i, this, i==0);
|
||||
connect(m_config->channelOutTest, SIGNAL(toggled(bool)),
|
||||
form, SLOT(enableChannelTest(bool)));
|
||||
connect(form, SIGNAL(channelChanged(int,int)),
|
||||
this, SLOT(sendChannelTest(int,int)));
|
||||
m_config->channelLayout->addWidget(form);
|
||||
}
|
||||
|
||||
connect(m_config->channelOutTest, SIGNAL(toggled(bool)), this, SLOT(runChannelTests(bool)));
|
||||
|
||||
for (int i = 0; i < links.count(); i++)
|
||||
links[i]->setChecked(false);
|
||||
for (int i = 0; i < links.count(); i++)
|
||||
connect(links[i], SIGNAL(toggled(bool)), this, SLOT(linkToggled(bool)));
|
||||
|
||||
|
||||
refreshWidgetsValues();
|
||||
|
||||
firstUpdate = true;
|
||||
@ -158,10 +81,10 @@ ConfigOutputWidget::ConfigOutputWidget(QWidget *parent) : ConfigTaskWidget(paren
|
||||
|
||||
// Connect the help button
|
||||
connect(m_config->outputHelp, SIGNAL(clicked()), this, SLOT(openHelp()));
|
||||
addWidget(m_config->outputRate3);
|
||||
addWidget(m_config->outputRate2);
|
||||
addWidget(m_config->outputRate1);
|
||||
|
||||
addWidget(m_config->cb_outputRate4);
|
||||
addWidget(m_config->cb_outputRate3);
|
||||
addWidget(m_config->cb_outputRate2);
|
||||
addWidget(m_config->cb_outputRate1);
|
||||
addWidget(m_config->spinningArmed);
|
||||
|
||||
UAVObjectManager *objManager = pm->getObject<UAVObjectManager>();
|
||||
@ -170,6 +93,13 @@ ConfigOutputWidget::ConfigOutputWidget(QWidget *parent) : ConfigTaskWidget(paren
|
||||
this->setEnabled(false);
|
||||
connect(obj,SIGNAL(objectUpdated(UAVObject*)),this,SLOT(disableIfNotMe(UAVObject*)));
|
||||
}
|
||||
void ConfigOutputWidget::enableControls(bool enable)
|
||||
{
|
||||
ConfigTaskWidget::enableControls(enable);
|
||||
if(!enable)
|
||||
m_config->channelOutTest->setChecked(false);
|
||||
m_config->channelOutTest->setEnabled(enable);
|
||||
}
|
||||
|
||||
ConfigOutputWidget::~ConfigOutputWidget()
|
||||
{
|
||||
@ -179,43 +109,13 @@ ConfigOutputWidget::~ConfigOutputWidget()
|
||||
|
||||
// ************************************
|
||||
|
||||
/**
|
||||
Toggles the channel linked state for use in testing mode
|
||||
*/
|
||||
void ConfigOutputWidget::linkToggled(bool state)
|
||||
{
|
||||
Q_UNUSED(state)
|
||||
// find the minimum slider value for the linked ones
|
||||
int min = 10000;
|
||||
int linked_count = 0;
|
||||
for (int i = 0; i < outSliders.count(); i++)
|
||||
{
|
||||
if (!links[i]->checkState()) continue;
|
||||
int value = outSliders[i]->value();
|
||||
if (min > value) min = value;
|
||||
linked_count++;
|
||||
}
|
||||
|
||||
if (linked_count <= 0)
|
||||
return; // no linked channels
|
||||
|
||||
if (!m_config->channelOutTest->checkState())
|
||||
return; // we are not in Test Output mode
|
||||
|
||||
// set the linked channels to the same value
|
||||
for (int i = 0; i < outSliders.count(); i++)
|
||||
{
|
||||
if (!links[i]->checkState()) continue;
|
||||
outSliders[i]->setValue(min);
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
Toggles the channel testing mode by making the GCS take over
|
||||
the ActuatorCommand objects
|
||||
*/
|
||||
void ConfigOutputWidget::runChannelTests(bool state)
|
||||
{
|
||||
qDebug()<<"configoutputwidget runChannelTests"<<state;
|
||||
SystemAlarms * systemAlarmsObj = SystemAlarms::GetInstance(getObjectManager());
|
||||
SystemAlarms::DataFields systemAlarms = systemAlarmsObj->getData();
|
||||
|
||||
@ -257,79 +157,43 @@ void ConfigOutputWidget::runChannelTests(bool state)
|
||||
mdata.gcsTelemetryAcked = false;
|
||||
mdata.gcsTelemetryUpdateMode = UAVObject::UPDATEMODE_ONCHANGE;
|
||||
mdata.gcsTelemetryUpdatePeriod = 100;
|
||||
|
||||
// Prevent stupid users from touching the minimum & maximum ranges while
|
||||
// moving the sliders. Thanks Ivan for the tip :)
|
||||
foreach (QSpinBox* box, outMin) {
|
||||
box->setEnabled(false);
|
||||
}
|
||||
foreach (QSpinBox* box, outMax) {
|
||||
box->setEnabled(false);
|
||||
}
|
||||
foreach (QCheckBox* box, reversals) {
|
||||
box->setEnabled(false);
|
||||
}
|
||||
|
||||
}
|
||||
else
|
||||
{
|
||||
wasItMe=false;
|
||||
mdata = accInitialData; // Restore metadata
|
||||
foreach (QSpinBox* box, outMin) {
|
||||
box->setEnabled(true);
|
||||
}
|
||||
foreach (QSpinBox* box, outMax) {
|
||||
box->setEnabled(true);
|
||||
}
|
||||
foreach (QCheckBox* box, reversals) {
|
||||
box->setEnabled(true);
|
||||
}
|
||||
|
||||
}
|
||||
obj->setMetadata(mdata);
|
||||
obj->updated();
|
||||
|
||||
}
|
||||
|
||||
OutputChannelForm* ConfigOutputWidget::getOutputChannelForm(const int index) const
|
||||
{
|
||||
QList<OutputChannelForm*> outputChannelForms = findChildren<OutputChannelForm*>();
|
||||
foreach(OutputChannelForm *outputChannelForm, outputChannelForms)
|
||||
{
|
||||
if( outputChannelForm->index() == index)
|
||||
return outputChannelForm;
|
||||
}
|
||||
|
||||
// no OutputChannelForm found with given index
|
||||
return NULL;
|
||||
}
|
||||
|
||||
/**
|
||||
* Set the label for a channel output assignement
|
||||
*/
|
||||
void ConfigOutputWidget::assignOutputChannel(UAVDataObject *obj, QString str)
|
||||
{
|
||||
//FIXME: use signal/ slot approach
|
||||
UAVObjectField* field = obj->getField(str);
|
||||
QStringList options = field->getOptions();
|
||||
switch (options.indexOf(field->getValue().toString())) {
|
||||
case 0:
|
||||
m_config->ch0Output->setText(str);
|
||||
break;
|
||||
case 1:
|
||||
m_config->ch1Output->setText(str);
|
||||
break;
|
||||
case 2:
|
||||
m_config->ch2Output->setText(str);
|
||||
break;
|
||||
case 3:
|
||||
m_config->ch3Output->setText(str);
|
||||
break;
|
||||
case 4:
|
||||
m_config->ch4Output->setText(str);
|
||||
break;
|
||||
case 5:
|
||||
m_config->ch5Output->setText(str);
|
||||
break;
|
||||
case 6:
|
||||
m_config->ch6Output->setText(str);
|
||||
break;
|
||||
case 7:
|
||||
m_config->ch7Output->setText(str);
|
||||
break;
|
||||
case 8:
|
||||
m_config->ch8Output->setText(str);
|
||||
break;
|
||||
case 9:
|
||||
m_config->ch9Output->setText(str);
|
||||
break;
|
||||
}
|
||||
int index = options.indexOf(field->getValue().toString());
|
||||
|
||||
OutputChannelForm *outputChannelForm = getOutputChannelForm(index);
|
||||
if(outputChannelForm)
|
||||
outputChannelForm->setAssignment(str);
|
||||
}
|
||||
|
||||
/**
|
||||
@ -337,63 +201,36 @@ void ConfigOutputWidget::assignOutputChannel(UAVDataObject *obj, QString str)
|
||||
*/
|
||||
void ConfigOutputWidget::setSpinningArmed(bool val)
|
||||
{
|
||||
UAVDataObject *obj = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("ActuatorSettings")));
|
||||
if (!obj) return;
|
||||
UAVObjectField *field = obj->getField("MotorsSpinWhileArmed");
|
||||
if (!field) return;
|
||||
ActuatorSettings *actuatorSettings = ActuatorSettings::GetInstance(getObjectManager());
|
||||
Q_ASSERT(actuatorSettings);
|
||||
ActuatorSettings::DataFields actuatorSettingsData = actuatorSettings->getData();
|
||||
|
||||
if(val)
|
||||
field->setValue("TRUE");
|
||||
actuatorSettingsData.MotorsSpinWhileArmed = ActuatorSettings::MOTORSSPINWHILEARMED_TRUE;
|
||||
else
|
||||
field->setValue("FALSE");
|
||||
actuatorSettingsData.MotorsSpinWhileArmed = ActuatorSettings::MOTORSSPINWHILEARMED_FALSE;
|
||||
|
||||
// Apply settings
|
||||
actuatorSettings->setData(actuatorSettingsData);
|
||||
}
|
||||
|
||||
/**
|
||||
Sends the channel value to the UAV to move the servo.
|
||||
Returns immediately if we are not in testing mode
|
||||
*/
|
||||
void ConfigOutputWidget::sendChannelTest(int value)
|
||||
void ConfigOutputWidget::sendChannelTest(int index, int value)
|
||||
{
|
||||
int in_value = value;
|
||||
if (!m_config->channelOutTest->isChecked())
|
||||
return;
|
||||
|
||||
QSlider *ob = (QSlider *)QObject::sender();
|
||||
if (!ob) return;
|
||||
int index = outSliders.indexOf(ob);
|
||||
if (index < 0) return;
|
||||
if(index < 0 || (unsigned)index >= ActuatorCommand::CHANNEL_NUMELEM)
|
||||
return;
|
||||
|
||||
if (reversals[index]->isChecked())
|
||||
value = outMin[index]->value() - value + outMax[index]->value(); // the chsnnel is reversed
|
||||
|
||||
// update the label
|
||||
outLabels[index]->setText(QString::number(value));
|
||||
|
||||
if (links[index]->checkState())
|
||||
{ // the channel is linked to other channels
|
||||
// set the linked channels to the same value
|
||||
for (int i = 0; i < outSliders.count(); i++)
|
||||
{
|
||||
if (i == index) continue;
|
||||
if (!links[i]->checkState()) continue;
|
||||
|
||||
int val = in_value;
|
||||
if (val < outSliders[i]->minimum()) val = outSliders[i]->minimum();
|
||||
if (val > outSliders[i]->maximum()) val = outSliders[i]->maximum();
|
||||
|
||||
if (outSliders[i]->value() == val) continue;
|
||||
|
||||
outSliders[i]->setValue(val);
|
||||
outLabels[i]->setText(QString::number(val));
|
||||
}
|
||||
}
|
||||
|
||||
if (!m_config->channelOutTest->isChecked())
|
||||
return;
|
||||
|
||||
UAVDataObject *obj = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("ActuatorCommand")));
|
||||
if (!obj) return;
|
||||
UAVObjectField *channel = obj->getField("Channel");
|
||||
if (!channel) return;
|
||||
channel->setValue(value, index);
|
||||
obj->updated();
|
||||
ActuatorCommand *actuatorCommand = ActuatorCommand::GetInstance(getObjectManager());
|
||||
Q_ASSERT(actuatorCommand);
|
||||
ActuatorCommand::DataFields actuatorCommandFields = actuatorCommand->getData();
|
||||
actuatorCommandFields.Channel[index] = value;
|
||||
actuatorCommand->setData(actuatorCommandFields);
|
||||
}
|
||||
|
||||
|
||||
@ -408,14 +245,21 @@ void ConfigOutputWidget::sendChannelTest(int value)
|
||||
void ConfigOutputWidget::refreshWidgetsValues()
|
||||
{
|
||||
bool dirty=isDirty();
|
||||
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
|
||||
UAVObjectManager *objManager = pm->getObject<UAVObjectManager>();
|
||||
|
||||
// Reset all channel assignements:
|
||||
for (int i = 0; i < ActuatorCommand::CHANNEL_NUMELEM; i++)
|
||||
outLabels[i]->setText("-");
|
||||
QList<OutputChannelForm*> outputChannelForms = findChildren<OutputChannelForm*>();
|
||||
foreach(OutputChannelForm *outputChannelForm, outputChannelForms)
|
||||
{
|
||||
outputChannelForm->setAssignment("-");
|
||||
}
|
||||
|
||||
// Get the channel assignements:
|
||||
// FIXME: Use static accessor method for retrieving channel assignments
|
||||
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
|
||||
Q_ASSERT(pm);
|
||||
UAVObjectManager *objManager = pm->getObject<UAVObjectManager>();
|
||||
Q_ASSERT(objManager);
|
||||
|
||||
// Get the channel assignements:
|
||||
UAVDataObject * obj = dynamic_cast<UAVDataObject*>(objManager->getObject(QString("ActuatorSettings")));
|
||||
Q_ASSERT(obj);
|
||||
QList<UAVObjectField*> fieldList = obj->getFields();
|
||||
@ -425,15 +269,26 @@ void ConfigOutputWidget::refreshWidgetsValues()
|
||||
}
|
||||
}
|
||||
|
||||
ActuatorSettings *actuatorSettings = ActuatorSettings::GetInstance(getObjectManager());
|
||||
Q_ASSERT(actuatorSettings);
|
||||
ActuatorSettings::DataFields actuatorSettingsData = actuatorSettings->getData();
|
||||
|
||||
// Get the SpinWhileArmed setting
|
||||
UAVObjectField *field = obj->getField(QString("MotorsSpinWhileArmed"));
|
||||
m_config->spinningArmed->setChecked(field->getValue().toString().contains("TRUE"));
|
||||
m_config->spinningArmed->setChecked(actuatorSettingsData.MotorsSpinWhileArmed == ActuatorSettings::MOTORSSPINWHILEARMED_TRUE);
|
||||
|
||||
// Get Output rates for both banks
|
||||
field = obj->getField(QString("ChannelUpdateFreq"));
|
||||
if(m_config->cb_outputRate1->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[0]))==-1)
|
||||
{
|
||||
m_config->cb_outputRate1->addItem(QString::number(actuatorSettingsData.ChannelUpdateFreq[0]));
|
||||
}
|
||||
if(m_config->cb_outputRate2->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[1]))==-1)
|
||||
{
|
||||
m_config->cb_outputRate2->addItem(QString::number(actuatorSettingsData.ChannelUpdateFreq[1]));
|
||||
}
|
||||
m_config->cb_outputRate1->setCurrentIndex(m_config->cb_outputRate1->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[0])));
|
||||
m_config->cb_outputRate2->setCurrentIndex(m_config->cb_outputRate2->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[1])));
|
||||
|
||||
UAVObjectUtilManager* utilMngr = pm->getObject<UAVObjectUtilManager>();
|
||||
m_config->outputRate1->setValue(field->getValue(0).toInt());
|
||||
m_config->outputRate2->setValue(field->getValue(1).toInt());
|
||||
if (utilMngr) {
|
||||
int board = utilMngr->getBoardModel();
|
||||
if ((board & 0xff00) == 1024) {
|
||||
@ -442,55 +297,49 @@ void ConfigOutputWidget::refreshWidgetsValues()
|
||||
m_config->chBank2->setText("4");
|
||||
m_config->chBank3->setText("5,7-8");
|
||||
m_config->chBank4->setText("6,9-10");
|
||||
m_config->outputRate1->setEnabled(true);
|
||||
m_config->outputRate2->setEnabled(true);
|
||||
m_config->outputRate3->setEnabled(true);
|
||||
m_config->outputRate4->setEnabled(true);
|
||||
m_config->outputRate3->setValue(field->getValue(2).toInt());
|
||||
m_config->outputRate4->setValue(field->getValue(3).toInt());
|
||||
m_config->cb_outputRate1->setEnabled(true);
|
||||
m_config->cb_outputRate2->setEnabled(true);
|
||||
m_config->cb_outputRate3->setEnabled(true);
|
||||
m_config->cb_outputRate4->setEnabled(true);
|
||||
if(m_config->cb_outputRate3->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[2]))==-1)
|
||||
{
|
||||
m_config->cb_outputRate3->addItem(QString::number(actuatorSettingsData.ChannelUpdateFreq[2]));
|
||||
}
|
||||
if(m_config->cb_outputRate4->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[3]))==-1)
|
||||
{
|
||||
m_config->cb_outputRate4->addItem(QString::number(actuatorSettingsData.ChannelUpdateFreq[3]));
|
||||
}
|
||||
m_config->cb_outputRate3->setCurrentIndex(m_config->cb_outputRate3->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[2])));
|
||||
m_config->cb_outputRate4->setCurrentIndex(m_config->cb_outputRate4->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[3])));
|
||||
} else if ((board & 0xff00) == 256 ) {
|
||||
// Mainboard family
|
||||
m_config->outputRate1->setEnabled(true);
|
||||
m_config->outputRate2->setEnabled(true);
|
||||
m_config->outputRate3->setEnabled(false);
|
||||
m_config->outputRate4->setEnabled(false);
|
||||
m_config->cb_outputRate1->setEnabled(true);
|
||||
m_config->cb_outputRate2->setEnabled(true);
|
||||
m_config->cb_outputRate3->setEnabled(false);
|
||||
m_config->cb_outputRate4->setEnabled(false);
|
||||
m_config->chBank1->setText("1-4");
|
||||
m_config->chBank2->setText("5-8");
|
||||
m_config->chBank3->setText("-");
|
||||
m_config->chBank4->setText("-");
|
||||
m_config->outputRate3->setValue(0);
|
||||
m_config->outputRate4->setValue(0);
|
||||
m_config->cb_outputRate3->addItem("0");
|
||||
m_config->cb_outputRate3->setCurrentIndex(m_config->cb_outputRate3->findText("0"));
|
||||
m_config->cb_outputRate4->addItem("0");
|
||||
m_config->cb_outputRate4->setCurrentIndex(m_config->cb_outputRate4->findText("0"));
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
// Get Channel ranges:
|
||||
for (int i=0;i<ActuatorCommand::CHANNEL_NUMELEM;i++) {
|
||||
field = obj->getField(QString("ChannelMin"));
|
||||
int minValue = field->getValue(i).toInt();
|
||||
outMin[i]->setValue(minValue);
|
||||
field = obj->getField(QString("ChannelMax"));
|
||||
int maxValue = field->getValue(i).toInt();
|
||||
outMax[i]->setValue(maxValue);
|
||||
if (maxValue>minValue) {
|
||||
outSliders[i]->setMinimum(minValue);
|
||||
outSliders[i]->setMaximum(maxValue);
|
||||
reversals[i]->setChecked(false);
|
||||
} else {
|
||||
outSliders[i]->setMinimum(maxValue);
|
||||
outSliders[i]->setMaximum(minValue);
|
||||
reversals[i]->setChecked(true);
|
||||
}
|
||||
foreach(OutputChannelForm *outputChannelForm, outputChannelForms)
|
||||
{
|
||||
int minValue = actuatorSettingsData.ChannelMin[outputChannelForm->index()];
|
||||
int maxValue = actuatorSettingsData.ChannelMax[outputChannelForm->index()];
|
||||
outputChannelForm->minmax(minValue, maxValue);
|
||||
|
||||
int neutral = actuatorSettingsData.ChannelNeutral[outputChannelForm->index()];
|
||||
outputChannelForm->neutral(neutral);
|
||||
}
|
||||
|
||||
field = obj->getField(QString("ChannelNeutral"));
|
||||
for (int i=0; i<ActuatorCommand::CHANNEL_NUMELEM; i++) {
|
||||
int value = field->getValue(i).toInt();
|
||||
outSliders[i]->setValue(value);
|
||||
outLabels[i]->setText(QString::number(value));
|
||||
}
|
||||
setDirty(dirty);
|
||||
|
||||
}
|
||||
|
||||
/**
|
||||
@ -498,105 +347,26 @@ void ConfigOutputWidget::refreshWidgetsValues()
|
||||
*/
|
||||
void ConfigOutputWidget::updateObjectsFromWidgets()
|
||||
{
|
||||
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
|
||||
UAVObjectManager *objManager = pm->getObject<UAVObjectManager>();
|
||||
UAVDataObject* obj = dynamic_cast<UAVDataObject*>(objManager->getObject(QString("ActuatorSettings")));
|
||||
Q_ASSERT(obj);
|
||||
ActuatorSettings *actuatorSettings = ActuatorSettings::GetInstance(getObjectManager());
|
||||
Q_ASSERT(actuatorSettings);
|
||||
ActuatorSettings::DataFields actuatorSettingsData = actuatorSettings->getData();
|
||||
|
||||
// Now send channel ranges:
|
||||
UAVObjectField * field = obj->getField(QString("ChannelMax"));
|
||||
for (int i = 0; i < ActuatorCommand::CHANNEL_NUMELEM; i++) {
|
||||
field->setValue(outMax[i]->value(),i);
|
||||
}
|
||||
|
||||
field = obj->getField(QString("ChannelMin"));
|
||||
for (int i = 0; i < ActuatorCommand::CHANNEL_NUMELEM; i++) {
|
||||
field->setValue(outMin[i]->value(),i);
|
||||
}
|
||||
|
||||
field = obj->getField(QString("ChannelNeutral"));
|
||||
for (int i = 0; i < ActuatorCommand::CHANNEL_NUMELEM; i++) {
|
||||
field->setValue(outSliders[i]->value(),i);
|
||||
}
|
||||
|
||||
field = obj->getField(QString("ChannelUpdateFreq"));
|
||||
field->setValue(m_config->outputRate1->value(),0);
|
||||
field->setValue(m_config->outputRate2->value(),1);
|
||||
field->setValue(m_config->outputRate3->value(),2);
|
||||
field->setValue(m_config->outputRate4->value(),3);
|
||||
}
|
||||
|
||||
/**
|
||||
Sets the minimum/maximum value of the channel 0 to seven output sliders.
|
||||
Have to do it here because setMinimum is not a slot.
|
||||
|
||||
One added trick: if the slider is at its min when the value
|
||||
is changed, then keep it on the min.
|
||||
*/
|
||||
void ConfigOutputWidget::setChOutRange()
|
||||
{
|
||||
QSpinBox *spinbox = (QSpinBox*)QObject::sender();
|
||||
|
||||
int index = outMin.indexOf(spinbox); // This is the channel number
|
||||
if (index < 0)
|
||||
index = outMax.indexOf(spinbox); // We can't know if the signal came from min or max
|
||||
|
||||
QSlider *slider = outSliders[index];
|
||||
|
||||
int oldMini = slider->minimum();
|
||||
// int oldMaxi = slider->maximum();
|
||||
|
||||
if (outMin[index]->value()<outMax[index]->value())
|
||||
// Set channel ranges
|
||||
QList<OutputChannelForm*> outputChannelForms = findChildren<OutputChannelForm*>();
|
||||
foreach(OutputChannelForm *outputChannelForm, outputChannelForms)
|
||||
{
|
||||
slider->setRange(outMin[index]->value(), outMax[index]->value());
|
||||
reversals[index]->setChecked(false);
|
||||
}
|
||||
else
|
||||
{
|
||||
slider->setRange(outMax[index]->value(), outMin[index]->value());
|
||||
reversals[index]->setChecked(true);
|
||||
}
|
||||
|
||||
if (slider->value() == oldMini)
|
||||
slider->setValue(slider->minimum());
|
||||
|
||||
// if (slider->value() == oldMaxi)
|
||||
// slider->setValue(slider->maximum()); // this can be dangerous if it happens to be controlling a motor at the time!
|
||||
}
|
||||
|
||||
/**
|
||||
Reverses the channel when the checkbox is clicked
|
||||
*/
|
||||
void ConfigOutputWidget::reverseChannel(bool state)
|
||||
{
|
||||
QCheckBox *checkbox = (QCheckBox*)QObject::sender();
|
||||
int index = reversals.indexOf(checkbox); // This is the channel number
|
||||
|
||||
// Sanity check: if state became true, make sure the Maxvalue was higher than Minvalue
|
||||
// the situations below can happen!
|
||||
if (state && (outMax[index]->value()<outMin[index]->value()))
|
||||
return;
|
||||
if (!state && (outMax[index]->value()>outMin[index]->value()))
|
||||
return;
|
||||
|
||||
// Now, swap the min & max values (only on the spinboxes, the slider
|
||||
// does not change!
|
||||
int temp = outMax[index]->value();
|
||||
outMax[index]->setValue(outMin[index]->value());
|
||||
outMin[index]->setValue(temp);
|
||||
|
||||
// Also update the channel value
|
||||
// This is a trick to force the slider to update its value and
|
||||
// emit the right signal itself, because our sendChannelTest(int) method
|
||||
// relies on the object sender's identity.
|
||||
if (outSliders[index]->value()<outSliders[index]->maximum()) {
|
||||
outSliders[index]->setValue(outSliders[index]->value()+1);
|
||||
outSliders[index]->setValue(outSliders[index]->value()-1);
|
||||
} else {
|
||||
outSliders[index]->setValue(outSliders[index]->value()-1);
|
||||
outSliders[index]->setValue(outSliders[index]->value()+1);
|
||||
actuatorSettingsData.ChannelMax[outputChannelForm->index()] = outputChannelForm->max();
|
||||
actuatorSettingsData.ChannelMin[outputChannelForm->index()] = outputChannelForm->min();
|
||||
actuatorSettingsData.ChannelNeutral[outputChannelForm->index()] = outputChannelForm->neutral();
|
||||
}
|
||||
|
||||
// Set update rates
|
||||
actuatorSettingsData.ChannelUpdateFreq[0] = m_config->cb_outputRate1->currentText().toUInt();
|
||||
actuatorSettingsData.ChannelUpdateFreq[1] = m_config->cb_outputRate2->currentText().toUInt();
|
||||
actuatorSettingsData.ChannelUpdateFreq[2] = m_config->cb_outputRate3->currentText().toUInt();
|
||||
actuatorSettingsData.ChannelUpdateFreq[3] = m_config->cb_outputRate4->currentText().toUInt();
|
||||
// Apply settings
|
||||
actuatorSettings->setData(actuatorSettingsData);
|
||||
}
|
||||
|
||||
void ConfigOutputWidget::openHelp()
|
||||
|
@ -1,13 +1,13 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file configservowidget.h
|
||||
* @file configoutputwidget.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @addtogroup GCSPlugins GCS Plugins
|
||||
* @{
|
||||
* @addtogroup ConfigPlugin Config Plugin
|
||||
* @{
|
||||
* @brief Servo input/output configuration panel for the config gadget
|
||||
* @brief Servo output configuration panel for the config gadget
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* This program is free software; you can redistribute it and/or modify
|
||||
@ -37,6 +37,7 @@
|
||||
#include <QList>
|
||||
|
||||
class Ui_OutputWidget;
|
||||
class OutputChannelForm;
|
||||
|
||||
class ConfigOutputWidget: public ConfigTaskWidget
|
||||
{
|
||||
@ -46,6 +47,7 @@ public:
|
||||
ConfigOutputWidget(QWidget *parent = 0);
|
||||
~ConfigOutputWidget();
|
||||
|
||||
|
||||
private:
|
||||
Ui_OutputWidget *m_config;
|
||||
|
||||
@ -55,18 +57,12 @@ private:
|
||||
|
||||
void assignChannel(UAVDataObject *obj, QString str);
|
||||
void assignOutputChannel(UAVDataObject *obj, QString str);
|
||||
OutputChannelForm* getOutputChannelForm(const int index) const;
|
||||
|
||||
int mccDataRate;
|
||||
|
||||
UAVObject::Metadata accInitialData;
|
||||
|
||||
QList<QSlider*> outSliders;
|
||||
QList<QSpinBox*> outMin;
|
||||
QList<QSpinBox*> outMax;
|
||||
QList<QCheckBox*> reversals;
|
||||
QList<QCheckBox*> links;
|
||||
QList<QLabel*> outLabels;
|
||||
|
||||
bool firstUpdate;
|
||||
|
||||
bool wasItMe;
|
||||
@ -76,12 +72,11 @@ private slots:
|
||||
virtual void refreshWidgetsValues();
|
||||
void updateObjectsFromWidgets();
|
||||
void runChannelTests(bool state);
|
||||
void sendChannelTest(int value);
|
||||
void setChOutRange();
|
||||
void reverseChannel(bool state);
|
||||
void linkToggled(bool state);
|
||||
void sendChannelTest(int index, int value);
|
||||
void setSpinningArmed(bool val);
|
||||
void openHelp();
|
||||
protected:
|
||||
void enableControls(bool enable);
|
||||
};
|
||||
|
||||
#endif
|
||||
|
@ -94,6 +94,7 @@ void inputChannelForm::groupUpdated()
|
||||
break;
|
||||
case ManualControlSettings::CHANNELGROUPS_GCS:
|
||||
count = 5;
|
||||
break;
|
||||
case ManualControlSettings::CHANNELGROUPS_NONE:
|
||||
count = 0;
|
||||
break;
|
||||
|
@ -142,6 +142,12 @@
|
||||
<property name="enabled">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="MinimumExpanding" vsizetype="Preferred">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Neutral</string>
|
||||
</property>
|
||||
@ -149,6 +155,12 @@
|
||||
</item>
|
||||
<item row="2" column="6">
|
||||
<widget class="QSlider" name="channelNeutral">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
|
@ -38,102 +38,6 @@
|
||||
<property name="spacing">
|
||||
<number>2</number>
|
||||
</property>
|
||||
<item row="1" column="4">
|
||||
<widget class="QSpinBox" name="outputRate4">
|
||||
<property name="enabled">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Setup "TurboPWM" here: usual value is 400 Hz for multirotor airframes.
|
||||
Leave at 50Hz for fixed wing.</string>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>400</number>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="3">
|
||||
<widget class="QLabel" name="chBank3">
|
||||
<property name="text">
|
||||
<string>-</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="2">
|
||||
<widget class="QLabel" name="chBank2">
|
||||
<property name="text">
|
||||
<string>-</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="1">
|
||||
<widget class="QLabel" name="chBank1">
|
||||
<property name="text">
|
||||
<string>-</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="3">
|
||||
<widget class="QSpinBox" name="outputRate3">
|
||||
<property name="enabled">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Setup "TurboPWM" here: usual value is 400 Hz for multirotor airframes.
|
||||
Leave at 50Hz for fixed wing.</string>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>400</number>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="2">
|
||||
<widget class="QSpinBox" name="outputRate2">
|
||||
<property name="enabled">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Setup "TurboPWM" here: usual value is 400 Hz for multirotor airframes.
|
||||
Leave at 50Hz for fixed wing.</string>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>400</number>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="1">
|
||||
<widget class="QSpinBox" name="outputRate1">
|
||||
<property name="enabled">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Setup "TurboPWM" here: usual value is 400 Hz for multirotor airframes.
|
||||
Leave at 50Hz for fixed wing.</string>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>400</number>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="4">
|
||||
<widget class="QLabel" name="chBank4">
|
||||
<property name="text">
|
||||
<string>-</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="0">
|
||||
<layout class="QHBoxLayout" name="horizontalLayout_6">
|
||||
<item>
|
||||
@ -206,937 +110,235 @@ Leave at 50Hz for fixed wing.</string>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
<item row="1" column="1">
|
||||
<widget class="QComboBox" name="cb_outputRate1">
|
||||
<property name="enabled">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Setup "TurboPWM" here: usual value is 400 Hz for multirotor airframes.
|
||||
Leave at 50Hz for fixed wing.</string>
|
||||
</property>
|
||||
<item>
|
||||
<property name="text">
|
||||
<string>50</string>
|
||||
</property>
|
||||
</item>
|
||||
<item>
|
||||
<property name="text">
|
||||
<string>60</string>
|
||||
</property>
|
||||
</item>
|
||||
<item>
|
||||
<property name="text">
|
||||
<string>125</string>
|
||||
</property>
|
||||
</item>
|
||||
<item>
|
||||
<property name="text">
|
||||
<string>165</string>
|
||||
</property>
|
||||
</item>
|
||||
<item>
|
||||
<property name="text">
|
||||
<string>270</string>
|
||||
</property>
|
||||
</item>
|
||||
<item>
|
||||
<property name="text">
|
||||
<string>330</string>
|
||||
</property>
|
||||
</item>
|
||||
<item>
|
||||
<property name="text">
|
||||
<string>400</string>
|
||||
</property>
|
||||
</item>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="2">
|
||||
<widget class="QComboBox" name="cb_outputRate2">
|
||||
<property name="enabled">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Setup "TurboPWM" here: usual value is 400 Hz for multirotor airframes.
|
||||
Leave at 50Hz for fixed wing.</string>
|
||||
</property>
|
||||
<item>
|
||||
<property name="text">
|
||||
<string>50</string>
|
||||
</property>
|
||||
</item>
|
||||
<item>
|
||||
<property name="text">
|
||||
<string>60</string>
|
||||
</property>
|
||||
</item>
|
||||
<item>
|
||||
<property name="text">
|
||||
<string>125</string>
|
||||
</property>
|
||||
</item>
|
||||
<item>
|
||||
<property name="text">
|
||||
<string>165</string>
|
||||
</property>
|
||||
</item>
|
||||
<item>
|
||||
<property name="text">
|
||||
<string>270</string>
|
||||
</property>
|
||||
</item>
|
||||
<item>
|
||||
<property name="text">
|
||||
<string>330</string>
|
||||
</property>
|
||||
</item>
|
||||
<item>
|
||||
<property name="text">
|
||||
<string>400</string>
|
||||
</property>
|
||||
</item>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="3">
|
||||
<widget class="QComboBox" name="cb_outputRate3">
|
||||
<property name="enabled">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Setup "TurboPWM" here: usual value is 400 Hz for multirotor airframes.
|
||||
Leave at 50Hz for fixed wing.</string>
|
||||
</property>
|
||||
<item>
|
||||
<property name="text">
|
||||
<string>50</string>
|
||||
</property>
|
||||
</item>
|
||||
<item>
|
||||
<property name="text">
|
||||
<string>60</string>
|
||||
</property>
|
||||
</item>
|
||||
<item>
|
||||
<property name="text">
|
||||
<string>125</string>
|
||||
</property>
|
||||
</item>
|
||||
<item>
|
||||
<property name="text">
|
||||
<string>165</string>
|
||||
</property>
|
||||
</item>
|
||||
<item>
|
||||
<property name="text">
|
||||
<string>270</string>
|
||||
</property>
|
||||
</item>
|
||||
<item>
|
||||
<property name="text">
|
||||
<string>330</string>
|
||||
</property>
|
||||
</item>
|
||||
<item>
|
||||
<property name="text">
|
||||
<string>400</string>
|
||||
</property>
|
||||
</item>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="4">
|
||||
<widget class="QComboBox" name="cb_outputRate4">
|
||||
<property name="enabled">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Setup "TurboPWM" here: usual value is 400 Hz for multirotor airframes.
|
||||
Leave at 50Hz for fixed wing.</string>
|
||||
</property>
|
||||
<item>
|
||||
<property name="text">
|
||||
<string>50</string>
|
||||
</property>
|
||||
</item>
|
||||
<item>
|
||||
<property name="text">
|
||||
<string>60</string>
|
||||
</property>
|
||||
</item>
|
||||
<item>
|
||||
<property name="text">
|
||||
<string>125</string>
|
||||
</property>
|
||||
</item>
|
||||
<item>
|
||||
<property name="text">
|
||||
<string>165</string>
|
||||
</property>
|
||||
</item>
|
||||
<item>
|
||||
<property name="text">
|
||||
<string>270</string>
|
||||
</property>
|
||||
</item>
|
||||
<item>
|
||||
<property name="text">
|
||||
<string>330</string>
|
||||
</property>
|
||||
</item>
|
||||
<item>
|
||||
<property name="text">
|
||||
<string>400</string>
|
||||
</property>
|
||||
</item>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="1">
|
||||
<widget class="QLabel" name="chBank1">
|
||||
<property name="text">
|
||||
<string>-</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="2">
|
||||
<widget class="QLabel" name="chBank2">
|
||||
<property name="text">
|
||||
<string>-</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="3">
|
||||
<widget class="QLabel" name="chBank3">
|
||||
<property name="text">
|
||||
<string>-</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="4">
|
||||
<widget class="QLabel" name="chBank4">
|
||||
<property name="text">
|
||||
<string>-</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<layout class="QGridLayout" name="gridLayout_2">
|
||||
<item row="1" column="0">
|
||||
<widget class="QLabel" name="actuator0Label">
|
||||
<property name="text">
|
||||
<string>Channel 1:</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="2">
|
||||
<widget class="QSpinBox" name="ch0OutMin">
|
||||
<property name="enabled">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string><!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd">
|
||||
<html><head><meta name="qrichtext" content="1" /><style type="text/css">
|
||||
p, li { white-space: pre-wrap; }
|
||||
</style></head><body style=" font-family:'Sans'; font-size:8pt; font-weight:400; font-style:normal;">
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">Minimum PWM value, beware of not overdriving your servo.</p></body></html></string>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>9999</number>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="3">
|
||||
<widget class="QSlider" name="ch0OutSlider">
|
||||
<property name="enabled">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>9999</number>
|
||||
</property>
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="4">
|
||||
<widget class="QSpinBox" name="ch0OutMax">
|
||||
<property name="enabled">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string><!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd">
|
||||
<html><head><meta name="qrichtext" content="1" /><style type="text/css">
|
||||
p, li { white-space: pre-wrap; }
|
||||
</style></head><body style=" font-family:'Sans'; font-size:8pt; font-weight:400; font-style:normal;">
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">Maximum PWM value, beware of not overdriving your servo.</p></body></html></string>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>9999</number>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="5">
|
||||
<widget class="QLabel" name="ch0OutValue">
|
||||
<property name="toolTip">
|
||||
<string>Current value of slider.</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>0000</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="6">
|
||||
<widget class="QCheckBox" name="ch0Rev">
|
||||
<property name="font">
|
||||
<font>
|
||||
<family>FreeSans</family>
|
||||
<pointsize>8</pointsize>
|
||||
</font>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string><!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd">
|
||||
<html><head><meta name="qrichtext" content="1" /><style type="text/css">
|
||||
p, li { white-space: pre-wrap; }
|
||||
</style></head><body style=" font-family:'FreeSans'; font-size:8pt; font-weight:400; font-style:normal;">
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">Check to invert the channel.</p></body></html></string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string/>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="7">
|
||||
<widget class="QCheckBox" name="ch0Link">
|
||||
<property name="toolTip">
|
||||
<string>Only used with Test Output mode</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string/>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="7">
|
||||
<widget class="QLabel" name="label_2">
|
||||
<property name="text">
|
||||
<string>Link</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="6">
|
||||
<widget class="QLabel" name="label">
|
||||
<property name="text">
|
||||
<string>Rev.</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="0">
|
||||
<widget class="QLabel" name="actuator1Label">
|
||||
<property name="text">
|
||||
<string>Channel 2:</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="2">
|
||||
<widget class="QSpinBox" name="ch1OutMin">
|
||||
<property name="enabled">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>9999</number>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="3">
|
||||
<widget class="QSlider" name="ch1OutSlider">
|
||||
<property name="enabled">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>9999</number>
|
||||
</property>
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="4">
|
||||
<widget class="QSpinBox" name="ch1OutMax">
|
||||
<property name="enabled">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>9999</number>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="5">
|
||||
<widget class="QLabel" name="ch1OutValue">
|
||||
<property name="text">
|
||||
<string>0000</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="6">
|
||||
<widget class="QCheckBox" name="ch1Rev">
|
||||
<property name="font">
|
||||
<font>
|
||||
<family>FreeSans</family>
|
||||
<pointsize>8</pointsize>
|
||||
</font>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string><!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd">
|
||||
<html><head><meta name="qrichtext" content="1" /><style type="text/css">
|
||||
p, li { white-space: pre-wrap; }
|
||||
</style></head><body style=" font-family:'FreeSans'; font-size:8pt; font-weight:400; font-style:normal;">
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">Check to invert the channel.</p></body></html></string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string/>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="7">
|
||||
<widget class="QCheckBox" name="ch1Link">
|
||||
<property name="toolTip">
|
||||
<string>Only used with Test Output mode</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string/>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="0">
|
||||
<widget class="QLabel" name="actuator2Label">
|
||||
<property name="text">
|
||||
<string>Channel 3:</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="2">
|
||||
<widget class="QSpinBox" name="ch2OutMin">
|
||||
<property name="enabled">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>9999</number>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="3">
|
||||
<widget class="QSlider" name="ch2OutSlider">
|
||||
<property name="enabled">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>9999</number>
|
||||
</property>
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="4">
|
||||
<widget class="QSpinBox" name="ch2OutMax">
|
||||
<property name="enabled">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>9999</number>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="5">
|
||||
<widget class="QLabel" name="ch2OutValue">
|
||||
<property name="text">
|
||||
<string>0000</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="6">
|
||||
<widget class="QCheckBox" name="ch2Rev">
|
||||
<property name="font">
|
||||
<font>
|
||||
<family>FreeSans</family>
|
||||
<pointsize>8</pointsize>
|
||||
</font>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string><!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd">
|
||||
<html><head><meta name="qrichtext" content="1" /><style type="text/css">
|
||||
p, li { white-space: pre-wrap; }
|
||||
</style></head><body style=" font-family:'FreeSans'; font-size:8pt; font-weight:400; font-style:normal;">
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">Check to invert the channel.</p></body></html></string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string/>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="7">
|
||||
<widget class="QCheckBox" name="ch2Link">
|
||||
<property name="toolTip">
|
||||
<string>Only used with Test Output mode</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string/>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="4" column="0">
|
||||
<widget class="QLabel" name="actuator3Label">
|
||||
<property name="text">
|
||||
<string>Channel 4:</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="4" column="2">
|
||||
<widget class="QSpinBox" name="ch3OutMin">
|
||||
<property name="enabled">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>9999</number>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="4" column="3">
|
||||
<widget class="QSlider" name="ch3OutSlider">
|
||||
<property name="enabled">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>9999</number>
|
||||
</property>
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="4" column="4">
|
||||
<widget class="QSpinBox" name="ch3OutMax">
|
||||
<property name="enabled">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>9999</number>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="4" column="5">
|
||||
<widget class="QLabel" name="ch3OutValue">
|
||||
<property name="text">
|
||||
<string>0000</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="4" column="6">
|
||||
<widget class="QCheckBox" name="ch3Rev">
|
||||
<property name="font">
|
||||
<font>
|
||||
<family>FreeSans</family>
|
||||
<pointsize>8</pointsize>
|
||||
</font>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string><!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd">
|
||||
<html><head><meta name="qrichtext" content="1" /><style type="text/css">
|
||||
p, li { white-space: pre-wrap; }
|
||||
</style></head><body style=" font-family:'FreeSans'; font-size:8pt; font-weight:400; font-style:normal;">
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">Check to invert the channel.</p></body></html></string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string/>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="4" column="7">
|
||||
<widget class="QCheckBox" name="ch3Link">
|
||||
<property name="toolTip">
|
||||
<string>Only used with Test Output mode</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string/>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="5" column="0">
|
||||
<widget class="QLabel" name="actuator4Label">
|
||||
<property name="text">
|
||||
<string>Channel 5:</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="5" column="2">
|
||||
<widget class="QSpinBox" name="ch4OutMin">
|
||||
<property name="maximum">
|
||||
<number>9999</number>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="5" column="3">
|
||||
<widget class="QSlider" name="ch4OutSlider">
|
||||
<property name="maximum">
|
||||
<number>9999</number>
|
||||
</property>
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="5" column="4">
|
||||
<widget class="QSpinBox" name="ch4OutMax">
|
||||
<property name="maximum">
|
||||
<number>9999</number>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="5" column="5">
|
||||
<widget class="QLabel" name="ch4OutValue">
|
||||
<property name="text">
|
||||
<string>0000</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="5" column="6">
|
||||
<widget class="QCheckBox" name="ch4Rev">
|
||||
<property name="font">
|
||||
<font>
|
||||
<family>FreeSans</family>
|
||||
<pointsize>8</pointsize>
|
||||
</font>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string><!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd">
|
||||
<html><head><meta name="qrichtext" content="1" /><style type="text/css">
|
||||
p, li { white-space: pre-wrap; }
|
||||
</style></head><body style=" font-family:'FreeSans'; font-size:8pt; font-weight:400; font-style:normal;">
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">Check to invert the channel.</p></body></html></string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string/>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="5" column="7">
|
||||
<widget class="QCheckBox" name="ch4Link">
|
||||
<property name="toolTip">
|
||||
<string>Only used with Test Output mode</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string/>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="6" column="0">
|
||||
<widget class="QLabel" name="actuator5Label">
|
||||
<property name="text">
|
||||
<string>Channel 6:</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="6" column="2">
|
||||
<widget class="QSpinBox" name="ch5OutMin">
|
||||
<property name="maximum">
|
||||
<number>9999</number>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="6" column="3">
|
||||
<widget class="QSlider" name="ch5OutSlider">
|
||||
<property name="maximum">
|
||||
<number>9999</number>
|
||||
</property>
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="6" column="4">
|
||||
<widget class="QSpinBox" name="ch5OutMax">
|
||||
<property name="maximum">
|
||||
<number>9999</number>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="6" column="5">
|
||||
<widget class="QLabel" name="ch5OutValue">
|
||||
<property name="text">
|
||||
<string>0000</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="6" column="6">
|
||||
<widget class="QCheckBox" name="ch5Rev">
|
||||
<property name="font">
|
||||
<font>
|
||||
<family>FreeSans</family>
|
||||
<pointsize>8</pointsize>
|
||||
</font>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string><!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd">
|
||||
<html><head><meta name="qrichtext" content="1" /><style type="text/css">
|
||||
p, li { white-space: pre-wrap; }
|
||||
</style></head><body style=" font-family:'FreeSans'; font-size:8pt; font-weight:400; font-style:normal;">
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">Check to invert the channel.</p></body></html></string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string/>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="6" column="7">
|
||||
<widget class="QCheckBox" name="ch5Link">
|
||||
<property name="toolTip">
|
||||
<string>Only used with Test Output mode</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string/>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="7" column="0">
|
||||
<widget class="QLabel" name="actuator6Label">
|
||||
<property name="text">
|
||||
<string>Channel 7:</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="8" column="0">
|
||||
<widget class="QLabel" name="actuator7Label">
|
||||
<property name="text">
|
||||
<string>Channel 8:</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="7" column="2">
|
||||
<widget class="QSpinBox" name="ch6OutMin">
|
||||
<property name="maximum">
|
||||
<number>9999</number>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="7" column="3">
|
||||
<widget class="QSlider" name="ch6OutSlider">
|
||||
<property name="maximum">
|
||||
<number>9999</number>
|
||||
</property>
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="7" column="4">
|
||||
<widget class="QSpinBox" name="ch6OutMax">
|
||||
<property name="maximum">
|
||||
<number>9999</number>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="7" column="5">
|
||||
<widget class="QLabel" name="ch6OutValue">
|
||||
<property name="text">
|
||||
<string>0000</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="7" column="6">
|
||||
<widget class="QCheckBox" name="ch6Rev">
|
||||
<property name="font">
|
||||
<font>
|
||||
<family>FreeSans</family>
|
||||
<pointsize>8</pointsize>
|
||||
</font>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string><!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd">
|
||||
<html><head><meta name="qrichtext" content="1" /><style type="text/css">
|
||||
p, li { white-space: pre-wrap; }
|
||||
</style></head><body style=" font-family:'FreeSans'; font-size:8pt; font-weight:400; font-style:normal;">
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">Check to invert the channel.</p></body></html></string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string/>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="7" column="7">
|
||||
<widget class="QCheckBox" name="ch6Link">
|
||||
<property name="toolTip">
|
||||
<string>Only used with Test Output mode</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string/>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="8" column="2">
|
||||
<widget class="QSpinBox" name="ch7OutMin">
|
||||
<property name="maximum">
|
||||
<number>9999</number>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="8" column="3">
|
||||
<widget class="QSlider" name="ch7OutSlider">
|
||||
<property name="maximum">
|
||||
<number>9999</number>
|
||||
</property>
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="8" column="4">
|
||||
<widget class="QSpinBox" name="ch7OutMax">
|
||||
<property name="maximum">
|
||||
<number>9999</number>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="8" column="5">
|
||||
<widget class="QLabel" name="ch7OutValue">
|
||||
<property name="text">
|
||||
<string>0000</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="8" column="6">
|
||||
<widget class="QCheckBox" name="ch7Rev">
|
||||
<property name="font">
|
||||
<font>
|
||||
<family>FreeSans</family>
|
||||
<pointsize>8</pointsize>
|
||||
</font>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string><!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd">
|
||||
<html><head><meta name="qrichtext" content="1" /><style type="text/css">
|
||||
p, li { white-space: pre-wrap; }
|
||||
</style></head><body style=" font-family:'FreeSans'; font-size:8pt; font-weight:400; font-style:normal;">
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">Check to invert the channel.</p></body></html></string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string/>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="8" column="7">
|
||||
<widget class="QCheckBox" name="ch7Link">
|
||||
<property name="toolTip">
|
||||
<string>Only used with Test Output mode</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string/>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="1">
|
||||
<widget class="QLabel" name="ch0Output">
|
||||
<property name="font">
|
||||
<font>
|
||||
<pointsize>9</pointsize>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>-</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="1">
|
||||
<widget class="QLabel" name="ch1Output">
|
||||
<property name="font">
|
||||
<font>
|
||||
<pointsize>9</pointsize>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>-</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="1">
|
||||
<widget class="QLabel" name="ch2Output">
|
||||
<property name="font">
|
||||
<font>
|
||||
<pointsize>9</pointsize>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>-</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="4" column="1">
|
||||
<widget class="QLabel" name="ch3Output">
|
||||
<property name="font">
|
||||
<font>
|
||||
<pointsize>9</pointsize>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>-</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="5" column="1">
|
||||
<widget class="QLabel" name="ch4Output">
|
||||
<property name="font">
|
||||
<font>
|
||||
<pointsize>9</pointsize>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>-</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="6" column="1">
|
||||
<widget class="QLabel" name="ch5Output">
|
||||
<property name="font">
|
||||
<font>
|
||||
<pointsize>9</pointsize>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>-</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="7" column="1">
|
||||
<widget class="QLabel" name="ch6Output">
|
||||
<property name="font">
|
||||
<font>
|
||||
<pointsize>9</pointsize>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>-</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="8" column="1">
|
||||
<widget class="QLabel" name="ch7Output">
|
||||
<property name="font">
|
||||
<font>
|
||||
<pointsize>9</pointsize>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>-</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="1">
|
||||
<widget class="QLabel" name="label_4">
|
||||
<property name="text">
|
||||
<string>Assignment</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="2">
|
||||
<widget class="QLabel" name="label_5">
|
||||
<property name="text">
|
||||
<string>Min</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="3">
|
||||
<widget class="QLabel" name="label_6">
|
||||
<property name="text">
|
||||
<string>Neutral (slowest for motor)</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="4">
|
||||
<widget class="QLabel" name="label_7">
|
||||
<property name="text">
|
||||
<string>Max</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="9" column="0">
|
||||
<widget class="QLabel" name="actuator8Label">
|
||||
<property name="text">
|
||||
<string>Channel 9:</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="10" column="0">
|
||||
<widget class="QLabel" name="actuator9Label">
|
||||
<property name="text">
|
||||
<string>Channel 10:</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="9" column="1">
|
||||
<widget class="QLabel" name="ch8Output">
|
||||
<property name="font">
|
||||
<font>
|
||||
<pointsize>9</pointsize>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>-</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="10" column="1">
|
||||
<widget class="QLabel" name="ch9Output">
|
||||
<property name="font">
|
||||
<font>
|
||||
<pointsize>9</pointsize>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>-</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="9" column="2">
|
||||
<widget class="QSpinBox" name="ch8OutMin">
|
||||
<property name="maximum">
|
||||
<number>9999</number>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="10" column="2">
|
||||
<widget class="QSpinBox" name="ch9OutMin">
|
||||
<property name="maximum">
|
||||
<number>9999</number>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="9" column="3">
|
||||
<widget class="QSlider" name="ch8OutSlider">
|
||||
<property name="maximum">
|
||||
<number>9999</number>
|
||||
</property>
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="10" column="3">
|
||||
<widget class="QSlider" name="ch9OutSlider">
|
||||
<property name="maximum">
|
||||
<number>9999</number>
|
||||
</property>
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="9" column="4">
|
||||
<widget class="QSpinBox" name="ch8OutMax">
|
||||
<property name="maximum">
|
||||
<number>9999</number>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="10" column="4">
|
||||
<widget class="QSpinBox" name="ch9OutMax">
|
||||
<property name="maximum">
|
||||
<number>9999</number>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="9" column="5">
|
||||
<widget class="QLabel" name="ch8OutValue">
|
||||
<property name="text">
|
||||
<string>0000</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="10" column="5">
|
||||
<widget class="QLabel" name="ch9OutValue">
|
||||
<property name="text">
|
||||
<string>0000</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="9" column="6">
|
||||
<widget class="QCheckBox" name="ch8Rev">
|
||||
<property name="font">
|
||||
<font>
|
||||
<family>FreeSans</family>
|
||||
<pointsize>8</pointsize>
|
||||
</font>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string><!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd">
|
||||
<html><head><meta name="qrichtext" content="1" /><style type="text/css">
|
||||
p, li { white-space: pre-wrap; }
|
||||
</style></head><body style=" font-family:'FreeSans'; font-size:8pt; font-weight:400; font-style:normal;">
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">Check to invert the channel.</p></body></html></string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string/>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="10" column="6">
|
||||
<widget class="QCheckBox" name="ch9Rev">
|
||||
<property name="font">
|
||||
<font>
|
||||
<family>FreeSans</family>
|
||||
<pointsize>8</pointsize>
|
||||
</font>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string><!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd">
|
||||
<html><head><meta name="qrichtext" content="1" /><style type="text/css">
|
||||
p, li { white-space: pre-wrap; }
|
||||
</style></head><body style=" font-family:'FreeSans'; font-size:8pt; font-weight:400; font-style:normal;">
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">Check to invert the channel.</p></body></html></string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string/>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="9" column="7">
|
||||
<widget class="QCheckBox" name="ch8Link">
|
||||
<property name="toolTip">
|
||||
<string>Only used with Test Output mode</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string/>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="10" column="7">
|
||||
<widget class="QCheckBox" name="ch9Link">
|
||||
<property name="toolTip">
|
||||
<string>Only used with Test Output mode</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string/>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
<layout class="QVBoxLayout" name="channelLayout"/>
|
||||
</item>
|
||||
<item>
|
||||
<spacer name="verticalSpacer_2">
|
||||
@ -1277,50 +479,6 @@ Applies and Saves all settings to SD</string>
|
||||
</layout>
|
||||
</widget>
|
||||
<tabstops>
|
||||
<tabstop>outputRate1</tabstop>
|
||||
<tabstop>outputRate2</tabstop>
|
||||
<tabstop>outputRate3</tabstop>
|
||||
<tabstop>outputRate4</tabstop>
|
||||
<tabstop>ch0OutMin</tabstop>
|
||||
<tabstop>ch0OutMax</tabstop>
|
||||
<tabstop>ch1OutMin</tabstop>
|
||||
<tabstop>ch1OutMax</tabstop>
|
||||
<tabstop>ch2OutMin</tabstop>
|
||||
<tabstop>ch2OutMax</tabstop>
|
||||
<tabstop>ch3OutMin</tabstop>
|
||||
<tabstop>ch3OutMax</tabstop>
|
||||
<tabstop>ch4OutMin</tabstop>
|
||||
<tabstop>ch4OutMax</tabstop>
|
||||
<tabstop>ch5OutMin</tabstop>
|
||||
<tabstop>ch5OutMax</tabstop>
|
||||
<tabstop>ch6OutMin</tabstop>
|
||||
<tabstop>ch6OutMax</tabstop>
|
||||
<tabstop>ch7OutMin</tabstop>
|
||||
<tabstop>ch7OutMax</tabstop>
|
||||
<tabstop>ch0OutSlider</tabstop>
|
||||
<tabstop>ch0Rev</tabstop>
|
||||
<tabstop>ch0Link</tabstop>
|
||||
<tabstop>ch1OutSlider</tabstop>
|
||||
<tabstop>ch1Rev</tabstop>
|
||||
<tabstop>ch1Link</tabstop>
|
||||
<tabstop>ch2OutSlider</tabstop>
|
||||
<tabstop>ch2Rev</tabstop>
|
||||
<tabstop>ch2Link</tabstop>
|
||||
<tabstop>ch3OutSlider</tabstop>
|
||||
<tabstop>ch3Rev</tabstop>
|
||||
<tabstop>ch3Link</tabstop>
|
||||
<tabstop>ch4OutSlider</tabstop>
|
||||
<tabstop>ch4Rev</tabstop>
|
||||
<tabstop>ch4Link</tabstop>
|
||||
<tabstop>ch5OutSlider</tabstop>
|
||||
<tabstop>ch5Rev</tabstop>
|
||||
<tabstop>ch5Link</tabstop>
|
||||
<tabstop>ch6OutSlider</tabstop>
|
||||
<tabstop>ch6Rev</tabstop>
|
||||
<tabstop>ch6Link</tabstop>
|
||||
<tabstop>ch7OutSlider</tabstop>
|
||||
<tabstop>ch7Rev</tabstop>
|
||||
<tabstop>ch7Link</tabstop>
|
||||
<tabstop>channelOutTest</tabstop>
|
||||
<tabstop>saveRCOutputToRAM</tabstop>
|
||||
<tabstop>saveRCOutputToSD</tabstop>
|
||||
|
297
ground/openpilotgcs/src/plugins/config/outputchannelform.cpp
Normal file
@ -0,0 +1,297 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file outputchannelform.cpp
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2011.
|
||||
* @addtogroup GCSPlugins GCS Plugins
|
||||
* @{
|
||||
* @addtogroup ConfigPlugin Config Plugin
|
||||
* @{
|
||||
* @brief Servo output configuration form for the config output gadget
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* 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 "outputchannelform.h"
|
||||
#include "configoutputwidget.h"
|
||||
|
||||
OutputChannelForm::OutputChannelForm(const int index, QWidget *parent, const bool showLegend) :
|
||||
QWidget(parent),
|
||||
ui(),
|
||||
m_index(index),
|
||||
m_inChannelTest(false)
|
||||
{
|
||||
ui.setupUi(this);
|
||||
if(!showLegend)
|
||||
{
|
||||
// Remove legend
|
||||
QGridLayout *grid_layout = dynamic_cast<QGridLayout*>(layout());
|
||||
Q_ASSERT(grid_layout);
|
||||
for (int col = 0; col < grid_layout->columnCount(); col++)
|
||||
{ // remove every item in first row
|
||||
QLayoutItem *item = grid_layout->itemAtPosition(0, col);
|
||||
if (!item) continue;
|
||||
// get widget from layout item
|
||||
QWidget *legend_widget = item->widget();
|
||||
if (!legend_widget) continue;
|
||||
// delete widget
|
||||
grid_layout->removeWidget(legend_widget);
|
||||
delete legend_widget;
|
||||
}
|
||||
}
|
||||
|
||||
// The convention for OP is Channel 1 to Channel 10.
|
||||
ui.actuatorNumber->setText(QString("%1:").arg(m_index+1));
|
||||
|
||||
// Register for ActuatorSettings changes:
|
||||
connect(ui.actuatorMin, SIGNAL(editingFinished()),
|
||||
this, SLOT(setChannelRange()));
|
||||
connect(ui.actuatorMax, SIGNAL(editingFinished()),
|
||||
this, SLOT(setChannelRange()));
|
||||
connect(ui.actuatorRev, SIGNAL(toggled(bool)),
|
||||
this, SLOT(reverseChannel(bool)));
|
||||
// Now connect the channel out sliders to our signal to send updates in test mode
|
||||
connect(ui.actuatorNeutral, SIGNAL(valueChanged(int)),
|
||||
this, SLOT(sendChannelTest(int)));
|
||||
|
||||
ui.actuatorLink->setChecked(false);
|
||||
connect(ui.actuatorLink, SIGNAL(toggled(bool)),
|
||||
this, SLOT(linkToggled(bool)));
|
||||
}
|
||||
|
||||
OutputChannelForm::~OutputChannelForm()
|
||||
{
|
||||
// Do nothing
|
||||
}
|
||||
|
||||
/**
|
||||
* Restrict UI to protect users from accidental misuse.
|
||||
*/
|
||||
void OutputChannelForm::enableChannelTest(bool state)
|
||||
{
|
||||
if (m_inChannelTest == state) return;
|
||||
m_inChannelTest = state;
|
||||
|
||||
if(m_inChannelTest)
|
||||
{
|
||||
// Prevent stupid users from touching the minimum & maximum ranges while
|
||||
// moving the sliders. Thanks Ivan for the tip :)
|
||||
ui.actuatorMin->setEnabled(false);
|
||||
ui.actuatorMax->setEnabled(false);
|
||||
ui.actuatorRev->setEnabled(false);
|
||||
}
|
||||
else
|
||||
{
|
||||
ui.actuatorMin->setEnabled(true);
|
||||
ui.actuatorMax->setEnabled(true);
|
||||
ui.actuatorRev->setEnabled(true);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* Toggles the channel linked state for use in testing mode
|
||||
*/
|
||||
void OutputChannelForm::linkToggled(bool state)
|
||||
{
|
||||
Q_UNUSED(state)
|
||||
|
||||
if (!m_inChannelTest)
|
||||
return; // we are not in Test Output mode
|
||||
|
||||
// find the minimum slider value for the linked ones
|
||||
if (!parent()) return;
|
||||
int min = 10000;
|
||||
int linked_count = 0;
|
||||
QList<OutputChannelForm*> outputChannelForms = parent()->findChildren<OutputChannelForm*>();
|
||||
// set the linked channels of the parent widget to the same value
|
||||
foreach(OutputChannelForm *outputChannelForm, outputChannelForms)
|
||||
{
|
||||
if (!outputChannelForm->ui.actuatorLink->checkState())
|
||||
continue;
|
||||
if (this == outputChannelForm)
|
||||
continue;
|
||||
int value = outputChannelForm->ui.actuatorNeutral->value();
|
||||
if(min > value) min = value;
|
||||
linked_count++;
|
||||
}
|
||||
|
||||
if (linked_count <= 0)
|
||||
return; // no linked channels
|
||||
|
||||
// set the linked channels to the same value
|
||||
foreach(OutputChannelForm *outputChannelForm, outputChannelForms)
|
||||
{
|
||||
if (!outputChannelForm->ui.actuatorLink->checkState())
|
||||
continue;
|
||||
outputChannelForm->ui.actuatorNeutral->setValue(min);
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Set maximal channel value.
|
||||
*/
|
||||
void OutputChannelForm::max(int maximum)
|
||||
{
|
||||
minmax(ui.actuatorMin->value(), maximum);
|
||||
}
|
||||
|
||||
/**
|
||||
* Set minimal channel value.
|
||||
*/
|
||||
void OutputChannelForm::min(int minimum)
|
||||
{
|
||||
minmax(minimum, ui.actuatorMax->value());
|
||||
}
|
||||
|
||||
/**
|
||||
* Set minimal and maximal channel value.
|
||||
*/
|
||||
void OutputChannelForm::minmax(int minimum, int maximum)
|
||||
{
|
||||
ui.actuatorMin->setValue(minimum);
|
||||
ui.actuatorMax->setValue(maximum);
|
||||
setChannelRange();
|
||||
if(ui.actuatorMin->value() > ui.actuatorMax->value())
|
||||
ui.actuatorRev->setChecked(true);
|
||||
else
|
||||
ui.actuatorRev->setChecked(false);
|
||||
}
|
||||
|
||||
/**
|
||||
* Set neutral of channel.
|
||||
*/
|
||||
void OutputChannelForm::neutral(int value)
|
||||
{
|
||||
ui.actuatorNeutral->setValue(value);
|
||||
}
|
||||
|
||||
/**
|
||||
* Set the channel assignment label.
|
||||
*/
|
||||
void OutputChannelForm::setAssignment(const QString &assignment)
|
||||
{
|
||||
ui.actuatorName->setText(assignment);
|
||||
}
|
||||
|
||||
/**
|
||||
* Sets the minimum/maximum value of the channel output sliders.
|
||||
* Have to do it here because setMinimum is not a slot.
|
||||
*
|
||||
* One added trick: if the slider is at its min when the value
|
||||
* is changed, then keep it on the min.
|
||||
*/
|
||||
void OutputChannelForm::setChannelRange()
|
||||
{
|
||||
int oldMini = ui.actuatorNeutral->minimum();
|
||||
// int oldMaxi = ui.actuatorNeutral->maximum();
|
||||
|
||||
if (ui.actuatorMin->value() < ui.actuatorMax->value())
|
||||
{
|
||||
ui.actuatorNeutral->setRange(ui.actuatorMin->value(), ui.actuatorMax->value());
|
||||
ui.actuatorRev->setChecked(false);
|
||||
}
|
||||
else
|
||||
{
|
||||
ui.actuatorNeutral->setRange(ui.actuatorMax->value(), ui.actuatorMin->value());
|
||||
ui.actuatorRev->setChecked(true);
|
||||
}
|
||||
|
||||
if (ui.actuatorNeutral->value() == oldMini)
|
||||
ui.actuatorNeutral->setValue(ui.actuatorNeutral->minimum());
|
||||
|
||||
// if (ui.actuatorNeutral->value() == oldMaxi)
|
||||
// ui.actuatorNeutral->setValue(ui.actuatorNeutral->maximum()); // this can be dangerous if it happens to be controlling a motor at the time!
|
||||
}
|
||||
|
||||
/**
|
||||
* Reverses the channel when the checkbox is clicked
|
||||
*/
|
||||
void OutputChannelForm::reverseChannel(bool state)
|
||||
{
|
||||
// Sanity check: if state became true, make sure the Maxvalue was higher than Minvalue
|
||||
// the situations below can happen!
|
||||
if (state && (ui.actuatorMax->value() < ui.actuatorMin->value()))
|
||||
return;
|
||||
if (!state && (ui.actuatorMax->value() > ui.actuatorMin->value()))
|
||||
return;
|
||||
|
||||
// Now, swap the min & max values (only on the spinboxes, the slider
|
||||
// does not change!
|
||||
int temp = ui.actuatorMax->value();
|
||||
ui.actuatorMax->setValue(ui.actuatorMin->value());
|
||||
ui.actuatorMin->setValue(temp);
|
||||
|
||||
// Also update the channel value
|
||||
// This is a trick to force the slider to update its value and
|
||||
// emit the right signal itself, because our sendChannelTest(int) method
|
||||
// relies on the object sender's identity.
|
||||
if (ui.actuatorNeutral->value() < ui.actuatorNeutral->maximum())
|
||||
{
|
||||
ui.actuatorNeutral->setValue(ui.actuatorNeutral->value()+1);
|
||||
ui.actuatorNeutral->setValue(ui.actuatorNeutral->value()-1);
|
||||
}
|
||||
else
|
||||
{
|
||||
ui.actuatorNeutral->setValue(ui.actuatorNeutral->value()-1);
|
||||
ui.actuatorNeutral->setValue(ui.actuatorNeutral->value()+1);
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Emits the channel value which will be send to the UAV to move the servo.
|
||||
* Returns immediately if we are not in testing mode.
|
||||
*/
|
||||
void OutputChannelForm::sendChannelTest(int value)
|
||||
{
|
||||
int in_value = value;
|
||||
|
||||
QSlider *ob = (QSlider *)QObject::sender();
|
||||
if (!ob) return;
|
||||
|
||||
if (ui.actuatorRev->isChecked())
|
||||
value = ui.actuatorMin->value() - value + ui.actuatorMax->value(); // the channel is reversed
|
||||
|
||||
// update the label
|
||||
ui.actuatorValue->setText(QString::number(value));
|
||||
|
||||
if (ui.actuatorLink->checkState() && parent())
|
||||
{ // the channel is linked to other channels
|
||||
QList<OutputChannelForm*> outputChannelForms = parent()->findChildren<OutputChannelForm*>();
|
||||
// set the linked channels of the parent widget to the same value
|
||||
foreach(OutputChannelForm *outputChannelForm, outputChannelForms)
|
||||
{
|
||||
if (this == outputChannelForm) continue;
|
||||
if (!outputChannelForm->ui.actuatorLink->checkState()) continue;
|
||||
|
||||
int val = in_value;
|
||||
if (val < outputChannelForm->ui.actuatorNeutral->minimum())
|
||||
val = outputChannelForm->ui.actuatorNeutral->minimum();
|
||||
if (val > outputChannelForm->ui.actuatorNeutral->maximum())
|
||||
val = outputChannelForm->ui.actuatorNeutral->maximum();
|
||||
|
||||
if (outputChannelForm->ui.actuatorNeutral->value() == val) continue;
|
||||
|
||||
outputChannelForm->ui.actuatorNeutral->setValue(val);
|
||||
outputChannelForm->ui.actuatorValue->setText(QString::number(val));
|
||||
}
|
||||
}
|
||||
|
||||
if (!m_inChannelTest)
|
||||
return; // we are not in Test Output mode
|
||||
|
||||
emit channelChanged(index(), value);
|
||||
}
|
92
ground/openpilotgcs/src/plugins/config/outputchannelform.h
Normal file
@ -0,0 +1,92 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file outputchannelform.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2011.
|
||||
* @addtogroup GCSPlugins GCS Plugins
|
||||
* @{
|
||||
* @addtogroup ConfigPlugin Config Plugin
|
||||
* @{
|
||||
* @brief Servo output configuration form for the config output gadget
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* 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 OUTPUTCHANNELFORM_H
|
||||
#define OUTPUTCHANNELFORM_H
|
||||
|
||||
#include <QWidget>
|
||||
#include "ui_outputchannelform.h"
|
||||
|
||||
class ConfigOnputWidget;
|
||||
|
||||
class OutputChannelForm : public QWidget
|
||||
{
|
||||
Q_OBJECT
|
||||
|
||||
public:
|
||||
explicit OutputChannelForm(const int index, QWidget *parent = NULL, const bool showLegend = false);
|
||||
~OutputChannelForm();
|
||||
friend class ConfigOnputWidget;
|
||||
|
||||
void setAssignment(const QString &assignment);
|
||||
int index() const;
|
||||
|
||||
public slots:
|
||||
void max(int maximum);
|
||||
int max() const;
|
||||
void min(int minimum);
|
||||
int min() const;
|
||||
void minmax(int minimum, int maximum);
|
||||
void neutral(int value);
|
||||
int neutral() const;
|
||||
void enableChannelTest(bool state);
|
||||
|
||||
signals:
|
||||
void channelChanged(int index, int value);
|
||||
|
||||
private:
|
||||
Ui::outputChannelForm ui;
|
||||
/// Channel index
|
||||
int m_index;
|
||||
bool m_inChannelTest;
|
||||
|
||||
private slots:
|
||||
void linkToggled(bool state);
|
||||
void reverseChannel(bool state);
|
||||
void sendChannelTest(int value);
|
||||
void setChannelRange();
|
||||
};
|
||||
|
||||
inline int OutputChannelForm::index() const
|
||||
{
|
||||
return m_index;
|
||||
}
|
||||
|
||||
inline int OutputChannelForm::max() const
|
||||
{
|
||||
return ui.actuatorMax->value();
|
||||
}
|
||||
|
||||
inline int OutputChannelForm::min() const
|
||||
{
|
||||
return ui.actuatorMin->value();
|
||||
}
|
||||
|
||||
inline int OutputChannelForm::neutral() const
|
||||
{
|
||||
return ui.actuatorNeutral->value();
|
||||
}
|
||||
#endif // OUTPUTCHANNELFORM_H
|
323
ground/openpilotgcs/src/plugins/config/outputchannelform.ui
Normal file
@ -0,0 +1,323 @@
|
||||
<?xml version="1.0" encoding="UTF-8"?>
|
||||
<ui version="4.0">
|
||||
<class>outputChannelForm</class>
|
||||
<widget class="QWidget" name="outputChannelForm">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>0</x>
|
||||
<y>0</y>
|
||||
<width>605</width>
|
||||
<height>56</height>
|
||||
</rect>
|
||||
</property>
|
||||
<property name="windowTitle">
|
||||
<string>Form</string>
|
||||
</property>
|
||||
<layout class="QGridLayout" name="gridLayout">
|
||||
<property name="topMargin">
|
||||
<number>1</number>
|
||||
</property>
|
||||
<property name="bottomMargin">
|
||||
<number>1</number>
|
||||
</property>
|
||||
<item row="1" column="0">
|
||||
<widget class="QLabel" name="actuatorNumber">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Minimum" vsizetype="Preferred">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>20</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Channel Number</string>
|
||||
</property>
|
||||
<property name="layoutDirection">
|
||||
<enum>Qt::LeftToRight</enum>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>TextLabel</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="1">
|
||||
<widget class="QLabel" name="actuatorName">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Minimum" vsizetype="Preferred">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>90</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>TextLabel</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="2">
|
||||
<widget class="QSpinBox" name="actuatorMin">
|
||||
<property name="toolTip">
|
||||
<string>Minimum PWM value, beware of not overdriving your servo.</string>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>9999</number>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="3">
|
||||
<spacer name="horizontalSpacer">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="sizeType">
|
||||
<enum>QSizePolicy::Minimum</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>20</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item row="1" column="4">
|
||||
<widget class="QSlider" name="actuatorNeutral">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>9999</number>
|
||||
</property>
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="6">
|
||||
<spacer name="horizontalSpacer_2">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="sizeType">
|
||||
<enum>QSizePolicy::Minimum</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>5</width>
|
||||
<height>20</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item row="1" column="9">
|
||||
<widget class="QCheckBox" name="actuatorRev">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Fixed" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>40</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Check to invert the channel.</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="10">
|
||||
<widget class="QCheckBox" name="actuatorLink">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Fixed" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>40</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Output mode</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="8">
|
||||
<widget class="QSpinBox" name="actuatorMax">
|
||||
<property name="toolTip">
|
||||
<string>Maximum PWM value, beware of not overdriving your servo.</string>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>9999</number>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="1">
|
||||
<widget class="QLabel" name="legend0">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Minimum" vsizetype="Preferred">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Assignment</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="2">
|
||||
<widget class="QLabel" name="legend1">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Minimum" vsizetype="Preferred">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Min</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="4">
|
||||
<widget class="QLabel" name="legend2">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="MinimumExpanding" vsizetype="Preferred">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Neutral (slowest for motor)</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="8">
|
||||
<widget class="QLabel" name="legend3">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Minimum" vsizetype="Preferred">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Max</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="9">
|
||||
<widget class="QLabel" name="legend4">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Fixed" vsizetype="Preferred">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>25</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Rev.</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="10">
|
||||
<widget class="QLabel" name="legend5">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Fixed" vsizetype="Preferred">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>25</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Link</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="5">
|
||||
<widget class="QLabel" name="actuatorValue">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Minimum" vsizetype="Preferred">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Current value of slider.</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>0000</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="0">
|
||||
<widget class="QLabel" name="legend6">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Minimum" vsizetype="Preferred">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>20</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="layoutDirection">
|
||||
<enum>Qt::LeftToRight</enum>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>#</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
<property name="margin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
<resources/>
|
||||
<connections/>
|
||||
</ui>
|
@ -995,7 +995,7 @@
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<dFile>%%DATAPATH%%dials/default/lineardial-vertical.svg</dFile>
|
||||
<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>
|
||||
@ -1018,7 +1018,7 @@
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<dFile>%%DATAPATH%%dials/default/lineardial-horizontal.svg</dFile>
|
||||
<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>
|
||||
@ -1041,7 +1041,7 @@
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<dFile>%%DATAPATH%%dials/default/lineardial-horizontal.svg</dFile>
|
||||
<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>
|
||||
@ -1064,7 +1064,7 @@
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<dFile>%%DATAPATH%%dials/default/lineardial-horizontal.svg</dFile>
|
||||
<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>
|
||||
@ -1202,7 +1202,7 @@
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<dFile>%%DATAPATH%%dials/default/lineardial-vertical.svg</dFile>
|
||||
<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>
|
||||
@ -1225,7 +1225,7 @@
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<dFile>%%DATAPATH%%dials/default/lineardial-vertical.svg</dFile>
|
||||
<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>
|
||||
@ -1248,7 +1248,7 @@
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<dFile>%%DATAPATH%%dials/default/lineardial-vertical.svg</dFile>
|
||||
<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>
|
||||
@ -1271,7 +1271,7 @@
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<dFile>%%DATAPATH%%dials/default/lineardial-vertical.svg</dFile>
|
||||
<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>
|
||||
@ -1294,7 +1294,7 @@
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<dFile>%%DATAPATH%%dials/default/lineardial-vertical.svg</dFile>
|
||||
<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>
|
||||
@ -1317,7 +1317,7 @@
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<dFile>%%DATAPATH%%dials/default/lineardial-vertical.svg</dFile>
|
||||
<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>
|
||||
@ -1340,7 +1340,7 @@
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<dFile>%%DATAPATH%%dials/default/lineardial-horizontal.svg</dFile>
|
||||
<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>
|
||||
@ -1363,7 +1363,7 @@
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<dFile>%%DATAPATH%%dials/default/lineardial-horizontal.svg</dFile>
|
||||
<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>
|
||||
@ -1386,7 +1386,7 @@
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<dFile>%%DATAPATH%%dials/default/lineardial-vertical.svg</dFile>
|
||||
<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>
|
||||
@ -1409,7 +1409,7 @@
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<dFile>%%DATAPATH%%dials/default/lineardial-vertical.svg</dFile>
|
||||
<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>
|
||||
@ -1432,7 +1432,7 @@
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<dFile>%%DATAPATH%%dials/default/lineardial-vertical.svg</dFile>
|
||||
<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>
|
||||
@ -1627,6 +1627,17 @@
|
||||
<enableVbo>false</enableVbo>
|
||||
</data>
|
||||
</Test__PCT__20Quad__PCT__20X>
|
||||
<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>
|
||||
<CopterControl>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
|
@ -358,7 +358,10 @@ void ConnectionManager::devChanged(IConnection *connection)
|
||||
if(m_mainWindow->generalSettings()->autoConnect() || m_mainWindow->generalSettings()->autoSelect())
|
||||
m_availableDevList->setCurrentIndex(m_availableDevList->count()-1);
|
||||
if(m_mainWindow->generalSettings()->autoConnect())
|
||||
{
|
||||
connectDevice();
|
||||
qDebug()<<"ConnectionManager::devChanged autoconnected USB device";
|
||||
}
|
||||
}
|
||||
}
|
||||
if(m_ioDev)//if a device is connected make it the one selected on the dropbox
|
||||
|
@ -1,134 +1,140 @@
|
||||
<?xml version="1.0" encoding="UTF-8"?>
|
||||
<ui version="4.0">
|
||||
<class>GCSControl</class>
|
||||
<widget class="QWidget" name="GCSControl">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>0</x>
|
||||
<y>0</y>
|
||||
<width>653</width>
|
||||
<height>295</height>
|
||||
</rect>
|
||||
</property>
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Expanding" vsizetype="Expanding">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="windowTitle">
|
||||
<string>Form</string>
|
||||
</property>
|
||||
<layout class="QVBoxLayout" name="verticalLayout_2">
|
||||
<property name="spacing">
|
||||
<number>2</number>
|
||||
</property>
|
||||
<property name="margin">
|
||||
<number>5</number>
|
||||
</property>
|
||||
<item>
|
||||
<layout class="QVBoxLayout" name="verticalLayout">
|
||||
<item>
|
||||
<layout class="QHBoxLayout" name="horizontalLayout">
|
||||
<item>
|
||||
<widget class="QCheckBox" name="checkBoxGcsControl">
|
||||
<property name="text">
|
||||
<string>GCS Control</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QCheckBox" name="checkBoxArmed">
|
||||
<property name="text">
|
||||
<string>Armed</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QLabel" name="label">
|
||||
<property name="text">
|
||||
<string>Flight Mode:</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QComboBox" name="comboBoxFlightMode"/>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
<item>
|
||||
<layout class="QGridLayout" name="gridLayout" columnstretch="0,0,0">
|
||||
<property name="horizontalSpacing">
|
||||
<number>10</number>
|
||||
</property>
|
||||
<property name="leftMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<item row="0" column="0">
|
||||
<widget class="JoystickControl" name="widgetLeftStick" native="true">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Preferred">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>100</width>
|
||||
<height>100</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="mouseTracking">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="2">
|
||||
<widget class="JoystickControl" name="widgetRightStick" native="true">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Preferred">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>100</width>
|
||||
<height>100</height>
|
||||
</size>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="1">
|
||||
<spacer name="verticalSpacer">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Vertical</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>2</width>
|
||||
<height>40</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
<customwidgets>
|
||||
<customwidget>
|
||||
<class>JoystickControl</class>
|
||||
<extends>QWidget</extends>
|
||||
<header>joystickcontrol.h</header>
|
||||
<container>1</container>
|
||||
</customwidget>
|
||||
</customwidgets>
|
||||
<resources/>
|
||||
<connections/>
|
||||
</ui>
|
||||
<?xml version="1.0" encoding="UTF-8"?>
|
||||
<ui version="4.0">
|
||||
<class>GCSControl</class>
|
||||
<widget class="QWidget" name="GCSControl">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>0</x>
|
||||
<y>0</y>
|
||||
<width>653</width>
|
||||
<height>295</height>
|
||||
</rect>
|
||||
</property>
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Expanding" vsizetype="Expanding">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="windowTitle">
|
||||
<string>Form</string>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">background:transparent</string>
|
||||
</property>
|
||||
<layout class="QVBoxLayout" name="verticalLayout_2">
|
||||
<property name="spacing">
|
||||
<number>2</number>
|
||||
</property>
|
||||
<property name="margin">
|
||||
<number>5</number>
|
||||
</property>
|
||||
<item>
|
||||
<layout class="QVBoxLayout" name="verticalLayout">
|
||||
<item>
|
||||
<layout class="QHBoxLayout" name="horizontalLayout">
|
||||
<item>
|
||||
<widget class="QCheckBox" name="checkBoxGcsControl">
|
||||
<property name="text">
|
||||
<string>GCS Control</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QCheckBox" name="checkBoxArmed">
|
||||
<property name="text">
|
||||
<string>Armed</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QLabel" name="label">
|
||||
<property name="text">
|
||||
<string>Flight Mode:</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QComboBox" name="comboBoxFlightMode"/>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
<item>
|
||||
<layout class="QGridLayout" name="gridLayout" columnstretch="0,0,0,0">
|
||||
<property name="horizontalSpacing">
|
||||
<number>10</number>
|
||||
</property>
|
||||
<property name="leftMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<item row="0" column="0">
|
||||
<widget class="JoystickControl" name="widgetLeftStick" native="true">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Preferred">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>100</width>
|
||||
<height>100</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="mouseTracking">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">background:transparent</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="1">
|
||||
<spacer name="verticalSpacer">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Vertical</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>2</width>
|
||||
<height>40</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item row="0" column="2">
|
||||
<widget class="JoystickControl" name="widgetRightStick" native="true">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Preferred">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>100</width>
|
||||
<height>100</height>
|
||||
</size>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
<customwidgets>
|
||||
<customwidget>
|
||||
<class>JoystickControl</class>
|
||||
<extends>QWidget</extends>
|
||||
<header>joystickcontrol.h</header>
|
||||
<container>1</container>
|
||||
</customwidget>
|
||||
</customwidgets>
|
||||
<resources/>
|
||||
<connections/>
|
||||
</ui>
|
||||
|
@ -1,5 +1,5 @@
|
||||
<?xml version="1.0" encoding="UTF-8" standalone="no"?>
|
||||
<!-- Created with Inkscape (http://www.inkscape.org/) -->
|
||||
<!-- Generator: Adobe Illustrator 12.0.0, SVG Export Plug-In . SVG Version: 6.00 Build 51448) -->
|
||||
|
||||
<svg
|
||||
xmlns:dc="http://purl.org/dc/elements/1.1/"
|
||||
@ -11,185 +11,1885 @@
|
||||
xmlns:sodipodi="http://sodipodi.sourceforge.net/DTD/sodipodi-0.dtd"
|
||||
xmlns:inkscape="http://www.inkscape.org/namespaces/inkscape"
|
||||
version="1.1"
|
||||
width="490"
|
||||
height="487"
|
||||
viewBox="0 0 490 487"
|
||||
overflow="visible"
|
||||
enable-background="new 0 0 490 487"
|
||||
xml:space="preserve"
|
||||
id="svg2"
|
||||
inkscape:version="0.48.2 r9819"
|
||||
sodipodi:docname="joystick.svg"><metadata
|
||||
id="metadata723"><rdf:RDF><cc:Work
|
||||
rdf:about=""><dc:format>image/svg+xml</dc:format><dc:type
|
||||
rdf:resource="http://purl.org/dc/dcmitype/StillImage" /></cc:Work></rdf:RDF></metadata><defs
|
||||
id="defs721" /><sodipodi:namedview
|
||||
pagecolor="#ffffff"
|
||||
bordercolor="#666666"
|
||||
borderopacity="1"
|
||||
objecttolerance="10"
|
||||
gridtolerance="10"
|
||||
guidetolerance="10"
|
||||
inkscape:pageopacity="0"
|
||||
inkscape:pageshadow="2"
|
||||
inkscape:window-width="1052"
|
||||
inkscape:window-height="826"
|
||||
id="namedview719"
|
||||
showgrid="false"
|
||||
inkscape:zoom="0.96919918"
|
||||
inkscape:cx="295.47102"
|
||||
inkscape:cy="210.00484"
|
||||
inkscape:window-x="0"
|
||||
inkscape:window-y="0"
|
||||
inkscape:window-maximized="0"
|
||||
inkscape:current-layer="svg2" />
|
||||
<g
|
||||
id="background"
|
||||
inkscape:label="#BG"
|
||||
transform="matrix(0.78514439,0,0,0.78293167,43.169635,40.476837)">
|
||||
<linearGradient
|
||||
id="XMLID_52_"
|
||||
gradientUnits="userSpaceOnUse"
|
||||
x1="3.6933999"
|
||||
y1="241"
|
||||
x2="480.30661"
|
||||
y2="241">
|
||||
<stop
|
||||
offset="0.6629"
|
||||
style="stop-color:#BCBEC0"
|
||||
id="stop6" />
|
||||
<stop
|
||||
offset="0.7256"
|
||||
style="stop-color:#B2B4B6"
|
||||
id="stop8" />
|
||||
<stop
|
||||
offset="0.8308"
|
||||
style="stop-color:#999A9C"
|
||||
id="stop10" />
|
||||
<stop
|
||||
offset="0.9649"
|
||||
style="stop-color:#6F7072"
|
||||
id="stop12" />
|
||||
<stop
|
||||
offset="1"
|
||||
style="stop-color:#636466"
|
||||
id="stop14" />
|
||||
</linearGradient>
|
||||
<path
|
||||
d="M 461.069,2.524 H 22.927 c -10.622,0 -19.234,8.041 -19.234,17.961 v 441.031 c 0,9.918 8.612,17.959 19.234,17.959 h 438.142 c 10.626,0 19.237,-8.041 19.237,-17.959 V 20.485 c 0.001,-9.92 -8.611,-17.961 -19.237,-17.961 z m 11.143,451.502 c 0,9.582 -8.318,17.35 -18.582,17.35 H 30.368 c -10.262,0 -18.581,-7.768 -18.581,-17.35 V 27.976 c 0,-9.583 8.319,-17.351 18.581,-17.351 H 453.63 c 10.264,0 18.582,7.768 18.582,17.351 v 426.05 z"
|
||||
id="path16"
|
||||
style="fill:url(#XMLID_52_)"
|
||||
inkscape:connector-curvature="0" />
|
||||
<linearGradient
|
||||
id="XMLID_53_"
|
||||
gradientUnits="userSpaceOnUse"
|
||||
x1="13.9385"
|
||||
y1="468.12891"
|
||||
x2="469.09351"
|
||||
y2="12.9739">
|
||||
<stop
|
||||
offset="0.0056"
|
||||
style="stop-color:#FFFFFF"
|
||||
id="stop19" />
|
||||
<stop
|
||||
offset="0.1438"
|
||||
style="stop-color:#DADADA"
|
||||
id="stop21" />
|
||||
<stop
|
||||
offset="0.3481"
|
||||
style="stop-color:#AAAAAA"
|
||||
id="stop23" />
|
||||
<stop
|
||||
offset="0.5423"
|
||||
style="stop-color:#848484"
|
||||
id="stop25" />
|
||||
<stop
|
||||
offset="0.7213"
|
||||
style="stop-color:#696969"
|
||||
id="stop27" />
|
||||
<stop
|
||||
offset="0.8794"
|
||||
style="stop-color:#595959"
|
||||
id="stop29" />
|
||||
<stop
|
||||
offset="1"
|
||||
style="stop-color:#535353"
|
||||
id="stop31" />
|
||||
</linearGradient>
|
||||
<path
|
||||
d="m 474.797,455.541 c 0,9.67 -8.43,17.51 -18.83,17.51 H 27.063 c -10.399,0 -18.83,-7.84 -18.83,-17.51 V 25.562 c 0,-9.671 8.431,-17.511 18.83,-17.511 h 428.903 c 10.4,0 18.83,7.84 18.83,17.511 v 429.979 z"
|
||||
id="path33"
|
||||
style="fill:url(#XMLID_53_)"
|
||||
inkscape:connector-curvature="0" />
|
||||
<g
|
||||
id="g35"
|
||||
transform="matrix(0.96656026,0,0,0.9743773,4.0468958,2.3324246)">
|
||||
<g
|
||||
id="g37">
|
||||
<g
|
||||
id="g39">
|
||||
|
||||
<image
|
||||
width="64"
|
||||
height="64"
|
||||
id="svg2"
|
||||
inkscape:version="0.47 r22583"
|
||||
sodipodi:docname="joystick-3.svg">
|
||||
<sodipodi:namedview
|
||||
pagecolor="#ffffff"
|
||||
bordercolor="#666666"
|
||||
borderopacity="1"
|
||||
objecttolerance="10"
|
||||
gridtolerance="10"
|
||||
guidetolerance="10"
|
||||
inkscape:pageopacity="0"
|
||||
inkscape:pageshadow="2"
|
||||
inkscape:window-width="1280"
|
||||
inkscape:window-height="725"
|
||||
id="namedview7"
|
||||
showgrid="false"
|
||||
inkscape:zoom="6.4523494"
|
||||
inkscape:cx="34.428448"
|
||||
inkscape:cy="32.074874"
|
||||
inkscape:window-x="0"
|
||||
inkscape:window-y="24"
|
||||
inkscape:window-maximized="1"
|
||||
inkscape:current-layer="background"
|
||||
showguides="true"
|
||||
inkscape:guide-bbox="true" />
|
||||
<defs
|
||||
id="defs4">
|
||||
<inkscape:perspective
|
||||
sodipodi:type="inkscape:persp3d"
|
||||
inkscape:vp_x="0 : 32 : 1"
|
||||
inkscape:vp_y="0 : 1000 : 0"
|
||||
inkscape:vp_z="64 : 32 : 1"
|
||||
inkscape:persp3d-origin="32 : 21.333333 : 1"
|
||||
id="perspective9" />
|
||||
<inkscape:perspective
|
||||
id="perspective4576"
|
||||
inkscape:persp3d-origin="0.5 : 0.33333333 : 1"
|
||||
inkscape:vp_z="1 : 0.5 : 1"
|
||||
inkscape:vp_y="0 : 1000 : 0"
|
||||
inkscape:vp_x="0 : 0.5 : 1"
|
||||
sodipodi:type="inkscape:persp3d" />
|
||||
<linearGradient
|
||||
inkscape:collect="always"
|
||||
xlink:href="#linearGradient3899"
|
||||
id="linearGradient3820"
|
||||
gradientUnits="userSpaceOnUse"
|
||||
x1="337.63348"
|
||||
y1="371.99725"
|
||||
x2="729.8302"
|
||||
y2="676.58545" />
|
||||
<linearGradient
|
||||
id="linearGradient3899">
|
||||
<stop
|
||||
id="stop3901"
|
||||
offset="0"
|
||||
style="stop-color:#9699a3;stop-opacity:1;" />
|
||||
<stop
|
||||
style="stop-color:#1f1616;stop-opacity:1;"
|
||||
offset="0.49412024"
|
||||
id="stop3903" />
|
||||
<stop
|
||||
id="stop3905"
|
||||
offset="1"
|
||||
style="stop-color:#9498a5;stop-opacity:0;" />
|
||||
</linearGradient>
|
||||
<linearGradient
|
||||
inkscape:collect="always"
|
||||
xlink:href="#linearGradient3899"
|
||||
id="linearGradient4790"
|
||||
x1="14.99304"
|
||||
y1="1038.3234"
|
||||
x2="105.25183"
|
||||
y2="941.66919"
|
||||
gradientUnits="userSpaceOnUse" />
|
||||
</defs>
|
||||
<metadata
|
||||
id="metadata7">
|
||||
<rdf:RDF>
|
||||
<cc:Work
|
||||
rdf:about="">
|
||||
<dc:format>image/svg+xml</dc:format>
|
||||
<dc:type
|
||||
rdf:resource="http://purl.org/dc/dcmitype/StillImage" />
|
||||
<dc:title></dc:title>
|
||||
</cc:Work>
|
||||
</rdf:RDF>
|
||||
</metadata>
|
||||
<g
|
||||
id="background"
|
||||
inkscape:label="#g4757">
|
||||
<g
|
||||
inkscape:label="#layer1"
|
||||
id="Baba"
|
||||
transform="matrix(1.1638314,0,0,-1.1066141,-5.6432489,1159.5817)"
|
||||
style="fill-opacity:1;fill:url(#linearGradient4790)">
|
||||
<rect
|
||||
style="fill:url(#linearGradient4790);fill-opacity:1.0;stroke:#202020;stroke-width:0.88116424000000004;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect2985"
|
||||
y="990.19446"
|
||||
x="5.0757694"
|
||||
ry="28.718821"
|
||||
rx="0.09363886"
|
||||
height="57.437641"
|
||||
width="54.725903" />
|
||||
</g>
|
||||
<g
|
||||
id="g3789"
|
||||
transform="matrix(0.13698764,0,0,0.13698764,-19.020289,-22.990069)">
|
||||
<path
|
||||
style="fill:none;stroke:#f1f4fc;stroke-width:3.96819687;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
d="m 147.64949,401.70025 448.62372,0"
|
||||
id="path3604" />
|
||||
<path
|
||||
id="path3606"
|
||||
d="m 371.96135,177.80154 0,447.79741"
|
||||
style="fill:none;stroke:#f1f4fc;stroke-width:3.96454072;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
<g
|
||||
transform="translate(-55.093487,1.6686132)"
|
||||
id="text4694"
|
||||
style="font-size:18.68679619px;font-style:normal;font-weight:normal;fill:#f1f4fc;fill-opacity:1;stroke:none;font-family:Bitstream Vera Sans">
|
||||
<path
|
||||
id="path4735"
|
||||
style="font-variant:normal;font-weight:bold;font-stretch:normal;fill:#f1f4fc;fill-opacity:1;font-family:FreeSans;-inkscape-font-specification:FreeSans Bold"
|
||||
d="m 442.33813,294.19735 0,2.33585 -5.47523,0 -0.4298,2.76565 c 0.7101,-0.53568 1.47625,-0.80353 2.29848,-0.80354 1.22086,10e-6 2.21126,0.42358 2.9712,1.27071 0.77238,0.84714 1.15857,1.94966 1.15858,3.30756 -10e-6,1.43266 -0.44226,2.59124 -1.32676,3.47574 -0.88452,0.88451 -2.03687,1.32676 -3.45706,1.32677 -1.28316,-10e-6 -2.32962,-0.35505 -3.13938,-1.06515 -0.79731,-0.72256 -1.20841,-1.66312 -1.23333,-2.82171 l 2.57878,0 c 0.0623,1.0963 0.67272,1.64444 1.8313,1.64444 0.66027,0 1.17727,-0.22424 1.55101,-0.67272 0.38619,-0.44849 0.57928,-1.05892 0.57929,-1.83131 -10e-6,-0.7973 -0.1931,-1.42019 -0.57929,-1.86868 -0.37374,-0.46093 -0.89074,-0.69141 -1.55101,-0.69141 -0.83468,0 -1.39528,0.33637 -1.68181,1.00909 l -2.35453,0 1.17726,-7.38129 7.0823,0" />
|
||||
<path
|
||||
id="path4737"
|
||||
style="font-variant:normal;font-weight:bold;font-stretch:normal;fill:#f1f4fc;fill-opacity:1;font-family:FreeSans;-inkscape-font-specification:FreeSans Bold"
|
||||
d="m 450.94603,307.35286 c -0.61044,0.34882 -1.35792,0.52322 -2.24242,0.52323 -0.88451,-10e-6 -1.63198,-0.17441 -2.24241,-0.52323 -0.61044,-0.36128 -1.08384,-0.87205 -1.4202,-1.53232 -0.32391,-0.66027 -0.55438,-1.38282 -0.69141,-2.16767 -0.13704,-0.7973 -0.20556,-1.71295 -0.20556,-2.74696 0,-2.52894 0.37374,-4.29172 1.12121,-5.28836 0.82222,-1.13366 1.96834,-1.70049 3.43837,-1.7005 1.60706,10e-6 2.81547,0.65405 3.62524,1.96211 0.62288,1.0091 0.93433,2.7096 0.93434,5.1015 -1e-5,0.99663 -0.0685,1.88737 -0.20555,2.67221 -0.13705,0.77239 -0.36752,1.49495 -0.69142,2.16767 -0.32391,0.66027 -0.79731,1.17104 -1.42019,1.53232 m -0.29899,-6.42826 c -1e-5,-1.33299 -0.0872,-2.36699 -0.26162,-3.10201 -0.16196,-0.735 -0.37374,-1.21463 -0.63535,-1.43888 -0.26162,-0.23669 -0.61044,-0.35504 -1.04646,-0.35505 -0.69764,10e-6 -1.19596,0.35506 -1.49494,1.06514 -0.29899,0.69765 -0.44849,1.96213 -0.44848,3.79342 -1e-5,1.27071 0.081,2.26734 0.24292,2.98989 0.16195,0.7101 0.37374,1.1835 0.63535,1.4202 0.27407,0.22424 0.62912,0.33636 1.06515,0.33636 0.75993,0 1.29561,-0.40488 1.60707,-1.21464 0.22423,-0.62289 0.33635,-1.7877 0.33636,-3.49443" />
|
||||
<path
|
||||
id="path4739"
|
||||
style="font-variant:normal;font-weight:bold;font-stretch:normal;fill:#f1f4fc;fill-opacity:1;font-family:FreeSans;-inkscape-font-specification:FreeSans Bold"
|
||||
d="m 457.85343,294.34684 c 0.95925,2e-5 1.76901,0.33638 2.42928,1.00909 0.67272,0.66028 1.00908,1.47004 1.00909,2.42929 -1e-5,0.90943 -0.3426,1.7005 -1.02778,2.37322 -0.67273,0.66027 -1.47626,0.99041 -2.41059,0.9904 -0.9468,10e-6 -1.75656,-0.33013 -2.42929,-0.9904 -0.67272,-0.67272 -1.00908,-1.47625 -1.00908,-2.4106 0,-0.93433 0.33636,-1.73163 1.00908,-2.39191 0.67273,-0.67271 1.48249,-1.00907 2.42929,-1.00909 m 1.1212,2.31717 c -0.31145,-0.31144 -0.68518,-0.46716 -1.1212,-0.46717 -0.43603,10e-6 -0.80977,0.15573 -1.12121,0.46717 -0.31145,0.299 -0.46717,0.66027 -0.46717,1.08383 0,0.43604 0.15572,0.80977 0.46717,1.12121 0.31144,0.299 0.68518,0.44849 1.12121,0.44848 0.43602,1e-5 0.80975,-0.14948 1.1212,-0.44848 0.31145,-0.31144 0.46717,-0.67894 0.46717,-1.10252 0,-0.43602 -0.15572,-0.80352 -0.46717,-1.10252 m 6.35351,-2.46666 1.4202,0 -7.38128,13.62267 -1.43889,0 7.39997,-13.62267 m 1.36414,6.67119 c 0.95924,0 1.769,0.33637 2.42928,1.00908 0.67271,0.66028 1.00908,1.47626 1.00909,2.44797 -10e-6,0.90943 -0.34261,1.7005 -1.02777,2.37323 -0.67274,0.66026 -1.47627,0.9904 -2.4106,0.9904 -0.94681,0 -1.75657,-0.33014 -2.42928,-0.9904 -0.67274,-0.67273 -1.0091,-1.48249 -1.00909,-2.42929 -1e-5,-0.93433 0.33635,-1.73163 1.00909,-2.39191 0.67271,-0.67271 1.48247,-1.00908 2.42928,-1.00908 m 1.12121,2.31716 c -0.31146,-0.31144 -0.6852,-0.46717 -1.12121,-0.46717 -0.43604,0 -0.80977,0.15573 -1.12121,0.46717 -0.31145,0.29899 -0.46718,0.6665 -0.46717,1.10252 -1e-5,0.43603 0.15572,0.80976 0.46717,1.12121 0.31144,0.29899 0.68517,0.44848 1.12121,0.44848 0.43601,0 0.80975,-0.14949 1.12121,-0.44848 0.31143,-0.31145 0.46715,-0.67895 0.46717,-1.10252 -2e-5,-0.43602 -0.15574,-0.80976 -0.46717,-1.12121" />
|
||||
</g>
|
||||
<g
|
||||
transform="translate(-84.518596,-20.468429)"
|
||||
id="text4705"
|
||||
style="font-size:18.68679619px;font-style:normal;font-weight:normal;fill:#f1f4fc;fill-opacity:1;stroke:none;font-family:Bitstream Vera Sans">
|
||||
<path
|
||||
id="path4742"
|
||||
style="font-variant:normal;font-weight:bold;font-stretch:normal;fill:#f1f4fc;fill-opacity:1;font-family:FreeSans;-inkscape-font-specification:FreeSans Bold"
|
||||
d="m 472.26662,250.39779 0,2.05555 c -1.5697,1.8936 -2.72205,3.71245 -3.45706,5.45654 -0.73501,1.73165 -1.16481,3.64393 -1.28938,5.73685 l -2.63484,0 c 0.3239,-2.56632 0.90319,-4.72776 1.73787,-6.48432 0.26161,-0.57305 0.71009,-1.34544 1.34545,-2.31716 0.6478,-0.97171 1.17103,-1.67557 1.56969,-2.11161 l -6.59644,0 0,-2.33585 9.32471,0" />
|
||||
<path
|
||||
id="path4744"
|
||||
style="font-variant:normal;font-weight:bold;font-stretch:normal;fill:#f1f4fc;fill-opacity:1;font-family:FreeSans;-inkscape-font-specification:FreeSans Bold"
|
||||
d="m 481.93967,250.39779 0,2.33585 -5.47523,0 -0.4298,2.76565 c 0.71009,-0.53568 1.47625,-0.80353 2.29848,-0.80354 1.22086,1e-5 2.21126,0.42358 2.9712,1.27071 0.77237,0.84714 1.15857,1.94966 1.15858,3.30756 -10e-6,1.43266 -0.44227,2.59124 -1.32677,3.47574 -0.88451,0.88451 -2.03686,1.32676 -3.45705,1.32676 -1.28317,0 -2.32963,-0.35504 -3.13938,-1.06514 -0.79731,-0.72256 -1.20842,-1.66313 -1.23333,-2.82171 l 2.57877,0 c 0.0623,1.0963 0.67273,1.64444 1.83131,1.64444 0.66026,0 1.17726,-0.22424 1.55101,-0.67273 0.38618,-0.44848 0.57928,-1.05891 0.57929,-1.8313 -10e-6,-0.7973 -0.19311,-1.42019 -0.57929,-1.86868 -0.37375,-0.46094 -0.89075,-0.69141 -1.55101,-0.69141 -0.83468,0 -1.39528,0.33637 -1.68181,1.00908 l -2.35454,0 1.17727,-7.38128 7.0823,0" />
|
||||
<path
|
||||
id="path4746"
|
||||
style="font-variant:normal;font-weight:bold;font-stretch:normal;fill:#f1f4fc;fill-opacity:1;font-family:FreeSans;-inkscape-font-specification:FreeSans Bold"
|
||||
d="m 487.05313,250.54728 c 0.95925,2e-5 1.76901,0.33638 2.42929,1.00909 0.67271,0.66028 1.00908,1.47004 1.00908,2.42928 0,0.90944 -0.34259,1.70051 -1.02777,2.37323 -0.67273,0.66027 -1.47626,0.9904 -2.4106,0.9904 -0.9468,0 -1.75656,-0.33013 -2.42928,-0.9904 -0.67273,-0.67272 -1.00909,-1.47625 -1.00909,-2.4106 0,-0.93433 0.33636,-1.73163 1.00909,-2.39191 0.67272,-0.67271 1.48248,-1.00907 2.42928,-1.00909 m 1.12121,2.31717 c -0.31145,-0.31144 -0.68519,-0.46716 -1.12121,-0.46717 -0.43603,1e-5 -0.80976,0.15573 -1.1212,0.46717 -0.31145,0.299 -0.46718,0.66027 -0.46717,1.08383 -1e-5,0.43604 0.15572,0.80977 0.46717,1.12121 0.31144,0.299 0.68517,0.44849 1.1212,0.44848 0.43602,1e-5 0.80976,-0.14948 1.12121,-0.44848 0.31144,-0.31144 0.46717,-0.67895 0.46717,-1.10252 0,-0.43602 -0.15573,-0.80352 -0.46717,-1.10252 m 6.35351,-2.46666 1.4202,0 -7.38129,13.62267 -1.43888,0 7.39997,-13.62267 m 1.36414,6.67119 c 0.95924,0 1.769,0.33636 2.42928,1.00908 0.67271,0.66027 1.00907,1.47626 1.00909,2.44797 -2e-5,0.90943 -0.34261,1.7005 -1.02778,2.37323 -0.67273,0.66026 -1.47627,0.9904 -2.41059,0.9904 -0.94681,0 -1.75657,-0.33014 -2.42929,-0.9904 -0.67273,-0.67273 -1.00909,-1.48249 -1.00908,-2.42929 -10e-6,-0.93433 0.33635,-1.73164 1.00908,-2.39191 0.67272,-0.67272 1.48248,-1.00908 2.42929,-1.00908 m 1.12121,2.31716 c -0.31146,-0.31144 -0.6852,-0.46717 -1.12121,-0.46717 -0.43604,0 -0.80978,0.15573 -1.12121,0.46717 -0.31146,0.29899 -0.46718,0.6665 -0.46717,1.10252 -10e-6,0.43603 0.15571,0.80976 0.46717,1.12121 0.31143,0.29899 0.68517,0.44848 1.12121,0.44848 0.43601,0 0.80975,-0.14949 1.12121,-0.44848 0.31143,-0.31145 0.46715,-0.67895 0.46717,-1.10252 -2e-5,-0.43602 -0.15574,-0.80976 -0.46717,-1.12121" />
|
||||
</g>
|
||||
<rect
|
||||
style="fill:none;fill-opacity:1;stroke:#f1f4fc;stroke-width:0.53500000000000003;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect4780"
|
||||
width="31.073954"
|
||||
height="31.228935"
|
||||
x="16.428125"
|
||||
y="16.420431"
|
||||
transform="matrix(7.2999287,0,0,7.2999287,138.84675,167.82586)" />
|
||||
<rect
|
||||
style="fill:none;stroke:#f1f4fc;stroke-width:0.53500003;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect4782"
|
||||
width="46.52055"
|
||||
height="48.931507"
|
||||
x="8.6575346"
|
||||
y="7.5616441"
|
||||
transform="matrix(7.2999287,0,0,7.2999287,138.84675,167.82586)" />
|
||||
</g>
|
||||
</g>
|
||||
<path
|
||||
sodipodi:type="arc"
|
||||
style="fill:#ff201d;fill-opacity:1;stroke:#ef7d7d;stroke-width:0.39996386;stroke-miterlimit:4;stroke-opacity:0.59336093;stroke-dasharray:none"
|
||||
id="joystickEnd"
|
||||
sodipodi:cx="25.013699"
|
||||
sodipodi:cy="28.684931"
|
||||
sodipodi:rx="1.0136986"
|
||||
sodipodi:ry="1.0136986"
|
||||
d="m 26.027397,28.684931 a 1.0136986,1.0136986 0 1 1 -2.027397,0 1.0136986,1.0136986 0 1 1 2.027397,0 z"
|
||||
inkscape:label="#path3034"
|
||||
transform="matrix(2.1651956,0,0,2.1651956,-34.537402,-34.234392)" />
|
||||
</svg>
|
||||
xlink:href="data:image/png;base64,iVBORw0KGgoAAAANSUhEUgAAAEAAAABACAYAAACqaXHeAAAACXBIWXMAAAsSAAALEgHS3X78AAAA BGdBTUEAAK/INwWK6QAAABl0RVh0U29mdHdhcmUAQWRvYmUgSW1hZ2VSZWFkeXHJZTwAAAYeSURB VHja7FuLjts2ECQlSn4k6f9/Z5OzrSdbA2KxmMwuSdlO7poTQEhnnyzPcHa5D9q5z+PPPvw7fl78 PxDwzM+PH4UAX/l3Cdj4KjL8i4Cza7+DgEgAx2cS4V8E3Bdc470ILMJ1KSm/lACvAC8ZGgGxcjxE gn/SrONoyLkxiGDAV3Fe4bV07RR1FB/hSbOOQHG0QEIDBEgAKxkLeY2Zga8lIjwAHmdcgtVGel+S 4BTwS2Z4UAYSEZ9NAAPPgAcyWnFGNSABEuSsjEb8zwr3+xoSwoPgE5gErtuuOzIkIegTIhCQgE7K SO/77f/ddm8DJDxFARZ4OeMJaK8MSYRUgRMA5MzfgY5iDNu53d5jK8oiSHAlRNQoQAOfgB02oPfz cTvLIUlohS/wYP8I/g78tt1/2545iO+SjhnMoMgfhMrljoHvBcg78NM2juKMJEhf4Ij8pw1kAn+/ 9wo+BRWEx1pCQtjp9BB8AnoW4yTOR0FAL0CgAhYx+4mA6zZ6YUKNEsPIOMKXBEmhUPoNgA9C9kcB 9gsMSUZSAfqBdCyCgGmb+ZsgD++zgqgoVBAtfxAqIj0pf5z9O8ivYnwDEk4GEGco4E7AJTP7LHiS KjCDo1Dh+BqwfTn7XwTwv7bzV0FCIqAHAjQTkApg4PEeFj02xP5/UkGoiPOZ4zsK6SMBiYQzIaA1 CJg3BRwM6UcSMc4QRK3EH1SZgDfk34H8JQGoAukDegiGPIkD0ipwAIcpzQXjBRYtrmJJ3LUKOMMB ogLOYP/fhB84g/13xJFFADbB/6GvmJVgadxeCyQocswMQoX8W2X5OwEJuBIw+28UBSQVhAx4XCrT YObiLWcYdjpADH7OyjgR+SMwzAVWkjBp4G8iUOqVUNtbdY+wYwkMIqBJBBwh+juJ17Uv55UgZiEz huBv5PPxGUwFcc8yyBSAKjiQHACToM5IhZ2xdiezOMDqcDDA52b/PzJyJuAKkqAevkivpMAtOFRX kLRIAjojw+zgOa1RglN9gC8MhVkK3GW+EJbIWHU4fTHp9Fql0NIVgm9ydc9QEANoRZCWVHoCKYE1 hkfOZZ5amS0o5TZGcLUTtFTAzIFdNwZ4TXExU2ZnBdbcs7JV72ZHm6u29u8ywGsLsCW9huJyf+P+ 8CNHQDQKDnu7NqU1+z2dIkee/XBRNCpdGZl14bWWn+eaF9HoC5Y2TLRJKFaAxfBKQM+ZlLT0i0UD MOsVLAXPyioiKF6Yzf6aqduPSu0+rRArEB+VslYOOHs2koK9xGoTYAyyuv0ENfsRiOiM2N8rLfGV gJ6M1JeRoKmuKheIpPLCgA9Qwj5Caop5f0vWfGZmk6gOjaRPMADxk6KCaDn3oLzpM7MykpT0uoG/ FhQwG6UgEmHmB/KMq/j7ZpDAVFBtApoCRvhyF6WGh1mdVRBhdcFBAL8IAi5AxLBDBZSAaMwKI+AK LbFcyXs2/MIK5a4RwL+JcRFDI+BhH8Bq7jOZnYvS82PgWVHUE/nLwkcC/+Pf8X07/9hekyYxgjNc lVUglpqA5gMm0aAMRr8OKzlaXdARApJNJ4BvG/jvgoQ3QYJmArHWBHJmMBu7QFjTAk2mN1pj2BgZ gICkgL+FCqQvGAQB66NOEFWwiv57AsXS0FwN71BIAJrYRYBORLyBD0jEWQ4w1qwC2lLYiA0KjVHD QyAH0huwOkOD4gRR/tIJSvuPe02AqUDuuJiVHDwaBFwr2uPSB9yECq6wAjAHyHICt7c5ioVKaQqz siFBA3Eg5XFW91+M2v9VCYRGJRQuyghLFIDyzoXNKGNri0yj9AYx2pThL4bBJdHfbhNg8lkNAhZC gLZJqjVaY1rfbxQOz4r8Vle4e7S0IOINEnIhs7VNrlEIWJy9TU4Cn2vtfq8CNBKi0a+fXH6jpM98 BhsS+LKnElRLgEWClThpW2VZc0RKd1EKIlrZDTdPF9cea/cKs5XBKxnk4so3S7PaIwO6OH33+K6t 8+95u7y2VX7NVIR3A3mEiN/1gwn3CPhnEKB1fV7xkxlnzPZv+8lMjghNJTVNEefe+Y+mSvqJtc/8 kD+be/Xnf5gfTj7redF9Hp/Hy49/BBgApEegBA3kNcsAAAAASUVORK5CYII="
|
||||
transform="translate(1,1)"
|
||||
id="image41"
|
||||
style="opacity:0.75">
|
||||
</image>
|
||||
<radialGradient
|
||||
id="XMLID_54_"
|
||||
cx="30.4263"
|
||||
cy="30.189899"
|
||||
r="16.5"
|
||||
gradientUnits="userSpaceOnUse">
|
||||
<stop
|
||||
offset="0.5899"
|
||||
style="stop-color:#231F20"
|
||||
id="stop44" />
|
||||
<stop
|
||||
offset="0.6789"
|
||||
style="stop-color:#403D3E"
|
||||
id="stop46" />
|
||||
<stop
|
||||
offset="0.8716"
|
||||
style="stop-color:#88888A"
|
||||
id="stop48" />
|
||||
<stop
|
||||
offset="1"
|
||||
style="stop-color:#BCBEC0"
|
||||
id="stop50" />
|
||||
</radialGradient>
|
||||
<circle
|
||||
cx="30.426001"
|
||||
cy="30.190001"
|
||||
r="16.5"
|
||||
id="circle52"
|
||||
d="m 46.926001,30.190001 c 0,9.112698 -7.387302,16.5 -16.5,16.5 -9.112699,0 -16.5,-7.387302 -16.5,-16.5 0,-9.112699 7.387301,-16.5 16.5,-16.5 9.112698,0 16.5,7.387301 16.5,16.5 z"
|
||||
style="fill:url(#XMLID_54_)"
|
||||
sodipodi:cx="30.426001"
|
||||
sodipodi:cy="30.190001"
|
||||
sodipodi:rx="16.5"
|
||||
sodipodi:ry="16.5" />
|
||||
</g>
|
||||
<g
|
||||
id="g54">
|
||||
|
||||
<image
|
||||
width="57"
|
||||
height="56"
|
||||
xlink:href="data:image/png;base64,iVBORw0KGgoAAAANSUhEUgAAADkAAAA4CAYAAABHRFAgAAAACXBIWXMAAAsSAAALEgHS3X78AAAA BGdBTUEAAK/INwWK6QAAABl0RVh0U29mdHdhcmUAQWRvYmUgSW1hZ2VSZWFkeXHJZTwAAAQPSURB VHja7JoNb+MgDIaB0OzW7f//0tvWjwRulUCy3rONSei03TWSRZWuSZ69xjYmzj2Ox/FjDv9N7pF/ IqQ3nM9fBezveD1vuE9W4PJ3hPTGkQNpjbuOeAf1PIB5AZSCZEFJPwI03kG9mwUARFiEu1liYIeA xsGAgYzUNMhUzBPQNBJ0lJIc3ARjIL9BwBVGNxI0DpyHFG4q156IUUUR8GZL+W4l1x4CGne6KQdX AQ9lrEbVzARwKRYIqBsJGgcBBgJXAecyUliqJAW8ftpFSWkJALtA4wD3DABXAZ/KOBPQQAJMhbyA O2vFQN6iaNwRRTnACvWrQNaxwlN3rQoemDnrFEXRdZtFQ+wExCiKgE/FngtgHWcCUx+2qngWlLSA mlSNG9MEBpiZKHezYwE8EjVnBvLMKGn5Z2dmnm5Skt7QCvhc7KUAHkFNCnkFhYNQ41IXXkHNRABF 2GiMolbACvYKoBLkWZmTXgCmbhoIsKhqS0kOUgN8KfZKPiNkTfhVyWiYj1JhnyzBJxrSRehQsQK+ gpo9kK21Zy0JJyF3/qVmbKjIgVJIdFOEfGXmJIU8kHNOWaFkKN4Tcdfd0dUrkE/CfDyCy2qBJ5KA 48AN0VawROak19y2Z06iu2qB50gi7VFIIRGKg8zALFD61c9T+d5bcmtstENwESzNS5oj0ep3WAwE WJGsBKbWstQO5fwkrFO9lE6iIZp5ZkE8MQX5AUq7GWrXA9SuDgr1K1znAAX+ZFiI7yoGJNggLLUm 5qECUdIp32u/90IkVkHD/9BBjx1dbSmUS9FvZf7GwVLLEkETpI3U27qMCqBX4FZm0csFDKxLMYXg 318FWxhoqZXZhMxKRy0D3JUslW7B5cR0AyhgEmrXk2DnYhcFNguwucddqa1CmD9DiwMDhyPqc5Af n/bO2AeBpaDUlU1KTo0iwClNYq6JHJjoR71hIevIEwF8+7Tfxd6IISwqulpcdzLmSNfohktLoywk ewskAiJkvWZTzclQoG/dIMoMZHVxDvCtAXlpAOYttWtmiubVCOcYuLkxJyU3PQGg2U2tKQQf2HVA YttxVqLrOwGt0JagkwQ1u5T0UFCnTsikQGIA+lDm4cK4aXL6Jm5Xty6TKgV7Kj2QWkvyBO6JgWYV 8qNzG4oBzW099FRceVALpNZcvgCYFdCkYq+SWWjwLo20cTVsE1yIqpcOwGHbBE5YjEqgWCUtHRs+ UrJPzDQZvuEjqUpB1wZka+sODRXcBLh1f1IDzQKkdRN2HeWieyG1pRjCrm7bdvowwD2QXHrxjJrY MtRejEhCkt/9Ts/el5Xu9YrLMMARkNKqZevLSnhuN+AoSE3VVkftS147e7xAeIfr/hOvgm69R3aP 43E8jtvxR4ABAL1S3PlRWBIpAAAAAElFTkSuQmCC"
|
||||
transform="translate(5,5)"
|
||||
id="image56"
|
||||
style="opacity:0.75">
|
||||
</image>
|
||||
<radialGradient
|
||||
id="XMLID_55_"
|
||||
cx="30.4268"
|
||||
cy="30.190399"
|
||||
r="12.8335"
|
||||
gradientUnits="userSpaceOnUse">
|
||||
<stop
|
||||
offset="0"
|
||||
style="stop-color:#FFFFFF"
|
||||
id="stop59" />
|
||||
<stop
|
||||
offset="1"
|
||||
style="stop-color:#393939"
|
||||
id="stop61" />
|
||||
</radialGradient>
|
||||
<path
|
||||
d="m 39.948,26.878 h -6.209 v -6.209 c 0,-1.829 -1.483,-3.313 -3.313,-3.313 -1.828,0 -3.312,1.483 -3.312,3.313 v 6.209 h -6.21 c -1.829,0 -3.312,1.483 -3.312,3.313 0,1.828 1.482,3.312 3.312,3.312 h 6.21 v 6.21 c 0,1.829 1.483,3.312 3.312,3.312 1.829,0 3.313,-1.482 3.313,-3.312 v -6.21 h 6.209 c 1.829,0 3.313,-1.483 3.313,-3.312 -0.001,-1.829 -1.484,-3.313 -3.313,-3.313 z"
|
||||
id="path63"
|
||||
style="fill:url(#XMLID_55_)"
|
||||
inkscape:connector-curvature="0" />
|
||||
</g>
|
||||
<g
|
||||
id="g65">
|
||||
<g
|
||||
id="g67">
|
||||
|
||||
<image
|
||||
width="67"
|
||||
height="67"
|
||||
xlink:href="data:image/png;base64,iVBORw0KGgoAAAANSUhEUgAAAEMAAABDCAYAAADHyrhzAAAACXBIWXMAAAsSAAALEgHS3X78AAAA BGdBTUEAAK/INwWK6QAAABl0RVh0U29mdHdhcmUAQWRvYmUgSW1hZ2VSZWFkeXHJZTwAAAXCSURB VHja7FuBbuM6DLMd7/7/e7fEfjhgeRB4pCQnbd/toQGMdO2axgwly6Rdyvt4H+yoP+D35v8FjGdc f/6km62J36gXOz2fCUx90rXY63oDjOm89zBQ6pNAsOfqfBYBwc4zCdDLwVCdZ39XAU4EhmqF/H0L kPogNqjWgs89MFgb4m/FmqeDodjQyLmJzyJ2sA4P0yY532ZJvQFEFUDYtglQPHacHWAg2HYIcLyc 8jAwPCBsx9W5ATCMHUh5BsBhgDgcUJYBqTeAYAzo36+xKTBqIl8gCGfbCTgISiGhcwuMDBDdnDu8 t5Fw8fKGfZrIit2cbfNASbOjLzCDhcUGIHyY1wyM8/slCcYEMLbvswo5PCw7agRIX2COAuPDAPEB oChWZJmJ7FgBY5J85ALSL4aHBYI1ZEamtihBDjnB2AEMb2hGdpS7zGBgdAiN3+0XAQOfnjff8Er4 E4yIEaxQq+KcBgOp3AgrEAgEw950dMPFCSH7IEYiNFTZHhZifZEVDAgWIuf/YTLDQmqS32QV7Nnx LRFKrCJt8HuUHX0xaaoQYeFRSRI84MyYYRl4ftbgc690x9ZMeFSPHT3JihoMpyxPFFE57uY9jG0E /QQEE3ETIw7WGodhBeatP9iRqTM8ILoYQgtUj6pIUmCcQ+gJtj2wXpkC9POeLDvKSgKNQoQBgkXV eYOWCV/fDQEZJEzs9YeYjWLYdFG2s6p3ruaMGkzIVJnNGPEbhE8CiI1rBsZBkmx0X/372htcJxUq 2TqDsUON+UOw4hPAiJgxCCM82SA7OVwaTaIEqrSKCWAwID4hZzAwDgCD1TpYZ7QAlJoJlZ6Q9CuJ UTUNHyRpfpEzJlDs1AzY2Ux5XpwHxr5THlF0efJdEdrDDgz5ghAZpDBrAqBNhFAl7GiBZLCcQD12 VEehGgQMJs6oogtZsZtEeJCCqorSHR9cOEvOMCNiS3HEGPZ6QMWIU2yb+dX3o+S6YlH8+wCyRVek aCtZf4hODEeOG+YGIzW8LILhMqM9wFqIXK950SWLzKNsrkv3ZRWMleNlSwluWB6XNFCvg3XBalQx G9kRK9Zkth/zChgZilaYJjfHURsOhb2aRhlRWWvyluzHLuD9QHVcNTWDZEOrV/5704AMCMvqOLtA 5GlWp0BixVIxQ6eSC7pznSbEmil8WY/Zc4UZygRmGmYzne6ivihmDuJVm93RTTairw6nFkkZSt3x GRQrRhAmE/SIISZkzXlfSYtdAIFW5HDYsSwIR0XUQX6omae7ERMYZ5+R0tXBgugARoMq1TOoM+ES jibT0RgPIro2ok+qnMDEGyU6/yLMKMKc3h0jOh0mJagCFfIHgID6pALiCMKEWZdboLzvYkI4MqNL d/zJSRKTRb+D+DqENlmF2MvCpDrC8wasKI7gvIMKv5xAozA5jNdpzyieKI+DhYgKEza8NgGEAuNY ASJKoMygOUNiF4pSARNJVZSextkcxcre09nZLyEeqTApKwl0kqpuQG2wC0UJCzC0BhsMqVEVW50c sQsgdpJEbw2tXlWHgCg3fAtAmiLJsonZJEAwMJi0yIb4uRom+DROZmREE7ueoiU0yClmr56caJV3 68t4y5lurdyZkLCKAISNPj0AxNMXBslZSmRmBhUbui8n0EK8BUykkRN+lD9X70RrsKLrHcR28JT3 URZW+2WYgeGSuXlmAHvJNrPEYA/8GDWcplf8ZZUuFi7ZJ+nZkSvLHjM1xa2lj49cFLuRQqkLYcYD Y4pZKFsQu5cXL4rNAoJLpO+sEB4OO0Yw/3j6culIsG3FX0Tfki5Xxnth5tTLF9JnFWzV+azd522v mIEh9dItFiVhC9RgbpJdNx5tuPkrNt9c9TtWt2WtbMn6T7dlZUFZMZPu2pW3XbxHbeWsSZfNe12c zv2YrZxZYErxN/xe2dT7127yXbn21R3PDwfgVWA86rde6ea/j/fxPvzjHwEGACHoYu+QT2NyAAAA AElFTkSuQmCC"
|
||||
id="image69"
|
||||
style="opacity:0.75">
|
||||
</image>
|
||||
<g
|
||||
id="g71">
|
||||
<g
|
||||
id="g73">
|
||||
<linearGradient
|
||||
id="XMLID_56_"
|
||||
gradientUnits="userSpaceOnUse"
|
||||
x1="48.4263"
|
||||
y1="30.189899"
|
||||
x2="12.4263"
|
||||
y2="30.189899">
|
||||
<stop
|
||||
offset="0"
|
||||
style="stop-color:#FFFFFF"
|
||||
id="stop76" />
|
||||
<stop
|
||||
offset="1"
|
||||
style="stop-color:#000000"
|
||||
id="stop78" />
|
||||
</linearGradient>
|
||||
<path
|
||||
d="m 30.426,12.19 c -9.941,0 -18,8.059 -18,18 0,9.941 8.059,18 18,18 9.941,0 18,-8.059 18,-18 0,-9.941 -8.058,-18 -18,-18 z m 0,33.837 c -8.746,0 -15.837,-7.091 -15.837,-15.837 0,-8.746 7.091,-15.836 15.837,-15.836 8.746,0 15.836,7.09 15.836,15.836 0,8.746 -7.09,15.837 -15.836,15.837 z"
|
||||
id="path80"
|
||||
style="fill:url(#XMLID_56_)"
|
||||
inkscape:connector-curvature="0" />
|
||||
</g>
|
||||
</g>
|
||||
</g>
|
||||
<g
|
||||
id="g82">
|
||||
|
||||
<image
|
||||
width="63"
|
||||
height="64"
|
||||
xlink:href="data:image/png;base64,iVBORw0KGgoAAAANSUhEUgAAAD8AAABACAYAAACtK6/LAAAACXBIWXMAAAsSAAALEgHS3X78AAAA BGdBTUEAAK/INwWK6QAAABl0RVh0U29mdHdhcmUAQWRvYmUgSW1hZ2VSZWFkeXHJZTwAAAU9SURB VHja7FsBjtswDLMcd/9/75pYw4AroGmkJCfpcNsugJH0mktMUZYl2m3t6/g/D/lE79R/DfzV5+vf Bl5ueo++2xDyxmcJ+LssANZ3G0JufoYUz/4aAc3Ol40w3gDaX0tiBARawWd0v1wxwLgJ+Gqzz/BM +jaBQbwBTnmBXADuGe7guoPvBLzXszyTsxKD6LuYz9jupIm79uxHwH0TZ4B5ZRiMi8A9uI1cd2AA BN4DP9zZXqOYsGSAccLlEdObOfvGwAsZ6wi4bWL+3hz7SwYYi2NcCNPDgB0FA7QieNt2Y7zDPeOU AcZF4BbscI2Bl2Cqs26PgO+uL4f5/7ka9MYNwH+2BwA/3HCwMQJNdZ79l9vvSdxozgBSZX8sjnUG /GEM8HDMs0CHmLdt+zBAB89hwwZ5ATXAOMF6N+BfoL858Nbl2dwuSV4/zbt24DksG5QgdV5ye+by iPWHY72DzrIcnU2n3biyFLLCTtiG7I9idVYF/gCM285OAp6lv1KoA1jWl7I/iuOcBbpBgHdjbT+F KZiaWFr8+m4j7o6ywE5S39/YHzdE+gECnCRJC+qYfb6CnMB+x4AfYKhQ5rcAdA/c/RsIdMMxZqes nbTDdV5JLKjkBrpQDodjXojrbyST81PZNHO0b5Z9NI2+DKmGnA7um+b+g0yr4tz9F9evjnlkgA6A W5d8gX1+NMS2fc9mQCEv6EHOYfvjXX8p2rNpjhUzErj607XdpKw2KndTI8xkJkDlc5RGC0t2RkF1 ZS9Ec6/Py18G+O7ATxfxrStrgYRIP4jS30u5PeqIDz5RkHu6etxmZDOZASZIhHpCChr3SwGvBcw3 wLyvxnx03wHQDj7vZgwfJGOUBDDzZl1lvkUPAnPvQZqP9g14wWGAswCYeaZkOmWlno+k6JYIEqyp i/ZWn2P3o9Q1MsBbNLxM+dViq8jWGsjWq338bdz39nmOsxJ0mWl/9BMdyzq4unCxutgRedqSQUcB tBK3XMkJbLO1tyUBafy9sOBRNcTSmK8UB1456aQO2EDE9hF+K0jfKKnKCpqlwkbJyiiKwN4AAooO NFWhDK8DJdjLYT2ZXbK1vVYtbDSxMMvIFAC393aQ21vmH0Qj6IT1bFrUipKjRG+rvKQ513+xP9z3 NnNjzI/AAI2k04z5U2OesTzJmpkHyATKbsrNCPxwgqgvm2eg5DBydDXgscVDm6Zuxt27Yz8qUqb7 fgMSmXf5bElrFpKpNOC1wst2Jx50opsj1tGYjxY6hVSOB5HDWNALBUwNgsphgtVuFhN8MOouiAlx +RmUpyzITVAxZuwvS9caSM9+8RCVmh3EAD9mNUmQkCa4KoaeXrFRt/gnhv29oJowGWyC+r0lAgRS h54A/FF1eSRdR3JxZctZdbkbaYIrstjTXCPwWaKTgm8BWHad7ZmTQjWmRAXeHegK8LayaNEKTEth qGQZYiMdnCS27IDtJxFFyxpAVcxQt+7dgtWTV8dHW9uVoYWp1RvidKSvBDyvfswC8OkSoK3Fm5Gi NJqBP84GudV6PjMAY2xlTw7KJi2wHRhiBmt9t21Fywzgy9TZalvRKuDZlrRZGOe3bEVjAW26jnfX 8comxKryeywou63dvAmRbfCdIBPsLpmRxTGPxAlWts5kel2We1eSldbObTxmuUFUSmuBaT0D5KwB ziiwVRU2U2Uu7bi+Ar6SBK382EADL2gJy3oHgLuNUKkBpMW/q8mA6l0dv9MIlXpgZdXm0/7AaHXN 7O4Vok8F/s7n/3U/Kjz7Tm1fx9fxR44fAgwAvmzh1nziJNEAAAAASUVORK5CYII="
|
||||
transform="translate(2,1)"
|
||||
id="image84"
|
||||
style="opacity:0.75">
|
||||
</image>
|
||||
<g
|
||||
id="g86">
|
||||
<g
|
||||
id="g88">
|
||||
<linearGradient
|
||||
id="XMLID_57_"
|
||||
gradientUnits="userSpaceOnUse"
|
||||
x1="14.2183"
|
||||
y1="30.189899"
|
||||
x2="46.6353"
|
||||
y2="30.189899">
|
||||
<stop
|
||||
offset="0"
|
||||
style="stop-color:#FFFFFF"
|
||||
id="stop91" />
|
||||
<stop
|
||||
offset="1"
|
||||
style="stop-color:#000000"
|
||||
id="stop93" />
|
||||
</linearGradient>
|
||||
<path
|
||||
d="m 30.426,13.982 c -8.951,0 -16.208,7.257 -16.208,16.208 0,8.95 7.257,16.208 16.208,16.208 8.951,0 16.209,-7.258 16.209,-16.208 0,-8.951 -7.258,-16.208 -16.209,-16.208 z m 0,30.47 c -7.876,0 -14.261,-6.386 -14.261,-14.262 0,-7.876 6.385,-14.262 14.261,-14.262 7.877,0 14.262,6.386 14.262,14.262 0,7.876 -6.385,14.262 -14.262,14.262 z"
|
||||
id="path95"
|
||||
style="fill:url(#XMLID_57_)"
|
||||
inkscape:connector-curvature="0" />
|
||||
</g>
|
||||
</g>
|
||||
</g>
|
||||
</g>
|
||||
</g>
|
||||
<g
|
||||
id="g97">
|
||||
<g
|
||||
id="g99">
|
||||
|
||||
<image
|
||||
width="64"
|
||||
height="64"
|
||||
xlink:href="data:image/png;base64,iVBORw0KGgoAAAANSUhEUgAAAEAAAABACAYAAACqaXHeAAAACXBIWXMAAAsSAAALEgHS3X78AAAA BGdBTUEAAK/INwWK6QAAABl0RVh0U29mdHdhcmUAQWRvYmUgSW1hZ2VSZWFkeXHJZTwAAAYeSURB VHja7FuLjts2ECQlSn4k6f9/Z5OzrSdbA2KxmMwuSdlO7poTQEhnnyzPcHa5D9q5z+PPPvw7fl78 PxDwzM+PH4UAX/l3Cdj4KjL8i4Cza7+DgEgAx2cS4V8E3Bdc470ILMJ1KSm/lACvAC8ZGgGxcjxE gn/SrONoyLkxiGDAV3Fe4bV07RR1FB/hSbOOQHG0QEIDBEgAKxkLeY2Zga8lIjwAHmdcgtVGel+S 4BTwS2Z4UAYSEZ9NAAPPgAcyWnFGNSABEuSsjEb8zwr3+xoSwoPgE5gErtuuOzIkIegTIhCQgE7K SO/77f/ddm8DJDxFARZ4OeMJaK8MSYRUgRMA5MzfgY5iDNu53d5jK8oiSHAlRNQoQAOfgB02oPfz cTvLIUlohS/wYP8I/g78tt1/2545iO+SjhnMoMgfhMrljoHvBcg78NM2juKMJEhf4Ij8pw1kAn+/ 9wo+BRWEx1pCQtjp9BB8AnoW4yTOR0FAL0CgAhYx+4mA6zZ6YUKNEsPIOMKXBEmhUPoNgA9C9kcB 9gsMSUZSAfqBdCyCgGmb+ZsgD++zgqgoVBAtfxAqIj0pf5z9O8ivYnwDEk4GEGco4E7AJTP7LHiS KjCDo1Dh+BqwfTn7XwTwv7bzV0FCIqAHAjQTkApg4PEeFj02xP5/UkGoiPOZ4zsK6SMBiYQzIaA1 CJg3BRwM6UcSMc4QRK3EH1SZgDfk34H8JQGoAukDegiGPIkD0ipwAIcpzQXjBRYtrmJJ3LUKOMMB ogLOYP/fhB84g/13xJFFADbB/6GvmJVgadxeCyQocswMQoX8W2X5OwEJuBIw+28UBSQVhAx4XCrT YObiLWcYdjpADH7OyjgR+SMwzAVWkjBp4G8iUOqVUNtbdY+wYwkMIqBJBBwh+juJ17Uv55UgZiEz huBv5PPxGUwFcc8yyBSAKjiQHACToM5IhZ2xdiezOMDqcDDA52b/PzJyJuAKkqAevkivpMAtOFRX kLRIAjojw+zgOa1RglN9gC8MhVkK3GW+EJbIWHU4fTHp9Fql0NIVgm9ydc9QEANoRZCWVHoCKYE1 hkfOZZ5amS0o5TZGcLUTtFTAzIFdNwZ4TXExU2ZnBdbcs7JV72ZHm6u29u8ywGsLsCW9huJyf+P+ 8CNHQDQKDnu7NqU1+z2dIkee/XBRNCpdGZl14bWWn+eaF9HoC5Y2TLRJKFaAxfBKQM+ZlLT0i0UD MOsVLAXPyioiKF6Yzf6aqduPSu0+rRArEB+VslYOOHs2koK9xGoTYAyyuv0ENfsRiOiM2N8rLfGV gJ6M1JeRoKmuKheIpPLCgA9Qwj5Caop5f0vWfGZmk6gOjaRPMADxk6KCaDn3oLzpM7MykpT0uoG/ FhQwG6UgEmHmB/KMq/j7ZpDAVFBtApoCRvhyF6WGh1mdVRBhdcFBAL8IAi5AxLBDBZSAaMwKI+AK LbFcyXs2/MIK5a4RwL+JcRFDI+BhH8Bq7jOZnYvS82PgWVHUE/nLwkcC/+Pf8X07/9hekyYxgjNc lVUglpqA5gMm0aAMRr8OKzlaXdARApJNJ4BvG/jvgoQ3QYJmArHWBHJmMBu7QFjTAk2mN1pj2BgZ gICkgL+FCqQvGAQB66NOEFWwiv57AsXS0FwN71BIAJrYRYBORLyBD0jEWQ4w1qwC2lLYiA0KjVHD QyAH0huwOkOD4gRR/tIJSvuPe02AqUDuuJiVHDwaBFwr2uPSB9yECq6wAjAHyHICt7c5ioVKaQqz siFBA3Eg5XFW91+M2v9VCYRGJRQuyghLFIDyzoXNKGNri0yj9AYx2pThL4bBJdHfbhNg8lkNAhZC gLZJqjVaY1rfbxQOz4r8Vle4e7S0IOINEnIhs7VNrlEIWJy9TU4Cn2vtfq8CNBKi0a+fXH6jpM98 BhsS+LKnElRLgEWClThpW2VZc0RKd1EKIlrZDTdPF9cea/cKs5XBKxnk4so3S7PaIwO6OH33+K6t 8+95u7y2VX7NVIR3A3mEiN/1gwn3CPhnEKB1fV7xkxlnzPZv+8lMjghNJTVNEefe+Y+mSvqJtc/8 kD+be/Xnf5gfTj7redF9Hp/Hy49/BBgApEegBA3kNcsAAAAASUVORK5CYII="
|
||||
transform="translate(424,1)"
|
||||
id="image101"
|
||||
style="opacity:0.75">
|
||||
</image>
|
||||
<radialGradient
|
||||
id="XMLID_58_"
|
||||
cx="453.42581"
|
||||
cy="30.189899"
|
||||
r="16.5"
|
||||
gradientUnits="userSpaceOnUse">
|
||||
<stop
|
||||
offset="0.5899"
|
||||
style="stop-color:#231F20"
|
||||
id="stop104" />
|
||||
<stop
|
||||
offset="0.6789"
|
||||
style="stop-color:#403D3E"
|
||||
id="stop106" />
|
||||
<stop
|
||||
offset="0.8716"
|
||||
style="stop-color:#88888A"
|
||||
id="stop108" />
|
||||
<stop
|
||||
offset="1"
|
||||
style="stop-color:#BCBEC0"
|
||||
id="stop110" />
|
||||
</radialGradient>
|
||||
<circle
|
||||
cx="453.42599"
|
||||
cy="30.190001"
|
||||
r="16.5"
|
||||
id="circle112"
|
||||
d="m 469.92599,30.190001 c 0,9.112698 -7.3873,16.5 -16.5,16.5 -9.11269,0 -16.5,-7.387302 -16.5,-16.5 0,-9.112699 7.38731,-16.5 16.5,-16.5 9.1127,0 16.5,7.387301 16.5,16.5 z"
|
||||
style="fill:url(#XMLID_58_)"
|
||||
sodipodi:cx="453.42599"
|
||||
sodipodi:cy="30.190001"
|
||||
sodipodi:rx="16.5"
|
||||
sodipodi:ry="16.5" />
|
||||
</g>
|
||||
<g
|
||||
id="g114">
|
||||
|
||||
<image
|
||||
width="57"
|
||||
height="56"
|
||||
xlink:href="data:image/png;base64,iVBORw0KGgoAAAANSUhEUgAAADkAAAA4CAYAAABHRFAgAAAACXBIWXMAAAsSAAALEgHS3X78AAAA BGdBTUEAAK/INwWK6QAAABl0RVh0U29mdHdhcmUAQWRvYmUgSW1hZ2VSZWFkeXHJZTwAAAQPSURB VHja7JoNb+MgDIaB0OzW7f//0tvWjwRulUCy3rONSei03TWSRZWuSZ69xjYmzj2Ox/FjDv9N7pF/ IqQ3nM9fBezveD1vuE9W4PJ3hPTGkQNpjbuOeAf1PIB5AZSCZEFJPwI03kG9mwUARFiEu1liYIeA xsGAgYzUNMhUzBPQNBJ0lJIc3ARjIL9BwBVGNxI0DpyHFG4q156IUUUR8GZL+W4l1x4CGne6KQdX AQ9lrEbVzARwKRYIqBsJGgcBBgJXAecyUliqJAW8ftpFSWkJALtA4wD3DABXAZ/KOBPQQAJMhbyA O2vFQN6iaNwRRTnACvWrQNaxwlN3rQoemDnrFEXRdZtFQ+wExCiKgE/FngtgHWcCUx+2qngWlLSA mlSNG9MEBpiZKHezYwE8EjVnBvLMKGn5Z2dmnm5Skt7QCvhc7KUAHkFNCnkFhYNQ41IXXkHNRABF 2GiMolbACvYKoBLkWZmTXgCmbhoIsKhqS0kOUgN8KfZKPiNkTfhVyWiYj1JhnyzBJxrSRehQsQK+ gpo9kK21Zy0JJyF3/qVmbKjIgVJIdFOEfGXmJIU8kHNOWaFkKN4Tcdfd0dUrkE/CfDyCy2qBJ5KA 48AN0VawROak19y2Z06iu2qB50gi7VFIIRGKg8zALFD61c9T+d5bcmtstENwESzNS5oj0ep3WAwE WJGsBKbWstQO5fwkrFO9lE6iIZp5ZkE8MQX5AUq7GWrXA9SuDgr1K1znAAX+ZFiI7yoGJNggLLUm 5qECUdIp32u/90IkVkHD/9BBjx1dbSmUS9FvZf7GwVLLEkETpI3U27qMCqBX4FZm0csFDKxLMYXg 318FWxhoqZXZhMxKRy0D3JUslW7B5cR0AyhgEmrXk2DnYhcFNguwucddqa1CmD9DiwMDhyPqc5Af n/bO2AeBpaDUlU1KTo0iwClNYq6JHJjoR71hIevIEwF8+7Tfxd6IISwqulpcdzLmSNfohktLoywk ewskAiJkvWZTzclQoG/dIMoMZHVxDvCtAXlpAOYttWtmiubVCOcYuLkxJyU3PQGg2U2tKQQf2HVA YttxVqLrOwGt0JagkwQ1u5T0UFCnTsikQGIA+lDm4cK4aXL6Jm5Xty6TKgV7Kj2QWkvyBO6JgWYV 8qNzG4oBzW099FRceVALpNZcvgCYFdCkYq+SWWjwLo20cTVsE1yIqpcOwGHbBE5YjEqgWCUtHRs+ UrJPzDQZvuEjqUpB1wZka+sODRXcBLh1f1IDzQKkdRN2HeWieyG1pRjCrm7bdvowwD2QXHrxjJrY MtRejEhCkt/9Ts/el5Xu9YrLMMARkNKqZevLSnhuN+AoSE3VVkftS147e7xAeIfr/hOvgm69R3aP 43E8jtvxR4ABAL1S3PlRWBIpAAAAAElFTkSuQmCC"
|
||||
transform="translate(428,5)"
|
||||
id="image116"
|
||||
style="opacity:0.75">
|
||||
</image>
|
||||
<radialGradient
|
||||
id="XMLID_59_"
|
||||
cx="453.42679"
|
||||
cy="30.190399"
|
||||
r="12.8333"
|
||||
gradientUnits="userSpaceOnUse">
|
||||
<stop
|
||||
offset="0"
|
||||
style="stop-color:#FFFFFF"
|
||||
id="stop119" />
|
||||
<stop
|
||||
offset="1"
|
||||
style="stop-color:#393939"
|
||||
id="stop121" />
|
||||
</radialGradient>
|
||||
<path
|
||||
d="m 462.947,26.878 h -6.209 v -6.209 c 0,-1.829 -1.482,-3.313 -3.313,-3.313 -1.828,0 -3.311,1.483 -3.311,3.313 v 6.209 h -6.211 c -1.828,0 -3.311,1.483 -3.311,3.313 0,1.828 1.482,3.312 3.311,3.312 h 6.211 v 6.21 c 0,1.829 1.482,3.312 3.311,3.312 1.83,0 3.313,-1.482 3.313,-3.312 v -6.21 h 6.209 c 1.83,0 3.313,-1.483 3.313,-3.312 0,-1.829 -1.483,-3.313 -3.313,-3.313 z"
|
||||
id="path123"
|
||||
style="fill:url(#XMLID_59_)"
|
||||
inkscape:connector-curvature="0" />
|
||||
</g>
|
||||
<g
|
||||
id="g125">
|
||||
<g
|
||||
id="g127">
|
||||
|
||||
<image
|
||||
width="67"
|
||||
height="67"
|
||||
xlink:href="data:image/png;base64,iVBORw0KGgoAAAANSUhEUgAAAEMAAABDCAYAAADHyrhzAAAACXBIWXMAAAsSAAALEgHS3X78AAAA BGdBTUEAAK/INwWK6QAAABl0RVh0U29mdHdhcmUAQWRvYmUgSW1hZ2VSZWFkeXHJZTwAAAW0SURB VHja7FsBbtswDBQlpf9/b2NLw4B64Ig7krKTrB1iQHDaoo51PlLHo1zK+3gf6JAf8H3zfwHjGdef P+lmJfEdcnLS85nAyJOuhT7LBTCm87uHgSJPAkGfxflbBAQ6zyRALweDTR79LAScCAw2Cvj5EiDy IDawUYO/e2CgMcjPjDVPB4OxoYJzJX+L2IEmPNSY4HyZJXIBCCFA6NEIKB47jgkgEPTYCTheTnkY GB4QeuLsXA0wiB2W8giAXQGxO6AsAyIXgEAM6F+f7WBgSCJfWBCOsQFwLCgFhM4lMDJAdHXu5ncN hIuXN/TTtKzY1FkPD5Q0O/oCM1BYNAPCTX1GYBz/X5JgTANG+zqzkLOHZodEgPQF5jAwbgqImwGF sSLLTMuOFTAmyEcuIP1keGgg0LDMyGiLEuSQA4zNgOEtzZYd5SozEBjdhMbv8QHAsE/Pqzc8CX+A ETECCTUh5zQYlsoVsMICYcHQNx3dcHFCSD+IkQgNJttDIdYWE6ZmwwcYN7OaiGHFMMvlcKR1CeR9 cYCOCjnJgiGAEY3kCQuGzhX6pq1o2oBuQMthVPtka5qUzmhJVlQnNCwrdHgg0XQHgGxAI0T5S0xO iQq7kB0ZnSGOruhkCS0GCCaSbKLTwO8KfH1YvTKJXD/u6cgzGoRUAvV0BQPEiqrjBvVTv38NC8gA +UFffxCqV3N/nch2pHrpitIX6IgAaWDVsIz4DcInAMSGhAXDglUS99W/rt3MdY6VyC7xf4GS1RmI HWzNH4QVnwaMiBlRMq3Jh8Qq5bmiM9ATaI5XMQ0YCIhPkzMQGLsBA2kdu5rUABTJhEpPWPoCYpSV 4QMkzTs42wRqJzUDdlYlz4vzwND/nJLjEjhaAgqhATwHzZA7WEZtlVkJQI2EkAB21MAyWE6gHjvE cagGAGMnIgvJccuKTSVCq0UqmSiyGsMqOcOMiC3FMWPQZyvBbYmtMz/7/1Wl6kn4Pw8gK7oiR5up v0EmMRyZPIx69dzwsgiGy4z6gNZC1PWaJ7tkUfMom+vSc1kFY+V42VaCCy2PUx6oN0FZaDWymI3a ESutyew85hkwMhTVQgYJpAqSozhFoSS7cg8t4/siet4XiNNVYxXkJEYOk/9eGZABYdkdRxeIepri CCQklopaOpld0J3rICBYJy5i9lxhBmsCIw+zqkl3oi+KqkE8tdkd36QBf3U4WiTVUOpOn4GxYgRh Mo0fMUhBVp3fI/dd+6sVCL6ZEGjzTN8kElHIs6zq6TZg8trqM3K6umlBdANGNSrVa1BnwiVcTSax 1SwgVQFSnYQlxtYbJEw6cOItMwppTm9OIzodJiVQgQz53YBg/UkGxB6ECWpdNuKqjQXXna4u3elP TpCYNPrdmK+DeJNCzF4UJuIYz82wojiGs7YW9zMJNAqTXfU69dmaJxYQL0RYmKDltRIgGBj7ChBR Ai0FbxqpBIiqrlkDl8zzOKvjWOl70n0YZB5FzamZzRkCmCEGDOQoWQGmhVEzDMqoWHFyxEaA2EAS TS2tLdl4vrqvkxVhNeG8FwIEAoNZiyMjy9uC0xVVp4VYgZHfkCnAJjGaD8dd92V20JdJFWst8SSj p+yV+dH+7xJ000eCDahBhZbuMIG2BRPEc44yTtUIKktP02wGjM/F8EgZTZml1SavSL6zBrCXbL1r aWZ4/Ri2nKZ3/GWdrmnW98wEIjBYbiiB4vU0xaWtj4/cFNuAUOrEmPHAmKQKRRtit/LiTbGrS+NK E5iFyXDYMYL64+nbpSPDthZ/E31NdrkyvRfUnHr5Rvqsg80mn233ea9XzKAh9dJXLEqiLSBBbZLd Nx69cPMtXr452+9YfS1r5ZWsf/paVhaUlWbS1Xbl5S7eo17llGSXzfuckfDf/lXOLDCl+C/8nnmp 99u+5Hum0Muq3qcB8CowHvVdr+zmv4/38T7845cAAwA56FTs9t3zlwAAAABJRU5ErkJggg=="
|
||||
transform="translate(423,0)"
|
||||
id="image129"
|
||||
style="opacity:0.75">
|
||||
</image>
|
||||
<g
|
||||
id="g131">
|
||||
<g
|
||||
id="g133">
|
||||
<linearGradient
|
||||
id="XMLID_60_"
|
||||
gradientUnits="userSpaceOnUse"
|
||||
x1="471.42581"
|
||||
y1="30.189899"
|
||||
x2="435.42581"
|
||||
y2="30.189899">
|
||||
<stop
|
||||
offset="0"
|
||||
style="stop-color:#FFFFFF"
|
||||
id="stop136" />
|
||||
<stop
|
||||
offset="1"
|
||||
style="stop-color:#000000"
|
||||
id="stop138" />
|
||||
</linearGradient>
|
||||
<path
|
||||
d="m 453.426,12.19 c -9.941,0 -18,8.059 -18,18 0,9.941 8.059,18 18,18 9.941,0 18,-8.059 18,-18 0,-9.941 -8.059,-18 -18,-18 z m 0,33.837 c -8.746,0 -15.836,-7.091 -15.836,-15.837 0,-8.746 7.09,-15.836 15.836,-15.836 8.746,0 15.836,7.09 15.836,15.836 0,8.746 -7.09,15.837 -15.836,15.837 z"
|
||||
id="path140"
|
||||
style="fill:url(#XMLID_60_)"
|
||||
inkscape:connector-curvature="0" />
|
||||
</g>
|
||||
</g>
|
||||
</g>
|
||||
<g
|
||||
id="g142">
|
||||
|
||||
<image
|
||||
width="63"
|
||||
height="64"
|
||||
xlink:href="data:image/png;base64,iVBORw0KGgoAAAANSUhEUgAAAD8AAABACAYAAACtK6/LAAAACXBIWXMAAAsSAAALEgHS3X78AAAA BGdBTUEAAK/INwWK6QAAABl0RVh0U29mdHdhcmUAQWRvYmUgSW1hZ2VSZWFkeXHJZTwAAAUoSURB VHja7FuLjts4DBRlpf//vRdbKgpsAJad4cNxdtPrGhDsTbK2hi+RQ7m17+PfPOSNnrn+b+Cfvf/6 28DLRc9ZrxaEvPBeAj6XAuD1akHIxfeQ5NleI6DR+WkhyAtA22sJhIBAr+BvJoxPAW+BV4e+h9Wk HRN81sz1KSHIE8Cthju47uA7Ac+1gGZwRsIoC0Au1HYnQ8y11b4HnA3721NuIE8Ct+A2ct2BABB4 C/wwZ30duUR4jBMmjzS9qbMdDLwQX0fA9RD1efu4ti4kGQGMoo8L0fRQYEdCAC0JXo9dCe8w9zgl gPEkcA12mMHAi7PUaXNGwHczl0P9/6z6/LgA+K9xA+CHcQcdI9BSZ7X/MPs9iBvNCECy2h9FX2fA b0oAN6N5FuiQ5vXYPgTQwX2Y2yAroAIYJ7TeFfgH6B8GvDZ5trZLkNdP9awdWA7L/sRJnUtmz0we af1mtN7BZL31WIilTSBAlhV2om2o/ZGszrLAb0DjerKTgGfpryTqAJb1hdofST9ngW4Q4F1J2y5h CyxNLC1+fLcRc0fZXyep7x/aHxdE+gECnARJC5qYvv8COYH+jgE/gKtQzW8O6O6Y+w8Q6IbRmF6y djIOkrOz2OPlBpnKL+XzQkx/I5mcXcqmWqPt0NpHy+hDkEspp4PfTfX7gyyrYsz9N9PP+jwSQAfA tUk+wN4/BtK2fs6mQCEr6E7OoedjTb8U7dkyx4oZcUz9bsauUlYdlbuqEWawEqDy2UujhSU7I8G6 sgeitdfm5Q8B/GfATxPxtSmvhBI8/sBLf5/K7dFEbPDxgtzd1OM6I5vBCjBBItQDpSC/LwW85mi+ Ac3basxG9x0A7eDvXfnwQTJGCQAza15VzTfvRmDtPciw0b4BKzgUcBYAI8uUiK3K1PMeFd0CQsLj 4HS0n+rscXY2dfUEcBmNVWlBreTI0NaMpT0zxz/8vrf3Oc5S0GlN26OfmFg0wWrjotrs8CytJNCR AL2IWVZyAj107a2VgDj+nmh4ZAVR8vlMcWCZk07qgA1EbBvhtwT1jZKqqKApFTasKYgisBWAgKID LVUow+uACbZ0WA9WF1TlUVeoaJ41EG3CsQBw/dsOcnut+RvhCDrRerQsrgyTswjflnlIM6b/0P4w 3+vMjWl+OAJoJJ1mmj/l80zLk/TMLEBGUHZVbnrghyFEbdk8HSaHKWdVAx5rHuo0dVPm3o32vSJl mu83QJFZk49aWqXG5XB8PXrYbsiDTnhzpHXk816jU0jleBA6jAU9l8BcTlA5VLDaVTPBBqNugpgQ k59OecqC3AQVY6T9MnW9HOrZNg9RqdlBDLA+u4IECXGCVTL0dMdmmeafKO3vCdaE0WAT1O8tICAQ O3QH4I+sySPq2qOLM1vOsu1uxAlWaLG7ukbgo0QnBN8csOw62jMniWpsERZ4N6AzwFuladESmpaE q0QZYiMTnCS27EDbd0KKpjmALJmxTN+7Od2Tx8RHq+3KWIml1QridKTPBDzLfswE8GkSoK35m5G8 NJqBP84GuWo9HwmAaayyJwdlkxrYDgQxnV7fZVvRIgHYMnW23Fa0DHi2JW0m/PySrWgsoE0z8W4m ntmEmGV+jwKzm+YAv3r7aRTworL1U7aftiDBqW48ZrmBV0pntpu+bONxxQquYGEjVuZLtpxnk6DK ywbLsYLW3uxlg4wQMjWANP+9mgjol71m8mw9UOnavO0LRtWe2dUdorcCf+X9/7qXCs8+c7Xv4/v4 lOOnAAMAme3iy7JhkzkAAAAASUVORK5CYII="
|
||||
transform="translate(425,1)"
|
||||
id="image144"
|
||||
style="opacity:0.75">
|
||||
</image>
|
||||
<g
|
||||
id="g146">
|
||||
<g
|
||||
id="g148">
|
||||
<linearGradient
|
||||
id="XMLID_61_"
|
||||
gradientUnits="userSpaceOnUse"
|
||||
x1="437.21881"
|
||||
y1="30.189899"
|
||||
x2="469.6348"
|
||||
y2="30.189899">
|
||||
<stop
|
||||
offset="0"
|
||||
style="stop-color:#FFFFFF"
|
||||
id="stop151" />
|
||||
<stop
|
||||
offset="1"
|
||||
style="stop-color:#000000"
|
||||
id="stop153" />
|
||||
</linearGradient>
|
||||
<path
|
||||
d="m 453.426,13.982 c -8.951,0 -16.207,7.257 -16.207,16.208 0,8.95 7.256,16.208 16.207,16.208 8.951,0 16.209,-7.258 16.209,-16.208 0,-8.951 -7.258,-16.208 -16.209,-16.208 z m 0,30.47 c -7.875,0 -14.26,-6.386 -14.26,-14.262 0,-7.876 6.385,-14.262 14.26,-14.262 7.877,0 14.262,6.386 14.262,14.262 0,7.876 -6.385,14.262 -14.262,14.262 z"
|
||||
id="path155"
|
||||
style="fill:url(#XMLID_61_)"
|
||||
inkscape:connector-curvature="0" />
|
||||
</g>
|
||||
</g>
|
||||
</g>
|
||||
</g>
|
||||
</g>
|
||||
<g
|
||||
id="g157">
|
||||
<g
|
||||
id="g159">
|
||||
|
||||
<image
|
||||
width="64"
|
||||
height="64"
|
||||
xlink:href="data:image/png;base64,iVBORw0KGgoAAAANSUhEUgAAAEAAAABACAYAAACqaXHeAAAACXBIWXMAAAsSAAALEgHS3X78AAAA BGdBTUEAAK/INwWK6QAAABl0RVh0U29mdHdhcmUAQWRvYmUgSW1hZ2VSZWFkeXHJZTwAAAYeSURB VHja7FuLjts2ECQlSn4k6f9/Z5OzrSdbA2KxmMwuSdlO7poTQEhnnyzPcHa5D9q5z+PPPvw7fl78 PxDwzM+PH4UAX/l3Cdj4KjL8i4Cza7+DgEgAx2cS4V8E3Bdc470ILMJ1KSm/lACvAC8ZGgGxcjxE gn/SrONoyLkxiGDAV3Fe4bV07RR1FB/hSbOOQHG0QEIDBEgAKxkLeY2Zga8lIjwAHmdcgtVGel+S 4BTwS2Z4UAYSEZ9NAAPPgAcyWnFGNSABEuSsjEb8zwr3+xoSwoPgE5gErtuuOzIkIegTIhCQgE7K SO/77f/ddm8DJDxFARZ4OeMJaK8MSYRUgRMA5MzfgY5iDNu53d5jK8oiSHAlRNQoQAOfgB02oPfz cTvLIUlohS/wYP8I/g78tt1/2545iO+SjhnMoMgfhMrljoHvBcg78NM2juKMJEhf4Ij8pw1kAn+/ 9wo+BRWEx1pCQtjp9BB8AnoW4yTOR0FAL0CgAhYx+4mA6zZ6YUKNEsPIOMKXBEmhUPoNgA9C9kcB 9gsMSUZSAfqBdCyCgGmb+ZsgD++zgqgoVBAtfxAqIj0pf5z9O8ivYnwDEk4GEGco4E7AJTP7LHiS KjCDo1Dh+BqwfTn7XwTwv7bzV0FCIqAHAjQTkApg4PEeFj02xP5/UkGoiPOZ4zsK6SMBiYQzIaA1 CJg3BRwM6UcSMc4QRK3EH1SZgDfk34H8JQGoAukDegiGPIkD0ipwAIcpzQXjBRYtrmJJ3LUKOMMB ogLOYP/fhB84g/13xJFFADbB/6GvmJVgadxeCyQocswMQoX8W2X5OwEJuBIw+28UBSQVhAx4XCrT YObiLWcYdjpADH7OyjgR+SMwzAVWkjBp4G8iUOqVUNtbdY+wYwkMIqBJBBwh+juJ17Uv55UgZiEz huBv5PPxGUwFcc8yyBSAKjiQHACToM5IhZ2xdiezOMDqcDDA52b/PzJyJuAKkqAevkivpMAtOFRX kLRIAjojw+zgOa1RglN9gC8MhVkK3GW+EJbIWHU4fTHp9Fql0NIVgm9ydc9QEANoRZCWVHoCKYE1 hkfOZZ5amS0o5TZGcLUTtFTAzIFdNwZ4TXExU2ZnBdbcs7JV72ZHm6u29u8ywGsLsCW9huJyf+P+ 8CNHQDQKDnu7NqU1+z2dIkee/XBRNCpdGZl14bWWn+eaF9HoC5Y2TLRJKFaAxfBKQM+ZlLT0i0UD MOsVLAXPyioiKF6Yzf6aqduPSu0+rRArEB+VslYOOHs2koK9xGoTYAyyuv0ENfsRiOiM2N8rLfGV gJ6M1JeRoKmuKheIpPLCgA9Qwj5Caop5f0vWfGZmk6gOjaRPMADxk6KCaDn3oLzpM7MykpT0uoG/ FhQwG6UgEmHmB/KMq/j7ZpDAVFBtApoCRvhyF6WGh1mdVRBhdcFBAL8IAi5AxLBDBZSAaMwKI+AK LbFcyXs2/MIK5a4RwL+JcRFDI+BhH8Bq7jOZnYvS82PgWVHUE/nLwkcC/+Pf8X07/9hekyYxgjNc lVUglpqA5gMm0aAMRr8OKzlaXdARApJNJ4BvG/jvgoQ3QYJmArHWBHJmMBu7QFjTAk2mN1pj2BgZ gICkgL+FCqQvGAQB66NOEFWwiv57AsXS0FwN71BIAJrYRYBORLyBD0jEWQ4w1qwC2lLYiA0KjVHD QyAH0huwOkOD4gRR/tIJSvuPe02AqUDuuJiVHDwaBFwr2uPSB9yECq6wAjAHyHICt7c5ioVKaQqz siFBA3Eg5XFW91+M2v9VCYRGJRQuyghLFIDyzoXNKGNri0yj9AYx2pThL4bBJdHfbhNg8lkNAhZC gLZJqjVaY1rfbxQOz4r8Vle4e7S0IOINEnIhs7VNrlEIWJy9TU4Cn2vtfq8CNBKi0a+fXH6jpM98 BhsS+LKnElRLgEWClThpW2VZc0RKd1EKIlrZDTdPF9cea/cKs5XBKxnk4so3S7PaIwO6OH33+K6t 8+95u7y2VX7NVIR3A3mEiN/1gwn3CPhnEKB1fV7xkxlnzPZv+8lMjghNJTVNEefe+Y+mSvqJtc/8 kD+be/Xnf5gfTj7redF9Hp/Hy49/BBgApEegBA3kNcsAAAAASUVORK5CYII="
|
||||
transform="translate(1,421)"
|
||||
id="image161"
|
||||
style="opacity:0.75">
|
||||
</image>
|
||||
<radialGradient
|
||||
id="XMLID_62_"
|
||||
cx="30.4263"
|
||||
cy="450.18951"
|
||||
r="16.5"
|
||||
gradientUnits="userSpaceOnUse">
|
||||
<stop
|
||||
offset="0.5899"
|
||||
style="stop-color:#231F20"
|
||||
id="stop164" />
|
||||
<stop
|
||||
offset="0.6789"
|
||||
style="stop-color:#403D3E"
|
||||
id="stop166" />
|
||||
<stop
|
||||
offset="0.8716"
|
||||
style="stop-color:#88888A"
|
||||
id="stop168" />
|
||||
<stop
|
||||
offset="1"
|
||||
style="stop-color:#BCBEC0"
|
||||
id="stop170" />
|
||||
</radialGradient>
|
||||
<circle
|
||||
cx="30.426001"
|
||||
cy="450.189"
|
||||
r="16.5"
|
||||
id="circle172"
|
||||
d="m 46.926001,450.189 c 0,9.11269 -7.387302,16.5 -16.5,16.5 -9.112699,0 -16.5,-7.38731 -16.5,-16.5 0,-9.1127 7.387301,-16.5 16.5,-16.5 9.112698,0 16.5,7.3873 16.5,16.5 z"
|
||||
style="fill:url(#XMLID_62_)"
|
||||
sodipodi:cx="30.426001"
|
||||
sodipodi:cy="450.189"
|
||||
sodipodi:rx="16.5"
|
||||
sodipodi:ry="16.5" />
|
||||
</g>
|
||||
<g
|
||||
id="g174">
|
||||
|
||||
<image
|
||||
width="57"
|
||||
height="56"
|
||||
xlink:href="data:image/png;base64,iVBORw0KGgoAAAANSUhEUgAAADkAAAA4CAYAAABHRFAgAAAACXBIWXMAAAsSAAALEgHS3X78AAAA BGdBTUEAAK/INwWK6QAAABl0RVh0U29mdHdhcmUAQWRvYmUgSW1hZ2VSZWFkeXHJZTwAAAQPSURB VHja7JoNb+MgDIaB0OzW7f//0tvWjwRulUCy3rONSei03TWSRZWuSZ69xjYmzj2Ox/FjDv9N7pF/ IqQ3nM9fBezveD1vuE9W4PJ3hPTGkQNpjbuOeAf1PIB5AZSCZEFJPwI03kG9mwUARFiEu1liYIeA xsGAgYzUNMhUzBPQNBJ0lJIc3ARjIL9BwBVGNxI0DpyHFG4q156IUUUR8GZL+W4l1x4CGne6KQdX AQ9lrEbVzARwKRYIqBsJGgcBBgJXAecyUliqJAW8ftpFSWkJALtA4wD3DABXAZ/KOBPQQAJMhbyA O2vFQN6iaNwRRTnACvWrQNaxwlN3rQoemDnrFEXRdZtFQ+wExCiKgE/FngtgHWcCUx+2qngWlLSA mlSNG9MEBpiZKHezYwE8EjVnBvLMKGn5Z2dmnm5Skt7QCvhc7KUAHkFNCnkFhYNQ41IXXkHNRABF 2GiMolbACvYKoBLkWZmTXgCmbhoIsKhqS0kOUgN8KfZKPiNkTfhVyWiYj1JhnyzBJxrSRehQsQK+ gpo9kK21Zy0JJyF3/qVmbKjIgVJIdFOEfGXmJIU8kHNOWaFkKN4Tcdfd0dUrkE/CfDyCy2qBJ5KA 48AN0VawROak19y2Z06iu2qB50gi7VFIIRGKg8zALFD61c9T+d5bcmtstENwESzNS5oj0ep3WAwE WJGsBKbWstQO5fwkrFO9lE6iIZp5ZkE8MQX5AUq7GWrXA9SuDgr1K1znAAX+ZFiI7yoGJNggLLUm 5qECUdIp32u/90IkVkHD/9BBjx1dbSmUS9FvZf7GwVLLEkETpI3U27qMCqBX4FZm0csFDKxLMYXg 318FWxhoqZXZhMxKRy0D3JUslW7B5cR0AyhgEmrXk2DnYhcFNguwucddqa1CmD9DiwMDhyPqc5Af n/bO2AeBpaDUlU1KTo0iwClNYq6JHJjoR71hIevIEwF8+7Tfxd6IISwqulpcdzLmSNfohktLoywk ewskAiJkvWZTzclQoG/dIMoMZHVxDvCtAXlpAOYttWtmiubVCOcYuLkxJyU3PQGg2U2tKQQf2HVA YttxVqLrOwGt0JagkwQ1u5T0UFCnTsikQGIA+lDm4cK4aXL6Jm5Xty6TKgV7Kj2QWkvyBO6JgWYV 8qNzG4oBzW099FRceVALpNZcvgCYFdCkYq+SWWjwLo20cTVsE1yIqpcOwGHbBE5YjEqgWCUtHRs+ UrJPzDQZvuEjqUpB1wZka+sODRXcBLh1f1IDzQKkdRN2HeWieyG1pRjCrm7bdvowwD2QXHrxjJrY MtRejEhCkt/9Ts/el5Xu9YrLMMARkNKqZevLSnhuN+AoSE3VVkftS147e7xAeIfr/hOvgm69R3aP 43E8jtvxR4ABAL1S3PlRWBIpAAAAAElFTkSuQmCC"
|
||||
transform="translate(5,425)"
|
||||
id="image176"
|
||||
style="opacity:0.75">
|
||||
</image>
|
||||
<radialGradient
|
||||
id="XMLID_63_"
|
||||
cx="30.4268"
|
||||
cy="450.1904"
|
||||
r="12.8333"
|
||||
gradientUnits="userSpaceOnUse">
|
||||
<stop
|
||||
offset="0"
|
||||
style="stop-color:#FFFFFF"
|
||||
id="stop179" />
|
||||
<stop
|
||||
offset="1"
|
||||
style="stop-color:#393939"
|
||||
id="stop181" />
|
||||
</radialGradient>
|
||||
<path
|
||||
d="m 39.948,446.879 h -6.209 v -6.209 c 0,-1.83 -1.483,-3.313 -3.313,-3.313 -1.828,0 -3.312,1.482 -3.312,3.313 v 6.209 h -6.21 c -1.829,0 -3.312,1.482 -3.312,3.313 0,1.828 1.482,3.311 3.312,3.311 h 6.21 v 6.211 c 0,1.828 1.483,3.311 3.312,3.311 1.829,0 3.313,-1.482 3.313,-3.311 v -6.211 h 6.209 c 1.829,0 3.313,-1.482 3.313,-3.311 -0.001,-1.831 -1.484,-3.313 -3.313,-3.313 z"
|
||||
id="path183"
|
||||
style="fill:url(#XMLID_63_)"
|
||||
inkscape:connector-curvature="0" />
|
||||
</g>
|
||||
<g
|
||||
id="g185">
|
||||
<g
|
||||
id="g187">
|
||||
|
||||
<image
|
||||
width="67"
|
||||
height="67"
|
||||
xlink:href="data:image/png;base64,iVBORw0KGgoAAAANSUhEUgAAAEMAAABDCAYAAADHyrhzAAAACXBIWXMAAAsSAAALEgHS3X78AAAA BGdBTUEAAK/INwWK6QAAABl0RVh0U29mdHdhcmUAQWRvYmUgSW1hZ2VSZWFkeXHJZTwAAAW0SURB VHja7FsBbtswDBQlpf9/b2NLw4B64Ig7krKTrB1iQHDaoo51PlLHo1zK+3gf6JAf8H3zfwHjGdef P+lmJfEdcnLS85nAyJOuhT7LBTCm87uHgSJPAkGfxflbBAQ6zyRALweDTR79LAScCAw2Cvj5EiDy IDawUYO/e2CgMcjPjDVPB4OxoYJzJX+L2IEmPNSY4HyZJXIBCCFA6NEIKB47jgkgEPTYCTheTnkY GB4QeuLsXA0wiB2W8giAXQGxO6AsAyIXgEAM6F+f7WBgSCJfWBCOsQFwLCgFhM4lMDJAdHXu5ncN hIuXN/TTtKzY1FkPD5Q0O/oCM1BYNAPCTX1GYBz/X5JgTANG+zqzkLOHZodEgPQF5jAwbgqImwGF sSLLTMuOFTAmyEcuIP1keGgg0LDMyGiLEuSQA4zNgOEtzZYd5SozEBjdhMbv8QHAsE/Pqzc8CX+A ETECCTUh5zQYlsoVsMICYcHQNx3dcHFCSD+IkQgNJttDIdYWE6ZmwwcYN7OaiGHFMMvlcKR1CeR9 cYCOCjnJgiGAEY3kCQuGzhX6pq1o2oBuQMthVPtka5qUzmhJVlQnNCwrdHgg0XQHgGxAI0T5S0xO iQq7kB0ZnSGOruhkCS0GCCaSbKLTwO8KfH1YvTKJXD/u6cgzGoRUAvV0BQPEiqrjBvVTv38NC8gA +UFffxCqV3N/nch2pHrpitIX6IgAaWDVsIz4DcInAMSGhAXDglUS99W/rt3MdY6VyC7xf4GS1RmI HWzNH4QVnwaMiBlRMq3Jh8Qq5bmiM9ATaI5XMQ0YCIhPkzMQGLsBA2kdu5rUABTJhEpPWPoCYpSV 4QMkzTs42wRqJzUDdlYlz4vzwND/nJLjEjhaAgqhATwHzZA7WEZtlVkJQI2EkAB21MAyWE6gHjvE cagGAGMnIgvJccuKTSVCq0UqmSiyGsMqOcOMiC3FMWPQZyvBbYmtMz/7/1Wl6kn4Pw8gK7oiR5up v0EmMRyZPIx69dzwsgiGy4z6gNZC1PWaJ7tkUfMom+vSc1kFY+V42VaCCy2PUx6oN0FZaDWymI3a ESutyew85hkwMhTVQgYJpAqSozhFoSS7cg8t4/siet4XiNNVYxXkJEYOk/9eGZABYdkdRxeIepri CCQklopaOpld0J3rICBYJy5i9lxhBmsCIw+zqkl3oi+KqkE8tdkd36QBf3U4WiTVUOpOn4GxYgRh Mo0fMUhBVp3fI/dd+6sVCL6ZEGjzTN8kElHIs6zq6TZg8trqM3K6umlBdANGNSrVa1BnwiVcTSax 1SwgVQFSnYQlxtYbJEw6cOItMwppTm9OIzodJiVQgQz53YBg/UkGxB6ECWpdNuKqjQXXna4u3elP TpCYNPrdmK+DeJNCzF4UJuIYz82wojiGs7YW9zMJNAqTXfU69dmaJxYQL0RYmKDltRIgGBj7ChBR Ai0FbxqpBIiqrlkDl8zzOKvjWOl70n0YZB5FzamZzRkCmCEGDOQoWQGmhVEzDMqoWHFyxEaA2EAS TS2tLdl4vrqvkxVhNeG8FwIEAoNZiyMjy9uC0xVVp4VYgZHfkCnAJjGaD8dd92V20JdJFWst8SSj p+yV+dH+7xJ000eCDahBhZbuMIG2BRPEc44yTtUIKktP02wGjM/F8EgZTZml1SavSL6zBrCXbL1r aWZ4/Ri2nKZ3/GWdrmnW98wEIjBYbiiB4vU0xaWtj4/cFNuAUOrEmPHAmKQKRRtit/LiTbGrS+NK E5iFyXDYMYL64+nbpSPDthZ/E31NdrkyvRfUnHr5Rvqsg80mn233ea9XzKAh9dJXLEqiLSBBbZLd Nx69cPMtXr452+9YfS1r5ZWsf/paVhaUlWbS1Xbl5S7eo17llGSXzfuckfDf/lXOLDCl+C/8nnmp 99u+5Hum0Muq3qcB8CowHvVdr+zmv4/38T7845cAAwA56FTs9t3zlwAAAABJRU5ErkJggg=="
|
||||
transform="translate(0,420)"
|
||||
id="image189"
|
||||
style="opacity:0.75">
|
||||
</image>
|
||||
<g
|
||||
id="g191">
|
||||
<g
|
||||
id="g193">
|
||||
<linearGradient
|
||||
id="XMLID_64_"
|
||||
gradientUnits="userSpaceOnUse"
|
||||
x1="48.4263"
|
||||
y1="450.18951"
|
||||
x2="12.4263"
|
||||
y2="450.18951">
|
||||
<stop
|
||||
offset="0"
|
||||
style="stop-color:#FFFFFF"
|
||||
id="stop196" />
|
||||
<stop
|
||||
offset="1"
|
||||
style="stop-color:#000000"
|
||||
id="stop198" />
|
||||
</linearGradient>
|
||||
<path
|
||||
d="m 30.426,432.189 c -9.941,0 -18,8.059 -18,18 0,9.941 8.059,18 18,18 9.941,0 18,-8.059 18,-18 0,-9.941 -8.058,-18 -18,-18 z m 0,33.838 c -8.746,0 -15.837,-7.092 -15.837,-15.838 0,-8.746 7.091,-15.836 15.837,-15.836 8.746,0 15.836,7.09 15.836,15.836 0,8.746 -7.09,15.838 -15.836,15.838 z"
|
||||
id="path200"
|
||||
style="fill:url(#XMLID_64_)"
|
||||
inkscape:connector-curvature="0" />
|
||||
</g>
|
||||
</g>
|
||||
</g>
|
||||
<g
|
||||
id="g202">
|
||||
|
||||
<image
|
||||
width="63"
|
||||
height="64"
|
||||
xlink:href="data:image/png;base64,iVBORw0KGgoAAAANSUhEUgAAAD8AAABACAYAAACtK6/LAAAACXBIWXMAAAsSAAALEgHS3X78AAAA BGdBTUEAAK/INwWK6QAAABl0RVh0U29mdHdhcmUAQWRvYmUgSW1hZ2VSZWFkeXHJZTwAAAUoSURB VHja7FuLjts4DBRlpf//vRdbKgpsAJad4cNxdtPrGhDsTbK2hi+RQ7m17+PfPOSNnrn+b+Cfvf/6 28DLRc9ZrxaEvPBeAj6XAuD1akHIxfeQ5NleI6DR+WkhyAtA22sJhIBAr+BvJoxPAW+BV4e+h9Wk HRN81sz1KSHIE8Cthju47uA7Ac+1gGZwRsIoC0Au1HYnQ8y11b4HnA3721NuIE8Ct+A2ct2BABB4 C/wwZ30duUR4jBMmjzS9qbMdDLwQX0fA9RD1efu4ti4kGQGMoo8L0fRQYEdCAC0JXo9dCe8w9zgl gPEkcA12mMHAi7PUaXNGwHczl0P9/6z6/LgA+K9xA+CHcQcdI9BSZ7X/MPs9iBvNCECy2h9FX2fA b0oAN6N5FuiQ5vXYPgTQwX2Y2yAroAIYJ7TeFfgH6B8GvDZ5trZLkNdP9awdWA7L/sRJnUtmz0we af1mtN7BZL31WIilTSBAlhV2om2o/ZGszrLAb0DjerKTgGfpryTqAJb1hdofST9ngW4Q4F1J2y5h CyxNLC1+fLcRc0fZXyep7x/aHxdE+gECnARJC5qYvv8COYH+jgE/gKtQzW8O6O6Y+w8Q6IbRmF6y djIOkrOz2OPlBpnKL+XzQkx/I5mcXcqmWqPt0NpHy+hDkEspp4PfTfX7gyyrYsz9N9PP+jwSQAfA tUk+wN4/BtK2fs6mQCEr6E7OoedjTb8U7dkyx4oZcUz9bsauUlYdlbuqEWawEqDy2UujhSU7I8G6 sgeitdfm5Q8B/GfATxPxtSmvhBI8/sBLf5/K7dFEbPDxgtzd1OM6I5vBCjBBItQDpSC/LwW85mi+ Ac3basxG9x0A7eDvXfnwQTJGCQAza15VzTfvRmDtPciw0b4BKzgUcBYAI8uUiK3K1PMeFd0CQsLj 4HS0n+rscXY2dfUEcBmNVWlBreTI0NaMpT0zxz/8vrf3Oc5S0GlN26OfmFg0wWrjotrs8CytJNCR AL2IWVZyAj107a2VgDj+nmh4ZAVR8vlMcWCZk07qgA1EbBvhtwT1jZKqqKApFTasKYgisBWAgKID LVUow+uACbZ0WA9WF1TlUVeoaJ41EG3CsQBw/dsOcnut+RvhCDrRerQsrgyTswjflnlIM6b/0P4w 3+vMjWl+OAJoJJ1mmj/l80zLk/TMLEBGUHZVbnrghyFEbdk8HSaHKWdVAx5rHuo0dVPm3o32vSJl mu83QJFZk49aWqXG5XB8PXrYbsiDTnhzpHXk816jU0jleBA6jAU9l8BcTlA5VLDaVTPBBqNugpgQ k59OecqC3AQVY6T9MnW9HOrZNg9RqdlBDLA+u4IECXGCVTL0dMdmmeafKO3vCdaE0WAT1O8tICAQ O3QH4I+sySPq2qOLM1vOsu1uxAlWaLG7ukbgo0QnBN8csOw62jMniWpsERZ4N6AzwFuladESmpaE q0QZYiMTnCS27EDbd0KKpjmALJmxTN+7Od2Tx8RHq+3KWIml1QridKTPBDzLfswE8GkSoK35m5G8 NJqBP84GuWo9HwmAaayyJwdlkxrYDgQxnV7fZVvRIgHYMnW23Fa0DHi2JW0m/PySrWgsoE0z8W4m ntmEmGV+jwKzm+YAv3r7aRTworL1U7aftiDBqW48ZrmBV0pntpu+bONxxQquYGEjVuZLtpxnk6DK ywbLsYLW3uxlg4wQMjWANP+9mgjol71m8mw9UOnavO0LRtWe2dUdorcCf+X9/7qXCs8+c7Xv4/v4 lOOnAAMAme3iy7JhkzkAAAAASUVORK5CYII="
|
||||
transform="translate(2,421)"
|
||||
id="image204"
|
||||
style="opacity:0.75">
|
||||
</image>
|
||||
<g
|
||||
id="g206">
|
||||
<g
|
||||
id="g208">
|
||||
<linearGradient
|
||||
id="XMLID_65_"
|
||||
gradientUnits="userSpaceOnUse"
|
||||
x1="14.2183"
|
||||
y1="450.1904"
|
||||
x2="46.6353"
|
||||
y2="450.1904">
|
||||
<stop
|
||||
offset="0"
|
||||
style="stop-color:#FFFFFF"
|
||||
id="stop211" />
|
||||
<stop
|
||||
offset="1"
|
||||
style="stop-color:#000000"
|
||||
id="stop213" />
|
||||
</linearGradient>
|
||||
<path
|
||||
d="m 30.426,433.982 c -8.951,0 -16.208,7.256 -16.208,16.207 0,8.951 7.257,16.209 16.208,16.209 8.951,0 16.209,-7.258 16.209,-16.209 0,-8.951 -7.258,-16.207 -16.209,-16.207 z m 0,30.469 c -7.876,0 -14.261,-6.385 -14.261,-14.262 0,-7.875 6.385,-14.262 14.261,-14.262 7.877,0 14.262,6.387 14.262,14.262 0,7.877 -6.385,14.262 -14.262,14.262 z"
|
||||
id="path215"
|
||||
style="fill:url(#XMLID_65_)"
|
||||
inkscape:connector-curvature="0" />
|
||||
</g>
|
||||
</g>
|
||||
</g>
|
||||
</g>
|
||||
</g>
|
||||
<g
|
||||
id="g217">
|
||||
<g
|
||||
id="g219">
|
||||
|
||||
<image
|
||||
width="64"
|
||||
height="64"
|
||||
xlink:href="data:image/png;base64,iVBORw0KGgoAAAANSUhEUgAAAEAAAABACAYAAACqaXHeAAAACXBIWXMAAAsSAAALEgHS3X78AAAA BGdBTUEAAK/INwWK6QAAABl0RVh0U29mdHdhcmUAQWRvYmUgSW1hZ2VSZWFkeXHJZTwAAAYeSURB VHja7FuLjts2ECQlSn4k6f9/Z5OzrSdbA2KxmMwuSdlO7poTQEhnnyzPcHa5D9q5z+PPPvw7fl78 PxDwzM+PH4UAX/l3Cdj4KjL8i4Cza7+DgEgAx2cS4V8E3Bdc470ILMJ1KSm/lACvAC8ZGgGxcjxE gn/SrONoyLkxiGDAV3Fe4bV07RR1FB/hSbOOQHG0QEIDBEgAKxkLeY2Zga8lIjwAHmdcgtVGel+S 4BTwS2Z4UAYSEZ9NAAPPgAcyWnFGNSABEuSsjEb8zwr3+xoSwoPgE5gErtuuOzIkIegTIhCQgE7K SO/77f/ddm8DJDxFARZ4OeMJaK8MSYRUgRMA5MzfgY5iDNu53d5jK8oiSHAlRNQoQAOfgB02oPfz cTvLIUlohS/wYP8I/g78tt1/2545iO+SjhnMoMgfhMrljoHvBcg78NM2juKMJEhf4Ij8pw1kAn+/ 9wo+BRWEx1pCQtjp9BB8AnoW4yTOR0FAL0CgAhYx+4mA6zZ6YUKNEsPIOMKXBEmhUPoNgA9C9kcB 9gsMSUZSAfqBdCyCgGmb+ZsgD++zgqgoVBAtfxAqIj0pf5z9O8ivYnwDEk4GEGco4E7AJTP7LHiS KjCDo1Dh+BqwfTn7XwTwv7bzV0FCIqAHAjQTkApg4PEeFj02xP5/UkGoiPOZ4zsK6SMBiYQzIaA1 CJg3BRwM6UcSMc4QRK3EH1SZgDfk34H8JQGoAukDegiGPIkD0ipwAIcpzQXjBRYtrmJJ3LUKOMMB ogLOYP/fhB84g/13xJFFADbB/6GvmJVgadxeCyQocswMQoX8W2X5OwEJuBIw+28UBSQVhAx4XCrT YObiLWcYdjpADH7OyjgR+SMwzAVWkjBp4G8iUOqVUNtbdY+wYwkMIqBJBBwh+juJ17Uv55UgZiEz huBv5PPxGUwFcc8yyBSAKjiQHACToM5IhZ2xdiezOMDqcDDA52b/PzJyJuAKkqAevkivpMAtOFRX kLRIAjojw+zgOa1RglN9gC8MhVkK3GW+EJbIWHU4fTHp9Fql0NIVgm9ydc9QEANoRZCWVHoCKYE1 hkfOZZ5amS0o5TZGcLUTtFTAzIFdNwZ4TXExU2ZnBdbcs7JV72ZHm6u29u8ywGsLsCW9huJyf+P+ 8CNHQDQKDnu7NqU1+z2dIkee/XBRNCpdGZl14bWWn+eaF9HoC5Y2TLRJKFaAxfBKQM+ZlLT0i0UD MOsVLAXPyioiKF6Yzf6aqduPSu0+rRArEB+VslYOOHs2koK9xGoTYAyyuv0ENfsRiOiM2N8rLfGV gJ6M1JeRoKmuKheIpPLCgA9Qwj5Caop5f0vWfGZmk6gOjaRPMADxk6KCaDn3oLzpM7MykpT0uoG/ FhQwG6UgEmHmB/KMq/j7ZpDAVFBtApoCRvhyF6WGh1mdVRBhdcFBAL8IAi5AxLBDBZSAaMwKI+AK LbFcyXs2/MIK5a4RwL+JcRFDI+BhH8Bq7jOZnYvS82PgWVHUE/nLwkcC/+Pf8X07/9hekyYxgjNc lVUglpqA5gMm0aAMRr8OKzlaXdARApJNJ4BvG/jvgoQ3QYJmArHWBHJmMBu7QFjTAk2mN1pj2BgZ gICkgL+FCqQvGAQB66NOEFWwiv57AsXS0FwN71BIAJrYRYBORLyBD0jEWQ4w1qwC2lLYiA0KjVHD QyAH0huwOkOD4gRR/tIJSvuPe02AqUDuuJiVHDwaBFwr2uPSB9yECq6wAjAHyHICt7c5ioVKaQqz siFBA3Eg5XFW91+M2v9VCYRGJRQuyghLFIDyzoXNKGNri0yj9AYx2pThL4bBJdHfbhNg8lkNAhZC gLZJqjVaY1rfbxQOz4r8Vle4e7S0IOINEnIhs7VNrlEIWJy9TU4Cn2vtfq8CNBKi0a+fXH6jpM98 BhsS+LKnElRLgEWClThpW2VZc0RKd1EKIlrZDTdPF9cea/cKs5XBKxnk4so3S7PaIwO6OH33+K6t 8+95u7y2VX7NVIR3A3mEiN/1gwn3CPhnEKB1fV7xkxlnzPZv+8lMjghNJTVNEefe+Y+mSvqJtc/8 kD+be/Xnf5gfTj7redF9Hp/Hy49/BBgApEegBA3kNcsAAAAASUVORK5CYII="
|
||||
transform="translate(424,421)"
|
||||
id="image221"
|
||||
style="opacity:0.75">
|
||||
</image>
|
||||
<radialGradient
|
||||
id="XMLID_66_"
|
||||
cx="453.42581"
|
||||
cy="450.18951"
|
||||
r="16.5"
|
||||
gradientUnits="userSpaceOnUse">
|
||||
<stop
|
||||
offset="0.5899"
|
||||
style="stop-color:#231F20"
|
||||
id="stop224" />
|
||||
<stop
|
||||
offset="0.6789"
|
||||
style="stop-color:#403D3E"
|
||||
id="stop226" />
|
||||
<stop
|
||||
offset="0.8716"
|
||||
style="stop-color:#88888A"
|
||||
id="stop228" />
|
||||
<stop
|
||||
offset="1"
|
||||
style="stop-color:#BCBEC0"
|
||||
id="stop230" />
|
||||
</radialGradient>
|
||||
<circle
|
||||
cx="453.42599"
|
||||
cy="450.189"
|
||||
r="16.5"
|
||||
id="circle232"
|
||||
d="m 469.92599,450.189 c 0,9.11269 -7.3873,16.5 -16.5,16.5 -9.11269,0 -16.5,-7.38731 -16.5,-16.5 0,-9.1127 7.38731,-16.5 16.5,-16.5 9.1127,0 16.5,7.3873 16.5,16.5 z"
|
||||
style="fill:url(#XMLID_66_)"
|
||||
sodipodi:cx="453.42599"
|
||||
sodipodi:cy="450.189"
|
||||
sodipodi:rx="16.5"
|
||||
sodipodi:ry="16.5" />
|
||||
</g>
|
||||
<g
|
||||
id="g234">
|
||||
|
||||
<image
|
||||
width="57"
|
||||
height="56"
|
||||
xlink:href="data:image/png;base64,iVBORw0KGgoAAAANSUhEUgAAADkAAAA4CAYAAABHRFAgAAAACXBIWXMAAAsSAAALEgHS3X78AAAA BGdBTUEAAK/INwWK6QAAABl0RVh0U29mdHdhcmUAQWRvYmUgSW1hZ2VSZWFkeXHJZTwAAAQPSURB VHja7JoNb+MgDIaB0OzW7f//0tvWjwRulUCy3rONSei03TWSRZWuSZ69xjYmzj2Ox/FjDv9N7pF/ IqQ3nM9fBezveD1vuE9W4PJ3hPTGkQNpjbuOeAf1PIB5AZSCZEFJPwI03kG9mwUARFiEu1liYIeA xsGAgYzUNMhUzBPQNBJ0lJIc3ARjIL9BwBVGNxI0DpyHFG4q156IUUUR8GZL+W4l1x4CGne6KQdX AQ9lrEbVzARwKRYIqBsJGgcBBgJXAecyUliqJAW8ftpFSWkJALtA4wD3DABXAZ/KOBPQQAJMhbyA O2vFQN6iaNwRRTnACvWrQNaxwlN3rQoemDnrFEXRdZtFQ+wExCiKgE/FngtgHWcCUx+2qngWlLSA mlSNG9MEBpiZKHezYwE8EjVnBvLMKGn5Z2dmnm5Skt7QCvhc7KUAHkFNCnkFhYNQ41IXXkHNRABF 2GiMolbACvYKoBLkWZmTXgCmbhoIsKhqS0kOUgN8KfZKPiNkTfhVyWiYj1JhnyzBJxrSRehQsQK+ gpo9kK21Zy0JJyF3/qVmbKjIgVJIdFOEfGXmJIU8kHNOWaFkKN4Tcdfd0dUrkE/CfDyCy2qBJ5KA 48AN0VawROak19y2Z06iu2qB50gi7VFIIRGKg8zALFD61c9T+d5bcmtstENwESzNS5oj0ep3WAwE WJGsBKbWstQO5fwkrFO9lE6iIZp5ZkE8MQX5AUq7GWrXA9SuDgr1K1znAAX+ZFiI7yoGJNggLLUm 5qECUdIp32u/90IkVkHD/9BBjx1dbSmUS9FvZf7GwVLLEkETpI3U27qMCqBX4FZm0csFDKxLMYXg 318FWxhoqZXZhMxKRy0D3JUslW7B5cR0AyhgEmrXk2DnYhcFNguwucddqa1CmD9DiwMDhyPqc5Af n/bO2AeBpaDUlU1KTo0iwClNYq6JHJjoR71hIevIEwF8+7Tfxd6IISwqulpcdzLmSNfohktLoywk ewskAiJkvWZTzclQoG/dIMoMZHVxDvCtAXlpAOYttWtmiubVCOcYuLkxJyU3PQGg2U2tKQQf2HVA YttxVqLrOwGt0JagkwQ1u5T0UFCnTsikQGIA+lDm4cK4aXL6Jm5Xty6TKgV7Kj2QWkvyBO6JgWYV 8qNzG4oBzW099FRceVALpNZcvgCYFdCkYq+SWWjwLo20cTVsE1yIqpcOwGHbBE5YjEqgWCUtHRs+ UrJPzDQZvuEjqUpB1wZka+sODRXcBLh1f1IDzQKkdRN2HeWieyG1pRjCrm7bdvowwD2QXHrxjJrY MtRejEhCkt/9Ts/el5Xu9YrLMMARkNKqZevLSnhuN+AoSE3VVkftS147e7xAeIfr/hOvgm69R3aP 43E8jtvxR4ABAL1S3PlRWBIpAAAAAElFTkSuQmCC"
|
||||
transform="translate(428,425)"
|
||||
id="image236"
|
||||
style="opacity:0.75">
|
||||
</image>
|
||||
<radialGradient
|
||||
id="XMLID_67_"
|
||||
cx="453.42679"
|
||||
cy="450.1904"
|
||||
r="12.833"
|
||||
gradientUnits="userSpaceOnUse">
|
||||
<stop
|
||||
offset="0"
|
||||
style="stop-color:#FFFFFF"
|
||||
id="stop239" />
|
||||
<stop
|
||||
offset="1"
|
||||
style="stop-color:#393939"
|
||||
id="stop241" />
|
||||
</radialGradient>
|
||||
<path
|
||||
d="m 462.947,446.879 h -6.209 v -6.209 c 0,-1.83 -1.482,-3.313 -3.313,-3.313 -1.828,0 -3.311,1.482 -3.311,3.313 v 6.209 h -6.211 c -1.828,0 -3.311,1.482 -3.311,3.313 0,1.828 1.482,3.311 3.311,3.311 h 6.211 v 6.211 c 0,1.828 1.482,3.311 3.311,3.311 1.83,0 3.313,-1.482 3.313,-3.311 v -6.211 h 6.209 c 1.83,0 3.313,-1.482 3.313,-3.311 0,-1.831 -1.483,-3.313 -3.313,-3.313 z"
|
||||
id="path243"
|
||||
style="fill:url(#XMLID_67_)"
|
||||
inkscape:connector-curvature="0" />
|
||||
</g>
|
||||
<g
|
||||
id="g245">
|
||||
<g
|
||||
id="g247">
|
||||
|
||||
<image
|
||||
width="67"
|
||||
height="67"
|
||||
xlink:href="data:image/png;base64,iVBORw0KGgoAAAANSUhEUgAAAEMAAABDCAYAAADHyrhzAAAACXBIWXMAAAsSAAALEgHS3X78AAAA BGdBTUEAAK/INwWK6QAAABl0RVh0U29mdHdhcmUAQWRvYmUgSW1hZ2VSZWFkeXHJZTwAAAW0SURB VHja7FsBbtswDBQlpf9/b2NLw4B64Ig7krKTrB1iQHDaoo51PlLHo1zK+3gf6JAf8H3zfwHjGdef P+lmJfEdcnLS85nAyJOuhT7LBTCm87uHgSJPAkGfxflbBAQ6zyRALweDTR79LAScCAw2Cvj5EiDy IDawUYO/e2CgMcjPjDVPB4OxoYJzJX+L2IEmPNSY4HyZJXIBCCFA6NEIKB47jgkgEPTYCTheTnkY GB4QeuLsXA0wiB2W8giAXQGxO6AsAyIXgEAM6F+f7WBgSCJfWBCOsQFwLCgFhM4lMDJAdHXu5ncN hIuXN/TTtKzY1FkPD5Q0O/oCM1BYNAPCTX1GYBz/X5JgTANG+zqzkLOHZodEgPQF5jAwbgqImwGF sSLLTMuOFTAmyEcuIP1keGgg0LDMyGiLEuSQA4zNgOEtzZYd5SozEBjdhMbv8QHAsE/Pqzc8CX+A ETECCTUh5zQYlsoVsMICYcHQNx3dcHFCSD+IkQgNJttDIdYWE6ZmwwcYN7OaiGHFMMvlcKR1CeR9 cYCOCjnJgiGAEY3kCQuGzhX6pq1o2oBuQMthVPtka5qUzmhJVlQnNCwrdHgg0XQHgGxAI0T5S0xO iQq7kB0ZnSGOruhkCS0GCCaSbKLTwO8KfH1YvTKJXD/u6cgzGoRUAvV0BQPEiqrjBvVTv38NC8gA +UFffxCqV3N/nch2pHrpitIX6IgAaWDVsIz4DcInAMSGhAXDglUS99W/rt3MdY6VyC7xf4GS1RmI HWzNH4QVnwaMiBlRMq3Jh8Qq5bmiM9ATaI5XMQ0YCIhPkzMQGLsBA2kdu5rUABTJhEpPWPoCYpSV 4QMkzTs42wRqJzUDdlYlz4vzwND/nJLjEjhaAgqhATwHzZA7WEZtlVkJQI2EkAB21MAyWE6gHjvE cagGAGMnIgvJccuKTSVCq0UqmSiyGsMqOcOMiC3FMWPQZyvBbYmtMz/7/1Wl6kn4Pw8gK7oiR5up v0EmMRyZPIx69dzwsgiGy4z6gNZC1PWaJ7tkUfMom+vSc1kFY+V42VaCCy2PUx6oN0FZaDWymI3a ESutyew85hkwMhTVQgYJpAqSozhFoSS7cg8t4/siet4XiNNVYxXkJEYOk/9eGZABYdkdRxeIepri CCQklopaOpld0J3rICBYJy5i9lxhBmsCIw+zqkl3oi+KqkE8tdkd36QBf3U4WiTVUOpOn4GxYgRh Mo0fMUhBVp3fI/dd+6sVCL6ZEGjzTN8kElHIs6zq6TZg8trqM3K6umlBdANGNSrVa1BnwiVcTSax 1SwgVQFSnYQlxtYbJEw6cOItMwppTm9OIzodJiVQgQz53YBg/UkGxB6ECWpdNuKqjQXXna4u3elP TpCYNPrdmK+DeJNCzF4UJuIYz82wojiGs7YW9zMJNAqTXfU69dmaJxYQL0RYmKDltRIgGBj7ChBR Ai0FbxqpBIiqrlkDl8zzOKvjWOl70n0YZB5FzamZzRkCmCEGDOQoWQGmhVEzDMqoWHFyxEaA2EAS TS2tLdl4vrqvkxVhNeG8FwIEAoNZiyMjy9uC0xVVp4VYgZHfkCnAJjGaD8dd92V20JdJFWst8SSj p+yV+dH+7xJ000eCDahBhZbuMIG2BRPEc44yTtUIKktP02wGjM/F8EgZTZml1SavSL6zBrCXbL1r aWZ4/Ri2nKZ3/GWdrmnW98wEIjBYbiiB4vU0xaWtj4/cFNuAUOrEmPHAmKQKRRtit/LiTbGrS+NK E5iFyXDYMYL64+nbpSPDthZ/E31NdrkyvRfUnHr5Rvqsg80mn233ea9XzKAh9dJXLEqiLSBBbZLd Nx69cPMtXr452+9YfS1r5ZWsf/paVhaUlWbS1Xbl5S7eo17llGSXzfuckfDf/lXOLDCl+C/8nnmp 99u+5Hum0Muq3qcB8CowHvVdr+zmv4/38T7845cAAwA56FTs9t3zlwAAAABJRU5ErkJggg=="
|
||||
transform="translate(423,420)"
|
||||
id="image249"
|
||||
style="opacity:0.75">
|
||||
</image>
|
||||
<g
|
||||
id="g251">
|
||||
<g
|
||||
id="g253">
|
||||
<linearGradient
|
||||
id="XMLID_68_"
|
||||
gradientUnits="userSpaceOnUse"
|
||||
x1="471.42581"
|
||||
y1="450.18951"
|
||||
x2="435.42581"
|
||||
y2="450.18951">
|
||||
<stop
|
||||
offset="0"
|
||||
style="stop-color:#FFFFFF"
|
||||
id="stop256" />
|
||||
<stop
|
||||
offset="1"
|
||||
style="stop-color:#000000"
|
||||
id="stop258" />
|
||||
</linearGradient>
|
||||
<path
|
||||
d="m 453.426,432.189 c -9.941,0 -18,8.059 -18,18 0,9.941 8.059,18 18,18 9.941,0 18,-8.059 18,-18 0,-9.941 -8.059,-18 -18,-18 z m 0,33.838 c -8.746,0 -15.836,-7.092 -15.836,-15.838 0,-8.746 7.09,-15.836 15.836,-15.836 8.746,0 15.836,7.09 15.836,15.836 0,8.746 -7.09,15.838 -15.836,15.838 z"
|
||||
id="path260"
|
||||
style="fill:url(#XMLID_68_)"
|
||||
inkscape:connector-curvature="0" />
|
||||
</g>
|
||||
</g>
|
||||
</g>
|
||||
<g
|
||||
id="g262">
|
||||
|
||||
<image
|
||||
width="63"
|
||||
height="64"
|
||||
xlink:href="data:image/png;base64,iVBORw0KGgoAAAANSUhEUgAAAD8AAABACAYAAACtK6/LAAAACXBIWXMAAAsSAAALEgHS3X78AAAA BGdBTUEAAK/INwWK6QAAABl0RVh0U29mdHdhcmUAQWRvYmUgSW1hZ2VSZWFkeXHJZTwAAAUoSURB VHja7FuLjts4DBRlpf//vRdbKgpsAJad4cNxdtPrGhDsTbK2hi+RQ7m17+PfPOSNnrn+b+Cfvf/6 28DLRc9ZrxaEvPBeAj6XAuD1akHIxfeQ5NleI6DR+WkhyAtA22sJhIBAr+BvJoxPAW+BV4e+h9Wk HRN81sz1KSHIE8Cthju47uA7Ac+1gGZwRsIoC0Au1HYnQ8y11b4HnA3721NuIE8Ct+A2ct2BABB4 C/wwZ30duUR4jBMmjzS9qbMdDLwQX0fA9RD1efu4ti4kGQGMoo8L0fRQYEdCAC0JXo9dCe8w9zgl gPEkcA12mMHAi7PUaXNGwHczl0P9/6z6/LgA+K9xA+CHcQcdI9BSZ7X/MPs9iBvNCECy2h9FX2fA b0oAN6N5FuiQ5vXYPgTQwX2Y2yAroAIYJ7TeFfgH6B8GvDZ5trZLkNdP9awdWA7L/sRJnUtmz0we af1mtN7BZL31WIilTSBAlhV2om2o/ZGszrLAb0DjerKTgGfpryTqAJb1hdofST9ngW4Q4F1J2y5h CyxNLC1+fLcRc0fZXyep7x/aHxdE+gECnARJC5qYvv8COYH+jgE/gKtQzW8O6O6Y+w8Q6IbRmF6y djIOkrOz2OPlBpnKL+XzQkx/I5mcXcqmWqPt0NpHy+hDkEspp4PfTfX7gyyrYsz9N9PP+jwSQAfA tUk+wN4/BtK2fs6mQCEr6E7OoedjTb8U7dkyx4oZcUz9bsauUlYdlbuqEWawEqDy2UujhSU7I8G6 sgeitdfm5Q8B/GfATxPxtSmvhBI8/sBLf5/K7dFEbPDxgtzd1OM6I5vBCjBBItQDpSC/LwW85mi+ Ac3basxG9x0A7eDvXfnwQTJGCQAza15VzTfvRmDtPciw0b4BKzgUcBYAI8uUiK3K1PMeFd0CQsLj 4HS0n+rscXY2dfUEcBmNVWlBreTI0NaMpT0zxz/8vrf3Oc5S0GlN26OfmFg0wWrjotrs8CytJNCR AL2IWVZyAj107a2VgDj+nmh4ZAVR8vlMcWCZk07qgA1EbBvhtwT1jZKqqKApFTasKYgisBWAgKID LVUow+uACbZ0WA9WF1TlUVeoaJ41EG3CsQBw/dsOcnut+RvhCDrRerQsrgyTswjflnlIM6b/0P4w 3+vMjWl+OAJoJJ1mmj/l80zLk/TMLEBGUHZVbnrghyFEbdk8HSaHKWdVAx5rHuo0dVPm3o32vSJl mu83QJFZk49aWqXG5XB8PXrYbsiDTnhzpHXk816jU0jleBA6jAU9l8BcTlA5VLDaVTPBBqNugpgQ k59OecqC3AQVY6T9MnW9HOrZNg9RqdlBDLA+u4IECXGCVTL0dMdmmeafKO3vCdaE0WAT1O8tICAQ O3QH4I+sySPq2qOLM1vOsu1uxAlWaLG7ukbgo0QnBN8csOw62jMniWpsERZ4N6AzwFuladESmpaE q0QZYiMTnCS27EDbd0KKpjmALJmxTN+7Od2Tx8RHq+3KWIml1QridKTPBDzLfswE8GkSoK35m5G8 NJqBP84GuWo9HwmAaayyJwdlkxrYDgQxnV7fZVvRIgHYMnW23Fa0DHi2JW0m/PySrWgsoE0z8W4m ntmEmGV+jwKzm+YAv3r7aRTworL1U7aftiDBqW48ZrmBV0pntpu+bONxxQquYGEjVuZLtpxnk6DK ywbLsYLW3uxlg4wQMjWANP+9mgjol71m8mw9UOnavO0LRtWe2dUdorcCf+X9/7qXCs8+c7Xv4/v4 lOOnAAMAme3iy7JhkzkAAAAASUVORK5CYII="
|
||||
transform="translate(425,421)"
|
||||
id="image264"
|
||||
style="opacity:0.75">
|
||||
</image>
|
||||
<g
|
||||
id="g266">
|
||||
<g
|
||||
id="g268">
|
||||
<linearGradient
|
||||
id="XMLID_69_"
|
||||
gradientUnits="userSpaceOnUse"
|
||||
x1="437.21881"
|
||||
y1="450.1904"
|
||||
x2="469.6348"
|
||||
y2="450.1904">
|
||||
<stop
|
||||
offset="0"
|
||||
style="stop-color:#FFFFFF"
|
||||
id="stop271" />
|
||||
<stop
|
||||
offset="1"
|
||||
style="stop-color:#000000"
|
||||
id="stop273" />
|
||||
</linearGradient>
|
||||
<path
|
||||
d="m 453.426,433.982 c -8.951,0 -16.207,7.256 -16.207,16.207 0,8.951 7.256,16.209 16.207,16.209 8.951,0 16.209,-7.258 16.209,-16.209 0,-8.951 -7.258,-16.207 -16.209,-16.207 z m 0,30.469 c -7.875,0 -14.26,-6.385 -14.26,-14.262 0,-7.875 6.385,-14.262 14.26,-14.262 7.877,0 14.262,6.387 14.262,14.262 0,7.877 -6.385,14.262 -14.262,14.262 z"
|
||||
id="path275"
|
||||
style="fill:url(#XMLID_69_)"
|
||||
inkscape:connector-curvature="0" />
|
||||
</g>
|
||||
</g>
|
||||
</g>
|
||||
</g>
|
||||
</g>
|
||||
</g>
|
||||
<g
|
||||
id="g277">
|
||||
<radialGradient
|
||||
id="XMLID_70_"
|
||||
cx="242"
|
||||
cy="241"
|
||||
r="5.9590001"
|
||||
gradientUnits="userSpaceOnUse">
|
||||
<stop
|
||||
offset="0"
|
||||
style="stop-color:#FFFFFF"
|
||||
id="stop280" />
|
||||
<stop
|
||||
offset="0.1303"
|
||||
style="stop-color:#FBFBFB"
|
||||
id="stop282" />
|
||||
<stop
|
||||
offset="0.2725"
|
||||
style="stop-color:#EDEDED"
|
||||
id="stop284" />
|
||||
<stop
|
||||
offset="0.4204"
|
||||
style="stop-color:#D8D8D8"
|
||||
id="stop286" />
|
||||
<stop
|
||||
offset="0.5722"
|
||||
style="stop-color:#B9B9B9"
|
||||
id="stop288" />
|
||||
<stop
|
||||
offset="0.727"
|
||||
style="stop-color:#929292"
|
||||
id="stop290" />
|
||||
<stop
|
||||
offset="0.8821"
|
||||
style="stop-color:#626262"
|
||||
id="stop292" />
|
||||
<stop
|
||||
offset="1"
|
||||
style="stop-color:#393939"
|
||||
id="stop294" />
|
||||
</radialGradient>
|
||||
<circle
|
||||
cx="242"
|
||||
cy="241"
|
||||
r="5.9590001"
|
||||
id="circle296"
|
||||
d="m 247.959,241 c 0,3.29106 -2.66794,5.959 -5.959,5.959 -3.29106,0 -5.959,-2.66794 -5.959,-5.959 0,-3.29106 2.66794,-5.959 5.959,-5.959 3.29106,0 5.959,2.66794 5.959,5.959 z"
|
||||
style="fill:url(#XMLID_70_)"
|
||||
sodipodi:cx="242"
|
||||
sodipodi:cy="241"
|
||||
sodipodi:rx="5.9590001"
|
||||
sodipodi:ry="5.9590001" />
|
||||
<g
|
||||
id="g298">
|
||||
<g
|
||||
id="g300">
|
||||
<linearGradient
|
||||
id="XMLID_71_"
|
||||
gradientUnits="userSpaceOnUse"
|
||||
x1="248.5"
|
||||
y1="241.0005"
|
||||
x2="235.5005"
|
||||
y2="241.0005">
|
||||
<stop
|
||||
offset="0"
|
||||
style="stop-color:#FFFFFF"
|
||||
id="stop303" />
|
||||
<stop
|
||||
offset="1"
|
||||
style="stop-color:#000000"
|
||||
id="stop305" />
|
||||
</linearGradient>
|
||||
<path
|
||||
d="m 242,234.5 c -3.59,0 -6.5,2.91 -6.5,6.5 0,3.59 2.91,6.5 6.5,6.5 3.59,0 6.5,-2.91 6.5,-6.5 0,-3.59 -2.91,-6.5 -6.5,-6.5 z m 0,12.219 c -3.158,0 -5.719,-2.561 -5.719,-5.719 0,-3.158 2.561,-5.718 5.719,-5.718 3.158,0 5.719,2.56 5.719,5.718 0,3.158 -2.561,5.719 -5.719,5.719 z"
|
||||
id="path307"
|
||||
style="fill:url(#XMLID_71_)"
|
||||
inkscape:connector-curvature="0" />
|
||||
</g>
|
||||
</g>
|
||||
<g
|
||||
id="g309">
|
||||
<g
|
||||
id="g311">
|
||||
<linearGradient
|
||||
id="XMLID_72_"
|
||||
gradientUnits="userSpaceOnUse"
|
||||
x1="236.1465"
|
||||
y1="241"
|
||||
x2="247.8535"
|
||||
y2="241">
|
||||
<stop
|
||||
offset="0"
|
||||
style="stop-color:#FFFFFF"
|
||||
id="stop314" />
|
||||
<stop
|
||||
offset="1"
|
||||
style="stop-color:#000000"
|
||||
id="stop316" />
|
||||
</linearGradient>
|
||||
<path
|
||||
d="m 242,235.147 c -3.232,0 -5.854,2.621 -5.854,5.853 0,3.232 2.621,5.854 5.854,5.854 3.233,0 5.854,-2.621 5.854,-5.854 0,-3.233 -2.622,-5.853 -5.854,-5.853 z m 0,11.003 c -2.845,0 -5.15,-2.307 -5.15,-5.15 0,-2.844 2.305,-5.15 5.15,-5.15 2.845,0 5.15,2.306 5.15,5.15 0,2.844 -2.305,5.15 -5.15,5.15 z"
|
||||
id="path318"
|
||||
style="fill:url(#XMLID_72_)"
|
||||
inkscape:connector-curvature="0" />
|
||||
</g>
|
||||
</g>
|
||||
</g>
|
||||
<text
|
||||
transform="translate(225.9526,245.5713)"
|
||||
font-size="14"
|
||||
id="text320"
|
||||
style="font-size:14px;fill:#ffffff;font-family:ArialRoundedMTBold">50 %</text>
|
||||
|
||||
<text
|
||||
transform="translate(225.9526,245.5713)"
|
||||
font-size="14"
|
||||
id="text322"
|
||||
style="font-size:14px;fill:#ffffff;font-family:ArialRoundedMTBold">75 %</text>
|
||||
|
||||
<radialGradient
|
||||
id="XMLID_73_"
|
||||
cx="242"
|
||||
cy="241"
|
||||
r="196.6895"
|
||||
gradientUnits="userSpaceOnUse">
|
||||
<stop
|
||||
offset="0.0381"
|
||||
style="stop-color:#FFFFFF"
|
||||
id="stop325" />
|
||||
<stop
|
||||
offset="0.4259"
|
||||
style="stop-color:#979797"
|
||||
id="stop327" />
|
||||
<stop
|
||||
offset="1"
|
||||
style="stop-color:#000000"
|
||||
id="stop329" />
|
||||
</radialGradient>
|
||||
<circle
|
||||
cx="242"
|
||||
cy="240.99899"
|
||||
r="196.689"
|
||||
id="circle331"
|
||||
d="m 438.689,240.99899 c 0,108.62834 -88.06067,196.689 -196.689,196.689 -108.62833,0 -196.688995,-88.06066 -196.688995,-196.689 0,-108.62833 88.060665,-196.688992 196.688995,-196.688992 108.62833,0 196.689,88.060662 196.689,196.688992 z"
|
||||
style="fill:url(#XMLID_73_)"
|
||||
sodipodi:cx="242"
|
||||
sodipodi:cy="240.99899"
|
||||
sodipodi:rx="196.689"
|
||||
sodipodi:ry="196.689" />
|
||||
<g
|
||||
id="g333">
|
||||
<g
|
||||
id="g335">
|
||||
<linearGradient
|
||||
id="XMLID_74_"
|
||||
gradientUnits="userSpaceOnUse"
|
||||
x1="87.023399"
|
||||
y1="395.97659"
|
||||
x2="396.97711"
|
||||
y2="86.022903">
|
||||
<stop
|
||||
offset="0"
|
||||
style="stop-color:#231F20"
|
||||
id="stop338" />
|
||||
<stop
|
||||
offset="0.3491"
|
||||
style="stop-color:#84858E"
|
||||
id="stop340" />
|
||||
<stop
|
||||
offset="0.4719"
|
||||
style="stop-color:#A7AAB6"
|
||||
id="stop342" />
|
||||
<stop
|
||||
offset="1"
|
||||
style="stop-color:#231F20"
|
||||
id="stop344" />
|
||||
</linearGradient>
|
||||
<path
|
||||
d="m 241.999,21.829 c -121.044,0 -219.168,98.124 -219.168,219.169 0,121.046 98.124,219.173 219.168,219.173 121.045,0 219.17,-98.127 219.17,-219.173 0,-121.045 -98.125,-219.169 -219.17,-219.169 z m 0,411.999 c -106.496,0 -192.829,-86.332 -192.829,-192.83 0,-106.496 86.333,-192.829 192.829,-192.829 106.497,0 192.828,86.333 192.828,192.829 0,106.498 -86.331,192.83 -192.828,192.83 z"
|
||||
id="path346"
|
||||
style="fill:url(#XMLID_74_)"
|
||||
inkscape:connector-curvature="0" />
|
||||
</g>
|
||||
</g>
|
||||
<g
|
||||
id="g348"
|
||||
style="opacity:0.76999996">
|
||||
<g
|
||||
id="g350">
|
||||
<g
|
||||
id="g352">
|
||||
|
||||
<image
|
||||
width="420"
|
||||
height="34"
|
||||
xlink:href="data:image/png;base64,iVBORw0KGgoAAAANSUhEUgAAAacAAAAkCAYAAAAtvPVaAAAACXBIWXMAAArrAAAK6wGCiw1aAAAA BGdBTUEAAK/INwWK6QAAABl0RVh0U29mdHdhcmUAQWRvYmUgSW1hZ2VSZWFkeXHJZTwAAAMwSURB VHja7N2BitswDIBhOcne/4GX2uOgYUKVErm5Y7P7fxDa5npdYdAfJb5UBAAAAAAAAMBgyn/2OgCA sbV/GZVCqAAAiSC9Faty47kl8VqECgA+J0it8/HtOBXnfnSbDRcAYI4wteRtOlCl4zn61t4vzn7i BADzx0kHyN5vzv5UoEry5zY8i9q3ECgA+PiJyW412J8K1NYRpmKCpLezSBEmAJgzUlGQ6vNz3+7T v1/OArV1hkkHaXUipUMlQagAAOPHyQvT1/ZQ949IHWFKB2pLvhEvTJu6vzrBEqYoAJhuWpJgWnqo OOnNqpI457R1TE3FhGlT91ezHXFagsmJQAHAeFHSj6szMR3bLv4ahGb2h9PT1eTkHdJbTaA2Eys9 PUXnoAgUAIwbpxaEaXfC5J2fKsFrX8bJW523BIH69dx0oBYnUEQJAOaIlDc17eozPwqZHlZunXOK DuutzgRlA+Wt4CNOADB2mOwKvEcQpeoMNl6guianO6FanelJiBMATBMnPTXp0Bz7VvFP7aQ//zcn QFGUokB5WzQ5ESYAGDtSLZikvNM52RXbL1PU5vzDJXgz9o1dbd7rNf5vAWCKOLWTPtyZzNw49b6p arbHM0bHMUj9RjmsBwBjh8m2QC8fty24unzRqS3xZtpJmPR6dpHXVRn2ihHECQDGDZPI64KIKn+X kO9BrKr4562646SnHS9I+riiOGGKrrcnRAoAhg2T/ayvTqB+m0hFU9StySmaoPQhPPvHVlVyqzSI EwCMG6fo6hBRlKIJ6q04NROd43ySV9Cv/fbaenq6Ik4AMEecRM4vX/RQ09NuwpSanrbgjRSJ17Vr dk27XkIuwoVfAWDGSGUu/Krvd3+vU89hversW8Q/D1VO4gQAGD9UV6u37WII77BeqCR+Fl2dvMj5 lw0KExMAfMwE1YIQVXnj23C/42vae/4SmEABwBxhEsldoKE6z5OrCSoTi3IRqhI8hygBwGdMT1Go oiBdHtrLRqNcxEqEQ3gAQKjOb1Nh6o1I6XxMqADgM6IU7WuJ3/nWcJQfeE0AwDyh6g7ST4SEIAEA 3o4RAAAAAAAAgOH9EWAAFB+kItkjc+0AAAAASUVORK5CYII="
|
||||
transform="matrix(1.02,0,0,1.02,35.0356,231.8022)"
|
||||
id="image354"
|
||||
style="opacity:0.75">
|
||||
</image>
|
||||
<path
|
||||
d="m 43.449,243.666 c 0,0.154 1.229,0.28 2.747,0.28 h 391.196 c 1.517,0 2.746,-0.126 2.746,-0.28 v -3.292 H 43.449 v 3.292 z"
|
||||
id="path356"
|
||||
inkscape:connector-curvature="0" />
|
||||
</g>
|
||||
<g
|
||||
id="g358">
|
||||
|
||||
<image
|
||||
width="420"
|
||||
height="35"
|
||||
xlink:href="data:image/png;base64,iVBORw0KGgoAAAANSUhEUgAAAacAAAAkCAYAAAAtvPVaAAAACXBIWXMAAArrAAAK6wGCiw1aAAAA BGdBTUEAAK/INwWK6QAAABl0RVh0U29mdHdhcmUAQWRvYmUgSW1hZ2VSZWFkeXHJZTwAAANrSURB VHja7N3dbqMwEEDhMXj7/u8bfvYGq5Opx4zJVhuc80koiWi77E2OJjEgAgAAAAAAAOBm0pv8DQDA GPb/FadEqAAAwSBdilV64Wd7XwMAxg7S3tjfFal04edS8JFAAcBnBCr6GI5U6tiv4+NtXqQAAGPH aXde232hQEW/P/JiNB1bK1KECgDGC1IrQmXbjs0LmCsHp6takOym99spi0gBwNhh2o7HVT0vDdhV pETt23vjVPsIT4doNo/2eWuKAgDcP1A2SmVKWlWg1uP9v4QpHKgcnJhsmPLxqLfsTFIECgDGDFMt SmVbjvf91bz/bxL4zik3piYbqcmEqLbpiar2PZQQKgC4ZZCkEib9Md6iorQ0hpNdvXanpxyYmuzk VEL059js89mZoAAA40xOm9pKmB7yc92BHPvL7yQTp/Dk5EXKTk4lSF/quQ6UXc3HxAQA44SpTE2r CdMk9Y/x9mPfpqalS985nQVqVnH6qsRplvp3T/ZvAwDeO0j2tZ2aFhMlPVnNlakpSedqvda5TXbp +FyZpL7k+2M/XdCJOAHAEHGyiyBslHZ5XiDhnQtrW7D3Tk6tUM2NTS+MmAgRAAwRqk2eP54TMyW1 zn9N0ekp/8J/IDUqSaAA4J5h0t8TiZxfyu6l9/3ccWDRTV+uQqS9Yo9YAcD7T0u1FuiTbfV7v3ed vbO/3YyTXX9+FiB9stWkyrpLbDk5cQKA+8VpMx14yPN5TjZc3kVg3evs5eDB2YPRB1RbobGKf6UI AMC9Y+Wd4/QwodKRsleGePnCr/bA7CqMpRInuxCCyxgBwBhhqq3IKxNTCdPihKl2+4xLcdorB2Jj o/fpK0QkJicAGHZy8gK1VCaorXd6yicHoONTArMGwjSrKYnr6wHA/YPkDS3eRV/1Vn4mPD1l50BS 5UC2ys+Vf3CW70URZRPhIz0AGDFUXqBqk9QqP9ctnN50MAdr6YVJL36onXBLmADgcwJlQ7WZOIW/ c4rcpr11a3bv/k3cCRcAxg2TjZN348G98hi6VXvuPBiR59vvbtK+bhJhAoCxAyWNSEXOceqenLy4 nE1IBAkAPitUtatBnAXppTidRar1CAD43EjJlShdmWxS52tCBQCfEaWrr/9JnCK/Q4wAgFD17Pu1 mBAkAMBLMQIAAAAA9PorwAAKdbgZEEjcdAAAAABJRU5ErkJggg=="
|
||||
transform="matrix(1.02,0,0,1.02,35.0356,227.7222)"
|
||||
id="image360"
|
||||
style="opacity:0.75">
|
||||
</image>
|
||||
<path
|
||||
d="m 43.449,237.082 v 3.292 h 396.689 v -3.292 c 0,-0.155 -1.229,-0.28 -2.746,-0.28 H 46.196 c -1.517,-0.001 -2.747,0.125 -2.747,0.28 z"
|
||||
id="path362"
|
||||
inkscape:connector-curvature="0" />
|
||||
</g>
|
||||
</g>
|
||||
<g
|
||||
id="g364">
|
||||
<g
|
||||
id="g366">
|
||||
|
||||
<image
|
||||
width="35"
|
||||
height="420"
|
||||
xlink:href="data:image/png;base64,iVBORw0KGgoAAAANSUhEUgAAACQAAAGoCAYAAAAuBUePAAAACXBIWXMAAArrAAAK6wGCiw1aAAAA BGdBTUEAAK/INwWK6QAAABl0RVh0U29mdHdhcmUAQWRvYmUgSW1hZ2VSZWFkeXHJZTwAAAPLSURB VHja7NcNb9wgDIBhTNL9//+7AFMlqDzXEOCadapeJJQrl4/nbENoCDTaa00eukf5l6Cda8oTN5eN a8sqTDYw0jl6Dy2DsS1QDzJCFedYBsAtkAy6Ps8ibL9FyQYmmqOXMt3zBO6jnQsYDdFdnJRldZR6 zDM1dE4WdOtHRRwOyoLeezLfZZNescBzITqtnxV0KJiom1tMMlgZzbhzMjrRIE7VG1RHIal+majY +vkrSudEmizq/Zq32k8TpRahS0F0ccf6OXnpWo1QVFF5MygLOkxt6VRmde5tDXkLYTQpa6Bftbco 6dkUTZ209LV75VcjZFOmUW8G5M2sq56TOmvXB262hqKJlE7bLwUqTu2kev5lZqSsTvvRTPPqSEy6 kqqnQ6Fl9IY4J9MlTi1p2GFqI9fvkrNWee/BsrJShwHqVMeoXg/ZWTi9VX3r1THC2foKzsvXLpxb KZvZdthCF1NHdkcQnWXlU1HHxaj0ojO7G7jdocbNdM3skWRyy7u1/egde7NGViOzk7Ler1yJwJen LHRmiwz+EVhqr4Bmf708DZLwYIsPREa+G/TfRQgQIECAAAECBAgQIECAAAECBAgQIECAAAECBAgQ IECAAAECBAgQIECAAAECBAgQIECAAAECBAgQIECAAAECBAgQIECAAAECBAgQIECAAAECBAgQIECA AAECBAgQIECAAAECBAgQIECAAAECBAgQIECAAAECBAgQIECAAAECBAgQIECAAAECBAgQIECAAAEC BAgQIECAAAECBAgQIECAAAECBAgQIECAAAECBAgQIECAAAECBAgQIECAAAECBAgQIECAAAECBAgQ IECAAAECBAgQIECAAAECBAgQIECAAAECBAjQjwCVm78fB5Unz/9RKStPpO5cfLj30GK+LwNc+QpQ cY5eD4PxaVTcSJPXszmOYF+WMguwPThjHnILVCYi8t5T7aLG21i+iZgLXI1QVg9LN6AebDtlozTp B171/Ia6JlBlBVTqzT1YNpDf9dysQKmOXwbkzchPs+5cmE3JwbRZejig1lMHFnZqyCtijWnRsaBL RelaSds5SFdxprKOkAbMgEYFXnYilGpULoP2QElhrpXZtrIOZTOr2lhU6dPpvQwsfcU6pDFi1hwN EmdcRyo5K7jbjs64mM9ixkaFnztrkMUsTXv7wNxZm5KKkD3fzs7thVHPNn1hdurKi15vF5Bn1iG5 iY6YtEWDuAN5uOG+aBYUBghZ3C2EV0AeKmyAwgxmFjSC3YGmITugV64pT9585h4l0Gjf1P4IMACC CdEE2qwKSwAAAABJRU5ErkJggg=="
|
||||
transform="matrix(1.02,0,0,1.02,232.916,32.9019)"
|
||||
id="image368"
|
||||
style="opacity:0.75">
|
||||
</image>
|
||||
<path
|
||||
d="m 245.084,438.72 c 0.155,0 0.28,-1.229 0.28,-2.746 V 44.776 c 0,-1.517 -0.125,-2.746 -0.28,-2.746 h -3.293 v 396.69 h 3.293 z"
|
||||
id="path370"
|
||||
inkscape:connector-curvature="0" />
|
||||
</g>
|
||||
<g
|
||||
id="g372">
|
||||
|
||||
<image
|
||||
width="34"
|
||||
height="420"
|
||||
xlink:href="data:image/png;base64,iVBORw0KGgoAAAANSUhEUgAAACQAAAGoCAYAAAAuBUePAAAACXBIWXMAAArrAAAK6wGCiw1aAAAA BGdBTUEAAK/INwWK6QAAABl0RVh0U29mdHdhcmUAQWRvYmUgSW1hZ2VSZWFkeXHJZTwAAAOiSURB VHja7NftjuMgDIVhTNn7v+BtYFUpkSyPATudzs6PFwllmo/m0bFJM6UwGL9jyP/8ouw141NfLolr x12Y3MBIEjQyKElg9HaFsoBh9i9RLYGxf9t9w0F4WFmhJIGxs25AqzlNqiUxVW2rScnDdLUNJdUS TV0nU9SXW4goTI80ddsgbDqv+Tjn9bcHOtTWplKyJZNFMo/zmoeaHqhOymST+lK2tklHoy5MM6hq QP3cZ9PpzuNi3Fn2s5Qs6rrpYVLr6trtsm9vYP4olAY9TTm6QnWD3YJk0di6oVcgXZZ+Hj+ch2nx +qglV5iXkgXp3jicR0RZpRTtIZuQbfBqlvs1bePL7vezBX5OdqiH07C6byRarmhTr57UGncl1BdP 87JLqQV/NuwXVPO7Jmp/qDRZkGweA15i+iltsWFkS+B3ryGi+kgCkPQqk8A7kffmuOsZeTchCb4v rfaH39/rD/87Jd8NkklPrVZkarXVD6Zxa9QPlej2s6iWXzYAAQIECBAgQIAAAQIECBAgQIAAAQIE CBAgQIAAAQIECBAgQIAAAQIECBAgQIAAAQIECBAgQIAAAQIECBAgQIAAAQIECBAgQIAAAQIECBAg QIAAAQIECBAgQIAAAQIECBAgQIAAAQIECBAgQIAAAQIECBAgQIAAAQIECBAgQIAAAQIECBAgQIAA AQIECBAgQIAAAQIECBAgQIAAAQIECBAgQIAAAQIECBAgQIAAAQIECBAgQIAAAQIECBAgQIAAAQIE CBAgQIAAAQIECBAgQIAAAQIECBAgQIAAAQIECBAgQIAAAQI0GeOckXPGTyfk3XT8ZEJjc+PovrdA 45vKGPqud3toBGYqqXrjxtfnfk4L6JNrQ7CWiNa74fW5TFB9Uc6RAc2W8DDpdAM6zP5VCcsd0HDS 0fMFEHX8cM7ZlXALGuomZZLOcc56nnul9Nr3VOf0TULjTkIe5LrxBa/qnOc59bk9WrYW7Btbpqda oX0DsqVblq1NyuXhvHQ80Ov430RCI1oyLyGLeR17qM8afDgpjTtNbVFdNe61qmw6+nM3sNlqu/Vg 9Jpap1MNcJgV5pUs1UO2j4ZJyZZzBRqqdF5jp5e991AswYT65Gfm7R4qBmP31UlyM9h2SOCYqFnN VhxQcdLpkzeGFGiGEgcji8UwopgIqDg3lUk6q/eoEsFEQfY8L5nVe3fqrTEK8s6VwGJIv+xnQHev eevfortDCoPxS8Y/AQYAJhapOpCAmu4AAAAASUVORK5CYII="
|
||||
transform="matrix(1.02,0,0,1.02,229.856,32.9019)"
|
||||
id="image374"
|
||||
style="opacity:0.75">
|
||||
</image>
|
||||
<path
|
||||
d="m 238.5,438.72 h 3.291 V 42.03 H 238.5 c -0.153,0 -0.279,1.229 -0.279,2.746 v 391.197 c 0,1.518 0.126,2.747 0.279,2.747 z"
|
||||
id="path376"
|
||||
inkscape:connector-curvature="0" />
|
||||
</g>
|
||||
</g>
|
||||
<g
|
||||
id="g378">
|
||||
<g
|
||||
id="g380">
|
||||
|
||||
<image
|
||||
width="43"
|
||||
height="43"
|
||||
xlink:href="data:image/png;base64,iVBORw0KGgoAAAANSUhEUgAAACwAAAAsCAYAAAAehFoBAAAACXBIWXMAAArrAAAK6wGCiw1aAAAA BGdBTUEAAK/INwWK6QAAABl0RVh0U29mdHdhcmUAQWRvYmUgSW1hZ2VSZWFkeXHJZTwAAALfSURB VHja7JnrcuMgDIUBE6ft+z/rbnxD28zAztkzkgHbbfdHmNHkUsd8OTlIgjr3Gq/xbcPnuPymP3Ef +Qlgf+BechbenwT1O+9ZYFJ57zJgC9STX70BK5XnTeDxICxGMMA14BJJgZP8WTmrMCsXCDQQdIDr WckEjwlei6L8JQoHIwZ67RV1n3AbgG75uvK6SenYYQUGxIgEjdZARdcMWmA3uH9q8XJstALDRoob QA8EnAByzbEYfkdvqyq3KIzeHAhypEdUmoEXCM06aAfTGrExK7C6T7h7Br1DFOgAkyVQdfqMmWDF WHiuV2G/o/CY4/0z3nIgNAMvGTSCZUTJGKmW2losEXYUfsvQHwA95mvKxFuGncAujiCLx4Oi9D9f IFYWG8ZgAH9AFOgBJl9B3XLvjRZiufdGczZbosXDo6Lye34PFV7BJg4sUnzNKTHR3HJ1lmDoOyw8 AQUFIOccg5K/3RGFW8BZ7VFZeAlgi5dvVHSC0o+4o4XDCq3iRfoF8OeNSnUMSjm3oP+qHQ5ue7xS Ca1GaK+z6x6x83oxWkUtuI8QpUPr3nXETjgx8udKfYLAosOSvFJKs1pMsbZRsUNZBl0hx2JhECWt PfLfS2le4PPbjvLdltCUxdQ0Uf9QABn4ed3vDP4gaFTb2jpVgYV6AbZAAX5Ab+DgywxUmou6vwxo zf/NzQ/CcpOCQLPSGyxgDQReFJUnskaq+LjLEuzd2WghtY4MPzMR8NzgY+nJEo72Yz5P4Am2qHij XYcovp+VxWf5uNvD2ibSK9kDrWLtOFZKcZzqUs0OrZbgDaKrAAeqoFoqXBVlU8t2v2YJr1jDKcoN ZIWgfKmNMs3W490ehfGnDVR2ESaQurzN184mUmt2OHPy440Gx2psrGOqvZIsZw8DfWPbqR0ISqU3 kZ6TzN4Wzxv7Plc5vaydYDZ3bV9xPmwp3HJO/N+fwMvZSb/jXw/iXuM1rht/BBgATenS1pVPKE4A AAAASUVORK5CYII="
|
||||
transform="matrix(1.02,0,0,1.02,226.7959,225.6821)"
|
||||
id="image382"
|
||||
style="opacity:0.75">
|
||||
</image>
|
||||
<path
|
||||
d="m 247.875,240.374 c 0,3.359 -2.725,6.083 -6.084,6.083 -3.357,0 -6.077,-2.724 -6.077,-6.083 0,-3.359 2.72,-6.079 6.077,-6.079 3.359,-10e-4 6.084,2.72 6.084,6.079 z"
|
||||
id="path384"
|
||||
inkscape:connector-curvature="0" />
|
||||
</g>
|
||||
<g
|
||||
id="g386">
|
||||
|
||||
<image
|
||||
width="44"
|
||||
height="44"
|
||||
xlink:href="data:image/png;base64,iVBORw0KGgoAAAANSUhEUgAAAC0AAAAtCAYAAAA6GuKaAAAACXBIWXMAAArrAAAK6wGCiw1aAAAA BGdBTUEAAK/INwWK6QAAABl0RVh0U29mdHdhcmUAQWRvYmUgSW1hZ2VSZWFkeXHJZTwAAAJkSURB VHja7JmBboMwDETjkP//4iWeJhXJu50dh7TdNBEpAiqgD3OxL6GUu93tfzV54z31r0DvXK/v/lPZ uI/uwsvG+Zl9BqcOsL4CmoEJ7Hv3RDh1HiQF3haBERZ7BK2wz2QiGfi2AVxhi/AM+qsPOF6WSLsA XAGYwReIGkIPAz+ciOuuPBDY6160FSD745wTeAm8JaPMgA/YeuAswvIAt21kU2FGHkLAD9IRvDjQ PRi4A2BptFsyvXnAzWxZtNXAMGCW8mQW7ZaIcnGk0UzHaCPYCY1vAtNgJQ/yI9otWaJRIizaFtyD tm/ADs5qfpNZzr6q6UrkwaBtBLujc9wKie63453sgRo/wYVAazAwT9kMEqQlTUcSqUH687LHMPsH 6HuW4y9XxBk8VsTqZIBKBmRkAeSKpotjiCKzJInBHBktISn3G3j9hemd7Pr6K9DqGCHPJ0fnM+s6 nZa1JORKH06e9mzpygOkoDVhL23hQBnYa7op5YNYVM3OH1sAm/HD3UjsTGdKsscJ7YHPJgfpSGtQ DDop15iH0Xae132YB+iJaJeM99DAxA/i2Ow51dG0lQdCd0cql1yeOvO7Hvhlz+XZaztEfAQD9PJ0 C7NCJJ8Z9CBRttFODcbZQMTXNEgxUOIlInl1gB9BtLcmtkrmcQrWEz2It3wwgpQ3MksKM00zw8LA M7NxLDLe4Juuf2RqfmSUqrNfgilVtjo+Zd3DGyBo2GUyYCNIfVaks4uP4pynjr5ni5EvXerNrJqW 5EqprkI8Y0FdFiR2eXH9ePOnC03+9rJvJjv3edpHo7vdDdqnAAMABfWZSb34uVMAAAAASUVORK5C YII="
|
||||
transform="matrix(1.02,0,0,1.02,226.7959,224.6621)"
|
||||
id="image388"
|
||||
style="opacity:0.75">
|
||||
</image>
|
||||
<g
|
||||
id="g390">
|
||||
<g
|
||||
id="g392">
|
||||
<path
|
||||
d="m 241.791,233.741 c -3.662,0 -6.63,2.97 -6.63,6.632 0,3.664 2.968,6.635 6.63,6.635 3.665,0 6.636,-2.972 6.636,-6.635 0,-3.662 -2.971,-6.632 -6.636,-6.632 z m 0,12.47 c -3.221,0 -5.833,-2.613 -5.833,-5.837 0,-3.224 2.612,-5.835 5.833,-5.835 3.224,0 5.839,2.612 5.839,5.835 0,3.224 -2.615,5.837 -5.839,5.837 z"
|
||||
id="path394"
|
||||
inkscape:connector-curvature="0" />
|
||||
</g>
|
||||
</g>
|
||||
</g>
|
||||
<g
|
||||
id="g396">
|
||||
|
||||
<image
|
||||
width="43"
|
||||
height="43"
|
||||
xlink:href="data:image/png;base64,iVBORw0KGgoAAAANSUhEUgAAACwAAAAsCAYAAAAehFoBAAAACXBIWXMAAArrAAAK6wGCiw1aAAAA BGdBTUEAAK/INwWK6QAAABl0RVh0U29mdHdhcmUAQWRvYmUgSW1hZ2VSZWFkeXHJZTwAAAIvSURB VHja7JnhbsMgDIRxwvs/ccH7s0reyWdskraaVCSUpmnpx83YB2vt277tfzf5wDj6SWBJvK93gssN oJIYU4N7fSWwByqFsZRc0+ByAVbgNQNHKCWvU9C9COtBHgRYHDgFUJyYrKD7JuxhrgdMIAKecFXn LxBC9yIsgh7wHkKjuvO3C8Cnle7FGEbYk8B7wNP0YaBbBbon1WWgp+leeHjqPmEH/N68Y9GJ0y10 D6CtWggrRFFZqdyT6c6DPQG6OyqjunYyXtZYpre+GbtW4Q5KP59bpYZZbC1IdWKubSeGWd5lKj+7 /e5T2eGECca4OGHw576icKQyQtsftrBexhDS02lNNsFPAqwkxQ2SWVxlr2QJIdWO5eJpYKNCk4Ku FI5VbONkmqmOWdhlO15o/qVo9FNtR2EvZ0ZuTAMDX/bDPQmoxMtOsuIb5FL8nC4KR6vkYUzczBPM AFgXwAx8We16MRQ8I2Mrm5oFJlDpsDPwsJ0XtkPR6sZJYX/AdTjwt8QwOi5mIw/n+yMBqas47gEk M+FioL3nWDg8tR+J0NiKYVZW2W5iOG6twfNZCIVSaVbHu84gZCYpzWyLNGASmll82Ri2NX0SYGZk NICeZCfdroSE55omgbE+gu0sJsCnU1qllmfMjgSVzjubwPvUFmnnqGqVl6PjKk2UZX3FYSCDj8bU xflaygDtHLdGJ5gZ4LedXu743VaAf9u/DHbHeOsJ/M542r7t2+5vPwIMAJsLejqxHbqBAAAAAElF TkSuQmCC"
|
||||
transform="matrix(1.02,0,0,1.02,226.7959,225.6821)"
|
||||
id="image398"
|
||||
style="opacity:0.75">
|
||||
</image>
|
||||
<g
|
||||
id="g400">
|
||||
<g
|
||||
id="g402">
|
||||
<path
|
||||
d="m 241.791,234.402 c -3.297,0 -5.971,2.672 -5.971,5.972 0,3.3 2.674,5.975 5.971,5.975 3.3,0 5.977,-2.676 5.977,-5.975 0,-3.299 -2.677,-5.972 -5.977,-5.972 z m 0,11.229 c -2.901,0 -5.252,-2.354 -5.252,-5.257 0,-2.904 2.351,-5.254 5.252,-5.254 2.904,0 5.258,2.351 5.258,5.254 0,2.902 -2.354,5.257 -5.258,5.257 z"
|
||||
id="path404"
|
||||
inkscape:connector-curvature="0" />
|
||||
</g>
|
||||
</g>
|
||||
</g>
|
||||
</g>
|
||||
</g>
|
||||
<g
|
||||
id="g406">
|
||||
<g
|
||||
id="g408">
|
||||
<path
|
||||
d="m 43.525,244.19 c 0,0.154 1.229,0.28 2.747,0.28 h 391.19 c 1.517,0 2.746,-0.126 2.746,-0.28 V 240.9 H 43.525 v 3.29 z"
|
||||
id="path410"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:#808284" />
|
||||
<path
|
||||
d="m 43.525,237.61 v 3.29 h 396.683 v -3.29 c 0,-0.154 -1.229,-0.28 -2.746,-0.28 H 46.272 c -1.518,10e-4 -2.747,0.126 -2.747,0.28 z"
|
||||
id="path412"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:#e0e1e2" />
|
||||
</g>
|
||||
<g
|
||||
id="g414">
|
||||
<path
|
||||
d="m 245.156,439.242 c 0.155,0 0.28,-1.229 0.28,-2.747 V 45.306 c 0,-1.517 -0.125,-2.746 -0.28,-2.746 h -3.29 v 396.683 h 3.29 z"
|
||||
id="path416"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:#808284" />
|
||||
<path
|
||||
d="m 238.577,439.242 h 3.29 V 42.56 h -3.29 c -0.154,0 -0.28,1.229 -0.28,2.746 v 391.189 c -0.001,1.518 0.125,2.747 0.28,2.747 z"
|
||||
id="path418"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:#e0e1e2" />
|
||||
</g>
|
||||
<g
|
||||
id="g420">
|
||||
<radialGradient
|
||||
id="XMLID_75_"
|
||||
cx="241.8672"
|
||||
cy="240.90041"
|
||||
r="6.0776"
|
||||
gradientUnits="userSpaceOnUse">
|
||||
<stop
|
||||
offset="0"
|
||||
style="stop-color:#FFFFFF"
|
||||
id="stop423" />
|
||||
<stop
|
||||
offset="0.1303"
|
||||
style="stop-color:#FBFBFB"
|
||||
id="stop425" />
|
||||
<stop
|
||||
offset="0.2725"
|
||||
style="stop-color:#EDEDED"
|
||||
id="stop427" />
|
||||
<stop
|
||||
offset="0.4204"
|
||||
style="stop-color:#D8D8D8"
|
||||
id="stop429" />
|
||||
<stop
|
||||
offset="0.5722"
|
||||
style="stop-color:#B9B9B9"
|
||||
id="stop431" />
|
||||
<stop
|
||||
offset="0.727"
|
||||
style="stop-color:#929292"
|
||||
id="stop433" />
|
||||
<stop
|
||||
offset="0.8821"
|
||||
style="stop-color:#626262"
|
||||
id="stop435" />
|
||||
<stop
|
||||
offset="1"
|
||||
style="stop-color:#393939"
|
||||
id="stop437" />
|
||||
</radialGradient>
|
||||
<circle
|
||||
cx="241.867"
|
||||
cy="240.89999"
|
||||
r="6.0770001"
|
||||
id="circle439"
|
||||
d="m 247.944,240.89999 c 0,3.35624 -2.72076,6.077 -6.077,6.077 -3.35623,0 -6.077,-2.72076 -6.077,-6.077 0,-3.35623 2.72077,-6.077 6.077,-6.077 3.35624,0 6.077,2.72077 6.077,6.077 z"
|
||||
style="fill:url(#XMLID_75_)"
|
||||
sodipodi:cx="241.867"
|
||||
sodipodi:cy="240.89999"
|
||||
sodipodi:rx="6.0770001"
|
||||
sodipodi:ry="6.0770001" />
|
||||
<g
|
||||
id="g441">
|
||||
<g
|
||||
id="g443">
|
||||
<linearGradient
|
||||
id="XMLID_76_"
|
||||
gradientUnits="userSpaceOnUse"
|
||||
x1="248.4971"
|
||||
y1="240.90089"
|
||||
x2="235.2373"
|
||||
y2="240.90089">
|
||||
<stop
|
||||
offset="0"
|
||||
style="stop-color:#FFFFFF"
|
||||
id="stop446" />
|
||||
<stop
|
||||
offset="1"
|
||||
style="stop-color:#000000"
|
||||
id="stop448" />
|
||||
</linearGradient>
|
||||
<path
|
||||
d="m 241.867,234.271 c -3.662,0 -6.63,2.968 -6.63,6.63 0,3.662 2.968,6.63 6.63,6.63 3.662,0 6.63,-2.968 6.63,-6.63 0,-3.662 -2.969,-6.63 -6.63,-6.63 z m 0,12.462 c -3.222,0 -5.833,-2.611 -5.833,-5.833 0,-3.221 2.611,-5.833 5.833,-5.833 3.221,0 5.833,2.612 5.833,5.833 0,3.222 -2.612,5.833 -5.833,5.833 z"
|
||||
id="path450"
|
||||
style="fill:url(#XMLID_76_)"
|
||||
inkscape:connector-curvature="0" />
|
||||
</g>
|
||||
</g>
|
||||
<g
|
||||
id="g452">
|
||||
<g
|
||||
id="g454">
|
||||
<linearGradient
|
||||
id="XMLID_77_"
|
||||
gradientUnits="userSpaceOnUse"
|
||||
x1="235.896"
|
||||
y1="240.90041"
|
||||
x2="247.8369"
|
||||
y2="240.90041">
|
||||
<stop
|
||||
offset="0"
|
||||
style="stop-color:#FFFFFF"
|
||||
id="stop457" />
|
||||
<stop
|
||||
offset="1"
|
||||
style="stop-color:#000000"
|
||||
id="stop459" />
|
||||
</linearGradient>
|
||||
<path
|
||||
d="m 241.867,234.93 c -3.297,0 -5.971,2.673 -5.971,5.97 0,3.297 2.673,5.971 5.971,5.971 3.298,0 5.97,-2.674 5.97,-5.971 0,-3.297 -2.673,-5.97 -5.97,-5.97 z m 0,11.224 c -2.902,0 -5.252,-2.354 -5.252,-5.254 0,-2.901 2.351,-5.253 5.252,-5.253 2.901,0 5.253,2.352 5.253,5.253 0,2.901 -2.351,5.254 -5.253,5.254 z"
|
||||
id="path461"
|
||||
style="fill:url(#XMLID_77_)"
|
||||
inkscape:connector-curvature="0" />
|
||||
</g>
|
||||
</g>
|
||||
</g>
|
||||
</g>
|
||||
<g
|
||||
id="g463"
|
||||
style="opacity:0.36000001">
|
||||
<path
|
||||
d="m 42,241 c 0,110.28 89.72,200 200,200 110.28,0 200,-89.72 200,-200 C 442,130.72 352.28,41 242,41 131.72,41 42,130.72 42,241 z m 2,0 C 44,131.822 132.822,43 242,43 351.178,43 440,131.822 440,241 440,350.178 351.178,439 242,439 132.822,439 44,350.178 44,241 z"
|
||||
id="path465"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:#ffffff" />
|
||||
</g>
|
||||
<g
|
||||
id="g467"
|
||||
style="opacity:0.36000001">
|
||||
<path
|
||||
d="m 191.25,241 c 0,27.983 22.766,50.75 50.75,50.75 27.983,0 50.75,-22.767 50.75,-50.75 0,-27.983 -22.767,-50.75 -50.75,-50.75 -27.984,0 -50.75,22.767 -50.75,50.75 z m 2,0 c 0,-26.881 21.869,-48.75 48.75,-48.75 26.881,0 48.75,21.869 48.75,48.75 0,26.881 -21.869,48.75 -48.75,48.75 -26.881,0 -48.75,-21.869 -48.75,-48.75 z"
|
||||
id="path469"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:#ffffff" />
|
||||
</g>
|
||||
<g
|
||||
id="g471"
|
||||
style="opacity:0.8">
|
||||
<path
|
||||
d="m 141.5,241 c 0,55.416 45.084,100.5 100.5,100.5 55.416,0 100.5,-45.084 100.5,-100.5 0,-55.416 -45.084,-100.5 -100.5,-100.5 -55.416,0 -100.5,45.084 -100.5,100.5 z m 2,0 c 0,-54.313 44.187,-98.5 98.5,-98.5 54.313,0 98.5,44.187 98.5,98.5 0,54.313 -44.187,98.5 -98.5,98.5 -54.313,0 -98.5,-44.187 -98.5,-98.5 z"
|
||||
id="path473"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:#ffffff" />
|
||||
</g>
|
||||
<g
|
||||
id="g475"
|
||||
style="opacity:0.8">
|
||||
<path
|
||||
d="m 91.75,241 c 0,82.848 67.402,150.25 150.25,150.25 82.848,0 150.25,-67.402 150.25,-150.25 C 392.25,158.152 324.848,90.75 242,90.75 159.152,90.75 91.75,158.152 91.75,241 z m 2,0 c 0,-81.745 66.505,-148.25 148.25,-148.25 81.745,0 148.25,66.505 148.25,148.25 0,81.745 -66.505,148.25 -148.25,148.25 C 160.255,389.25 93.75,322.745 93.75,241 z"
|
||||
id="path477"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:#ffffff" />
|
||||
</g>
|
||||
<g
|
||||
id="g479">
|
||||
<linearGradient
|
||||
id="XMLID_78_"
|
||||
gradientUnits="userSpaceOnUse"
|
||||
x1="471.75"
|
||||
y1="241"
|
||||
x2="12.2505"
|
||||
y2="241">
|
||||
<stop
|
||||
offset="0"
|
||||
style="stop-color:#FFFFFF"
|
||||
id="stop482" />
|
||||
<stop
|
||||
offset="1"
|
||||
style="stop-color:#000000"
|
||||
id="stop484" />
|
||||
</linearGradient>
|
||||
<path
|
||||
d="M 12.25,241 C 12.25,367.685 115.315,470.75 242,470.75 368.685,470.75 471.75,367.685 471.75,241 471.75,114.315 368.685,11.25 242,11.25 115.315,11.25 12.25,114.315 12.25,241 z m 15.049,0 C 27.299,122.613 123.613,26.299 242,26.299 360.386,26.299 456.701,122.613 456.701,241 456.701,359.386 360.386,455.701 242,455.701 123.613,455.701 27.299,359.386 27.299,241 z"
|
||||
id="path486"
|
||||
style="fill:url(#XMLID_78_)"
|
||||
inkscape:connector-curvature="0" />
|
||||
</g>
|
||||
<g
|
||||
id="g488">
|
||||
<linearGradient
|
||||
id="XMLID_79_"
|
||||
gradientUnits="userSpaceOnUse"
|
||||
x1="28.433599"
|
||||
y1="241"
|
||||
x2="455.56641"
|
||||
y2="241">
|
||||
<stop
|
||||
offset="0"
|
||||
style="stop-color:#FFFFFF"
|
||||
id="stop491" />
|
||||
<stop
|
||||
offset="1"
|
||||
style="stop-color:#000000"
|
||||
id="stop493" />
|
||||
</linearGradient>
|
||||
<path
|
||||
d="m 28.434,240.999 c 0,117.763 95.806,213.567 213.566,213.567 117.762,0 213.566,-95.805 213.566,-213.567 C 455.566,123.238 359.761,27.434 242,27.434 124.239,27.434 28.434,123.238 28.434,240.999 z m 7.874,0 C 36.308,127.58 128.58,35.307 242,35.307 c 113.419,0 205.692,92.273 205.692,205.692 0,113.42 -92.273,205.693 -205.692,205.693 -113.42,0 -205.692,-92.273 -205.692,-205.693 z"
|
||||
id="path495"
|
||||
style="fill:url(#XMLID_79_)"
|
||||
inkscape:connector-curvature="0" />
|
||||
</g>
|
||||
<text
|
||||
transform="translate(250,86.457)"
|
||||
font-size="18"
|
||||
id="text497"
|
||||
style="font-size:18px;fill:#ffffff;font-family:ArialRoundedMTBold">75 %</text>
|
||||
|
||||
<text
|
||||
transform="translate(250,135.457)"
|
||||
font-size="18"
|
||||
id="text499"
|
||||
style="font-size:18px;fill:#ffffff;font-family:ArialRoundedMTBold">50 %</text>
|
||||
|
||||
</g>
|
||||
<g
|
||||
id="joystickEnd"
|
||||
inkscape:label="#STICK"
|
||||
transform="translate(215.51483,-164.18009)">
|
||||
<g
|
||||
id="g502">
|
||||
<g
|
||||
id="g504">
|
||||
<g
|
||||
id="g506">
|
||||
<radialGradient
|
||||
id="XMLID_80_"
|
||||
cx="241"
|
||||
cy="239.5107"
|
||||
r="16.643999"
|
||||
gradientUnits="userSpaceOnUse">
|
||||
<stop
|
||||
offset="0"
|
||||
style="stop-color:#FFFFFF"
|
||||
id="stop509" />
|
||||
<stop
|
||||
offset="1"
|
||||
style="stop-color:#000000"
|
||||
id="stop511" />
|
||||
</radialGradient>
|
||||
<path
|
||||
d="m 257.645,239.511 c 0,9.193 -7.452,16.643 -16.645,16.643 -9.193,0 -16.644,-7.45 -16.644,-16.643 0,-9.192 7.452,-16.644 16.644,-16.644 9.192,0 16.645,7.452 16.645,16.644 z M 241,227.442 c -6.666,0 -12.072,5.403 -12.072,12.068 0,6.667 5.406,12.07 12.072,12.07 6.666,0 12.07,-5.402 12.07,-12.07 0,-6.665 -5.404,-12.068 -12.07,-12.068 z"
|
||||
id="path513"
|
||||
style="fill:url(#XMLID_80_)"
|
||||
inkscape:connector-curvature="0" />
|
||||
<g
|
||||
id="g515">
|
||||
<radialGradient
|
||||
id="XMLID_81_"
|
||||
cx="241.00101"
|
||||
cy="221.3071"
|
||||
r="3.0035"
|
||||
gradientUnits="userSpaceOnUse">
|
||||
<stop
|
||||
offset="0"
|
||||
style="stop-color:#FFFFFF"
|
||||
id="stop518" />
|
||||
<stop
|
||||
offset="1"
|
||||
style="stop-color:#000000"
|
||||
id="stop520" />
|
||||
</radialGradient>
|
||||
<path
|
||||
d="m 242.695,222.523 c -0.018,-0.291 -0.239,-3.895 -0.239,-3.895 -0.021,-0.331 -0.264,-0.652 -0.548,-0.689 -0.722,-0.101 -1.093,-0.101 -1.815,0 -0.285,0.037 -0.528,0.358 -0.548,0.689 0,0 -0.223,3.604 -0.242,3.895 -0.017,0.293 -0.686,0.496 -0.686,0.496 -0.041,0.456 -0.061,0.684 -0.101,1.144 -0.029,0.326 0.246,0.588 0.612,0.588 0.749,0 1.123,0 1.871,0 0.751,0 1.125,0 1.874,0 0.368,0 0.644,-0.263 0.613,-0.588 -0.04,-0.459 -0.062,-0.688 -0.101,-1.144 -0.002,0 -0.671,-0.203 -0.69,-0.496 z"
|
||||
id="path522"
|
||||
style="fill:url(#XMLID_81_)"
|
||||
inkscape:connector-curvature="0" />
|
||||
</g>
|
||||
<g
|
||||
id="g524">
|
||||
<radialGradient
|
||||
id="XMLID_82_"
|
||||
cx="235.29539"
|
||||
cy="222.62109"
|
||||
r="3.2993"
|
||||
gradientUnits="userSpaceOnUse">
|
||||
<stop
|
||||
offset="0"
|
||||
style="stop-color:#FFFFFF"
|
||||
id="stop527" />
|
||||
<stop
|
||||
offset="1"
|
||||
style="stop-color:#000000"
|
||||
id="stop529" />
|
||||
</radialGradient>
|
||||
<path
|
||||
d="m 236.784,222.969 c -0.117,-0.27 -1.558,-3.578 -1.558,-3.578 -0.134,-0.305 -0.472,-0.524 -0.751,-0.464 -0.714,0.154 -1.062,0.28 -1.706,0.624 -0.254,0.132 -0.374,0.516 -0.279,0.835 0,0 1.024,3.461 1.109,3.743 0.081,0.281 -0.478,0.701 -0.478,0.701 0.117,0.442 0.176,0.665 0.295,1.109 0.082,0.315 0.431,0.468 0.775,0.342 0.704,-0.253 1.056,-0.384 1.761,-0.64 0.704,-0.255 1.055,-0.384 1.759,-0.64 0.345,-0.125 0.512,-0.466 0.375,-0.761 -0.194,-0.418 -0.293,-0.625 -0.488,-1.043 0,0 -0.698,0.039 -0.814,-0.228 z"
|
||||
id="path531"
|
||||
style="fill:url(#XMLID_82_)"
|
||||
inkscape:connector-curvature="0" />
|
||||
</g>
|
||||
<g
|
||||
id="g533">
|
||||
<radialGradient
|
||||
id="XMLID_83_"
|
||||
cx="229.74409"
|
||||
cy="225.9478"
|
||||
r="3.5329001"
|
||||
gradientUnits="userSpaceOnUse">
|
||||
<stop
|
||||
offset="0"
|
||||
style="stop-color:#FFFFFF"
|
||||
id="stop536" />
|
||||
<stop
|
||||
offset="1"
|
||||
style="stop-color:#000000"
|
||||
id="stop538" />
|
||||
</radialGradient>
|
||||
<path
|
||||
d="m 231.38,225.409 c -0.203,-0.213 -2.687,-2.829 -2.687,-2.829 -0.231,-0.242 -0.624,-0.33 -0.867,-0.177 -0.616,0.387 -0.899,0.625 -1.391,1.166 -0.193,0.213 -0.172,0.614 0.026,0.881 0,0 2.145,2.904 2.319,3.139 0.174,0.237 -0.209,0.823 -0.209,0.823 0.263,0.377 0.396,0.564 0.659,0.94 0.187,0.267 0.565,0.291 0.846,0.057 0.575,-0.483 0.861,-0.722 1.434,-1.204 0.576,-0.481 0.861,-0.721 1.436,-1.202 0.282,-0.236 0.321,-0.615 0.091,-0.845 -0.326,-0.325 -0.488,-0.487 -0.813,-0.811 0,-0.001 -0.642,0.274 -0.844,0.062 z"
|
||||
id="path540"
|
||||
style="fill:url(#XMLID_83_)"
|
||||
inkscape:connector-curvature="0" />
|
||||
</g>
|
||||
<g
|
||||
id="g542">
|
||||
<radialGradient
|
||||
id="XMLID_84_"
|
||||
cx="225.5361"
|
||||
cy="230.90331"
|
||||
r="3.4546001"
|
||||
gradientUnits="userSpaceOnUse">
|
||||
<stop
|
||||
offset="0"
|
||||
style="stop-color:#FFFFFF"
|
||||
id="stop545" />
|
||||
<stop
|
||||
offset="1"
|
||||
style="stop-color:#000000"
|
||||
id="stop547" />
|
||||
</radialGradient>
|
||||
<path
|
||||
d="m 227.136,229.548 c -0.262,-0.129 -3.495,-1.737 -3.495,-1.737 -0.297,-0.151 -0.697,-0.099 -0.872,0.127 -0.448,0.575 -0.631,0.896 -0.909,1.572 -0.108,0.266 0.049,0.638 0.327,0.821 0,0 3.01,1.994 3.253,2.156 0.245,0.161 0.084,0.844 0.084,0.844 0.375,0.263 0.563,0.395 0.939,0.659 0.268,0.188 0.633,0.081 0.815,-0.237 0.375,-0.649 0.563,-0.972 0.937,-1.621 0.375,-0.65 0.562,-0.972 0.937,-1.622 0.184,-0.319 0.092,-0.687 -0.204,-0.826 -0.416,-0.193 -0.624,-0.289 -1.041,-0.484 0.002,0.001 -0.508,0.48 -0.771,0.348 z"
|
||||
id="path549"
|
||||
style="fill:url(#XMLID_84_)"
|
||||
inkscape:connector-curvature="0" />
|
||||
</g>
|
||||
<g
|
||||
id="g551">
|
||||
<radialGradient
|
||||
id="XMLID_85_"
|
||||
cx="223.1982"
|
||||
cy="236.80569"
|
||||
r="3.1020999"
|
||||
gradientUnits="userSpaceOnUse">
|
||||
<stop
|
||||
offset="0"
|
||||
style="stop-color:#FFFFFF"
|
||||
id="stop554" />
|
||||
<stop
|
||||
offset="1"
|
||||
style="stop-color:#000000"
|
||||
id="stop556" />
|
||||
</radialGradient>
|
||||
<path
|
||||
d="m 224.564,234.892 c -0.291,-0.034 -3.878,-0.44 -3.878,-0.44 -0.33,-0.036 -0.687,0.146 -0.776,0.418 -0.223,0.696 -0.288,1.059 -0.313,1.79 -0.012,0.287 0.262,0.582 0.584,0.657 0,0 3.511,0.846 3.794,0.917 0.286,0.067 0.368,0.761 0.368,0.761 0.443,0.119 0.665,0.179 1.109,0.299 0.315,0.084 0.622,-0.14 0.686,-0.501 0.129,-0.737 0.194,-1.106 0.325,-1.845 0.129,-0.736 0.195,-1.105 0.326,-1.842 0.063,-0.364 -0.149,-0.677 -0.474,-0.705 -0.457,-0.041 -0.686,-0.06 -1.144,-0.1 -0.001,-0.002 -0.315,0.622 -0.607,0.591 z"
|
||||
id="path558"
|
||||
style="fill:url(#XMLID_85_)"
|
||||
inkscape:connector-curvature="0" />
|
||||
</g>
|
||||
<g
|
||||
id="g560">
|
||||
<radialGradient
|
||||
id="XMLID_86_"
|
||||
cx="223.1958"
|
||||
cy="242.2168"
|
||||
r="3.1020999"
|
||||
gradientUnits="userSpaceOnUse">
|
||||
<stop
|
||||
offset="0"
|
||||
style="stop-color:#FFFFFF"
|
||||
id="stop563" />
|
||||
<stop
|
||||
offset="1"
|
||||
style="stop-color:#000000"
|
||||
id="stop565" />
|
||||
</radialGradient>
|
||||
<path
|
||||
d="m 223.975,240.789 c -0.286,0.07 -3.794,0.914 -3.794,0.914 -0.322,0.08 -0.596,0.372 -0.586,0.659 0.028,0.728 0.092,1.096 0.315,1.789 0.089,0.273 0.445,0.456 0.775,0.419 0,0 3.588,-0.405 3.879,-0.44 0.292,-0.032 0.605,0.592 0.605,0.592 0.458,-0.038 0.687,-0.059 1.145,-0.098 0.326,-0.03 0.537,-0.343 0.471,-0.708 -0.127,-0.734 -0.193,-1.105 -0.323,-1.841 -0.13,-0.739 -0.195,-1.105 -0.325,-1.843 -0.065,-0.363 -0.372,-0.587 -0.686,-0.502 -0.445,0.12 -0.667,0.18 -1.109,0.298 10e-4,0 -0.082,0.695 -0.367,0.761 z"
|
||||
id="path567"
|
||||
style="fill:url(#XMLID_86_)"
|
||||
inkscape:connector-curvature="0" />
|
||||
</g>
|
||||
<g
|
||||
id="g569">
|
||||
<radialGradient
|
||||
id="XMLID_87_"
|
||||
cx="225.53709"
|
||||
cy="248.11909"
|
||||
r="3.4547999"
|
||||
gradientUnits="userSpaceOnUse">
|
||||
<stop
|
||||
offset="0"
|
||||
style="stop-color:#FFFFFF"
|
||||
id="stop572" />
|
||||
<stop
|
||||
offset="1"
|
||||
style="stop-color:#000000"
|
||||
id="stop574" />
|
||||
</radialGradient>
|
||||
<path
|
||||
d="m 225.44,246.536 c -0.245,0.161 -3.253,2.155 -3.253,2.155 -0.277,0.186 -0.435,0.554 -0.327,0.821 0.276,0.675 0.461,0.996 0.908,1.571 0.176,0.228 0.576,0.279 0.873,0.128 0,0 3.233,-1.607 3.495,-1.737 0.262,-0.132 0.772,0.349 0.772,0.349 0.416,-0.193 0.625,-0.291 1.04,-0.484 0.296,-0.139 0.388,-0.508 0.204,-0.826 -0.375,-0.647 -0.561,-0.973 -0.936,-1.62 -0.375,-0.651 -0.562,-0.972 -0.936,-1.623 -0.185,-0.315 -0.549,-0.425 -0.816,-0.235 -0.377,0.265 -0.563,0.395 -0.939,0.657 -0.001,-0.001 0.16,0.685 -0.085,0.844 z"
|
||||
id="path576"
|
||||
style="fill:url(#XMLID_87_)"
|
||||
inkscape:connector-curvature="0" />
|
||||
</g>
|
||||
<g
|
||||
id="g578">
|
||||
<radialGradient
|
||||
id="XMLID_88_"
|
||||
cx="229.7446"
|
||||
cy="253.0742"
|
||||
r="3.5330999"
|
||||
gradientUnits="userSpaceOnUse">
|
||||
<stop
|
||||
offset="0"
|
||||
style="stop-color:#FFFFFF"
|
||||
id="stop581" />
|
||||
<stop
|
||||
offset="1"
|
||||
style="stop-color:#000000"
|
||||
id="stop583" />
|
||||
</radialGradient>
|
||||
<path
|
||||
d="m 228.779,251.433 c -0.172,0.239 -2.317,3.14 -2.317,3.14 -0.199,0.268 -0.216,0.67 -0.026,0.883 0.49,0.54 0.773,0.781 1.39,1.166 0.244,0.151 0.636,0.063 0.867,-0.176 0,0 2.485,-2.618 2.688,-2.829 0.2,-0.213 0.844,0.062 0.844,0.062 0.326,-0.324 0.487,-0.485 0.813,-0.811 0.229,-0.23 0.19,-0.609 -0.093,-0.845 -0.572,-0.481 -0.859,-0.723 -1.434,-1.203 -0.573,-0.482 -0.86,-0.721 -1.435,-1.205 -0.281,-0.235 -0.66,-0.211 -0.847,0.06 -0.261,0.375 -0.394,0.562 -0.658,0.94 0.001,-0.001 0.385,0.585 0.208,0.818 z"
|
||||
id="path585"
|
||||
style="fill:url(#XMLID_88_)"
|
||||
inkscape:connector-curvature="0" />
|
||||
</g>
|
||||
<g
|
||||
id="g587">
|
||||
<radialGradient
|
||||
id="XMLID_89_"
|
||||
cx="235.29491"
|
||||
cy="256.40039"
|
||||
r="3.2997999"
|
||||
gradientUnits="userSpaceOnUse">
|
||||
<stop
|
||||
offset="0"
|
||||
style="stop-color:#FFFFFF"
|
||||
id="stop590" />
|
||||
<stop
|
||||
offset="1"
|
||||
style="stop-color:#000000"
|
||||
id="stop592" />
|
||||
</radialGradient>
|
||||
<path
|
||||
d="m 233.596,254.894 c -0.083,0.283 -1.107,3.743 -1.107,3.743 -0.094,0.318 0.025,0.703 0.278,0.837 0.645,0.341 0.992,0.468 1.705,0.621 0.281,0.06 0.619,-0.157 0.751,-0.462 0,0 1.443,-3.309 1.559,-3.58 0.117,-0.267 0.815,-0.227 0.815,-0.227 0.193,-0.417 0.293,-0.626 0.488,-1.042 0.137,-0.297 -0.03,-0.636 -0.375,-0.762 -0.704,-0.257 -1.057,-0.384 -1.76,-0.642 -0.704,-0.255 -1.055,-0.382 -1.76,-0.639 -0.345,-0.128 -0.693,0.027 -0.776,0.343 -0.118,0.445 -0.179,0.667 -0.296,1.111 0.001,-0.003 0.561,0.417 0.478,0.699 z"
|
||||
id="path594"
|
||||
style="fill:url(#XMLID_89_)"
|
||||
inkscape:connector-curvature="0" />
|
||||
</g>
|
||||
<g
|
||||
id="g596">
|
||||
<radialGradient
|
||||
id="XMLID_90_"
|
||||
cx="240.99899"
|
||||
cy="257.71579"
|
||||
r="3.0042"
|
||||
gradientUnits="userSpaceOnUse">
|
||||
<stop
|
||||
offset="0"
|
||||
style="stop-color:#FFFFFF"
|
||||
id="stop599" />
|
||||
<stop
|
||||
offset="1"
|
||||
style="stop-color:#000000"
|
||||
id="stop601" />
|
||||
</radialGradient>
|
||||
<path
|
||||
d="m 239.303,256.499 c 0.018,0.293 0.241,3.895 0.241,3.895 0.021,0.333 0.264,0.655 0.549,0.689 0.721,0.104 1.092,0.104 1.815,0 0.283,-0.034 0.527,-0.356 0.547,-0.689 0,0 0.222,-3.604 0.24,-3.895 0.019,-0.293 0.688,-0.496 0.688,-0.496 0.04,-0.458 0.062,-0.684 0.102,-1.144 0.027,-0.322 -0.245,-0.588 -0.614,-0.588 -0.747,0 -1.123,0 -1.872,0 -0.75,0 -1.123,0 -1.872,0 -0.368,0 -0.642,0.266 -0.613,0.588 0.041,0.46 0.062,0.686 0.101,1.144 0.002,0 0.671,0.201 0.688,0.496 z"
|
||||
id="path603"
|
||||
style="fill:url(#XMLID_90_)"
|
||||
inkscape:connector-curvature="0" />
|
||||
</g>
|
||||
<g
|
||||
id="g605">
|
||||
<radialGradient
|
||||
id="XMLID_91_"
|
||||
cx="246.7041"
|
||||
cy="256.40039"
|
||||
r="3.299"
|
||||
gradientUnits="userSpaceOnUse">
|
||||
<stop
|
||||
offset="0"
|
||||
style="stop-color:#FFFFFF"
|
||||
id="stop608" />
|
||||
<stop
|
||||
offset="1"
|
||||
style="stop-color:#000000"
|
||||
id="stop610" />
|
||||
</radialGradient>
|
||||
<path
|
||||
d="m 245.216,256.053 c 0.117,0.271 1.558,3.58 1.558,3.58 0.134,0.303 0.472,0.521 0.751,0.46 0.713,-0.151 1.062,-0.278 1.707,-0.619 0.253,-0.134 0.371,-0.519 0.279,-0.837 0,0 -1.024,-3.463 -1.107,-3.743 -0.084,-0.281 0.476,-0.697 0.476,-0.697 -0.117,-0.444 -0.177,-0.666 -0.297,-1.111 -0.083,-0.315 -0.43,-0.471 -0.774,-0.343 -0.705,0.257 -1.054,0.384 -1.76,0.639 -0.703,0.256 -1.056,0.385 -1.759,0.64 -0.347,0.126 -0.514,0.467 -0.374,0.762 0.193,0.416 0.292,0.625 0.485,1.044 -0.001,-0.002 0.699,-0.044 0.815,0.225 z"
|
||||
id="path612"
|
||||
style="fill:url(#XMLID_91_)"
|
||||
inkscape:connector-curvature="0" />
|
||||
</g>
|
||||
<g
|
||||
id="g614">
|
||||
<radialGradient
|
||||
id="XMLID_92_"
|
||||
cx="252.2549"
|
||||
cy="253.0742"
|
||||
r="3.5329001"
|
||||
gradientUnits="userSpaceOnUse">
|
||||
<stop
|
||||
offset="0"
|
||||
style="stop-color:#FFFFFF"
|
||||
id="stop617" />
|
||||
<stop
|
||||
offset="1"
|
||||
style="stop-color:#000000"
|
||||
id="stop619" />
|
||||
</radialGradient>
|
||||
<path
|
||||
d="m 250.62,253.616 c 0.201,0.211 2.688,2.829 2.688,2.829 0.229,0.239 0.624,0.327 0.864,0.176 0.618,-0.387 0.901,-0.626 1.393,-1.166 0.189,-0.213 0.17,-0.613 -0.027,-0.883 0,0 -2.146,-2.9 -2.319,-3.14 -0.175,-0.232 0.21,-0.818 0.21,-0.818 -0.264,-0.379 -0.395,-0.565 -0.66,-0.94 -0.187,-0.271 -0.565,-0.295 -0.845,-0.06 -0.573,0.484 -0.862,0.723 -1.434,1.205 -0.576,0.48 -0.863,0.722 -1.435,1.203 -0.281,0.235 -0.323,0.614 -0.092,0.845 0.324,0.325 0.486,0.486 0.813,0.811 -0.001,0 0.643,-0.275 0.844,-0.062 z"
|
||||
id="path621"
|
||||
style="fill:url(#XMLID_92_)"
|
||||
inkscape:connector-curvature="0" />
|
||||
</g>
|
||||
<g
|
||||
id="g623">
|
||||
<radialGradient
|
||||
id="XMLID_93_"
|
||||
cx="256.46289"
|
||||
cy="248.11909"
|
||||
r="3.454"
|
||||
gradientUnits="userSpaceOnUse">
|
||||
<stop
|
||||
offset="0"
|
||||
style="stop-color:#FFFFFF"
|
||||
id="stop626" />
|
||||
<stop
|
||||
offset="1"
|
||||
style="stop-color:#000000"
|
||||
id="stop628" />
|
||||
</radialGradient>
|
||||
<path
|
||||
d="m 254.863,249.475 c 0.262,0.13 3.495,1.737 3.495,1.737 0.294,0.151 0.694,0.1 0.872,-0.128 0.448,-0.575 0.632,-0.896 0.906,-1.571 0.109,-0.27 -0.046,-0.636 -0.324,-0.821 0,0 -3.009,-1.994 -3.254,-2.155 -0.245,-0.159 -0.083,-0.845 -0.083,-0.845 -0.379,-0.263 -0.563,-0.396 -0.938,-0.657 -0.27,-0.189 -0.634,-0.084 -0.817,0.235 -0.374,0.649 -0.562,0.972 -0.936,1.623 -0.375,0.647 -0.563,0.973 -0.937,1.62 -0.184,0.318 -0.092,0.688 0.203,0.824 0.416,0.193 0.626,0.293 1.04,0.484 0.001,0 0.513,-0.478 0.773,-0.346 z"
|
||||
id="path630"
|
||||
style="fill:url(#XMLID_93_)"
|
||||
inkscape:connector-curvature="0" />
|
||||
</g>
|
||||
<g
|
||||
id="g632">
|
||||
<radialGradient
|
||||
id="XMLID_94_"
|
||||
cx="258.80179"
|
||||
cy="242.2168"
|
||||
r="3.1026001"
|
||||
gradientUnits="userSpaceOnUse">
|
||||
<stop
|
||||
offset="0"
|
||||
style="stop-color:#FFFFFF"
|
||||
id="stop635" />
|
||||
<stop
|
||||
offset="1"
|
||||
style="stop-color:#000000"
|
||||
id="stop637" />
|
||||
</radialGradient>
|
||||
<path
|
||||
d="m 257.436,244.13 c 0.291,0.035 3.879,0.44 3.879,0.44 0.328,0.037 0.688,-0.147 0.772,-0.419 0.226,-0.693 0.291,-1.06 0.317,-1.789 0.01,-0.287 -0.264,-0.58 -0.586,-0.659 0,0 -3.51,-0.844 -3.795,-0.914 -0.285,-0.066 -0.367,-0.761 -0.367,-0.761 -0.441,-0.119 -0.665,-0.179 -1.109,-0.299 -0.316,-0.084 -0.619,0.14 -0.686,0.502 -0.129,0.738 -0.195,1.105 -0.324,1.842 -0.132,0.737 -0.195,1.106 -0.327,1.843 -0.063,0.365 0.149,0.678 0.473,0.706 0.46,0.041 0.688,0.062 1.146,0.1 10e-4,0 0.314,-0.624 0.607,-0.592 z"
|
||||
id="path639"
|
||||
style="fill:url(#XMLID_94_)"
|
||||
inkscape:connector-curvature="0" />
|
||||
</g>
|
||||
<g
|
||||
id="g641">
|
||||
<radialGradient
|
||||
id="XMLID_95_"
|
||||
cx="258.8027"
|
||||
cy="236.8047"
|
||||
r="3.1022999"
|
||||
gradientUnits="userSpaceOnUse">
|
||||
<stop
|
||||
offset="0"
|
||||
style="stop-color:#FFFFFF"
|
||||
id="stop644" />
|
||||
<stop
|
||||
offset="1"
|
||||
style="stop-color:#000000"
|
||||
id="stop646" />
|
||||
</radialGradient>
|
||||
<path
|
||||
d="m 258.025,238.234 c 0.285,-0.072 3.795,-0.915 3.795,-0.915 0.32,-0.08 0.596,-0.373 0.584,-0.661 -0.026,-0.73 -0.092,-1.095 -0.317,-1.791 -0.085,-0.27 -0.444,-0.453 -0.772,-0.417 0,0 -3.588,0.406 -3.879,0.441 -0.293,0.031 -0.605,-0.593 -0.605,-0.593 -0.458,0.041 -0.686,0.06 -1.146,0.1 -0.325,0.027 -0.536,0.342 -0.473,0.703 0.13,0.739 0.195,1.107 0.325,1.846 0.132,0.738 0.195,1.105 0.324,1.844 0.066,0.362 0.373,0.586 0.686,0.501 0.446,-0.12 0.666,-0.179 1.109,-0.298 0,0.001 0.082,-0.694 0.369,-0.76 z"
|
||||
id="path648"
|
||||
style="fill:url(#XMLID_95_)"
|
||||
inkscape:connector-curvature="0" />
|
||||
</g>
|
||||
<g
|
||||
id="g650">
|
||||
<radialGradient
|
||||
id="XMLID_96_"
|
||||
cx="256.46191"
|
||||
cy="230.90331"
|
||||
r="3.4546001"
|
||||
gradientUnits="userSpaceOnUse">
|
||||
<stop
|
||||
offset="0"
|
||||
style="stop-color:#FFFFFF"
|
||||
id="stop653" />
|
||||
<stop
|
||||
offset="1"
|
||||
style="stop-color:#000000"
|
||||
id="stop655" />
|
||||
</radialGradient>
|
||||
<path
|
||||
d="m 256.559,232.487 c 0.245,-0.163 3.254,-2.157 3.254,-2.157 0.276,-0.183 0.434,-0.556 0.324,-0.82 -0.274,-0.675 -0.458,-0.997 -0.906,-1.572 -0.178,-0.226 -0.576,-0.279 -0.872,-0.127 0,0 -3.231,1.608 -3.495,1.737 -0.261,0.131 -0.771,-0.35 -0.771,-0.35 -0.419,0.194 -0.626,0.293 -1.044,0.486 -0.295,0.138 -0.387,0.507 -0.201,0.825 0.374,0.649 0.562,0.971 0.937,1.621 0.374,0.65 0.562,0.973 0.934,1.623 0.186,0.317 0.55,0.424 0.819,0.237 0.376,-0.266 0.56,-0.396 0.938,-0.659 0,0 -0.163,-0.683 0.083,-0.844 z"
|
||||
id="path657"
|
||||
style="fill:url(#XMLID_96_)"
|
||||
inkscape:connector-curvature="0" />
|
||||
</g>
|
||||
<g
|
||||
id="g659">
|
||||
<radialGradient
|
||||
id="XMLID_97_"
|
||||
cx="252.25591"
|
||||
cy="225.9473"
|
||||
r="3.5329001"
|
||||
gradientUnits="userSpaceOnUse">
|
||||
<stop
|
||||
offset="0"
|
||||
style="stop-color:#FFFFFF"
|
||||
id="stop662" />
|
||||
<stop
|
||||
offset="1"
|
||||
style="stop-color:#000000"
|
||||
id="stop664" />
|
||||
</radialGradient>
|
||||
<path
|
||||
d="m 253.22,227.588 c 0.174,-0.235 2.319,-3.138 2.319,-3.138 0.197,-0.268 0.217,-0.669 0.025,-0.882 -0.491,-0.541 -0.774,-0.778 -1.393,-1.166 -0.24,-0.152 -0.635,-0.065 -0.864,0.177 0,0 -2.484,2.616 -2.688,2.829 -0.201,0.212 -0.845,-0.063 -0.845,-0.063 -0.326,0.324 -0.488,0.486 -0.813,0.811 -0.229,0.23 -0.189,0.608 0.094,0.843 0.571,0.481 0.858,0.723 1.433,1.203 0.571,0.482 0.86,0.722 1.432,1.205 0.283,0.234 0.662,0.209 0.847,-0.057 0.266,-0.377 0.396,-0.564 0.66,-0.94 0.001,0.001 -0.384,-0.587 -0.207,-0.822 z"
|
||||
id="path666"
|
||||
style="fill:url(#XMLID_97_)"
|
||||
inkscape:connector-curvature="0" />
|
||||
</g>
|
||||
<g
|
||||
id="g668">
|
||||
<radialGradient
|
||||
id="XMLID_98_"
|
||||
cx="246.70509"
|
||||
cy="222.62061"
|
||||
r="3.2988999"
|
||||
gradientUnits="userSpaceOnUse">
|
||||
<stop
|
||||
offset="0"
|
||||
style="stop-color:#FFFFFF"
|
||||
id="stop671" />
|
||||
<stop
|
||||
offset="1"
|
||||
style="stop-color:#000000"
|
||||
id="stop673" />
|
||||
</radialGradient>
|
||||
<path
|
||||
d="m 248.405,224.128 c 0.081,-0.282 1.105,-3.743 1.105,-3.743 0.094,-0.319 -0.026,-0.703 -0.279,-0.835 -0.644,-0.343 -0.992,-0.469 -1.705,-0.624 -0.281,-0.06 -0.619,0.16 -0.751,0.464 0,0 -1.442,3.308 -1.558,3.578 -0.118,0.267 -0.815,0.229 -0.815,0.229 -0.195,0.417 -0.294,0.624 -0.487,1.04 -0.138,0.297 0.029,0.637 0.375,0.763 0.702,0.255 1.055,0.383 1.758,0.639 0.706,0.257 1.055,0.383 1.76,0.641 0.347,0.125 0.693,-0.027 0.776,-0.342 0.12,-0.446 0.178,-0.667 0.297,-1.109 0,0.001 -0.562,-0.419 -0.476,-0.701 z"
|
||||
id="path675"
|
||||
style="fill:url(#XMLID_98_)"
|
||||
inkscape:connector-curvature="0" />
|
||||
</g>
|
||||
<radialGradient
|
||||
id="XMLID_99_"
|
||||
cx="240.99899"
|
||||
cy="239.5107"
|
||||
r="3.3778999"
|
||||
gradientUnits="userSpaceOnUse">
|
||||
<stop
|
||||
offset="0"
|
||||
style="stop-color:#FFFFFF"
|
||||
id="stop678" />
|
||||
<stop
|
||||
offset="1"
|
||||
style="stop-color:#000000"
|
||||
id="stop680" />
|
||||
</radialGradient>
|
||||
<circle
|
||||
cx="241"
|
||||
cy="239.511"
|
||||
r="3.378"
|
||||
id="circle682"
|
||||
style="fill:url(#XMLID_99_)"
|
||||
sodipodi:cx="241"
|
||||
sodipodi:cy="239.511"
|
||||
sodipodi:rx="3.378"
|
||||
sodipodi:ry="3.378"
|
||||
d="m 244.378,239.511 c 0,1.86562 -1.51238,3.378 -3.378,3.378 -1.86562,0 -3.378,-1.51238 -3.378,-3.378 0,-1.86562 1.51238,-3.378 3.378,-3.378 1.86562,0 3.378,1.51238 3.378,3.378 z" />
|
||||
</g>
|
||||
</g>
|
||||
<radialGradient
|
||||
id="XMLID_100_"
|
||||
cx="241"
|
||||
cy="239.5117"
|
||||
r="16.830099"
|
||||
gradientUnits="userSpaceOnUse">
|
||||
<stop
|
||||
offset="0"
|
||||
style="stop-color:#FFFFFF"
|
||||
id="stop685" />
|
||||
<stop
|
||||
offset="0.2855"
|
||||
style="stop-color:#BEBEBE"
|
||||
id="stop687" />
|
||||
<stop
|
||||
offset="0.6285"
|
||||
style="stop-color:#777777"
|
||||
id="stop689" />
|
||||
<stop
|
||||
offset="0.8756"
|
||||
style="stop-color:#4A4A4A"
|
||||
id="stop691" />
|
||||
<stop
|
||||
offset="1"
|
||||
style="stop-color:#393939"
|
||||
id="stop693" />
|
||||
</radialGradient>
|
||||
<circle
|
||||
cx="241"
|
||||
cy="239.513"
|
||||
r="16.83"
|
||||
id="circle695"
|
||||
style="fill:url(#XMLID_100_)"
|
||||
sodipodi:cx="241"
|
||||
sodipodi:cy="239.513"
|
||||
sodipodi:rx="16.83"
|
||||
sodipodi:ry="16.83"
|
||||
d="m 257.83,239.513 c 0,9.29495 -7.53505,16.83 -16.83,16.83 -9.29495,0 -16.83,-7.53505 -16.83,-16.83 0,-9.29495 7.53505,-16.83 16.83,-16.83 9.29495,0 16.83,7.53505 16.83,16.83 z" />
|
||||
<g
|
||||
id="g697">
|
||||
<g
|
||||
id="g699">
|
||||
<linearGradient
|
||||
id="XMLID_101_"
|
||||
gradientUnits="userSpaceOnUse"
|
||||
x1="259.36041"
|
||||
y1="239.51221"
|
||||
x2="222.64059"
|
||||
y2="239.51221">
|
||||
<stop
|
||||
offset="0"
|
||||
style="stop-color:#FFFFFF"
|
||||
id="stop702" />
|
||||
<stop
|
||||
offset="1"
|
||||
style="stop-color:#000000"
|
||||
id="stop704" />
|
||||
</linearGradient>
|
||||
<path
|
||||
d="m 241,221.152 c -10.14,0 -18.36,8.22 -18.36,18.361 0,10.139 8.22,18.359 18.36,18.359 10.141,0 18.36,-8.22 18.36,-18.359 0,-10.141 -8.219,-18.361 -18.36,-18.361 z m 0,34.514 c -8.921,0 -16.154,-7.233 -16.154,-16.153 0,-8.922 7.233,-16.154 16.154,-16.154 8.921,0 16.152,7.232 16.152,16.154 0,8.92 -7.231,16.153 -16.152,16.153 z"
|
||||
id="path706"
|
||||
style="fill:url(#XMLID_101_)"
|
||||
inkscape:connector-curvature="0" />
|
||||
</g>
|
||||
</g>
|
||||
<g
|
||||
id="g708">
|
||||
<g
|
||||
id="g710">
|
||||
<linearGradient
|
||||
id="XMLID_102_"
|
||||
gradientUnits="userSpaceOnUse"
|
||||
x1="224.4668"
|
||||
y1="239.5127"
|
||||
x2="257.5332"
|
||||
y2="239.5127">
|
||||
<stop
|
||||
offset="0"
|
||||
style="stop-color:#FFFFFF"
|
||||
id="stop713" />
|
||||
<stop
|
||||
offset="1"
|
||||
style="stop-color:#000000"
|
||||
id="stop715" />
|
||||
</linearGradient>
|
||||
<path
|
||||
d="m 241,222.98 c -9.13,0 -16.533,7.402 -16.533,16.532 0,9.129 7.403,16.533 16.533,16.533 9.13,0 16.533,-7.403 16.533,-16.533 0,-9.13 -7.403,-16.532 -16.533,-16.532 z m 0,31.079 c -8.035,0 -14.547,-6.513 -14.547,-14.546 0,-8.033 6.512,-14.547 14.547,-14.547 8.034,0 14.547,6.513 14.547,14.547 0,8.034 -6.513,14.546 -14.547,14.546 z"
|
||||
id="path717"
|
||||
style="fill:url(#XMLID_102_)"
|
||||
inkscape:connector-curvature="0" />
|
||||
</g>
|
||||
</g>
|
||||
</g>
|
||||
</g>
|
||||
</svg>
|
Before Width: | Height: | Size: 13 KiB After Width: | Height: | Size: 95 KiB |
@ -88,9 +88,12 @@ void LogFile::timerFired()
|
||||
if(file.bytesAvailable() > 4)
|
||||
{
|
||||
|
||||
// TODO: going back in time will be a problem
|
||||
while ((myTime.elapsed() - timeOffset) * playbackSpeed > lastTimeStamp) {
|
||||
int time;
|
||||
time = myTime.elapsed();
|
||||
|
||||
// TODO: going back in time will be a problem
|
||||
while ((lastPlayed + ((time - timeOffset)* playbackSpeed) > lastTimeStamp)) {
|
||||
lastPlayed += ((time - timeOffset)* playbackSpeed);
|
||||
if(file.bytesAvailable() < 4) {
|
||||
stopReplay();
|
||||
return;
|
||||
@ -98,6 +101,11 @@ void LogFile::timerFired()
|
||||
|
||||
file.read((char *) &dataSize, sizeof(dataSize));
|
||||
|
||||
if (dataSize<1 || dataSize>(1024*1024)) {
|
||||
qDebug() << "Error: Logfile corrupted! Unlikely packet size: " << dataSize << "\n";
|
||||
stopReplay();
|
||||
return;
|
||||
}
|
||||
if(file.bytesAvailable() < dataSize) {
|
||||
stopReplay();
|
||||
return;
|
||||
@ -113,7 +121,19 @@ void LogFile::timerFired()
|
||||
return;
|
||||
}
|
||||
|
||||
int save=lastTimeStamp;
|
||||
file.read((char *) &lastTimeStamp,sizeof(lastTimeStamp));
|
||||
// some validity checks
|
||||
if (lastTimeStamp<save // logfile goies back in time
|
||||
|| (lastTimeStamp-save) > (60*60*1000)) { // gap of more than 60 minutes)
|
||||
qDebug() << "Error: Logfile corrupted! Unlikely timestamp " << lastTimeStamp << " after "<< save << "\n";
|
||||
stopReplay();
|
||||
return;
|
||||
}
|
||||
|
||||
timeOffset = time;
|
||||
time = myTime.elapsed();
|
||||
|
||||
}
|
||||
} else {
|
||||
stopReplay();
|
||||
@ -125,6 +145,7 @@ bool LogFile::startReplay() {
|
||||
dataBuffer.clear();
|
||||
myTime.restart();
|
||||
timeOffset = 0;
|
||||
lastPlayed = 0;
|
||||
playbackSpeed = 1;
|
||||
file.read((char *) &lastTimeStamp,sizeof(lastTimeStamp));
|
||||
timer.setInterval(10);
|
||||
@ -142,12 +163,11 @@ bool LogFile::stopReplay() {
|
||||
void LogFile::pauseReplay()
|
||||
{
|
||||
timer.stop();
|
||||
pausedTime = myTime.elapsed();
|
||||
}
|
||||
|
||||
void LogFile::resumeReplay()
|
||||
{
|
||||
timeOffset += myTime.elapsed() - pausedTime;
|
||||
timeOffset = myTime.elapsed();
|
||||
timer.start();
|
||||
}
|
||||
|
||||
|
@ -27,7 +27,7 @@ public:
|
||||
bool stopReplay();
|
||||
|
||||
public slots:
|
||||
void setReplaySpeed(double val) { playbackSpeed = pow(10,(val)/100); qDebug() << playbackSpeed; };
|
||||
void setReplaySpeed(double val) { playbackSpeed = val; qDebug() << playbackSpeed; };
|
||||
void pauseReplay();
|
||||
void resumeReplay();
|
||||
|
||||
@ -45,11 +45,11 @@ protected:
|
||||
QTime myTime;
|
||||
QFile file;
|
||||
qint32 lastTimeStamp;
|
||||
qint32 lastPlayed;
|
||||
QMutex mutex;
|
||||
|
||||
|
||||
int timeOffset;
|
||||
int pausedTime;
|
||||
double playbackSpeed;
|
||||
};
|
||||
|
||||
|
@ -74,6 +74,7 @@ PFDGadgetWidget::PFDGadgetWidget(QWidget *parent) : QGraphicsView(parent)
|
||||
connect(&skyDialTimer, SIGNAL(timeout()), this, SLOT(moveSky()));
|
||||
skyDialTimer.start(30);
|
||||
|
||||
|
||||
}
|
||||
|
||||
PFDGadgetWidget::~PFDGadgetWidget()
|
||||
@ -82,6 +83,14 @@ PFDGadgetWidget::~PFDGadgetWidget()
|
||||
dialTimer.stop();
|
||||
}
|
||||
|
||||
void PFDGadgetWidget::setToolTipPrivate()
|
||||
{
|
||||
static qint32 updateRate=0;
|
||||
UAVObject::Metadata mdata=attitudeObj->getMetadata();
|
||||
if(mdata.flightTelemetryUpdatePeriod!=updateRate)
|
||||
this->setToolTip("Current refresh rate:"+QString::number(mdata.flightTelemetryUpdatePeriod)+" miliseconds"+"\nIf you want to change it please edit the AttitudeActual metadata on the object browser.");
|
||||
}
|
||||
|
||||
/*!
|
||||
\brief Enables/Disables OpenGL
|
||||
*/
|
||||
@ -174,7 +183,6 @@ void PFDGadgetWidget::connectNeedles() {
|
||||
qDebug() << "Error: Object is unknown (FlightBatteryState).";
|
||||
}
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
|
||||
@ -229,6 +237,7 @@ void PFDGadgetWidget::updateLinkStatus(UAVObject *object1) {
|
||||
Resolution is 1 degree roll & 1/7.5 degree pitch.
|
||||
*/
|
||||
void PFDGadgetWidget::updateAttitude(UAVObject *object1) {
|
||||
setToolTipPrivate();
|
||||
UAVObjectField * rollField = object1->getField(QString("Roll"));
|
||||
UAVObjectField * yawField = object1->getField(QString("Yaw"));
|
||||
UAVObjectField * pitchField = object1->getField(QString("Pitch"));
|
||||
|
@ -54,6 +54,7 @@ public:
|
||||
void setHqFonts(bool flag) { hqFonts = flag; }
|
||||
void enableSmoothUpdates(bool flag) { beSmooth = flag; }
|
||||
|
||||
|
||||
public slots:
|
||||
void updateAttitude(UAVObject *object1);
|
||||
void updateHeading(UAVObject *object1);
|
||||
@ -72,7 +73,7 @@ private slots:
|
||||
void moveNeedles();
|
||||
void moveVerticalScales();
|
||||
void moveSky();
|
||||
|
||||
void setToolTipPrivate();
|
||||
private:
|
||||
QSvgRenderer *m_renderer;
|
||||
|
||||
|
@ -7,9 +7,11 @@ HEADERS += rawhid_global.h \
|
||||
rawhid.h \
|
||||
pjrc_rawhid.h \
|
||||
rawhid_const.h \
|
||||
usbmonitor.h
|
||||
usbmonitor.h \
|
||||
usbsignalfilter.h
|
||||
SOURCES += rawhidplugin.cpp \
|
||||
rawhid.cpp
|
||||
rawhid.cpp \
|
||||
usbsignalfilter.cpp
|
||||
FORMS +=
|
||||
RESOURCES +=
|
||||
DEFINES += RAWHID_LIBRARY
|
||||
|
@ -31,7 +31,7 @@
|
||||
#include "rawhid_global.h"
|
||||
#include "rawhid.h"
|
||||
#include "usbmonitor.h"
|
||||
|
||||
#include "usbsignalfilter.h"
|
||||
#include "coreplugin/iconnection.h"
|
||||
#include <extensionsystem/iplugin.h>
|
||||
|
||||
|
@ -202,5 +202,4 @@ private:
|
||||
#endif
|
||||
|
||||
};
|
||||
|
||||
#endif // USBMONITOR_H
|
||||
|
@ -28,7 +28,8 @@
|
||||
#include <QMetaType>
|
||||
#include <QString>
|
||||
#include <initguid.h>
|
||||
|
||||
#include <QEventLoop>
|
||||
#include <QTimer>
|
||||
#include "usbmonitor.h"
|
||||
#include <QDebug>
|
||||
#define printf qDebug
|
||||
@ -77,14 +78,32 @@ USBMonitor::~USBMonitor()
|
||||
QList<USBPortInfo> USBMonitor::availableDevices(int vid, int pid, int bcdDeviceMSB, int bcdDeviceLSB)
|
||||
{
|
||||
QList<USBPortInfo> allPorts = availableDevices();
|
||||
qDebug()<<"USBMonitor::availableDevices list off all ports:";
|
||||
qDebug()<<"USBMonitor::availableDevices total ports:"<<allPorts.length();
|
||||
foreach (USBPortInfo info, allPorts) {
|
||||
qDebug()<<"----------";
|
||||
qDebug()<<"bcdDevice:"<<info.bcdDevice;
|
||||
qDebug()<<"devicePath:"<<info.devicePath;
|
||||
qDebug()<<"product:"<<info.product;
|
||||
}
|
||||
qDebug()<<"END OF LIST";
|
||||
QList<USBPortInfo> thePortsWeWant;
|
||||
|
||||
qDebug()<<"USBMonitor::availableDevices bcdLSB="<<bcdDeviceLSB;
|
||||
foreach (USBPortInfo port, allPorts) {
|
||||
//qDebug()<<"USBMonitorWin:Port VID="<<port.vendorID<<"PID="<<port.productID<<"bcddevice="<<port.bcdDevice;
|
||||
qDebug()<<"USBMonitorWin:Port VID="<<port.vendorID<<"PID="<<port.productID<<"bcddevice="<<port.bcdDevice;
|
||||
if((port.vendorID==vid || vid==-1) && (port.productID==pid || pid==-1) && ((port.bcdDevice>>8)==bcdDeviceMSB || bcdDeviceMSB==-1) &&
|
||||
( (port.bcdDevice&0x00ff) ==bcdDeviceLSB || bcdDeviceLSB==-1))
|
||||
thePortsWeWant.append(port);
|
||||
}
|
||||
qDebug()<<"USBMonitor::availableDevices list off matching ports vid pid bcdMSD bcdLSD:"<<vid<<pid<<bcdDeviceMSB<<bcdDeviceLSB;
|
||||
qDebug()<<"USBMonitor::availableDevices total matching ports:"<<thePortsWeWant.length();
|
||||
foreach (USBPortInfo info, thePortsWeWant) {
|
||||
qDebug()<<"----------";
|
||||
qDebug()<<"bcdDevice:"<<info.bcdDevice;
|
||||
qDebug()<<"devicePath:"<<info.devicePath;
|
||||
qDebug()<<"product:"<<info.product;
|
||||
}
|
||||
qDebug()<<"END OF LIST";
|
||||
return thePortsWeWant;
|
||||
}
|
||||
|
||||
@ -159,6 +178,7 @@ bool USBRegistrationWidget::winEvent( MSG* message, long* result )
|
||||
#endif
|
||||
bool USBMonitor::matchAndDispatchChangedDevice(const QString & deviceID, const GUID & guid, WPARAM wParam)
|
||||
{
|
||||
qDebug()<<"USB_MONITOR matchAndDispatchChangedDevice deviceID="<<deviceID;
|
||||
bool rv = false;
|
||||
DWORD dwFlag = (DBT_DEVICEARRIVAL == wParam) ? DIGCF_PRESENT : DIGCF_ALLCLASSES;
|
||||
HDEVINFO devInfo;
|
||||
@ -177,10 +197,30 @@ bool USBMonitor::matchAndDispatchChangedDevice(const QString & deviceID, const G
|
||||
info.devicePath=deviceID;
|
||||
if( wParam == DBT_DEVICEARRIVAL )
|
||||
{
|
||||
qDebug()<<"INSERTION";
|
||||
if(infoFromHandle(guid,info,devInfo,i)==0)
|
||||
qDebug()<<"USB_MONITOR INSERTION";
|
||||
if(infoFromHandle(guid,info,devInfo,i)!=1)
|
||||
{
|
||||
qDebug()<<"USB_MONITOR infoFromHandle failed on matchAndDispatchChangedDevice";
|
||||
break;
|
||||
}
|
||||
bool m_break=false;
|
||||
foreach (USBPortInfo m_info, knowndevices) {
|
||||
if(m_info.serialNumber==info.serialNumber && m_info.productID==info.productID && m_info.bcdDevice==info.bcdDevice && m_info.devicePath==info.devicePath)
|
||||
{
|
||||
qDebug()<<"USB_MONITOR device already present don't emit signal";
|
||||
m_break=true;
|
||||
}
|
||||
|
||||
}
|
||||
if(m_break)
|
||||
break;
|
||||
if(info.bcdDevice==0 || info.product.isEmpty())
|
||||
{
|
||||
qDebug()<<"USB_MONITOR empty information on device not emiting signal";
|
||||
break;
|
||||
}
|
||||
knowndevices.append(info);
|
||||
qDebug()<<"USB_MONITOR emit device discovered on device:"<<info.product<<info.bcdDevice;
|
||||
emit deviceDiscovered(info);
|
||||
break;
|
||||
|
||||
@ -193,13 +233,18 @@ bool USBMonitor::matchAndDispatchChangedDevice(const QString & deviceID, const G
|
||||
if(knowndevices[x].devicePath==deviceID)
|
||||
{
|
||||
USBPortInfo temp=knowndevices.at(x);
|
||||
knowndevices.removeAt(x);
|
||||
qDebug()<<"USB_MONITOR emit device removed on device:"<<temp.product<<temp.bcdDevice;
|
||||
emit deviceRemoved(temp);
|
||||
found=true;
|
||||
break;
|
||||
}
|
||||
}
|
||||
if(!found)
|
||||
{
|
||||
qDebug()<<"USB_MONITOR emit device removed on unknown device";
|
||||
emit deviceRemoved(info);
|
||||
}
|
||||
}
|
||||
break;
|
||||
|
||||
|
22
ground/openpilotgcs/src/plugins/rawhid/usbsignalfilter.cpp
Normal file
@ -0,0 +1,22 @@
|
||||
#include "usbsignalfilter.h"
|
||||
#include <QDebug>
|
||||
void USBSignalFilter::m_deviceDiscovered(USBPortInfo port)
|
||||
{
|
||||
if((port.vendorID==m_vid || m_vid==-1) && (port.productID==m_pid || m_pid==-1) && ((port.bcdDevice>>8)==m_boardModel || m_boardModel==-1) &&
|
||||
( (port.bcdDevice&0x00ff) ==m_runState || m_runState==-1))
|
||||
{
|
||||
qDebug()<<"USBSignalFilter emit device discovered";
|
||||
emit deviceDiscovered();
|
||||
}
|
||||
}
|
||||
|
||||
USBSignalFilter::USBSignalFilter(int vid, int pid, int boardModel, int runState):
|
||||
m_vid(vid),
|
||||
m_pid(pid),
|
||||
m_boardModel(boardModel),
|
||||
m_runState(runState)
|
||||
{
|
||||
connect(USBMonitor::instance(),SIGNAL(deviceDiscovered(USBPortInfo)),this,SLOT(m_deviceDiscovered(USBPortInfo)));
|
||||
}
|
||||
|
||||
|
21
ground/openpilotgcs/src/plugins/rawhid/usbsignalfilter.h
Normal file
@ -0,0 +1,21 @@
|
||||
#ifndef USBSIGNALFILTER_H
|
||||
#define USBSIGNALFILTER_H
|
||||
#include <QObject>
|
||||
#include "usbmonitor.h"
|
||||
|
||||
class RAWHID_EXPORT USBSignalFilter : public QObject
|
||||
{
|
||||
Q_OBJECT
|
||||
private:
|
||||
int m_vid;
|
||||
int m_pid;
|
||||
int m_boardModel;
|
||||
int m_runState;
|
||||
signals:
|
||||
void deviceDiscovered();
|
||||
private slots:
|
||||
void m_deviceDiscovered(USBPortInfo port);
|
||||
public:
|
||||
USBSignalFilter(int vid, int pid, int boardModel, int runState);
|
||||
};
|
||||
#endif // USBSIGNALFILTER_H
|
@ -709,7 +709,7 @@ int ScopeGadgetWidget::csvLoggingInsertData()
|
||||
}
|
||||
else
|
||||
{
|
||||
ss << QString().sprintf("%3.6g",plotData2->yData->last()/pow(10,plotData2->scalePower));
|
||||
ss << QString().sprintf("%3.6g",plotData2->yData->last());
|
||||
m_csvLoggingDataValid=1;
|
||||
}
|
||||
}
|
||||
|
@ -492,6 +492,45 @@ QVariant UAVObjectField::getValue(quint32 index)
|
||||
return QVariant();
|
||||
}
|
||||
|
||||
bool UAVObjectField::checkValue(const QVariant& value, quint32 index)
|
||||
{
|
||||
QMutexLocker locker(obj->getMutex());
|
||||
// Check that index is not out of bounds
|
||||
if ( index >= numElements )
|
||||
{
|
||||
return false;
|
||||
}
|
||||
// Get metadata
|
||||
UAVObject::Metadata mdata = obj->getMetadata();
|
||||
// Update value if the access mode permits
|
||||
if ( mdata.gcsAccess == UAVObject::ACCESS_READWRITE )
|
||||
{
|
||||
switch (type)
|
||||
{
|
||||
case INT8:
|
||||
case INT16:
|
||||
case INT32:
|
||||
case UINT8:
|
||||
case UINT16:
|
||||
case UINT32:
|
||||
case FLOAT32:
|
||||
case STRING:
|
||||
return true;
|
||||
break;
|
||||
case ENUM:
|
||||
{
|
||||
qint8 tmpenum = options.indexOf( value.toString() );
|
||||
return ((tmpenum < 0) ? false : true);
|
||||
break;
|
||||
}
|
||||
default:
|
||||
qDebug() << "checkValue: other types" << type;
|
||||
Q_ASSERT(0); // To catch any programming errors where we tried to test invalid values
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void UAVObjectField::setValue(const QVariant& value, quint32 index)
|
||||
{
|
||||
QMutexLocker locker(obj->getMutex());
|
||||
|
@ -56,6 +56,7 @@ public:
|
||||
qint32 pack(quint8* dataOut);
|
||||
qint32 unpack(const quint8* dataIn);
|
||||
QVariant getValue(quint32 index = 0);
|
||||
bool checkValue(const QVariant& data, quint32 index = 0);
|
||||
void setValue(const QVariant& data, quint32 index = 0);
|
||||
double getDouble(quint32 index = 0);
|
||||
void setDouble(double value, quint32 index = 0);
|
||||
|
@ -1,17 +1,19 @@
|
||||
function [] = OPLogConvert()
|
||||
function [] = OPLogConvert(logfile)
|
||||
%% Define indices and arrays of structures to hold data
|
||||
% THIS FILE IS AUTOMATICALLY GENERATED.
|
||||
$(ALLOCATIONCODE)
|
||||
|
||||
%% Open log file
|
||||
% [FileName,PathName,FilterIndex] = uigetfile('*.opl');
|
||||
if nargin==0
|
||||
%%
|
||||
if (exist('uigetfile'))
|
||||
[FileName, PathName]=uigetfile;
|
||||
logfile=fullfile(PathName, FileName);
|
||||
|
||||
else
|
||||
error('Your technical computing program does not support file choosers. Please input the file name in the argument. ')
|
||||
end
|
||||
end
|
||||
|
||||
FileName='OP-2011-10-22_22-27-09.opl';
|
||||
PathName='/Users/kenz/Movies/brisk_videos/rover_test_1/';
|
||||
FilterIndex=1;
|
||||
|
||||
|
||||
logfile = fullfile(PathName,FileName);
|
||||
fid = fopen(logfile);
|
||||
|
||||
% Parse log file, entry by entry
|
||||
@ -55,6 +57,9 @@ end
|
||||
%% Clean Up and Save mat file
|
||||
fclose(fid);
|
||||
|
||||
% Trim output structs
|
||||
$(CLEANUPCODE)
|
||||
|
||||
matfile = strrep(logfile,'opl','mat');
|
||||
save(matfile $(SAVEOBJECTSCODE));
|
||||
|
||||
|
@ -34,7 +34,6 @@
|
||||
#include <QDebug>
|
||||
#include <QEventLoop>
|
||||
#include <QTimer>
|
||||
#include <QErrorMessage>
|
||||
#include <objectpersistence.h>
|
||||
|
||||
// ******************************
|
||||
@ -186,11 +185,6 @@ void UAVObjectUtilManager::objectPersistenceOperationFailed()
|
||||
saveState = IDLE;
|
||||
emit saveCompleted(obj->getObjID(), false);
|
||||
|
||||
// For now cause error message here to make sure user knows
|
||||
QErrorMessage err;
|
||||
err.showMessage("Saving object " + obj->getName() + " failed. Please try again");
|
||||
err.exec();
|
||||
|
||||
saveNextObject();
|
||||
}
|
||||
|
||||
|
@ -153,6 +153,7 @@ void UAVSettingsImportExportFactory::importUAVSettings()
|
||||
// - Update each field
|
||||
// - Issue and "updated" command
|
||||
bool error=false;
|
||||
bool setError=false;
|
||||
QDomNode field = node.firstChild();
|
||||
while(!field.isNull()) {
|
||||
QDomElement f = field.toElement();
|
||||
@ -161,16 +162,24 @@ void UAVSettingsImportExportFactory::importUAVSettings()
|
||||
if (uavfield) {
|
||||
QStringList list = f.attribute("values").split(",");
|
||||
if (list.length() == 1) {
|
||||
uavfield->setValue(f.attribute("values"));
|
||||
if (false == uavfield->checkValue(f.attribute("values"))) {
|
||||
qDebug() << "checkValue returned false on: " << uavObjectName << f.attribute("values");
|
||||
setError = true;
|
||||
} else
|
||||
uavfield->setValue(f.attribute("values"));
|
||||
} else {
|
||||
// This is an enum:
|
||||
int i=0;
|
||||
QStringList list = f.attribute("values").split(",");
|
||||
foreach (QString element, list) {
|
||||
uavfield->setValue(element,i++);
|
||||
if (false == uavfield->checkValue(element,i)) {
|
||||
qDebug() << "checkValue(list) returned false on: " << uavObjectName << list;
|
||||
setError = true;
|
||||
} else
|
||||
uavfield->setValue(element,i);
|
||||
i++;
|
||||
}
|
||||
}
|
||||
error = false;
|
||||
} else {
|
||||
error = true;
|
||||
}
|
||||
@ -183,7 +192,9 @@ void UAVSettingsImportExportFactory::importUAVSettings()
|
||||
} else if (uavObjectID != obj->getObjID()) {
|
||||
qDebug() << "Mismatch for Object " << uavObjectName << uavObjectID << " - " << obj->getObjID();
|
||||
swui.addLine(uavObjectName, "Warning (ObjectID mismatch)", true);
|
||||
} else
|
||||
} else if (setError) {
|
||||
swui.addLine(uavObjectName, "Warning (Objects field value(s) invalid)", false);
|
||||
} else
|
||||
swui.addLine(uavObjectName, "OK", true);
|
||||
}
|
||||
}
|
||||
@ -212,8 +223,9 @@ QString UAVSettingsImportExportFactory::createXMLDocument(
|
||||
QDomElement fw=doc.createElement("Embedded");
|
||||
UAVObjectUtilManager* utilMngr = pm->getObject<UAVObjectUtilManager>();
|
||||
|
||||
fw.setAttribute("gitcommittag",utilMngr->getBoardDescriptionStruct().gitTag);
|
||||
fw.setAttribute("fwtag",utilMngr->getBoardDescriptionStruct().description);
|
||||
deviceDescriptorStruct struc=utilMngr->getBoardDescriptionStruct();
|
||||
fw.setAttribute("gitcommittag",struc.gitTag);
|
||||
fw.setAttribute("fwtag",struc.description);
|
||||
fw.setAttribute("cpuSerial",QString(utilMngr->getBoardCPUSerial().toHex()));
|
||||
|
||||
versionInfo.appendChild(fw);
|
||||
|
@ -183,7 +183,7 @@ bool deviceWidget::populateBoardStructuredDescription(QByteArray desc)
|
||||
if(UAVObjectUtilManager::descriptionToStructure(desc,&onBoardDescrition))
|
||||
{
|
||||
myDevice->lblGitTag->setText(onBoardDescrition.gitTag);
|
||||
myDevice->lblBuildDate->setText(onBoardDescrition.buildDate);
|
||||
myDevice->lblBuildDate->setText(onBoardDescrition.buildDate.insert(4,"-").insert(7,"-"));
|
||||
if(onBoardDescrition.description.startsWith("release",Qt::CaseInsensitive))
|
||||
{
|
||||
myDevice->lblDescription->setText(QString("Firmware tag: ")+onBoardDescrition.description);
|
||||
@ -213,7 +213,7 @@ bool deviceWidget::populateLoadedStructuredDescription(QByteArray desc)
|
||||
if(UAVObjectUtilManager::descriptionToStructure(desc,&LoadedDescrition))
|
||||
{
|
||||
myDevice->lblGitTagL->setText(LoadedDescrition.gitTag);
|
||||
myDevice->lblBuildDateL->setText( LoadedDescrition.buildDate);
|
||||
myDevice->lblBuildDateL->setText( LoadedDescrition.buildDate.insert(4,"-").insert(7,"-"));
|
||||
if(LoadedDescrition.description.startsWith("release",Qt::CaseInsensitive))
|
||||
{
|
||||
myDevice->lblDescritpionL->setText(LoadedDescrition.description);
|
||||
|
@ -80,24 +80,41 @@ DFUObject::DFUObject(bool _debug,bool _use_serial,QString portname):
|
||||
}
|
||||
else
|
||||
{
|
||||
mready = false;
|
||||
QEventLoop m_eventloop;
|
||||
QTimer::singleShot(200,&m_eventloop, SLOT(quit()));
|
||||
m_eventloop.exec();
|
||||
QList<USBPortInfo> devices;
|
||||
devices = USBMonitor::instance()->availableDevices(0x20a0,-1,-1,USBMonitor::Bootloader);
|
||||
if (devices.length()==1) {
|
||||
hidHandle.open(1,devices.first().vendorID,devices.first().productID,0,0);
|
||||
if (devices.length()==1 && hidHandle.open(1,devices.first().vendorID,devices.first().productID,0,0)==1) {
|
||||
qDebug()<<"OP_DFU detected first time";
|
||||
mready=true;
|
||||
} else {
|
||||
// Wait for the board to appear on the USB bus:
|
||||
QEventLoop m_eventloop;
|
||||
connect(USBMonitor::instance(), SIGNAL(deviceDiscovered(USBPortInfo)),&m_eventloop, SLOT(quit()));
|
||||
QTimer::singleShot(5000,&m_eventloop, SLOT(quit()));
|
||||
m_eventloop.exec();
|
||||
devices = USBMonitor::instance()->availableDevices(0x20a0,-1,-1,USBMonitor::Bootloader);
|
||||
if (devices.length()==1) {
|
||||
delay::msleep(2000); // Let the USB Subsystem settle (especially important on Mac!)
|
||||
hidHandle.open(1,devices.first().vendorID,devices.first().productID,0,0);
|
||||
}
|
||||
else {
|
||||
qDebug() << devices.length() << " device(s) detected, don't know what to do!";
|
||||
mready = false;
|
||||
USBSignalFilter filter(0x20a0,-1,-1,USBMonitor::Bootloader);
|
||||
connect(&filter, SIGNAL(deviceDiscovered()),&m_eventloop, SLOT(quit()));
|
||||
for(int x=0;x<4;++x)
|
||||
{
|
||||
qDebug()<<"OP_DFU trying to detect bootloader:"<<x;
|
||||
|
||||
if(x==0)
|
||||
QTimer::singleShot(10000,&m_eventloop, SLOT(quit()));
|
||||
else
|
||||
QTimer::singleShot(2000,&m_eventloop, SLOT(quit()));
|
||||
m_eventloop.exec();
|
||||
devices = USBMonitor::instance()->availableDevices(0x20a0,-1,-1,USBMonitor::Bootloader);
|
||||
if (devices.length()==1) {
|
||||
if(hidHandle.open(1,devices.first().vendorID,devices.first().productID,0,0)==1)
|
||||
{
|
||||
qDebug()<<"OP_DFU detected after delay";
|
||||
mready=true;
|
||||
break;
|
||||
}
|
||||
}
|
||||
else {
|
||||
qDebug() << devices.length() << " device(s) detected, don't know what to do!";
|
||||
mready = false;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -4,6 +4,7 @@
|
||||
#include <QByteArray>
|
||||
#include <rawhid/pjrc_rawhid.h>
|
||||
#include <rawhid/usbmonitor.h>
|
||||
#include <rawhid/usbsignalfilter.h>
|
||||
#include <QDebug>
|
||||
#include <QFile>
|
||||
#include <QThread>
|
||||
|
@ -128,7 +128,7 @@ void runningDeviceWidget::populate()
|
||||
myDevice->lblCertified->setToolTip(tr("Untagged or custom firmware build"));
|
||||
}
|
||||
myDevice->lblGitCommitTag->setText("Git commit tag: "+devDesc.gitTag);
|
||||
myDevice->lblFWDate->setText(QString("Firmware date: ") + devDesc.buildDate);
|
||||
myDevice->lblFWDate->setText(QString("Firmware date: ") + devDesc.buildDate.insert(4,"-").insert(7,"-"));
|
||||
}
|
||||
else
|
||||
{
|
||||
|
@ -25,6 +25,9 @@
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
#include "uploadergadgetwidget.h"
|
||||
#include "../../../../../build/ground/openpilotgcs/gcsversioninfo.h"
|
||||
#include <coreplugin/coreconstants.h>
|
||||
#include <QDebug>
|
||||
|
||||
#define DFU_DEBUG true
|
||||
|
||||
@ -37,11 +40,13 @@ UploaderGadgetWidget::UploaderGadgetWidget(QWidget *parent) : QWidget(parent)
|
||||
dfu = NULL;
|
||||
m_timer = 0;
|
||||
m_progress = 0;
|
||||
|
||||
msg=new QErrorMessage(this);
|
||||
// Listen to autopilot connection events
|
||||
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
|
||||
TelemetryManager* telMngr = pm->getObject<TelemetryManager>();
|
||||
connect(telMngr, SIGNAL(connected()), this, SLOT(onAutopilotConnect()));
|
||||
connect(telMngr, SIGNAL(connected()), this, SLOT(versionMatchCheck()));
|
||||
|
||||
connect(telMngr, SIGNAL(disconnected()), this, SLOT(onAutopilotDisconnect()));
|
||||
|
||||
connect(m_config->haltButton, SIGNAL(clicked()), this, SLOT(goToBootloader()));
|
||||
@ -60,7 +65,10 @@ UploaderGadgetWidget::UploaderGadgetWidget(QWidget *parent) : QWidget(parent)
|
||||
|
||||
// And check whether by any chance we are not already connected
|
||||
if (telMngr->isConnected())
|
||||
{
|
||||
onAutopilotConnect();
|
||||
versionMatchCheck();
|
||||
}
|
||||
|
||||
|
||||
}
|
||||
@ -117,6 +125,11 @@ void UploaderGadgetWidget::onPhisicalHWConnect()
|
||||
Enables widget buttons if autopilot connected
|
||||
*/
|
||||
void UploaderGadgetWidget::onAutopilotConnect(){
|
||||
QTimer::singleShot(1000,this,SLOT(populate()));
|
||||
}
|
||||
|
||||
void UploaderGadgetWidget::populate()
|
||||
{
|
||||
m_config->haltButton->setEnabled(true);
|
||||
m_config->resetButton->setEnabled(true);
|
||||
m_config->bootButton->setEnabled(false);
|
||||
@ -133,7 +146,6 @@ void UploaderGadgetWidget::onAutopilotConnect(){
|
||||
runningDeviceWidget* dw = new runningDeviceWidget(this);
|
||||
dw->populate();
|
||||
m_config->systemElements->addTab(dw, QString("Connected Device"));
|
||||
|
||||
}
|
||||
|
||||
/**
|
||||
@ -603,3 +615,22 @@ void UploaderGadgetWidget::info(QString infoString, int infoNumber)
|
||||
Q_UNUSED(infoNumber);
|
||||
m_config->boardStatus->setText(infoString);
|
||||
}
|
||||
|
||||
void UploaderGadgetWidget::versionMatchCheck()
|
||||
{
|
||||
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
|
||||
UAVObjectUtilManager* utilMngr = pm->getObject<UAVObjectUtilManager>();
|
||||
deviceDescriptorStruct boardDescription=utilMngr->getBoardDescriptionStruct();
|
||||
QString gcsDescription=QString::fromLatin1(Core::Constants::GCS_REVISION_STR);
|
||||
if(boardDescription.gitTag!=gcsDescription.mid(gcsDescription.indexOf(":")+1,8))
|
||||
{
|
||||
qDebug()<<QDate::fromString(boardDescription.buildDate.mid(0,8),"yyyyMMdd");
|
||||
qDebug()<<QDate::fromString(gcsDescription.mid(gcsDescription.indexOf(" ")+1,8),"yyyyMMdd");
|
||||
qDebug()<<QDate::fromString(boardDescription.buildDate.mid(0,8),"yyyyMMdd").daysTo(QDate::fromString(gcsDescription.mid(gcsDescription.indexOf(" ")+1,8),"yyyyMMdd"));
|
||||
if(QDate::fromString(boardDescription.buildDate.mid(0,8),"yyyyMMdd").daysTo(QDate::fromString(gcsDescription.mid(gcsDescription.indexOf(" ")+1,8),"yyyyMMdd"))>0)
|
||||
msg->showMessage(QString("Incompatible GCS and FW detected, you should upgrade your board's Firmware to %1 version.").arg(gcsDescription));
|
||||
else
|
||||
msg->showMessage(QString("Incompatible GCS and FW detected, you should upgrade your GCS to %1 version.").arg(boardDescription.gitTag+":"+boardDescription.buildDate));
|
||||
|
||||
}
|
||||
}
|
||||
|
@ -54,6 +54,7 @@
|
||||
#include <QTimer>
|
||||
#include "devicedescriptorstruct.h"
|
||||
#include <QProgressDialog>
|
||||
#include <QErrorMessage>
|
||||
|
||||
using namespace OP_DFU;
|
||||
|
||||
@ -72,7 +73,7 @@ public:
|
||||
public slots:
|
||||
void onAutopilotConnect();
|
||||
void onAutopilotDisconnect();
|
||||
|
||||
void populate();
|
||||
private:
|
||||
Ui_UploaderWidget *m_config;
|
||||
DFUObject *dfu;
|
||||
@ -84,8 +85,10 @@ private:
|
||||
QTimer* m_timer;
|
||||
QLineEdit* openFileNameLE;
|
||||
QEventLoop m_eventloop;
|
||||
QErrorMessage * msg;
|
||||
private slots:
|
||||
void onPhisicalHWConnect();
|
||||
void versionMatchCheck();
|
||||
void error(QString errorString,int errorNumber);
|
||||
void info(QString infoString,int infoNumber);
|
||||
void goToBootloader(UAVObject* = NULL, bool = false);
|
||||
|
@ -51,6 +51,7 @@ bool UAVObjectGeneratorMatlab::generate(UAVObjectParser* parser,QString template
|
||||
|
||||
matlabCodeTemplate.replace( QString("$(ALLOCATIONCODE)"), matlabAllocationCode);
|
||||
matlabCodeTemplate.replace( QString("$(SWITCHCODE)"), matlabSwitchCode);
|
||||
matlabCodeTemplate.replace( QString("$(CLEANUPCODE)"), matlabCleanupCode);
|
||||
matlabCodeTemplate.replace( QString("$(SAVEOBJECTSCODE)"), matlabSaveObjectsCode);
|
||||
matlabCodeTemplate.replace( QString("$(FUNCTIONSCODE)"), matlabFunctionsCode);
|
||||
|
||||
@ -103,6 +104,9 @@ bool UAVObjectGeneratorMatlab::process_object(ObjectInfo* info)
|
||||
}
|
||||
else{
|
||||
matlabAllocationCode.append("\t" + objectTableName + "=struct('timestamp', 0");
|
||||
if (!info->isSingleInst) {
|
||||
allocfields.append(",...\n\t\t 'instanceID', 0");
|
||||
}
|
||||
for (int n = 0; n < info->fields.length(); ++n) {
|
||||
// Determine type
|
||||
type = fieldTypeStrMatlab[info->fields[n]->type];
|
||||
@ -124,7 +128,17 @@ bool UAVObjectGeneratorMatlab::process_object(ObjectInfo* info)
|
||||
matlabSwitchCode.append("\t\tcase " + objectTableName.toUpper() + "_OBJID\n");
|
||||
matlabSwitchCode.append("\t\t\t" + objectTableName + "(" + tableIdxName +") = " + functionCall + ";\n");
|
||||
matlabSwitchCode.append("\t\t\t" + tableIdxName + " = " + tableIdxName +" + 1;\n");
|
||||
|
||||
matlabSwitchCode.append("\t\t\tif " + tableIdxName + " > length(" + objectTableName +")\n");
|
||||
matlabSwitchCode.append("\t\t\t\t" + objectTableName + "(" + tableIdxName + "*2+1) = " + objectTableName +"(end);\n");
|
||||
matlabSwitchCode.append("\t\t\t\t" + objectTableName +"(end)=[];\n");
|
||||
matlabSwitchCode.append("\t\t\tend\n");
|
||||
|
||||
|
||||
//=============================================================//
|
||||
// Generate 'Cleanup:' code (will replace the $(CLEANUP) tag) //
|
||||
//=============================================================//
|
||||
matlabCleanupCode.append(objectTableName + "(" + tableIdxName +":end) = [];\n");
|
||||
|
||||
|
||||
//=============================================================================//
|
||||
// Generate objects saving code code (will replace the $(SAVEOBJECTSCODE) tag) //
|
||||
@ -139,13 +153,13 @@ bool UAVObjectGeneratorMatlab::process_object(ObjectInfo* info)
|
||||
//=================================================================//
|
||||
//Generate function description comment
|
||||
matlabFunctionsCode.append("function [" + objectName + "] = " + functionCall + "\n");
|
||||
matlabFunctionsCode.append("\t" + objectName + ".timestamp = timestamp;\n");
|
||||
matlabFunctionsCode.append("\tif " + isSingleInst + "\n");
|
||||
matlabFunctionsCode.append("\t\theaderSize = 8;\n");
|
||||
matlabFunctionsCode.append("\telse\n");
|
||||
matlabFunctionsCode.append("\t\t" + objectName + ".instanceID = fread(fid, 1, 'uint16');\n");
|
||||
matlabFunctionsCode.append("\t\theaderSize = 10;\n");
|
||||
matlabFunctionsCode.append("\tend\n\n");
|
||||
matlabFunctionsCode.append("\t" + objectName + ".timestamp = timestamp;\n");
|
||||
|
||||
// Generate functions code, actual fields of the object
|
||||
QString funcfields;
|
||||
|
@ -38,6 +38,7 @@ private:
|
||||
bool process_object(ObjectInfo* info);
|
||||
QString matlabAllocationCode;
|
||||
QString matlabSwitchCode;
|
||||
QString matlabCleanupCode;
|
||||
QString matlabSaveObjectsCode;
|
||||
QString matlabFunctionsCode;
|
||||
QStringList fieldTypeStrMatlab;
|
||||
|
@ -111,6 +111,11 @@ int UAVObjectParser::getNumBytes(int objIndex)
|
||||
}
|
||||
}
|
||||
|
||||
bool fieldTypeLessThan(const FieldInfo* f1, const FieldInfo* f2)
|
||||
{
|
||||
return f1->numBytes > f2->numBytes;
|
||||
}
|
||||
|
||||
/**
|
||||
* Parse supplied XML file
|
||||
* @param xml The xml text
|
||||
@ -200,6 +205,9 @@ QString UAVObjectParser::parseXML(QString& xml, QString& filename)
|
||||
// Get next element
|
||||
childNode = childNode.nextSibling();
|
||||
}
|
||||
|
||||
// Sort all fields according to size
|
||||
qStableSort(info->fields.begin(), info->fields.end(), fieldTypeLessThan);
|
||||
|
||||
// Make sure that required elements were found
|
||||
if ( !accessFound )
|
||||
|
@ -30,8 +30,10 @@ cp "${ROOT_DIR}/HISTORY.txt" "/Volumes/${VOL_NAME}"
|
||||
|
||||
hdiutil detach ${device}
|
||||
|
||||
echo "Resizing dmg"
|
||||
hdiutil resize -size 250m ${TEMP_FILE}
|
||||
min=`hdiutil resize ${TEMP_FILE} | awk \{print\ \$\1\}`
|
||||
echo "Resizing dmg to ${min}"
|
||||
|
||||
hdiutil resize -sectors ${min} ${TEMP_FILE}
|
||||
hdiutil convert "${TEMP_FILE}" -format UDZO -o "${OUT_FILE}"
|
||||
|
||||
# cleanup
|
||||
|
@ -1,7 +1,7 @@
|
||||
<xml>
|
||||
<object name="HwSettings" singleinstance="true" settings="true">
|
||||
<description>Selection of optional hardware configurations.</description>
|
||||
<field name="CC_RcvrPort" units="function" type="enum" elements="1" options="Disabled,PWM,PPM,PPM+Servo,Servo" defaultvalue="PWM"/>
|
||||
<field name="CC_RcvrPort" units="function" type="enum" elements="1" options="Disabled,PWM,PPM,PPM+Outputs,Outputs" defaultvalue="PWM"/>
|
||||
<field name="CC_MainPort" units="function" type="enum" elements="1" options="Disabled,Telemetry,GPS,S.Bus,DSM2,DSMX (10bit),DSMX (11bit),ComAux" defaultvalue="Disabled"/>
|
||||
<field name="CC_FlexiPort" units="function" type="enum" elements="1" options="Disabled,Telemetry,GPS,I2C,DSM2,DSMX (10bit),DSMX (11bit),ComAux" defaultvalue="Disabled"/>
|
||||
|
||||
|