Merge branch 'AlessioMorale-amorale/LP05-Readd_CC_rebased' into next
3
Makefile
@ -214,9 +214,10 @@ export OPGCSSYNTHDIR := $(BUILD_DIR)/openpilotgcs-synthetics
|
||||
DIRS += $(OPGCSSYNTHDIR)
|
||||
|
||||
# Define supported board lists
|
||||
ALL_BOARDS := oplinkmini revolution osd revoproto simposix discoveryf4bare gpsplatinum revonano
|
||||
ALL_BOARDS := coptercontrol oplinkmini revolution osd revoproto simposix discoveryf4bare gpsplatinum revonano
|
||||
|
||||
# Short names of each board (used to display board name in parallel builds)
|
||||
coptercontrol_short := 'cc '
|
||||
oplinkmini_short := 'oplm'
|
||||
revolution_short := 'revo'
|
||||
osd_short := 'osd '
|
||||
|
@ -105,8 +105,9 @@ static void stabilizationOuterloopTask()
|
||||
int t;
|
||||
float dT = PIOS_DELTATIME_GetAverageSeconds(&timeval);
|
||||
StabilizationStatusOuterLoopOptions newThrustMode = StabilizationStatusOuterLoopToArray(enabled)[STABILIZATIONSTATUS_OUTERLOOP_THRUST];
|
||||
|
||||
bool reinit = (newThrustMode != previous_mode[STABILIZATIONSTATUS_OUTERLOOP_THRUST]);
|
||||
|
||||
#ifndef PIOS_EXCLUDE_ADVANCED_FEATURES
|
||||
// Trigger a disable message to the alt hold on reinit to prevent that loop from running when not in use.
|
||||
if (reinit) {
|
||||
if (previous_mode[STABILIZATIONSTATUS_OUTERLOOP_THRUST] == STABILIZATIONSTATUS_OUTERLOOP_ALTITUDE ||
|
||||
@ -117,17 +118,20 @@ static void stabilizationOuterloopTask()
|
||||
}
|
||||
}
|
||||
}
|
||||
#endif
|
||||
// update previous mode
|
||||
previous_mode[STABILIZATIONSTATUS_OUTERLOOP_THRUST] = newThrustMode;
|
||||
|
||||
// calculate the thrust desired
|
||||
switch (newThrustMode) {
|
||||
#ifndef PIOS_EXCLUDE_ADVANCED_FEATURES
|
||||
case STABILIZATIONSTATUS_OUTERLOOP_ALTITUDE:
|
||||
rateDesiredAxis[STABILIZATIONSTATUS_OUTERLOOP_THRUST] = stabilizationAltitudeHold(stabilizationDesiredAxis[STABILIZATIONSTATUS_OUTERLOOP_THRUST], ALTITUDEHOLD, reinit);
|
||||
break;
|
||||
case STABILIZATIONSTATUS_OUTERLOOP_ALTITUDEVARIO:
|
||||
rateDesiredAxis[STABILIZATIONSTATUS_OUTERLOOP_THRUST] = stabilizationAltitudeHold(stabilizationDesiredAxis[STABILIZATIONSTATUS_OUTERLOOP_THRUST], ALTITUDEVARIO, reinit);
|
||||
break;
|
||||
#endif
|
||||
case STABILIZATIONSTATUS_OUTERLOOP_DIRECT:
|
||||
case STABILIZATIONSTATUS_OUTERLOOP_DIRECTWITHLIMITS:
|
||||
default:
|
||||
|
@ -95,6 +95,9 @@
|
||||
#define STATS_UPDATE_PERIOD_MS 4000
|
||||
#define CONNECTION_TIMEOUT_MS 8000
|
||||
|
||||
#ifdef PIOS_INCLUDE_RFM22B
|
||||
#define HAS_RADIO
|
||||
#endif
|
||||
// Private types
|
||||
typedef struct {
|
||||
// Determine port on which to communicate telemetry information
|
||||
@ -111,12 +114,14 @@ typedef struct {
|
||||
// Telemetry stream
|
||||
UAVTalkConnection uavTalkCon;
|
||||
} channelContext;
|
||||
|
||||
#ifdef HAS_RADIO
|
||||
// Main telemetry channel
|
||||
static channelContext localChannel;
|
||||
static int32_t transmitLocalData(uint8_t *data, int32_t length);
|
||||
static void registerLocalObject(UAVObjHandle obj);
|
||||
static uint32_t localPort();
|
||||
static void updateSettings(channelContext *channel);
|
||||
#endif
|
||||
|
||||
// OPLink telemetry channel
|
||||
static channelContext radioChannel;
|
||||
@ -150,7 +155,6 @@ static int32_t setLoggingPeriod(
|
||||
int32_t updatePeriodMs);
|
||||
static void updateTelemetryStats();
|
||||
static void gcsTelemetryStatsUpdated();
|
||||
static void updateSettings(channelContext *channel);
|
||||
|
||||
/**
|
||||
* Initialise the telemetry module
|
||||
@ -159,6 +163,7 @@ static void updateSettings(channelContext *channel);
|
||||
*/
|
||||
int32_t TelemetryStart(void)
|
||||
{
|
||||
#ifdef HAS_RADIO
|
||||
// Only start the local telemetry tasks if needed
|
||||
if (localPort()) {
|
||||
UAVObjIterate(®isterLocalObject);
|
||||
@ -187,8 +192,8 @@ int32_t TelemetryStart(void)
|
||||
PIOS_TASK_MONITOR_RegisterTask(TASKINFO_RUNNING_TELEMETRYRX,
|
||||
localChannel.rxTaskHandle);
|
||||
}
|
||||
|
||||
// Start the telemetry tasks associated with Radio/USB
|
||||
#endif /* ifdef HAS_RADIO */
|
||||
// Start the telemetry tasks associated with Radio/USB
|
||||
UAVObjIterate(®isterRadioObject);
|
||||
|
||||
// Listen to objects of interest
|
||||
@ -229,9 +234,6 @@ void TelemetryInitializeChannel(channelContext *channel)
|
||||
sizeof(UAVObjEvent));
|
||||
#endif /* PIOS_TELEM_PRIORITY_QUEUE */
|
||||
|
||||
// Initialise UAVTalk
|
||||
channel->uavTalkCon = UAVTalkInitialize(&transmitLocalData);
|
||||
|
||||
// Create periodic event that will be used to update the telemetry stats
|
||||
UAVObjEvent ev;
|
||||
memset(&ev, 0, sizeof(UAVObjEvent));
|
||||
@ -267,7 +269,7 @@ int32_t TelemetryInitialize(void)
|
||||
radio_port = PIOS_COM_RF;
|
||||
}
|
||||
#else /* PIOS_INCLUDE_RFM22B */
|
||||
radio_port = 0;
|
||||
radio_port = PIOS_COM_TELEM_RF;
|
||||
#endif /* PIOS_INCLUDE_RFM22B */
|
||||
|
||||
FlightTelemetryStatsInitialize();
|
||||
@ -279,10 +281,9 @@ int32_t TelemetryInitialize(void)
|
||||
// Reset link stats
|
||||
txErrors = 0;
|
||||
txRetries = 0;
|
||||
|
||||
#ifdef HAS_RADIO
|
||||
// Set channel port handlers
|
||||
localChannel.getPort = localPort;
|
||||
radioChannel.getPort = radioPort;
|
||||
|
||||
// Set the local telemetry baud rate
|
||||
updateSettings(&localChannel);
|
||||
@ -295,6 +296,9 @@ int32_t TelemetryInitialize(void)
|
||||
localChannel.uavTalkCon = UAVTalkInitialize(&transmitLocalData);
|
||||
}
|
||||
|
||||
#endif
|
||||
// Set channel port handlers
|
||||
radioChannel.getPort = radioPort;
|
||||
// Initialise channel
|
||||
TelemetryInitializeChannel(&radioChannel);
|
||||
// Initialise UAVTalk
|
||||
@ -304,7 +308,7 @@ int32_t TelemetryInitialize(void)
|
||||
}
|
||||
|
||||
MODULE_INITCALL(TelemetryInitialize, TelemetryStart);
|
||||
|
||||
#ifdef HAS_RADIO
|
||||
/**
|
||||
* Register a new object, adds object to local list and connects the queue depending on the object's
|
||||
* telemetry settings.
|
||||
@ -327,7 +331,7 @@ static void registerLocalObject(UAVObjHandle obj)
|
||||
EV_NONE);
|
||||
}
|
||||
}
|
||||
|
||||
#endif
|
||||
static void registerRadioObject(UAVObjHandle obj)
|
||||
{
|
||||
if (UAVObjIsMetaobject(obj)) {
|
||||
@ -635,7 +639,7 @@ static void telemetryRxTask(void *parameters)
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
#ifdef HAS_RADIO
|
||||
/**
|
||||
* Determine the port to be used for communication on the telemetry channel
|
||||
* \return com port number
|
||||
@ -644,7 +648,7 @@ static uint32_t localPort()
|
||||
{
|
||||
return PIOS_COM_TELEM_RF;
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Determine the port to be used for communication on the radio channel
|
||||
@ -664,7 +668,7 @@ static uint32_t radioPort()
|
||||
return port;
|
||||
}
|
||||
|
||||
|
||||
#ifdef HAS_RADIO
|
||||
/**
|
||||
* Transmit data buffer to the modem or USB port.
|
||||
* \param[in] data Data buffer to send
|
||||
@ -682,7 +686,7 @@ static int32_t transmitLocalData(uint8_t *data, int32_t length)
|
||||
|
||||
return -1;
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Transmit data buffer to the radioport.
|
||||
@ -804,9 +808,10 @@ static void updateTelemetryStats()
|
||||
uint32_t timeNow;
|
||||
|
||||
// Get stats
|
||||
UAVTalkGetStats(localChannel.uavTalkCon, &utalkStats, true);
|
||||
UAVTalkAddStats(radioChannel.uavTalkCon, &utalkStats, true);
|
||||
|
||||
UAVTalkGetStats(radioChannel.uavTalkCon, &utalkStats, true);
|
||||
#ifdef HAS_RADIO
|
||||
UAVTalkAddStats(localChannel.uavTalkCon, &utalkStats, true);
|
||||
#endif
|
||||
// Get object data
|
||||
FlightTelemetryStatsGet(&flightStats);
|
||||
GCSTelemetryStatsGet(&gcsStats);
|
||||
@ -888,6 +893,7 @@ static void updateTelemetryStats()
|
||||
}
|
||||
}
|
||||
|
||||
#ifdef HAS_RADIO
|
||||
/**
|
||||
* Update the telemetry settings, called on startup.
|
||||
* FIXME: This should be in the TelemetrySettings object. But objects
|
||||
@ -931,7 +937,7 @@ static void updateSettings(channelContext *channel)
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
#endif /* ifdef HAS_RADIO */
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
|
@ -353,6 +353,7 @@ enum usb_cdc_notification {
|
||||
|
||||
enum usb_product_ids {
|
||||
USB_PRODUCT_ID_OPENPILOT_MAIN = 0x415A,
|
||||
USB_PRODUCT_ID_COPTERCONTROL = 0x415B,
|
||||
USB_PRODUCT_ID_OPLINK = 0x415C,
|
||||
USB_PRODUCT_ID_CC3D = 0x415D,
|
||||
USB_PRODUCT_ID_REVOLUTION = 0x415E,
|
||||
@ -363,9 +364,9 @@ enum usb_product_ids {
|
||||
enum usb_op_board_ids {
|
||||
USB_OP_BOARD_ID_OPENPILOT_MAIN = 1,
|
||||
/* Board ID 2 may be unused or AHRS */
|
||||
USB_OP_BOARD_ID_OPLINK = 3,
|
||||
/* USB_OP_BOARD_ID_COPTERCONTROL = 4, */
|
||||
USB_OP_BOARD_ID_REVOLUTION = 5,
|
||||
USB_OP_BOARD_ID_OPLINK = 3,
|
||||
USB_OP_BOARD_ID_COPTERCONTROL = 4,
|
||||
USB_OP_BOARD_ID_REVOLUTION = 5,
|
||||
USB_OP_BOARD_ID_OSD = 6,
|
||||
} __attribute__((packed));
|
||||
|
||||
|
23
flight/targets/boards/coptercontrol/board-info.mk
Normal file
@ -0,0 +1,23 @@
|
||||
BOARD_TYPE := 0x04
|
||||
BOARD_REVISION := 0x02
|
||||
BOOTLOADER_VERSION := 0x04
|
||||
HW_TYPE := 0x01
|
||||
|
||||
MCU := cortex-m3
|
||||
CHIP := STM32F103CBT
|
||||
BOARD := STM32103CB_CC_Rev1
|
||||
MODEL := MD
|
||||
MODEL_SUFFIX := _CC
|
||||
|
||||
OPENOCD_JTAG_CONFIG := foss-jtag.revb.cfg
|
||||
OPENOCD_CONFIG := stm32f1x.cfg
|
||||
|
||||
# Note: These must match the values in link_$(BOARD)_memory.ld
|
||||
BL_BANK_BASE := 0x08000000 # Start of bootloader flash
|
||||
BL_BANK_SIZE := 0x00003000 # Should include BD_INFO region
|
||||
FW_BANK_BASE := 0x08003000 # Start of firmware flash
|
||||
FW_BANK_SIZE := 0x0001D000 # Should include FW_DESC_SIZE
|
||||
|
||||
FW_DESC_SIZE := 0x00000064
|
||||
|
||||
OSCILLATOR_FREQ := 8000000
|
1525
flight/targets/boards/coptercontrol/board_hw_defs.c
Normal file
@ -0,0 +1,1525 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @file board_hw_defs.c
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @author PhoenixPilot, http://github.com/PhoenixPilot, Copyright (C) 2012
|
||||
* @addtogroup OpenPilotSystem OpenPilot System
|
||||
* @{
|
||||
* @addtogroup OpenPilotCore OpenPilot Core
|
||||
* @{
|
||||
* @brief Defines board specific static initializers for hardware for the CopterControl board.
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* 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
|
||||
*/
|
||||
|
||||
#define BOARD_REVISION_CC 1
|
||||
#define BOARD_REVISION_CC3D 2
|
||||
|
||||
#if defined(PIOS_INCLUDE_LED)
|
||||
|
||||
#include <pios_led_priv.h>
|
||||
static const struct pios_gpio pios_leds_cc[] = {
|
||||
[PIOS_LED_HEARTBEAT] = {
|
||||
.pin = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_6,
|
||||
.GPIO_Mode = GPIO_Mode_Out_PP,
|
||||
.GPIO_Speed = GPIO_Speed_50MHz,
|
||||
},
|
||||
},
|
||||
.active_low = true
|
||||
},
|
||||
};
|
||||
|
||||
static const struct pios_gpio_cfg pios_led_cfg_cc = {
|
||||
.gpios = pios_leds_cc,
|
||||
.num_gpios = NELEMENTS(pios_leds_cc),
|
||||
};
|
||||
|
||||
static const struct pios_gpio pios_leds_cc3d[] = {
|
||||
[PIOS_LED_HEARTBEAT] = {
|
||||
.pin = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_3,
|
||||
.GPIO_Mode = GPIO_Mode_Out_PP,
|
||||
.GPIO_Speed = GPIO_Speed_50MHz,
|
||||
},
|
||||
},
|
||||
.remap = GPIO_Remap_SWJ_JTAGDisable,
|
||||
.active_low = true
|
||||
},
|
||||
};
|
||||
|
||||
static const struct pios_gpio_cfg pios_led_cfg_cc3d = {
|
||||
.gpios = pios_leds_cc3d,
|
||||
.num_gpios = NELEMENTS(pios_leds_cc3d),
|
||||
};
|
||||
|
||||
const struct pios_gpio_cfg *PIOS_BOARD_HW_DEFS_GetLedCfg(uint32_t board_revision)
|
||||
{
|
||||
switch (board_revision) {
|
||||
case BOARD_REVISION_CC: return &pios_led_cfg_cc;
|
||||
|
||||
case BOARD_REVISION_CC3D: return &pios_led_cfg_cc3d;
|
||||
|
||||
default: return NULL;
|
||||
}
|
||||
}
|
||||
|
||||
#endif /* PIOS_INCLUDE_LED */
|
||||
|
||||
#if defined(PIOS_INCLUDE_SPI)
|
||||
|
||||
#include <pios_spi_priv.h>
|
||||
|
||||
/* Gyro interface */
|
||||
void PIOS_SPI_gyro_irq_handler(void);
|
||||
void DMA1_Channel2_IRQHandler() __attribute__((alias("PIOS_SPI_gyro_irq_handler")));
|
||||
void DMA1_Channel3_IRQHandler() __attribute__((alias("PIOS_SPI_gyro_irq_handler")));
|
||||
static const struct pios_spi_cfg pios_spi_gyro_cfg = {
|
||||
.regs = SPI1,
|
||||
.init = {
|
||||
.SPI_Mode = SPI_Mode_Master,
|
||||
.SPI_Direction = SPI_Direction_2Lines_FullDuplex,
|
||||
.SPI_DataSize = SPI_DataSize_8b,
|
||||
.SPI_NSS = SPI_NSS_Soft,
|
||||
.SPI_FirstBit = SPI_FirstBit_MSB,
|
||||
.SPI_CRCPolynomial = 7,
|
||||
.SPI_CPOL = SPI_CPOL_High,
|
||||
.SPI_CPHA = SPI_CPHA_2Edge,
|
||||
.SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_16, /* 10 Mhz */
|
||||
},
|
||||
.use_crc = false,
|
||||
.dma = {
|
||||
.ahb_clk = RCC_AHBPeriph_DMA1,
|
||||
|
||||
.irq = {
|
||||
.flags = (DMA1_FLAG_TC2 | DMA1_FLAG_TE2 | DMA1_FLAG_HT2 | DMA1_FLAG_GL2),
|
||||
.init = {
|
||||
.NVIC_IRQChannel = DMA1_Channel2_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
|
||||
.rx = {
|
||||
.channel = DMA1_Channel2,
|
||||
.init = {
|
||||
.DMA_PeripheralBaseAddr = (uint32_t)&(SPI1->DR),
|
||||
.DMA_DIR = DMA_DIR_PeripheralSRC,
|
||||
.DMA_PeripheralInc = DMA_PeripheralInc_Disable,
|
||||
.DMA_MemoryInc = DMA_MemoryInc_Enable,
|
||||
.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte,
|
||||
.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte,
|
||||
.DMA_Mode = DMA_Mode_Normal,
|
||||
.DMA_Priority = DMA_Priority_Medium,
|
||||
.DMA_M2M = DMA_M2M_Disable,
|
||||
},
|
||||
},
|
||||
.tx = {
|
||||
.channel = DMA1_Channel3,
|
||||
.init = {
|
||||
.DMA_PeripheralBaseAddr = (uint32_t)&(SPI1->DR),
|
||||
.DMA_DIR = DMA_DIR_PeripheralDST,
|
||||
.DMA_PeripheralInc = DMA_PeripheralInc_Disable,
|
||||
.DMA_MemoryInc = DMA_MemoryInc_Enable,
|
||||
.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte,
|
||||
.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte,
|
||||
.DMA_Mode = DMA_Mode_Normal,
|
||||
.DMA_Priority = DMA_Priority_Medium,
|
||||
.DMA_M2M = DMA_M2M_Disable,
|
||||
},
|
||||
},
|
||||
},
|
||||
.sclk = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_5,
|
||||
.GPIO_Speed = GPIO_Speed_50MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF_PP,
|
||||
},
|
||||
},
|
||||
.miso = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_6,
|
||||
.GPIO_Speed = GPIO_Speed_50MHz,
|
||||
.GPIO_Mode = GPIO_Mode_IPU,
|
||||
},
|
||||
},
|
||||
.mosi = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_7,
|
||||
.GPIO_Speed = GPIO_Speed_50MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF_PP,
|
||||
},
|
||||
},
|
||||
.slave_count = 1,
|
||||
.ssel = {
|
||||
{
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_4,
|
||||
.GPIO_Speed = GPIO_Speed_50MHz,
|
||||
.GPIO_Mode = GPIO_Mode_Out_PP,
|
||||
},
|
||||
}
|
||||
},
|
||||
};
|
||||
|
||||
static uint32_t pios_spi_gyro_id;
|
||||
void PIOS_SPI_gyro_irq_handler(void)
|
||||
{
|
||||
/* Call into the generic code to handle the IRQ for this specific device */
|
||||
PIOS_SPI_IRQ_Handler(pios_spi_gyro_id);
|
||||
}
|
||||
|
||||
|
||||
/* Flash/Accel Interface
|
||||
*
|
||||
* NOTE: Leave this declared as const data so that it ends up in the
|
||||
* .rodata section (ie. Flash) rather than in the .bss section (RAM).
|
||||
*/
|
||||
void PIOS_SPI_flash_accel_irq_handler(void);
|
||||
void DMA1_Channel4_IRQHandler() __attribute__((alias("PIOS_SPI_flash_accel_irq_handler")));
|
||||
void DMA1_Channel5_IRQHandler() __attribute__((alias("PIOS_SPI_flash_accel_irq_handler")));
|
||||
static const struct pios_spi_cfg pios_spi_flash_accel_cfg_cc3d = {
|
||||
.regs = SPI2,
|
||||
.init = {
|
||||
.SPI_Mode = SPI_Mode_Master,
|
||||
.SPI_Direction = SPI_Direction_2Lines_FullDuplex,
|
||||
.SPI_DataSize = SPI_DataSize_8b,
|
||||
.SPI_NSS = SPI_NSS_Soft,
|
||||
.SPI_FirstBit = SPI_FirstBit_MSB,
|
||||
.SPI_CRCPolynomial = 7,
|
||||
.SPI_CPOL = SPI_CPOL_High,
|
||||
.SPI_CPHA = SPI_CPHA_2Edge,
|
||||
.SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_8,
|
||||
},
|
||||
.use_crc = false,
|
||||
.dma = {
|
||||
.ahb_clk = RCC_AHBPeriph_DMA1,
|
||||
|
||||
.irq = {
|
||||
.flags = (DMA1_FLAG_TC4 | DMA1_FLAG_TE4 | DMA1_FLAG_HT4 | DMA1_FLAG_GL4),
|
||||
.init = {
|
||||
.NVIC_IRQChannel = DMA1_Channel4_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
|
||||
.rx = {
|
||||
.channel = DMA1_Channel4,
|
||||
.init = {
|
||||
.DMA_PeripheralBaseAddr = (uint32_t)&(SPI2->DR),
|
||||
.DMA_DIR = DMA_DIR_PeripheralSRC,
|
||||
.DMA_PeripheralInc = DMA_PeripheralInc_Disable,
|
||||
.DMA_MemoryInc = DMA_MemoryInc_Enable,
|
||||
.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte,
|
||||
.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte,
|
||||
.DMA_Mode = DMA_Mode_Normal,
|
||||
.DMA_Priority = DMA_Priority_High,
|
||||
.DMA_M2M = DMA_M2M_Disable,
|
||||
},
|
||||
},
|
||||
.tx = {
|
||||
.channel = DMA1_Channel5,
|
||||
.init = {
|
||||
.DMA_PeripheralBaseAddr = (uint32_t)&(SPI2->DR),
|
||||
.DMA_DIR = DMA_DIR_PeripheralDST,
|
||||
.DMA_PeripheralInc = DMA_PeripheralInc_Disable,
|
||||
.DMA_MemoryInc = DMA_MemoryInc_Enable,
|
||||
.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte,
|
||||
.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte,
|
||||
.DMA_Mode = DMA_Mode_Normal,
|
||||
.DMA_Priority = DMA_Priority_High,
|
||||
.DMA_M2M = DMA_M2M_Disable,
|
||||
},
|
||||
},
|
||||
},
|
||||
.sclk = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_13,
|
||||
.GPIO_Speed = GPIO_Speed_50MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF_PP,
|
||||
},
|
||||
},
|
||||
.miso = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_14,
|
||||
.GPIO_Speed = GPIO_Speed_50MHz,
|
||||
.GPIO_Mode = GPIO_Mode_IN_FLOATING,
|
||||
},
|
||||
},
|
||||
.mosi = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_15,
|
||||
.GPIO_Speed = GPIO_Speed_50MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF_PP,
|
||||
},
|
||||
},
|
||||
.slave_count = 2,
|
||||
.ssel = {
|
||||
{
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_12,
|
||||
.GPIO_Speed = GPIO_Speed_50MHz,
|
||||
.GPIO_Mode = GPIO_Mode_Out_PP,
|
||||
}
|
||||
},{
|
||||
.gpio = GPIOC,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_15,
|
||||
.GPIO_Speed = GPIO_Speed_50MHz,
|
||||
.GPIO_Mode = GPIO_Mode_Out_PP,
|
||||
},
|
||||
}
|
||||
},
|
||||
};
|
||||
|
||||
static const struct pios_spi_cfg pios_spi_flash_accel_cfg_cc = {
|
||||
.regs = SPI2,
|
||||
.init = {
|
||||
.SPI_Mode = SPI_Mode_Master,
|
||||
.SPI_Direction = SPI_Direction_2Lines_FullDuplex,
|
||||
.SPI_DataSize = SPI_DataSize_8b,
|
||||
.SPI_NSS = SPI_NSS_Soft,
|
||||
.SPI_FirstBit = SPI_FirstBit_MSB,
|
||||
.SPI_CRCPolynomial = 7,
|
||||
.SPI_CPOL = SPI_CPOL_High,
|
||||
.SPI_CPHA = SPI_CPHA_2Edge,
|
||||
.SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_8,
|
||||
},
|
||||
.use_crc = false,
|
||||
.dma = {
|
||||
.ahb_clk = RCC_AHBPeriph_DMA1,
|
||||
|
||||
.irq = {
|
||||
.flags = (DMA1_FLAG_TC4 | DMA1_FLAG_TE4 | DMA1_FLAG_HT4 | DMA1_FLAG_GL4),
|
||||
.init = {
|
||||
.NVIC_IRQChannel = DMA1_Channel4_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
|
||||
.rx = {
|
||||
.channel = DMA1_Channel4,
|
||||
.init = {
|
||||
.DMA_PeripheralBaseAddr = (uint32_t)&(SPI2->DR),
|
||||
.DMA_DIR = DMA_DIR_PeripheralSRC,
|
||||
.DMA_PeripheralInc = DMA_PeripheralInc_Disable,
|
||||
.DMA_MemoryInc = DMA_MemoryInc_Enable,
|
||||
.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte,
|
||||
.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte,
|
||||
.DMA_Mode = DMA_Mode_Normal,
|
||||
.DMA_Priority = DMA_Priority_High,
|
||||
.DMA_M2M = DMA_M2M_Disable,
|
||||
},
|
||||
},
|
||||
.tx = {
|
||||
.channel = DMA1_Channel5,
|
||||
.init = {
|
||||
.DMA_PeripheralBaseAddr = (uint32_t)&(SPI2->DR),
|
||||
.DMA_DIR = DMA_DIR_PeripheralDST,
|
||||
.DMA_PeripheralInc = DMA_PeripheralInc_Disable,
|
||||
.DMA_MemoryInc = DMA_MemoryInc_Enable,
|
||||
.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte,
|
||||
.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte,
|
||||
.DMA_Mode = DMA_Mode_Normal,
|
||||
.DMA_Priority = DMA_Priority_High,
|
||||
.DMA_M2M = DMA_M2M_Disable,
|
||||
},
|
||||
},
|
||||
},
|
||||
.sclk = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_13,
|
||||
.GPIO_Speed = GPIO_Speed_50MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF_PP,
|
||||
},
|
||||
},
|
||||
.miso = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_14,
|
||||
.GPIO_Speed = GPIO_Speed_50MHz,
|
||||
.GPIO_Mode = GPIO_Mode_IN_FLOATING,
|
||||
},
|
||||
},
|
||||
.mosi = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_15,
|
||||
.GPIO_Speed = GPIO_Speed_50MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF_PP,
|
||||
},
|
||||
},
|
||||
.slave_count = 2,
|
||||
.ssel = {
|
||||
{
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_12,
|
||||
.GPIO_Speed = GPIO_Speed_50MHz,
|
||||
.GPIO_Mode = GPIO_Mode_Out_PP,
|
||||
}
|
||||
},{
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_7,
|
||||
.GPIO_Speed = GPIO_Speed_50MHz,
|
||||
.GPIO_Mode = GPIO_Mode_Out_PP,
|
||||
},
|
||||
}
|
||||
},
|
||||
};
|
||||
|
||||
static uint32_t pios_spi_flash_accel_id;
|
||||
void PIOS_SPI_flash_accel_irq_handler(void)
|
||||
{
|
||||
/* Call into the generic code to handle the IRQ for this specific device */
|
||||
PIOS_SPI_IRQ_Handler(pios_spi_flash_accel_id);
|
||||
}
|
||||
|
||||
#endif /* PIOS_INCLUDE_SPI */
|
||||
|
||||
#if defined(PIOS_INCLUDE_FLASH)
|
||||
#include "pios_flashfs_logfs_priv.h"
|
||||
#include "pios_flash_jedec_priv.h"
|
||||
|
||||
static const struct flashfs_logfs_cfg flashfs_w25x_cfg = {
|
||||
.fs_magic = 0x99abcdef,
|
||||
.total_fs_size = 0x00080000, /* 512K bytes (128 sectors = entire chip) */
|
||||
.arena_size = 0x00010000, /* 256 * slot size */
|
||||
.slot_size = 0x00000100, /* 256 bytes */
|
||||
|
||||
.start_offset = 0, /* start at the beginning of the chip */
|
||||
.sector_size = 0x00001000, /* 4K bytes */
|
||||
.page_size = 0x00000100, /* 256 bytes */
|
||||
};
|
||||
|
||||
|
||||
static const struct flashfs_logfs_cfg flashfs_m25p_cfg = {
|
||||
.fs_magic = 0x99abceef,
|
||||
.total_fs_size = 0x00200000, /* 2M bytes (32 sectors = entire chip) */
|
||||
.arena_size = 0x00010000, /* 256 * slot size */
|
||||
.slot_size = 0x00000100, /* 256 bytes */
|
||||
|
||||
.start_offset = 0, /* start at the beginning of the chip */
|
||||
.sector_size = 0x00010000, /* 64K bytes */
|
||||
.page_size = 0x00000100, /* 256 bytes */
|
||||
};
|
||||
|
||||
#include "pios_flash.h"
|
||||
|
||||
#endif /* PIOS_INCLUDE_FLASH */
|
||||
|
||||
/*
|
||||
* ADC system
|
||||
*/
|
||||
#if defined(PIOS_INCLUDE_ADC)
|
||||
#include "pios_adc_priv.h"
|
||||
extern void PIOS_ADC_handler(void);
|
||||
void DMA1_Channel1_IRQHandler() __attribute__((alias("PIOS_ADC_handler")));
|
||||
// Remap the ADC DMA handler to this one
|
||||
static const struct pios_adc_cfg pios_adc_cfg = {
|
||||
.dma = {
|
||||
.ahb_clk = RCC_AHBPeriph_DMA1,
|
||||
.irq = {
|
||||
.flags = (DMA1_FLAG_TC1 | DMA1_FLAG_TE1 | DMA1_FLAG_HT1 | DMA1_FLAG_GL1),
|
||||
.init = {
|
||||
.NVIC_IRQChannel = DMA1_Channel1_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
.rx = {
|
||||
.channel = DMA1_Channel1,
|
||||
.init = {
|
||||
.DMA_PeripheralBaseAddr = (uint32_t)&ADC1->DR,
|
||||
.DMA_DIR = DMA_DIR_PeripheralSRC,
|
||||
.DMA_PeripheralInc = DMA_PeripheralInc_Disable,
|
||||
.DMA_MemoryInc = DMA_MemoryInc_Enable,
|
||||
.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Word,
|
||||
.DMA_MemoryDataSize = DMA_MemoryDataSize_Word,
|
||||
.DMA_Mode = DMA_Mode_Circular,
|
||||
.DMA_Priority = DMA_Priority_High,
|
||||
.DMA_M2M = DMA_M2M_Disable,
|
||||
},
|
||||
}
|
||||
},
|
||||
.half_flag = DMA1_IT_HT1,
|
||||
.full_flag = DMA1_IT_TC1,
|
||||
};
|
||||
|
||||
void PIOS_ADC_handler()
|
||||
{
|
||||
PIOS_ADC_DMA_Handler();
|
||||
}
|
||||
#endif /* if defined(PIOS_INCLUDE_ADC) */
|
||||
|
||||
#include "pios_tim_priv.h"
|
||||
|
||||
static const TIM_TimeBaseInitTypeDef tim_1_2_3_4_time_base = {
|
||||
.TIM_Prescaler = (PIOS_MASTER_CLOCK / 1000000) - 1,
|
||||
.TIM_ClockDivision = TIM_CKD_DIV1,
|
||||
.TIM_CounterMode = TIM_CounterMode_Up,
|
||||
.TIM_Period = ((1000000 / PIOS_SERVO_UPDATE_HZ) - 1),
|
||||
.TIM_RepetitionCounter = 0x0000,
|
||||
};
|
||||
|
||||
static const struct pios_tim_clock_cfg tim_1_cfg = {
|
||||
.timer = TIM1,
|
||||
.time_base_init = &tim_1_2_3_4_time_base,
|
||||
.irq = {
|
||||
.init = {
|
||||
.NVIC_IRQChannel = TIM1_CC_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
static const struct pios_tim_clock_cfg tim_2_cfg = {
|
||||
.timer = TIM2,
|
||||
.time_base_init = &tim_1_2_3_4_time_base,
|
||||
.irq = {
|
||||
.init = {
|
||||
.NVIC_IRQChannel = TIM2_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
static const struct pios_tim_clock_cfg tim_3_cfg = {
|
||||
.timer = TIM3,
|
||||
.time_base_init = &tim_1_2_3_4_time_base,
|
||||
.irq = {
|
||||
.init = {
|
||||
.NVIC_IRQChannel = TIM3_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
static const struct pios_tim_clock_cfg tim_4_cfg = {
|
||||
.timer = TIM4,
|
||||
.time_base_init = &tim_1_2_3_4_time_base,
|
||||
.irq = {
|
||||
.init = {
|
||||
.NVIC_IRQChannel = TIM4_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
static const struct pios_tim_channel pios_tim_rcvrport_all_channels[] = {
|
||||
{
|
||||
.timer = TIM4,
|
||||
.timer_chan = TIM_Channel_1,
|
||||
.pin = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_6,
|
||||
.GPIO_Mode = GPIO_Mode_IPD,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
},
|
||||
},
|
||||
},
|
||||
{
|
||||
.timer = TIM3,
|
||||
.timer_chan = TIM_Channel_2,
|
||||
.pin = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_5,
|
||||
.GPIO_Mode = GPIO_Mode_IPD,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
},
|
||||
},
|
||||
.remap = GPIO_PartialRemap_TIM3,
|
||||
},
|
||||
{
|
||||
.timer = TIM3,
|
||||
.timer_chan = TIM_Channel_3,
|
||||
.pin = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_0,
|
||||
.GPIO_Mode = GPIO_Mode_IPD,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
},
|
||||
},
|
||||
},
|
||||
{
|
||||
.timer = TIM3,
|
||||
.timer_chan = TIM_Channel_4,
|
||||
.pin = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_1,
|
||||
.GPIO_Mode = GPIO_Mode_IPD,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
},
|
||||
},
|
||||
},
|
||||
{
|
||||
.timer = TIM2,
|
||||
.timer_chan = TIM_Channel_1,
|
||||
.pin = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_0,
|
||||
.GPIO_Mode = GPIO_Mode_IPD,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
},
|
||||
},
|
||||
},
|
||||
{
|
||||
.timer = TIM2,
|
||||
.timer_chan = TIM_Channel_2,
|
||||
.pin = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_1,
|
||||
.GPIO_Mode = GPIO_Mode_IPD,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
},
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
static const struct pios_tim_channel pios_tim_servoport_all_pins[] = {
|
||||
{
|
||||
.timer = TIM4,
|
||||
.timer_chan = TIM_Channel_4,
|
||||
.pin = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_9,
|
||||
.GPIO_Mode = GPIO_Mode_AF_PP,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
},
|
||||
},
|
||||
},
|
||||
{
|
||||
.timer = TIM4,
|
||||
.timer_chan = TIM_Channel_3,
|
||||
.pin = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_8,
|
||||
.GPIO_Mode = GPIO_Mode_AF_PP,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
},
|
||||
},
|
||||
},
|
||||
{
|
||||
.timer = TIM4,
|
||||
.timer_chan = TIM_Channel_2,
|
||||
.pin = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_7,
|
||||
.GPIO_Mode = GPIO_Mode_AF_PP,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
},
|
||||
},
|
||||
},
|
||||
{
|
||||
.timer = TIM1,
|
||||
.timer_chan = TIM_Channel_1,
|
||||
.pin = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_8,
|
||||
.GPIO_Mode = GPIO_Mode_AF_PP,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
},
|
||||
},
|
||||
},
|
||||
{
|
||||
.timer = TIM3,
|
||||
.timer_chan = TIM_Channel_1,
|
||||
.pin = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_4,
|
||||
.GPIO_Mode = GPIO_Mode_AF_PP,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
},
|
||||
},
|
||||
.remap = GPIO_PartialRemap_TIM3,
|
||||
},
|
||||
{
|
||||
.timer = TIM2,
|
||||
.timer_chan = TIM_Channel_3,
|
||||
.pin = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_2,
|
||||
.GPIO_Mode = GPIO_Mode_AF_PP,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
},
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
|
||||
static const struct pios_tim_channel pios_tim_servoport_rcvrport_pins[] = {
|
||||
{
|
||||
.timer = TIM4,
|
||||
.timer_chan = TIM_Channel_4,
|
||||
.pin = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_9,
|
||||
.GPIO_Mode = GPIO_Mode_AF_PP,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
},
|
||||
},
|
||||
},
|
||||
{
|
||||
.timer = TIM4,
|
||||
.timer_chan = TIM_Channel_3,
|
||||
.pin = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_8,
|
||||
.GPIO_Mode = GPIO_Mode_AF_PP,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
},
|
||||
},
|
||||
},
|
||||
{
|
||||
.timer = TIM4,
|
||||
.timer_chan = TIM_Channel_2,
|
||||
.pin = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_7,
|
||||
.GPIO_Mode = GPIO_Mode_AF_PP,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
},
|
||||
},
|
||||
},
|
||||
{
|
||||
.timer = TIM1,
|
||||
.timer_chan = TIM_Channel_1,
|
||||
.pin = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_8,
|
||||
.GPIO_Mode = GPIO_Mode_AF_PP,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
},
|
||||
},
|
||||
},
|
||||
{
|
||||
.timer = TIM3,
|
||||
.timer_chan = TIM_Channel_1,
|
||||
.pin = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_4,
|
||||
.GPIO_Mode = GPIO_Mode_AF_PP,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
},
|
||||
},
|
||||
.remap = GPIO_PartialRemap_TIM3,
|
||||
},
|
||||
{
|
||||
.timer = TIM2,
|
||||
.timer_chan = TIM_Channel_3,
|
||||
.pin = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_2,
|
||||
.GPIO_Mode = GPIO_Mode_AF_PP,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
},
|
||||
},
|
||||
},
|
||||
|
||||
// Receiver port pins
|
||||
// S3-S6 inputs are used as outputs in this case
|
||||
{
|
||||
.timer = TIM3,
|
||||
.timer_chan = TIM_Channel_3,
|
||||
.pin = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_0,
|
||||
.GPIO_Mode = GPIO_Mode_AF_PP,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
},
|
||||
},
|
||||
},
|
||||
{
|
||||
.timer = TIM3,
|
||||
.timer_chan = TIM_Channel_4,
|
||||
.pin = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_1,
|
||||
.GPIO_Mode = GPIO_Mode_AF_PP,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
},
|
||||
},
|
||||
},
|
||||
{
|
||||
.timer = TIM2,
|
||||
.timer_chan = TIM_Channel_1,
|
||||
.pin = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_0,
|
||||
.GPIO_Mode = GPIO_Mode_AF_PP,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
},
|
||||
},
|
||||
},
|
||||
{
|
||||
.timer = TIM2,
|
||||
.timer_chan = TIM_Channel_2,
|
||||
.pin = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_1,
|
||||
.GPIO_Mode = GPIO_Mode_AF_PP,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
},
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
static const struct pios_tim_channel pios_tim_ppm_flexi_port = {
|
||||
.timer = TIM2,
|
||||
.timer_chan = TIM_Channel_4,
|
||||
.pin = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_11,
|
||||
.GPIO_Mode = GPIO_Mode_IPD,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
},
|
||||
},
|
||||
.remap = GPIO_PartialRemap2_TIM2,
|
||||
};
|
||||
|
||||
#if defined(PIOS_INCLUDE_USART)
|
||||
|
||||
#include "pios_usart_priv.h"
|
||||
|
||||
static const struct pios_usart_cfg pios_usart_generic_main_cfg = {
|
||||
.regs = USART1,
|
||||
.init = {
|
||||
.USART_BaudRate = 57600,
|
||||
.USART_WordLength = USART_WordLength_8b,
|
||||
.USART_Parity = USART_Parity_No,
|
||||
.USART_StopBits = USART_StopBits_1,
|
||||
.USART_HardwareFlowControl = USART_HardwareFlowControl_None,
|
||||
.USART_Mode = USART_Mode_Rx | USART_Mode_Tx,
|
||||
},
|
||||
.irq = {
|
||||
.init = {
|
||||
.NVIC_IRQChannel = USART1_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
.rx = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_10,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_IPU,
|
||||
},
|
||||
},
|
||||
.tx = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_9,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF_PP,
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
static const struct pios_usart_cfg pios_usart_generic_flexi_cfg = {
|
||||
.regs = USART3,
|
||||
.init = {
|
||||
.USART_BaudRate = 57600,
|
||||
.USART_WordLength = USART_WordLength_8b,
|
||||
.USART_Parity = USART_Parity_No,
|
||||
.USART_StopBits = USART_StopBits_1,
|
||||
.USART_HardwareFlowControl = USART_HardwareFlowControl_None,
|
||||
.USART_Mode = USART_Mode_Rx | USART_Mode_Tx,
|
||||
},
|
||||
.irq = {
|
||||
.init = {
|
||||
.NVIC_IRQChannel = USART3_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
.rx = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_11,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_IPU,
|
||||
},
|
||||
},
|
||||
.tx = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_10,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF_PP,
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
#if defined(PIOS_INCLUDE_DSM)
|
||||
/*
|
||||
* Spektrum/JR DSM USART
|
||||
*/
|
||||
#include <pios_dsm_priv.h>
|
||||
|
||||
static const struct pios_usart_cfg pios_usart_dsm_main_cfg = {
|
||||
.regs = USART1,
|
||||
.init = {
|
||||
.USART_BaudRate = 115200,
|
||||
.USART_WordLength = USART_WordLength_8b,
|
||||
.USART_Parity = USART_Parity_No,
|
||||
.USART_StopBits = USART_StopBits_1,
|
||||
.USART_HardwareFlowControl = USART_HardwareFlowControl_None,
|
||||
.USART_Mode = USART_Mode_Rx,
|
||||
},
|
||||
.irq = {
|
||||
.init = {
|
||||
.NVIC_IRQChannel = USART1_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
.rx = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_10,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_IPU,
|
||||
},
|
||||
},
|
||||
.tx = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_9,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_IN_FLOATING,
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
static const struct pios_dsm_cfg pios_dsm_main_cfg = {
|
||||
.bind = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_10,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_Out_PP,
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
static const struct pios_usart_cfg pios_usart_dsm_flexi_cfg = {
|
||||
.regs = USART3,
|
||||
.init = {
|
||||
.USART_BaudRate = 115200,
|
||||
.USART_WordLength = USART_WordLength_8b,
|
||||
.USART_Parity = USART_Parity_No,
|
||||
.USART_StopBits = USART_StopBits_1,
|
||||
.USART_HardwareFlowControl = USART_HardwareFlowControl_None,
|
||||
.USART_Mode = USART_Mode_Rx,
|
||||
},
|
||||
.irq = {
|
||||
.init = {
|
||||
.NVIC_IRQChannel = USART3_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
.rx = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_11,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_IPU,
|
||||
},
|
||||
},
|
||||
.tx = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_10,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_IN_FLOATING,
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
static const struct pios_dsm_cfg pios_dsm_flexi_cfg = {
|
||||
.bind = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_11,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_Out_PP,
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
#endif /* PIOS_INCLUDE_DSM */
|
||||
|
||||
|
||||
#if defined(PIOS_INCLUDE_SBUS)
|
||||
/*
|
||||
* S.Bus USART
|
||||
*/
|
||||
#include <pios_sbus_priv.h>
|
||||
|
||||
static const struct pios_usart_cfg pios_usart_sbus_main_cfg = {
|
||||
.regs = USART1,
|
||||
.init = {
|
||||
.USART_BaudRate = 100000,
|
||||
.USART_WordLength = USART_WordLength_8b,
|
||||
.USART_Parity = USART_Parity_Even,
|
||||
.USART_StopBits = USART_StopBits_2,
|
||||
.USART_HardwareFlowControl = USART_HardwareFlowControl_None,
|
||||
.USART_Mode = USART_Mode_Rx,
|
||||
},
|
||||
.irq = {
|
||||
.init = {
|
||||
.NVIC_IRQChannel = USART1_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
.rx = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_10,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_IPU,
|
||||
},
|
||||
},
|
||||
.tx = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_9,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_IN_FLOATING,
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
static const struct pios_sbus_cfg pios_sbus_cfg = {
|
||||
/* Inverter configuration */
|
||||
.inv = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_2,
|
||||
.GPIO_Mode = GPIO_Mode_Out_PP,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
},
|
||||
},
|
||||
.gpio_clk_func = RCC_APB2PeriphClockCmd,
|
||||
.gpio_clk_periph = RCC_APB2Periph_GPIOB,
|
||||
.gpio_inv_enable = Bit_SET,
|
||||
};
|
||||
|
||||
#endif /* PIOS_INCLUDE_SBUS */
|
||||
|
||||
/*
|
||||
* HK OSD
|
||||
*/
|
||||
static const struct pios_usart_cfg pios_usart_hkosd_main_cfg = {
|
||||
.regs = USART1,
|
||||
.init = {
|
||||
.USART_BaudRate = 57600,
|
||||
.USART_WordLength = USART_WordLength_8b,
|
||||
.USART_Parity = USART_Parity_No,
|
||||
.USART_StopBits = USART_StopBits_1,
|
||||
.USART_HardwareFlowControl = USART_HardwareFlowControl_None,
|
||||
.USART_Mode = USART_Mode_Rx | USART_Mode_Tx,
|
||||
},
|
||||
.irq = {
|
||||
.init = {
|
||||
.NVIC_IRQChannel = USART1_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
.rx = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_10,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_IPU,
|
||||
},
|
||||
},
|
||||
.tx = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_9,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF_PP,
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
static const struct pios_usart_cfg pios_usart_hkosd_flexi_cfg = {
|
||||
.regs = USART3,
|
||||
.init = {
|
||||
.USART_BaudRate = 57600,
|
||||
.USART_WordLength = USART_WordLength_8b,
|
||||
.USART_Parity = USART_Parity_No,
|
||||
.USART_StopBits = USART_StopBits_1,
|
||||
.USART_HardwareFlowControl = USART_HardwareFlowControl_None,
|
||||
.USART_Mode = USART_Mode_Rx | USART_Mode_Tx,
|
||||
},
|
||||
.irq = {
|
||||
.init = {
|
||||
.NVIC_IRQChannel = USART3_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
.rx = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_11,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_IPU,
|
||||
},
|
||||
},
|
||||
.tx = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_10,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF_PP,
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
|
||||
#endif /* PIOS_INCLUDE_USART */
|
||||
|
||||
#if defined(PIOS_INCLUDE_COM)
|
||||
|
||||
#include "pios_com_priv.h"
|
||||
|
||||
#endif /* PIOS_INCLUDE_COM */
|
||||
|
||||
#if defined(PIOS_INCLUDE_RTC)
|
||||
/*
|
||||
* Realtime Clock (RTC)
|
||||
*/
|
||||
#include <pios_rtc_priv.h>
|
||||
|
||||
void PIOS_RTC_IRQ_Handler(void);
|
||||
void RTC_IRQHandler() __attribute__((alias("PIOS_RTC_IRQ_Handler")));
|
||||
static const struct pios_rtc_cfg pios_rtc_main_cfg = {
|
||||
.clksrc = RCC_RTCCLKSource_HSE_Div128,
|
||||
.prescaler = 100,
|
||||
.irq = {
|
||||
.init = {
|
||||
.NVIC_IRQChannel = RTC_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
void PIOS_RTC_IRQ_Handler(void)
|
||||
{
|
||||
PIOS_RTC_irq_handler();
|
||||
}
|
||||
|
||||
#endif /* if defined(PIOS_INCLUDE_RTC) */
|
||||
|
||||
#if defined(PIOS_INCLUDE_SERVO) && defined(PIOS_INCLUDE_TIM)
|
||||
/*
|
||||
* Servo outputs
|
||||
*/
|
||||
#include <pios_servo_priv.h>
|
||||
|
||||
const struct pios_servo_cfg pios_servo_cfg = {
|
||||
.tim_oc_init = {
|
||||
.TIM_OCMode = TIM_OCMode_PWM1,
|
||||
.TIM_OutputState = TIM_OutputState_Enable,
|
||||
.TIM_OutputNState = TIM_OutputNState_Disable,
|
||||
.TIM_Pulse = PIOS_SERVOS_INITIAL_POSITION,
|
||||
.TIM_OCPolarity = TIM_OCPolarity_High,
|
||||
.TIM_OCNPolarity = TIM_OCPolarity_High,
|
||||
.TIM_OCIdleState = TIM_OCIdleState_Reset,
|
||||
.TIM_OCNIdleState = TIM_OCNIdleState_Reset,
|
||||
},
|
||||
.channels = pios_tim_servoport_all_pins,
|
||||
.num_channels = NELEMENTS(pios_tim_servoport_all_pins),
|
||||
};
|
||||
|
||||
const struct pios_servo_cfg pios_servo_rcvr_cfg = {
|
||||
.tim_oc_init = {
|
||||
.TIM_OCMode = TIM_OCMode_PWM1,
|
||||
.TIM_OutputState = TIM_OutputState_Enable,
|
||||
.TIM_OutputNState = TIM_OutputNState_Disable,
|
||||
.TIM_Pulse = PIOS_SERVOS_INITIAL_POSITION,
|
||||
.TIM_OCPolarity = TIM_OCPolarity_High,
|
||||
.TIM_OCNPolarity = TIM_OCPolarity_High,
|
||||
.TIM_OCIdleState = TIM_OCIdleState_Reset,
|
||||
.TIM_OCNIdleState = TIM_OCNIdleState_Reset,
|
||||
},
|
||||
.channels = pios_tim_servoport_rcvrport_pins,
|
||||
.num_channels = NELEMENTS(pios_tim_servoport_rcvrport_pins),
|
||||
};
|
||||
|
||||
#endif /* PIOS_INCLUDE_SERVO && PIOS_INCLUDE_TIM */
|
||||
|
||||
/*
|
||||
* PPM Inputs
|
||||
*/
|
||||
#if defined(PIOS_INCLUDE_PPM)
|
||||
#include <pios_ppm_priv.h>
|
||||
|
||||
const struct pios_ppm_cfg pios_ppm_cfg = {
|
||||
.tim_ic_init = {
|
||||
.TIM_ICPolarity = TIM_ICPolarity_Rising,
|
||||
.TIM_ICSelection = TIM_ICSelection_DirectTI,
|
||||
.TIM_ICPrescaler = TIM_ICPSC_DIV1,
|
||||
.TIM_ICFilter = 0x0,
|
||||
},
|
||||
/* Use only the first channel for ppm */
|
||||
.channels = &pios_tim_rcvrport_all_channels[0],
|
||||
.num_channels = 1,
|
||||
};
|
||||
|
||||
const struct pios_ppm_cfg pios_ppm_pin8_cfg = {
|
||||
.tim_ic_init = {
|
||||
.TIM_ICPolarity = TIM_ICPolarity_Rising,
|
||||
.TIM_ICSelection = TIM_ICSelection_DirectTI,
|
||||
.TIM_ICPrescaler = TIM_ICPSC_DIV1,
|
||||
.TIM_ICFilter = 0x0,
|
||||
},
|
||||
/* Use only the first channel for ppm */
|
||||
.channels = &pios_tim_rcvrport_all_channels[5],
|
||||
.num_channels = 1,
|
||||
};
|
||||
|
||||
#endif /* PIOS_INCLUDE_PPM */
|
||||
|
||||
#if defined(PIOS_INCLUDE_PPM_FLEXI)
|
||||
#include <pios_ppm_priv.h>
|
||||
|
||||
const struct pios_ppm_cfg pios_ppm_flexi_cfg = {
|
||||
.tim_ic_init = {
|
||||
.TIM_ICPolarity = TIM_ICPolarity_Rising,
|
||||
.TIM_ICSelection = TIM_ICSelection_DirectTI,
|
||||
.TIM_ICPrescaler = TIM_ICPSC_DIV1,
|
||||
.TIM_ICFilter = 0x0,
|
||||
},
|
||||
.channels = &pios_tim_ppm_flexi_port,
|
||||
.num_channels = 1,
|
||||
};
|
||||
|
||||
#endif /* PIOS_INCLUDE_PPM_FLEXI */
|
||||
|
||||
/*
|
||||
* PWM Inputs
|
||||
*/
|
||||
#if defined(PIOS_INCLUDE_PWM)
|
||||
#include <pios_pwm_priv.h>
|
||||
|
||||
const struct pios_pwm_cfg pios_pwm_cfg = {
|
||||
.tim_ic_init = {
|
||||
.TIM_ICPolarity = TIM_ICPolarity_Rising,
|
||||
.TIM_ICSelection = TIM_ICSelection_DirectTI,
|
||||
.TIM_ICPrescaler = TIM_ICPSC_DIV1,
|
||||
.TIM_ICFilter = 0x0,
|
||||
},
|
||||
.channels = pios_tim_rcvrport_all_channels,
|
||||
.num_channels = NELEMENTS(pios_tim_rcvrport_all_channels),
|
||||
};
|
||||
|
||||
const struct pios_pwm_cfg pios_pwm_with_ppm_cfg = {
|
||||
.tim_ic_init = {
|
||||
.TIM_ICPolarity = TIM_ICPolarity_Rising,
|
||||
.TIM_ICSelection = TIM_ICSelection_DirectTI,
|
||||
.TIM_ICPrescaler = TIM_ICPSC_DIV1,
|
||||
.TIM_ICFilter = 0x0,
|
||||
},
|
||||
/* Leave the first channel for PPM use and use the rest for PWM */
|
||||
.channels = &pios_tim_rcvrport_all_channels[1],
|
||||
.num_channels = NELEMENTS(pios_tim_rcvrport_all_channels) - 1,
|
||||
};
|
||||
|
||||
#endif /* if defined(PIOS_INCLUDE_PWM) */
|
||||
|
||||
|
||||
/*
|
||||
* SONAR Inputs
|
||||
*/
|
||||
#if defined(PIOS_INCLUDE_HCSR04)
|
||||
#include <pios_hcsr04_priv.h>
|
||||
|
||||
static const struct pios_tim_channel pios_tim_hcsr04_port_all_channels[] = {
|
||||
{
|
||||
.timer = TIM3,
|
||||
.timer_chan = TIM_Channel_2,
|
||||
.pin = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_5,
|
||||
.GPIO_Mode = GPIO_Mode_IPD,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
},
|
||||
},
|
||||
.remap = GPIO_PartialRemap_TIM3,
|
||||
},
|
||||
};
|
||||
|
||||
const struct pios_hcsr04_cfg pios_hcsr04_cfg = {
|
||||
.tim_ic_init = {
|
||||
.TIM_ICPolarity = TIM_ICPolarity_Rising,
|
||||
.TIM_ICSelection = TIM_ICSelection_DirectTI,
|
||||
.TIM_ICPrescaler = TIM_ICPSC_DIV1,
|
||||
.TIM_ICFilter = 0x0,
|
||||
},
|
||||
.channels = pios_tim_hcsr04_port_all_channels,
|
||||
.num_channels = NELEMENTS(pios_tim_hcsr04_port_all_channels),
|
||||
.trigger = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_6,
|
||||
.GPIO_Mode = GPIO_Mode_Out_PP,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
},
|
||||
},
|
||||
};
|
||||
#endif /* if defined(PIOS_INCLUDE_HCSR04) */
|
||||
|
||||
#if defined(PIOS_INCLUDE_I2C)
|
||||
|
||||
#include <pios_i2c_priv.h>
|
||||
|
||||
/*
|
||||
* I2C Adapters
|
||||
*/
|
||||
|
||||
void PIOS_I2C_flexi_adapter_ev_irq_handler(void);
|
||||
void PIOS_I2C_flexi_adapter_er_irq_handler(void);
|
||||
void I2C2_EV_IRQHandler() __attribute__((alias("PIOS_I2C_flexi_adapter_ev_irq_handler")));
|
||||
void I2C2_ER_IRQHandler() __attribute__((alias("PIOS_I2C_flexi_adapter_er_irq_handler")));
|
||||
|
||||
static const struct pios_i2c_adapter_cfg pios_i2c_flexi_adapter_cfg = {
|
||||
.regs = I2C2,
|
||||
.init = {
|
||||
.I2C_Mode = I2C_Mode_I2C,
|
||||
.I2C_OwnAddress1 = 0,
|
||||
.I2C_Ack = I2C_Ack_Enable,
|
||||
.I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit,
|
||||
.I2C_DutyCycle = I2C_DutyCycle_2,
|
||||
.I2C_ClockSpeed = 400000, /* bits/s */
|
||||
},
|
||||
.transfer_timeout_ms = 50,
|
||||
.scl = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_10,
|
||||
.GPIO_Speed = GPIO_Speed_10MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF_OD,
|
||||
},
|
||||
},
|
||||
.sda = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_11,
|
||||
.GPIO_Speed = GPIO_Speed_10MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF_OD,
|
||||
},
|
||||
},
|
||||
.event = {
|
||||
.flags = 0, /* FIXME: check this */
|
||||
.init = {
|
||||
.NVIC_IRQChannel = I2C2_EV_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGHEST,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
.error = {
|
||||
.flags = 0, /* FIXME: check this */
|
||||
.init = {
|
||||
.NVIC_IRQChannel = I2C2_ER_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGHEST,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
uint32_t pios_i2c_flexi_adapter_id;
|
||||
void PIOS_I2C_flexi_adapter_ev_irq_handler(void)
|
||||
{
|
||||
/* Call into the generic code to handle the IRQ for this specific device */
|
||||
PIOS_I2C_EV_IRQ_Handler(pios_i2c_flexi_adapter_id);
|
||||
}
|
||||
|
||||
void PIOS_I2C_flexi_adapter_er_irq_handler(void)
|
||||
{
|
||||
/* Call into the generic code to handle the IRQ for this specific device */
|
||||
PIOS_I2C_ER_IRQ_Handler(pios_i2c_flexi_adapter_id);
|
||||
}
|
||||
|
||||
#endif /* PIOS_INCLUDE_I2C */
|
||||
|
||||
#if defined(PIOS_INCLUDE_GCSRCVR)
|
||||
#include "pios_gcsrcvr_priv.h"
|
||||
#endif /* PIOS_INCLUDE_GCSRCVR */
|
||||
|
||||
#if defined(PIOS_INCLUDE_RCVR)
|
||||
#include "pios_rcvr_priv.h"
|
||||
|
||||
#endif /* PIOS_INCLUDE_RCVR */
|
||||
|
||||
#if defined(PIOS_INCLUDE_USB)
|
||||
#include "pios_usb_priv.h"
|
||||
|
||||
static const struct pios_usb_cfg pios_usb_main_cfg_cc = {
|
||||
.irq = {
|
||||
.init = {
|
||||
.NVIC_IRQChannel = USB_LP_CAN1_RX0_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_LOW,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
.vsense = {
|
||||
.gpio = GPIOC,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_15,
|
||||
.GPIO_Speed = GPIO_Speed_10MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF_OD,
|
||||
},
|
||||
},
|
||||
.vsense_active_low = false
|
||||
};
|
||||
|
||||
static const struct pios_usb_cfg pios_usb_main_cfg_cc3d = {
|
||||
.irq = {
|
||||
.init = {
|
||||
.NVIC_IRQChannel = USB_LP_CAN1_RX0_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_LOW,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
.vsense = {
|
||||
.gpio = GPIOC,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_14,
|
||||
.GPIO_Speed = GPIO_Speed_10MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF_OD,
|
||||
},
|
||||
},
|
||||
.vsense_active_low = false
|
||||
};
|
||||
|
||||
#include "pios_usb_board_data_priv.h"
|
||||
#include "pios_usb_desc_hid_cdc_priv.h"
|
||||
#include "pios_usb_desc_hid_only_priv.h"
|
||||
|
||||
#endif /* PIOS_INCLUDE_USB */
|
||||
|
||||
#if defined(PIOS_INCLUDE_COM_MSG)
|
||||
|
||||
#include <pios_com_msg_priv.h>
|
||||
|
||||
#endif /* PIOS_INCLUDE_COM_MSG */
|
||||
|
||||
#if defined(PIOS_INCLUDE_USB_HID)
|
||||
#include <pios_usb_hid_priv.h>
|
||||
|
||||
const struct pios_usb_hid_cfg pios_usb_hid_cfg = {
|
||||
.data_if = 2,
|
||||
.data_rx_ep = 1,
|
||||
.data_tx_ep = 1,
|
||||
};
|
||||
|
||||
#endif /* PIOS_INCLUDE_USB_HID */
|
||||
|
||||
#if defined(PIOS_INCLUDE_USB_RCTX)
|
||||
#include <pios_usb_rctx_priv.h>
|
||||
|
||||
const struct pios_usb_rctx_cfg pios_usb_rctx_cfg = {
|
||||
.data_if = 2,
|
||||
.data_tx_ep = 1,
|
||||
};
|
||||
|
||||
#endif /* PIOS_INCLUDE_USB_RCTX */
|
||||
|
||||
#if defined(PIOS_INCLUDE_USB_CDC)
|
||||
#include <pios_usb_cdc_priv.h>
|
||||
|
||||
const struct pios_usb_cdc_cfg pios_usb_cdc_cfg = {
|
||||
.ctrl_if = 0,
|
||||
.ctrl_tx_ep = 2,
|
||||
|
||||
.data_if = 1,
|
||||
.data_rx_ep = 3,
|
||||
.data_tx_ep = 3,
|
||||
};
|
||||
#endif /* PIOS_INCLUDE_USB_CDC */
|
32
flight/targets/boards/coptercontrol/bootloader/Makefile
Normal file
@ -0,0 +1,32 @@
|
||||
#
|
||||
# Copyright (c) 2009-2013, The OpenPilot Team, http://www.openpilot.org
|
||||
#
|
||||
# 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 OPENPILOT_IS_COOL
|
||||
$(error Top level Makefile must be used to build this target)
|
||||
endif
|
||||
|
||||
## The standard CMSIS startup
|
||||
SRC += $(CMSIS_DEVICEDIR)/system_stm32f10x.c
|
||||
|
||||
include ../board-info.mk
|
||||
include $(ROOT_DIR)/make/firmware-defs.mk
|
||||
include $(ROOT_DIR)/make/boot-defs.mk
|
||||
include $(ROOT_DIR)/make/common-defs.mk
|
||||
|
||||
$(info Making bootloader for CopterControl, board revision $(BOARD_REVISION))
|
||||
$(info Use BOARD_REVISION=1 for CC, BOARD_REVISION=2 for CC3D (default))
|
115
flight/targets/boards/coptercontrol/bootloader/inc/common.h
Normal file
@ -0,0 +1,115 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup CopterControlBL CopterControl BootLoader
|
||||
* @brief These files contain the code to the CopterControl Bootloader.
|
||||
*
|
||||
* @{
|
||||
* @file common.c
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @brief This file contains various common defines for the BootLoader
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
*
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* This program is free software; you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation; either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful, but
|
||||
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
|
||||
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
|
||||
* for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License along
|
||||
* with this program; if not, write to the Free Software Foundation, Inc.,
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
#ifndef COMMON_H_
|
||||
#define COMMON_H_
|
||||
|
||||
// #include "board.h"
|
||||
|
||||
typedef enum {
|
||||
start, keepgoing,
|
||||
} DownloadAction;
|
||||
|
||||
/**************************************************/
|
||||
/* OP_DFU states */
|
||||
/**************************************************/
|
||||
|
||||
typedef enum {
|
||||
DFUidle, // 0
|
||||
uploading, // 1
|
||||
wrong_packet_received, // 2
|
||||
too_many_packets, // 3
|
||||
too_few_packets, // 4
|
||||
Last_operation_Success, // 5
|
||||
downloading, // 6
|
||||
BLidle, // 7
|
||||
Last_operation_failed, // 8
|
||||
uploadingStarting, // 9
|
||||
outsideDevCapabilities, // 10
|
||||
CRC_Fail, // 11
|
||||
failed_jump,
|
||||
// 12
|
||||
} DFUStates;
|
||||
/**************************************************/
|
||||
/* OP_DFU commands */
|
||||
/**************************************************/
|
||||
typedef enum {
|
||||
Reserved, // 0
|
||||
Req_Capabilities, // 1
|
||||
Rep_Capabilities, // 2
|
||||
EnterDFU, // 3
|
||||
JumpFW, // 4
|
||||
Reset, // 5
|
||||
Abort_Operation, // 6
|
||||
Upload, // 7
|
||||
Op_END, // 8
|
||||
Download_Req, // 9
|
||||
Download, // 10
|
||||
Status_Request, // 11
|
||||
Status_Rep
|
||||
// 12
|
||||
} DFUCommands;
|
||||
|
||||
typedef enum {
|
||||
High_Density, Medium_Density
|
||||
} DeviceType;
|
||||
/**************************************************/
|
||||
/* OP_DFU transfer types */
|
||||
/**************************************************/
|
||||
typedef enum {
|
||||
FW, // 0
|
||||
Descript
|
||||
// 2
|
||||
} DFUTransfer;
|
||||
/**************************************************/
|
||||
/* OP_DFU transfer port */
|
||||
/**************************************************/
|
||||
typedef enum {
|
||||
Usb, // 0
|
||||
Serial
|
||||
// 2
|
||||
} DFUPort;
|
||||
/**************************************************/
|
||||
/* OP_DFU programable programable HW types */
|
||||
/**************************************************/
|
||||
typedef enum {
|
||||
Self_flash, // 0
|
||||
Remote_flash_via_spi
|
||||
// 1
|
||||
} DFUProgType;
|
||||
/**************************************************/
|
||||
/* OP_DFU programable sources */
|
||||
/**************************************************/
|
||||
#define USB 0
|
||||
#define SPI 1
|
||||
|
||||
#define DownloadDelay 100000
|
||||
|
||||
#define MAX_DEL_RETRYS 3
|
||||
#define MAX_WRI_RETRYS 3
|
||||
|
||||
#endif /* COMMON_H_ */
|
@ -0,0 +1,53 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup CopterControlBL CopterControl BootLoader
|
||||
* @brief These files contain the code to the CopterControl Bootloader.
|
||||
* @{
|
||||
* @file pios_config.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @brief PiOS configuration header.
|
||||
* Central compile time config for the project.
|
||||
* In particular, pios_config.h is where you define which PiOS libraries
|
||||
* and features are included in the firmware.
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
*
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* This program is free software; you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation; either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful, but
|
||||
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
|
||||
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
|
||||
* for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License along
|
||||
* with this program; if not, write to the Free Software Foundation, Inc.,
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
|
||||
#ifndef PIOS_CONFIG_H
|
||||
#define PIOS_CONFIG_H
|
||||
|
||||
/* Enable/Disable PiOS modules */
|
||||
#define PIOS_INCLUDE_DELAY
|
||||
#define PIOS_INCLUDE_SYS
|
||||
#define PIOS_INCLUDE_IRQ
|
||||
#define PIOS_INCLUDE_GPIO
|
||||
#define PIOS_INCLUDE_USB
|
||||
#define PIOS_INCLUDE_USB_HID
|
||||
#define PIOS_INCLUDE_LED
|
||||
#define PIOS_INCLUDE_IAP
|
||||
#define PIOS_INCLUDE_COM
|
||||
#define PIOS_INCLUDE_COM_MSG
|
||||
#define PIOS_INCLUDE_BL_HELPER
|
||||
#define PIOS_INCLUDE_BL_HELPER_WRITE_SUPPORT
|
||||
|
||||
#endif /* PIOS_CONFIG_H */
|
||||
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
@ -0,0 +1,53 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup PIOS PIOS Core hardware abstraction layer
|
||||
* @{
|
||||
* @addtogroup PIOS_USB_BOARD Board specific USB definitions
|
||||
* @brief Board specific USB definitions
|
||||
* @{
|
||||
*
|
||||
* @file pios_usb_board_data.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @brief Board specific USB definitions
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
*
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* This program is free software; you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation; either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful, but
|
||||
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
|
||||
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
|
||||
* for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License along
|
||||
* with this program; if not, write to the Free Software Foundation, Inc.,
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
|
||||
#ifndef PIOS_USB_BOARD_DATA_H
|
||||
#define PIOS_USB_BOARD_DATA_H
|
||||
|
||||
// Note : changing below length will require changes to the USB buffer setup
|
||||
#define PIOS_USB_BOARD_HID_DATA_LENGTH 64
|
||||
|
||||
#define PIOS_USB_BOARD_EP_NUM 2
|
||||
|
||||
#include <pios_usb_defs.h> /* struct usb_* */
|
||||
|
||||
#define PIOS_USB_BOARD_PRODUCT_ID USB_PRODUCT_ID_COPTERCONTROL
|
||||
#define PIOS_USB_BOARD_DEVICE_VER USB_OP_DEVICE_VER(USB_OP_BOARD_ID_COPTERCONTROL, USB_OP_BOARD_MODE_BL)
|
||||
#define PIOS_USB_BOARD_SN_SUFFIX "+BL"
|
||||
|
||||
/*
|
||||
* The bootloader uses a simplified report structure
|
||||
* BL: <REPORT_ID><DATA>...<DATA>
|
||||
* FW: <REPORT_ID><LENGTH><DATA>...<DATA>
|
||||
* This define changes the behaviour in pios_usb_hid.c
|
||||
*/
|
||||
#define PIOS_USB_BOARD_BL_HID_HAS_NO_LENGTH_BYTE
|
||||
|
||||
#endif /* PIOS_USB_BOARD_DATA_H */
|
223
flight/targets/boards/coptercontrol/bootloader/main.c
Normal file
@ -0,0 +1,223 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup CopterControlBL CopterControl BootLoader
|
||||
* @brief These files contain the code to the CopterControl Bootloader.
|
||||
*
|
||||
* @{
|
||||
* @file main.c
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @brief This is the file with the main function of the OpenPilot BootLoader
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
*
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* This program is free software; you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation; either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful, but
|
||||
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
|
||||
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
|
||||
* for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License along
|
||||
* with this program; if not, write to the Free Software Foundation, Inc.,
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
|
||||
#include <pios.h>
|
||||
#include <pios_board_info.h>
|
||||
#include <op_dfu.h>
|
||||
#include <usb_lib.h>
|
||||
#include <pios_iap.h>
|
||||
#include <fifo_buffer.h>
|
||||
#include <pios_com_msg.h>
|
||||
|
||||
/* Prototype of PIOS_Board_Init() function */
|
||||
extern void PIOS_Board_Init(void);
|
||||
extern void FLASH_Download();
|
||||
#define BSL_HOLD_STATE ((PIOS_USB_DETECT_GPIO_PORT->IDR & PIOS_USB_DETECT_GPIO_PIN) ? 0 : 1)
|
||||
|
||||
/* Private typedef -----------------------------------------------------------*/
|
||||
typedef void (*pFunction)(void);
|
||||
/* Private define ------------------------------------------------------------*/
|
||||
/* Private macro -------------------------------------------------------------*/
|
||||
/* Private variables ---------------------------------------------------------*/
|
||||
pFunction Jump_To_Application;
|
||||
uint32_t JumpAddress;
|
||||
|
||||
/// LEDs PWM
|
||||
uint32_t period1 = 5000; // 5 mS
|
||||
uint32_t sweep_steps1 = 100; // * 5 mS -> 500 mS
|
||||
uint32_t period2 = 5000; // 5 mS
|
||||
uint32_t sweep_steps2 = 100; // * 5 mS -> 500 mS
|
||||
|
||||
|
||||
////////////////////////////////////////
|
||||
uint8_t tempcount = 0;
|
||||
|
||||
/* Extern variables ----------------------------------------------------------*/
|
||||
DFUStates DeviceState;
|
||||
int16_t status = 0;
|
||||
uint8_t JumpToApp = FALSE;
|
||||
uint8_t GO_dfu = FALSE;
|
||||
uint8_t USB_connected = FALSE;
|
||||
uint8_t User_DFU_request = FALSE;
|
||||
static uint8_t mReceive_Buffer[63];
|
||||
/* Private function prototypes -----------------------------------------------*/
|
||||
uint32_t LedPWM(uint32_t pwm_period, uint32_t pwm_sweep_steps, uint32_t count);
|
||||
uint8_t processRX();
|
||||
void jump_to_app();
|
||||
|
||||
int main()
|
||||
{
|
||||
PIOS_SYS_Init();
|
||||
PIOS_Board_Init();
|
||||
PIOS_IAP_Init();
|
||||
|
||||
USB_connected = PIOS_USB_CableConnected(0);
|
||||
|
||||
if (PIOS_IAP_CheckRequest() == TRUE) {
|
||||
PIOS_DELAY_WaitmS(1000);
|
||||
User_DFU_request = TRUE;
|
||||
PIOS_IAP_ClearRequest();
|
||||
}
|
||||
|
||||
GO_dfu = (USB_connected == TRUE) || (User_DFU_request == TRUE);
|
||||
|
||||
if (GO_dfu == TRUE) {
|
||||
PIOS_Board_Init();
|
||||
if (User_DFU_request == TRUE) {
|
||||
DeviceState = DFUidle;
|
||||
} else {
|
||||
DeviceState = BLidle;
|
||||
}
|
||||
} else {
|
||||
JumpToApp = TRUE;
|
||||
}
|
||||
|
||||
uint32_t stopwatch = 0;
|
||||
uint32_t prev_ticks = PIOS_DELAY_GetuS();
|
||||
while (TRUE) {
|
||||
/* Update the stopwatch */
|
||||
uint32_t elapsed_ticks = PIOS_DELAY_GetuSSince(prev_ticks);
|
||||
prev_ticks += elapsed_ticks;
|
||||
stopwatch += elapsed_ticks;
|
||||
|
||||
if (JumpToApp == TRUE) {
|
||||
jump_to_app();
|
||||
}
|
||||
|
||||
switch (DeviceState) {
|
||||
case Last_operation_Success:
|
||||
case uploadingStarting:
|
||||
case DFUidle:
|
||||
period1 = 5000;
|
||||
sweep_steps1 = 100;
|
||||
PIOS_LED_Off(PIOS_LED_HEARTBEAT);
|
||||
period2 = 0;
|
||||
break;
|
||||
case uploading:
|
||||
period1 = 5000;
|
||||
sweep_steps1 = 100;
|
||||
period2 = 2500;
|
||||
sweep_steps2 = 50;
|
||||
break;
|
||||
case downloading:
|
||||
period1 = 2500;
|
||||
sweep_steps1 = 50;
|
||||
PIOS_LED_Off(PIOS_LED_HEARTBEAT);
|
||||
period2 = 0;
|
||||
break;
|
||||
case BLidle:
|
||||
period1 = 0;
|
||||
PIOS_LED_On(PIOS_LED_HEARTBEAT);
|
||||
period2 = 0;
|
||||
break;
|
||||
default: // error
|
||||
period1 = 5000;
|
||||
sweep_steps1 = 100;
|
||||
period2 = 5000;
|
||||
sweep_steps2 = 100;
|
||||
}
|
||||
|
||||
if (period1 != 0) {
|
||||
if (LedPWM(period1, sweep_steps1, stopwatch)) {
|
||||
PIOS_LED_On(PIOS_LED_HEARTBEAT);
|
||||
} else {
|
||||
PIOS_LED_Off(PIOS_LED_HEARTBEAT);
|
||||
}
|
||||
} else {
|
||||
PIOS_LED_On(PIOS_LED_HEARTBEAT);
|
||||
}
|
||||
|
||||
if (period2 != 0) {
|
||||
if (LedPWM(period2, sweep_steps2, stopwatch)) {
|
||||
PIOS_LED_On(PIOS_LED_HEARTBEAT);
|
||||
} else {
|
||||
PIOS_LED_Off(PIOS_LED_HEARTBEAT);
|
||||
}
|
||||
} else {
|
||||
PIOS_LED_Off(PIOS_LED_HEARTBEAT);
|
||||
}
|
||||
|
||||
if (stopwatch > 50 * 1000 * 1000) {
|
||||
stopwatch = 0;
|
||||
}
|
||||
if ((stopwatch > 6 * 1000 * 1000) && ((DeviceState == BLidle) || (DeviceState == DFUidle && !USB_connected))) {
|
||||
JumpToApp = TRUE;
|
||||
}
|
||||
|
||||
processRX();
|
||||
DataDownload(start);
|
||||
}
|
||||
}
|
||||
|
||||
void jump_to_app()
|
||||
{
|
||||
const struct pios_board_info *bdinfo = &pios_board_info_blob;
|
||||
|
||||
if (((*(__IO uint32_t *)bdinfo->fw_base) & 0x2FFE0000) == 0x20000000) { /* Jump to user application */
|
||||
FLASH_Lock();
|
||||
RCC_APB2PeriphResetCmd(0xffffffff, ENABLE);
|
||||
RCC_APB1PeriphResetCmd(0xffffffff, ENABLE);
|
||||
RCC_APB2PeriphResetCmd(0xffffffff, DISABLE);
|
||||
RCC_APB1PeriphResetCmd(0xffffffff, DISABLE);
|
||||
_SetCNTR(0); // clear interrupt mask
|
||||
_SetISTR(0); // clear all requests
|
||||
JumpAddress = *(__IO uint32_t *)(bdinfo->fw_base + 4);
|
||||
Jump_To_Application = (pFunction)JumpAddress;
|
||||
/* Initialize user application's Stack Pointer */
|
||||
__set_MSP(*(__IO uint32_t *)bdinfo->fw_base);
|
||||
Jump_To_Application();
|
||||
} else {
|
||||
DeviceState = failed_jump;
|
||||
return;
|
||||
}
|
||||
}
|
||||
uint32_t LedPWM(uint32_t pwm_period, uint32_t pwm_sweep_steps, uint32_t count)
|
||||
{
|
||||
uint32_t curr_step = (count / pwm_period) % pwm_sweep_steps; /* 0 - pwm_sweep_steps */
|
||||
uint32_t pwm_duty = pwm_period * curr_step / pwm_sweep_steps; /* fraction of pwm_period */
|
||||
|
||||
uint32_t curr_sweep = (count / (pwm_period * pwm_sweep_steps)); /* ticks once per full sweep */
|
||||
|
||||
if (curr_sweep & 1) {
|
||||
pwm_duty = pwm_period - pwm_duty; /* reverse direction in odd sweeps */
|
||||
}
|
||||
return ((count % pwm_period) > pwm_duty) ? 1 : 0;
|
||||
}
|
||||
|
||||
uint8_t processRX()
|
||||
{
|
||||
if (PIOS_COM_MSG_Receive(PIOS_COM_TELEM_USB, mReceive_Buffer, sizeof(mReceive_Buffer))) {
|
||||
processComand(mReceive_Buffer);
|
||||
}
|
||||
return TRUE;
|
||||
}
|
||||
|
||||
int32_t platform_senddata(const uint8_t *msg, uint16_t msg_len)
|
||||
{
|
||||
return PIOS_COM_MSG_Send(PIOS_COM_TELEM_USB, msg, msg_len);
|
||||
}
|
106
flight/targets/boards/coptercontrol/bootloader/pios_board.c
Normal file
@ -0,0 +1,106 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file pios_board.c
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @brief Defines board specific static initializers for hardware for the CopterControl board.
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
*
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* This program is free software; you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation; either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful, but
|
||||
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
|
||||
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
|
||||
* for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License along
|
||||
* with this program; if not, write to the Free Software Foundation, Inc.,
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
|
||||
#include <pios.h>
|
||||
#include <pios_board_info.h>
|
||||
|
||||
/*
|
||||
* Pull in the board-specific static HW definitions.
|
||||
* Including .c files is a bit ugly but this allows all of
|
||||
* the HW definitions to be const and static to limit their
|
||||
* scope.
|
||||
*
|
||||
* NOTE: THIS IS THE ONLY PLACE THAT SHOULD EVER INCLUDE THIS FILE
|
||||
*/
|
||||
#include "../board_hw_defs.c"
|
||||
|
||||
uint32_t pios_com_telem_usb_id;
|
||||
|
||||
/**
|
||||
* PIOS_Board_Init()
|
||||
* initializes all the core subsystems on this specific hardware
|
||||
* called from System/openpilot.c
|
||||
*/
|
||||
static bool board_init_complete = false;
|
||||
void PIOS_Board_Init(void)
|
||||
{
|
||||
if (board_init_complete) {
|
||||
return;
|
||||
}
|
||||
|
||||
/* Enable Prefetch Buffer */
|
||||
FLASH_PrefetchBufferCmd(FLASH_PrefetchBuffer_Enable);
|
||||
|
||||
/* Flash 2 wait state */
|
||||
FLASH_SetLatency(FLASH_Latency_2);
|
||||
|
||||
/* Delay system */
|
||||
PIOS_DELAY_Init();
|
||||
|
||||
const struct pios_board_info *bdinfo = &pios_board_info_blob;
|
||||
|
||||
#if defined(PIOS_INCLUDE_LED)
|
||||
const struct pios_gpio_cfg *led_cfg = PIOS_BOARD_HW_DEFS_GetLedCfg(bdinfo->board_rev);
|
||||
PIOS_Assert(led_cfg);
|
||||
PIOS_LED_Init(led_cfg);
|
||||
#endif /* PIOS_INCLUDE_LED */
|
||||
|
||||
#if defined(PIOS_INCLUDE_USB)
|
||||
/* Initialize board specific USB data */
|
||||
PIOS_USB_BOARD_DATA_Init();
|
||||
|
||||
/* Activate the HID-only USB configuration */
|
||||
PIOS_USB_DESC_HID_ONLY_Init();
|
||||
|
||||
uint32_t pios_usb_id;
|
||||
switch (bdinfo->board_rev) {
|
||||
case BOARD_REVISION_CC:
|
||||
PIOS_USB_Init(&pios_usb_id, &pios_usb_main_cfg_cc);
|
||||
break;
|
||||
case BOARD_REVISION_CC3D:
|
||||
PIOS_USB_Init(&pios_usb_id, &pios_usb_main_cfg_cc3d);
|
||||
break;
|
||||
default:
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
#if defined(PIOS_INCLUDE_USB_HID) && defined(PIOS_INCLUDE_COM_MSG)
|
||||
uint32_t pios_usb_hid_id;
|
||||
if (PIOS_USB_HID_Init(&pios_usb_hid_id, &pios_usb_hid_cfg, pios_usb_id)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
if (PIOS_COM_MSG_Init(&pios_com_telem_usb_id, &pios_usb_hid_com_driver, pios_usb_hid_id)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_USB_HID && PIOS_INCLUDE_COM_MSG */
|
||||
|
||||
#endif /* PIOS_INCLUDE_USB */
|
||||
|
||||
RCC_AHBPeriphClockCmd(RCC_AHBPeriph_CRC, ENABLE); // TODO Tirar
|
||||
|
||||
board_init_complete = true;
|
||||
}
|
||||
|
||||
void PIOS_ADC_DMA_Handler()
|
||||
{}
|
152
flight/targets/boards/coptercontrol/firmware/Makefile
Normal file
@ -0,0 +1,152 @@
|
||||
#
|
||||
# Copyright (c) 2009-2013, The OpenPilot Team, http://www.openpilot.org
|
||||
# Copyright (c) 2012, PhoenixPilot, http://github.com/PhoenixPilot
|
||||
#
|
||||
# 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 OPENPILOT_IS_COOL
|
||||
$(error Top level Makefile must be used to build this target)
|
||||
endif
|
||||
|
||||
include ../board-info.mk
|
||||
include $(ROOT_DIR)/make/firmware-defs.mk
|
||||
|
||||
# ARM DSP library
|
||||
USE_DSP_LIB ?= NO
|
||||
|
||||
# Set to YES to build a FW version that will erase data flash memory
|
||||
ERASE_FLASH ?= NO
|
||||
|
||||
# Set to yes to include Gcsreceiver module
|
||||
GCSRECEIVER ?= NO
|
||||
|
||||
# Enable Diag tasks ?
|
||||
DIAG_TASKS ?= NO
|
||||
|
||||
# List of mandatory modules to include
|
||||
MODULES += Attitude
|
||||
MODULES += Stabilization
|
||||
MODULES += Actuator
|
||||
MODULES += Receiver
|
||||
MODULES += ManualControl
|
||||
MODULES += FirmwareIAP
|
||||
MODULES += Telemetry
|
||||
|
||||
# List of optional modules to include
|
||||
OPTMODULES += CameraStab
|
||||
OPTMODULES += ComUsbBridge
|
||||
OPTMODULES += GPS
|
||||
OPTMODULES += TxPID
|
||||
OPTMODULES += Osd/osdoutput
|
||||
#OPTMODULES += Altitude
|
||||
#OPTMODULES += Fault
|
||||
|
||||
SRC += $(FLIGHTLIB)/notification.c
|
||||
|
||||
# Include all camera options
|
||||
CDEFS += -DUSE_INPUT_LPF -DUSE_GIMBAL_LPF -DUSE_GIMBAL_FF
|
||||
|
||||
|
||||
|
||||
# Erase flash firmware should be buildable from command line
|
||||
ifeq ($(ERASE_FLASH), YES)
|
||||
CDEFS += -DERASE_FLASH
|
||||
endif
|
||||
|
||||
# List C source files here (C dependencies are automatically generated).
|
||||
# Use file-extension c for "c-only"-files
|
||||
ifndef TESTAPP
|
||||
## The standard CMSIS startup
|
||||
SRC += $(CMSIS_DEVICEDIR)/system_stm32f10x.c
|
||||
|
||||
## Application Core
|
||||
SRC += ../pios_usb_board_data.c
|
||||
SRC += $(OPMODULEDIR)/System/systemmod.c
|
||||
SRC += $(OPSYSTEM)/coptercontrol.c
|
||||
SRC += $(OPSYSTEM)/pios_board.c
|
||||
SRC += $(FLIGHTLIB)/alarms.c
|
||||
SRC += $(FLIGHTLIB)/instrumentation.c
|
||||
SRC += $(OPUAVTALK)/uavtalk.c
|
||||
SRC += $(OPUAVOBJ)/uavobjectmanager.c
|
||||
SRC += $(OPUAVOBJ)/uavobjectpersistence.c
|
||||
SRC += $(PIOSCOMMON)/pios_flashfs_logfs.c
|
||||
SRC += $(PIOSCOMMON)/pios_flash_jedec.c
|
||||
SRC += $(OPUAVOBJ)/eventdispatcher.c
|
||||
|
||||
## UAVObjects
|
||||
SRC += $(OPUAVSYNTHDIR)/accessorydesired.c
|
||||
SRC += $(OPUAVSYNTHDIR)/objectpersistence.c
|
||||
SRC += $(OPUAVSYNTHDIR)/gcstelemetrystats.c
|
||||
SRC += $(OPUAVSYNTHDIR)/flighttelemetrystats.c
|
||||
SRC += $(OPUAVSYNTHDIR)/faultsettings.c
|
||||
SRC += $(OPUAVSYNTHDIR)/flightstatus.c
|
||||
SRC += $(OPUAVSYNTHDIR)/systemstats.c
|
||||
SRC += $(OPUAVSYNTHDIR)/systemalarms.c
|
||||
SRC += $(OPUAVSYNTHDIR)/systemsettings.c
|
||||
SRC += $(OPUAVSYNTHDIR)/stabilizationdesired.c
|
||||
SRC += $(OPUAVSYNTHDIR)/stabilizationsettings.c
|
||||
SRC += $(OPUAVSYNTHDIR)/stabilizationsettingsbank1.c
|
||||
SRC += $(OPUAVSYNTHDIR)/stabilizationsettingsbank2.c
|
||||
SRC += $(OPUAVSYNTHDIR)/stabilizationsettingsbank3.c
|
||||
SRC += $(OPUAVSYNTHDIR)/stabilizationstatus.c
|
||||
SRC += $(OPUAVSYNTHDIR)/stabilizationbank.c
|
||||
SRC += $(OPUAVSYNTHDIR)/actuatorcommand.c
|
||||
SRC += $(OPUAVSYNTHDIR)/actuatordesired.c
|
||||
SRC += $(OPUAVSYNTHDIR)/actuatorsettings.c
|
||||
SRC += $(OPUAVSYNTHDIR)/accelstate.c
|
||||
SRC += $(OPUAVSYNTHDIR)/accelgyrosettings.c
|
||||
SRC += $(OPUAVSYNTHDIR)/gyrostate.c
|
||||
SRC += $(OPUAVSYNTHDIR)/attitudestate.c
|
||||
SRC += $(OPUAVSYNTHDIR)/manualcontrolcommand.c
|
||||
SRC += $(OPUAVSYNTHDIR)/watchdogstatus.c
|
||||
SRC += $(OPUAVSYNTHDIR)/manualcontrolsettings.c
|
||||
SRC += $(OPUAVSYNTHDIR)/flightmodesettings.c
|
||||
SRC += $(OPUAVSYNTHDIR)/mixersettings.c
|
||||
SRC += $(OPUAVSYNTHDIR)/firmwareiapobj.c
|
||||
SRC += $(OPUAVSYNTHDIR)/attitudesettings.c
|
||||
SRC += $(OPUAVSYNTHDIR)/camerastabsettings.c
|
||||
SRC += $(OPUAVSYNTHDIR)/cameradesired.c
|
||||
SRC += $(OPUAVSYNTHDIR)/gpspositionsensor.c
|
||||
SRC += $(OPUAVSYNTHDIR)/gpsvelocitysensor.c
|
||||
SRC += $(OPUAVSYNTHDIR)/gpssettings.c
|
||||
SRC += $(OPUAVSYNTHDIR)/hwsettings.c
|
||||
SRC += $(OPUAVSYNTHDIR)/receiveractivity.c
|
||||
SRC += $(OPUAVSYNTHDIR)/receiverstatus.c
|
||||
SRC += $(OPUAVSYNTHDIR)/mixerstatus.c
|
||||
SRC += $(OPUAVSYNTHDIR)/ratedesired.c
|
||||
SRC += $(OPUAVSYNTHDIR)/txpidsettings.c
|
||||
SRC += $(OPUAVSYNTHDIR)/txpidstatus.c
|
||||
SRC += $(OPUAVSYNTHDIR)/mpugyroaccelsettings.c
|
||||
# Command line option for Gcsreceiver module
|
||||
ifeq ($(GCSRECEIVER), YES)
|
||||
SRC += $(OPUAVSYNTHDIR)/gcsreceiver.c
|
||||
endif
|
||||
# Enable Diag tasks and UAVOs needed
|
||||
ifeq ($(DIAG_TASKS), YES)
|
||||
CDEFS += -DDIAG_TASKS
|
||||
SRC += $(OPUAVSYNTHDIR)/taskinfo.c
|
||||
SRC += $(OPUAVSYNTHDIR)/callbackinfo.c
|
||||
SRC += $(OPUAVSYNTHDIR)/perfcounter.c
|
||||
SRC += $(OPUAVSYNTHDIR)/i2cstats.c
|
||||
endif
|
||||
else
|
||||
## Test Code
|
||||
SRC += $(OPTESTS)/test_common.c
|
||||
SRC += $(OPTESTS)/$(TESTAPP).c
|
||||
endif
|
||||
|
||||
include $(ROOT_DIR)/make/apps-defs.mk
|
||||
include $(ROOT_DIR)/make/common-defs.mk
|
117
flight/targets/boards/coptercontrol/firmware/coptercontrol.c
Normal file
@ -0,0 +1,117 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup OpenPilotSystem OpenPilot System
|
||||
* @brief These files are the core system files of OpenPilot.
|
||||
* They are the ground layer just above PiOS. In practice, OpenPilot actually starts
|
||||
* in the main() function of openpilot.c
|
||||
* @{
|
||||
* @addtogroup OpenPilotCore OpenPilot Core
|
||||
* @brief This is where the OP firmware starts. Those files also define the compile-time
|
||||
* options of the firmware.
|
||||
* @{
|
||||
* @file openpilot.c
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @brief Sets up and runs main OpenPilot tasks.
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
*
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* This program is free software; you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation; either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful, but
|
||||
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
|
||||
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
|
||||
* for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License along
|
||||
* with this program; if not, write to the Free Software Foundation, Inc.,
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
|
||||
#include "inc/openpilot.h"
|
||||
#include <uavobjectsinit.h>
|
||||
#include <hwsettings.h>
|
||||
|
||||
/* Task Priorities */
|
||||
#define PRIORITY_TASK_HOOKS (tskIDLE_PRIORITY + 3)
|
||||
|
||||
/* Global Variables */
|
||||
|
||||
/* Prototype of PIOS_Board_Init() function */
|
||||
extern void PIOS_Board_Init(void);
|
||||
extern void Stack_Change(void);
|
||||
|
||||
/**
|
||||
* OpenPilot Main function:
|
||||
*
|
||||
* Initialize PiOS<BR>
|
||||
* Create the "System" task (SystemModInitializein Modules/System/systemmod.c) <BR>
|
||||
* Start FreeRTOS Scheduler (vTaskStartScheduler) (Now handled by caller)
|
||||
* If something goes wrong, blink LED1 and LED2 every 100ms
|
||||
*
|
||||
*/
|
||||
int main()
|
||||
{
|
||||
/* NOTE: Do NOT modify the following start-up sequence */
|
||||
/* Any new initialization functions should be added in OpenPilotInit() */
|
||||
|
||||
/* Brings up System using CMSIS functions, enables the LEDs. */
|
||||
PIOS_SYS_Init();
|
||||
|
||||
/* Architecture dependant Hardware and
|
||||
* core subsystem initialisation
|
||||
* (see pios_board.c for your arch)
|
||||
* */
|
||||
PIOS_Board_Init();
|
||||
|
||||
#ifdef ERASE_FLASH
|
||||
PIOS_Flash_Jedec_EraseChip();
|
||||
#if defined(PIOS_LED_HEARTBEAT)
|
||||
PIOS_LED_Off(PIOS_LED_HEARTBEAT);
|
||||
#endif /* PIOS_LED_HEARTBEAT */
|
||||
while (1) {
|
||||
;
|
||||
}
|
||||
#endif
|
||||
|
||||
/* Initialize modules */
|
||||
MODULE_INITIALISE_ALL
|
||||
/* swap the stack to use the IRQ stack */
|
||||
Stack_Change();
|
||||
|
||||
/* Start the FreeRTOS scheduler, which should never return.
|
||||
*
|
||||
* NOTE: OpenPilot runs an operating system (FreeRTOS), which constantly calls
|
||||
* (schedules) function files (modules). These functions never return from their
|
||||
* while loops, which explains why each module has a while(1){} segment. Thus,
|
||||
* the OpenPilot software actually starts at the vTaskStartScheduler() function,
|
||||
* even though this is somewhat obscure.
|
||||
*
|
||||
* In addition, there are many main() functions in the OpenPilot firmware source tree
|
||||
* This is because each main() refers to a separate hardware platform. Of course,
|
||||
* C only allows one main(), so only the relevant main() function is compiled when
|
||||
* making a specific firmware.
|
||||
*
|
||||
*/
|
||||
vTaskStartScheduler();
|
||||
|
||||
/* 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 */
|
||||
while (1) {
|
||||
#if defined(PIOS_LED_HEARTBEAT)
|
||||
PIOS_LED_Toggle(PIOS_LED_HEARTBEAT);
|
||||
#endif /* PIOS_LED_HEARTBEAT */
|
||||
PIOS_DELAY_WaitmS(100);
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
@ -0,0 +1,99 @@
|
||||
#ifndef FREERTOS_CONFIG_H
|
||||
#define FREERTOS_CONFIG_H
|
||||
|
||||
/*-----------------------------------------------------------
|
||||
* Application specific definitions.
|
||||
*
|
||||
* These definitions should be adjusted for your particular hardware and
|
||||
* application requirements.
|
||||
*
|
||||
* THESE PARAMETERS ARE DESCRIBED WITHIN THE 'CONFIGURATION' SECTION OF THE
|
||||
* FreeRTOS API DOCUMENTATION AVAILABLE ON THE FreeRTOS.org WEB SITE.
|
||||
*
|
||||
* See http://www.freertos.org/a00110.html.
|
||||
*----------------------------------------------------------*/
|
||||
|
||||
/**
|
||||
* @addtogroup PIOS PIOS
|
||||
* @{
|
||||
* @addtogroup FreeRTOS FreeRTOS
|
||||
* @{
|
||||
*/
|
||||
|
||||
/* Notes: We use 5 task priorities */
|
||||
|
||||
#define configUSE_PREEMPTION 1
|
||||
#define configUSE_IDLE_HOOK 1
|
||||
#define configUSE_TICK_HOOK 0
|
||||
#define configUSE_MALLOC_FAILED_HOOK 1
|
||||
#define configCPU_CLOCK_HZ ((unsigned long)72000000)
|
||||
#define configTICK_RATE_HZ ((portTickType)1000)
|
||||
#define configMAX_PRIORITIES ((unsigned portBASE_TYPE)5)
|
||||
#define configMINIMAL_STACK_SIZE ((unsigned short)48)
|
||||
#define configTOTAL_HEAP_SIZE ((size_t)(53 * 256))
|
||||
#define configMAX_TASK_NAME_LEN (6)
|
||||
#define configUSE_TRACE_FACILITY 0
|
||||
#define configUSE_16_BIT_TICKS 0
|
||||
#define configIDLE_SHOULD_YIELD 0
|
||||
#define configUSE_MUTEXES 1
|
||||
#define configUSE_RECURSIVE_MUTEXES 1
|
||||
#define configUSE_COUNTING_SEMAPHORES 0
|
||||
#define configUSE_ALTERNATIVE_API 0
|
||||
#define configQUEUE_REGISTRY_SIZE 0
|
||||
|
||||
/* Co-routine definitions. */
|
||||
#define configUSE_CO_ROUTINES 0
|
||||
#define configMAX_CO_ROUTINE_PRIORITIES (2)
|
||||
|
||||
/* Set the following definitions to 1 to include the API function, or zero
|
||||
to exclude the API function. */
|
||||
|
||||
#define INCLUDE_vTaskPrioritySet 1
|
||||
#define INCLUDE_uxTaskPriorityGet 1
|
||||
#define INCLUDE_vTaskDelete 1
|
||||
#define INCLUDE_vTaskCleanUpResources 0
|
||||
#define INCLUDE_vTaskSuspend 1
|
||||
#define INCLUDE_vTaskDelayUntil 1
|
||||
#define INCLUDE_vTaskDelay 1
|
||||
#define INCLUDE_xTaskGetSchedulerState 0
|
||||
#define INCLUDE_xTaskGetCurrentTaskHandle 1
|
||||
#define INCLUDE_uxTaskGetStackHighWaterMark 1
|
||||
|
||||
/* This is the raw value as per the Cortex-M3 NVIC. Values can be 255
|
||||
(lowest) to 1 (highest maskable) to 0 (highest non-maskable). */
|
||||
#define configKERNEL_INTERRUPT_PRIORITY 15 << 4 /* equivalent to NVIC priority 15 */
|
||||
#define configMAX_SYSCALL_INTERRUPT_PRIORITY 3 << 4 /* equivalent to NVIC priority 3 */
|
||||
|
||||
/* This is the value being used as per the ST library which permits 16
|
||||
priority values, 0 to 15. This must correspond to the
|
||||
configKERNEL_INTERRUPT_PRIORITY setting. Here 15 corresponds to the lowest
|
||||
NVIC value of 255. */
|
||||
#define configLIBRARY_KERNEL_INTERRUPT_PRIORITY 15
|
||||
|
||||
#if !defined(ARCH_POSIX) && !defined(ARCH_WIN32)
|
||||
#define CHECK_IRQ_STACK
|
||||
#endif
|
||||
|
||||
/* Enable run time stats collection */
|
||||
#define configGENERATE_RUN_TIME_STATS 1
|
||||
#define INCLUDE_uxTaskGetRunTime 1
|
||||
#define INCLUDE_xTaskGetIdleTaskHandle 1
|
||||
#define portCONFIGURE_TIMER_FOR_RUN_TIME_STATS() \
|
||||
do { \
|
||||
(*(unsigned long *)0xe000edfc) |= (1 << 24); /* DEMCR |= DEMCR_TRCENA */ \
|
||||
(*(unsigned long *)0xe0001000) |= 1; /* DWT_CTRL |= DWT_CYCCNT_ENA */ \
|
||||
} \
|
||||
while (0)
|
||||
#define portGET_RUN_TIME_COUNTER_VALUE() (*(unsigned long *)0xe0001004) /* DWT_CYCCNT */
|
||||
|
||||
#ifdef DIAG_TASKS
|
||||
#define configCHECK_FOR_STACK_OVERFLOW 2
|
||||
#else
|
||||
#define configCHECK_FOR_STACK_OVERFLOW 1
|
||||
#endif
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
#endif /* FREERTOS_CONFIG_H */
|
52
flight/targets/boards/coptercontrol/firmware/inc/openpilot.h
Normal file
@ -0,0 +1,52 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup OpenPilotSystem OpenPilot System
|
||||
* @{
|
||||
* @addtogroup OpenPilotCore OpenPilot Core
|
||||
* @{
|
||||
* @file openpilot.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @brief Main OpenPilot header.
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
*
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* This program is free software; you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation; either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful, but
|
||||
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
|
||||
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
|
||||
* for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License along
|
||||
* with this program; if not, write to the Free Software Foundation, Inc.,
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
|
||||
#ifndef OPENPILOT_H
|
||||
#define OPENPILOT_H
|
||||
|
||||
/* PIOS Includes */
|
||||
#include <pios.h>
|
||||
|
||||
/* OpenPilot Libraries */
|
||||
#include <utlist.h>
|
||||
#include <uavobjectmanager.h>
|
||||
#include <eventdispatcher.h>
|
||||
#include <uavtalk.h>
|
||||
|
||||
#include "alarms.h"
|
||||
#include <mathmisc.h>
|
||||
|
||||
/* Global Functions */
|
||||
void OpenPilotInit(void);
|
||||
|
||||
#endif /* OPENPILOT_H */
|
||||
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
@ -0,0 +1,81 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file pios_board.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @brief Defines board hardware for the OpenPilot Version 1.1 hardware.
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
*
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* This program is free software; you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation; either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful, but
|
||||
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
|
||||
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
|
||||
* for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License along
|
||||
* with this program; if not, write to the Free Software Foundation, Inc.,
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
|
||||
|
||||
#ifndef PIOS_BOARD_H
|
||||
#define PIOS_BOARD_H
|
||||
|
||||
|
||||
// ------------------------
|
||||
// PIOS_LED
|
||||
// ------------------------
|
||||
// #define PIOS_LED_LED1_GPIO_PORT GPIOC
|
||||
// #define PIOS_LED_LED1_GPIO_PIN GPIO_Pin_12
|
||||
// #define PIOS_LED_LED1_GPIO_CLK RCC_APB2Periph_GPIOC
|
||||
// #define PIOS_LED_LED2_GPIO_PORT GPIOC
|
||||
// #define PIOS_LED_LED2_GPIO_PIN GPIO_Pin_13
|
||||
// #define PIOS_LED_LED2_GPIO_CLK RCC_APB2Periph_GPIOC
|
||||
#define PIOS_LED_NUM 2
|
||||
// #define PIOS_LED_PORTS { PIOS_LED_LED1_GPIO_PORT, PIOS_LED_LED2_GPIO_PORT }
|
||||
// #define PIOS_LED_PINS { PIOS_LED_LED1_GPIO_PIN, PIOS_LED_LED2_GPIO_PIN }
|
||||
// #define PIOS_LED_CLKS { PIOS_LED_LED1_GPIO_CLK, PIOS_LED_LED2_GPIO_CLK }
|
||||
|
||||
|
||||
// -------------------------
|
||||
// COM
|
||||
//
|
||||
// See also pios_board_posix.c
|
||||
// -------------------------
|
||||
// #define PIOS_USART_TX_BUFFER_SIZE 256
|
||||
#define PIOS_COM_BUFFER_SIZE 1024
|
||||
#define PIOS_UDP_RX_BUFFER_SIZE PIOS_COM_BUFFER_SIZE
|
||||
|
||||
#define PIOS_COM_TELEM_RF 0
|
||||
#define PIOS_COM_GPS 1
|
||||
#define PIOS_COM_TELEM_USB 2
|
||||
|
||||
#ifdef PIOS_ENABLE_AUX_UART
|
||||
#define PIOS_COM_AUX 3
|
||||
#define PIOS_COM_DEBUG PIOS_COM_AUX
|
||||
#endif
|
||||
|
||||
/**
|
||||
* glue macros for file IO
|
||||
* STM32 uses DOSFS for file IO
|
||||
*/
|
||||
#define PIOS_FOPEN_READ(filename, file) (file = fopen((char *)filename, "r")) == NULL
|
||||
|
||||
#define PIOS_FOPEN_WRITE(filename, file) (file = fopen((char *)filename, "w")) == NULL
|
||||
|
||||
#define PIOS_FREAD(file, bufferadr, length, resultadr) (*resultadr = fread((uint8_t *)bufferadr, 1, length, *file)) != length
|
||||
|
||||
#define PIOS_FWRITE(file, bufferadr, length, resultadr) *resultadr = fwrite((uint8_t *)bufferadr, 1, length, *file)
|
||||
|
||||
|
||||
#define PIOS_FCLOSE(file) fclose(file)
|
||||
|
||||
#define PIOS_FUNLINK(file) unlink((char *)filename)
|
||||
|
||||
#endif /* PIOS_BOARD_H */
|
188
flight/targets/boards/coptercontrol/firmware/inc/pios_config.h
Normal file
@ -0,0 +1,188 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup OpenPilotSystem OpenPilot System
|
||||
* @{
|
||||
* @addtogroup OpenPilotCore OpenPilot Core
|
||||
* @{
|
||||
* @file pios_config.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010-2013.
|
||||
* @brief PiOS configuration header, the compile time config file for the PIOS.
|
||||
* Defines which PiOS libraries and features are included in the firmware.
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* This program is free software; you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation; either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful, but
|
||||
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
|
||||
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
|
||||
* for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License along
|
||||
* with this program; if not, write to the Free Software Foundation, Inc.,
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
|
||||
#ifndef PIOS_CONFIG_H
|
||||
#define PIOS_CONFIG_H
|
||||
|
||||
/*
|
||||
* Below is a complete list of PIOS configurable options.
|
||||
* Please do not remove or rearrange them. Only comment out
|
||||
* unused options in the list. See main pios.h header for more
|
||||
* details.
|
||||
*/
|
||||
|
||||
/* #define PIOS_INCLUDE_DEBUG_CONSOLE */
|
||||
/* #define DEBUG_LEVEL 0 */
|
||||
/* #define PIOS_ENABLE_DEBUG_PINS */
|
||||
|
||||
/* PIOS FreeRTOS support */
|
||||
#define PIOS_INCLUDE_FREERTOS
|
||||
|
||||
|
||||
/* PIOS CallbackScheduler support */
|
||||
#define PIOS_INCLUDE_CALLBACKSCHEDULER
|
||||
|
||||
/* PIOS bootloader helper */
|
||||
#define PIOS_INCLUDE_BL_HELPER
|
||||
/* #define PIOS_INCLUDE_BL_HELPER_WRITE_SUPPORT */
|
||||
|
||||
/* PIOS system functions */
|
||||
#define PIOS_INCLUDE_DELAY
|
||||
#define PIOS_INCLUDE_INITCALL
|
||||
#define PIOS_INCLUDE_SYS
|
||||
#define PIOS_INCLUDE_TASK_MONITOR
|
||||
// #define PIOS_INCLUDE_INSTRUMENTATION
|
||||
#define PIOS_INSTRUMENTATION_MAX_COUNTERS 5
|
||||
|
||||
/* PIOS hardware peripherals */
|
||||
#define PIOS_INCLUDE_IRQ
|
||||
#define PIOS_INCLUDE_RTC
|
||||
#define PIOS_INCLUDE_TIM
|
||||
#define PIOS_INCLUDE_USART
|
||||
#define PIOS_INCLUDE_ADC
|
||||
/* #define PIOS_INCLUDE_I2C */
|
||||
#define PIOS_INCLUDE_SPI
|
||||
#define PIOS_INCLUDE_GPIO
|
||||
#define PIOS_INCLUDE_EXTI
|
||||
#define PIOS_INCLUDE_WDG
|
||||
|
||||
/* PIOS USB functions */
|
||||
#define PIOS_INCLUDE_USB
|
||||
#define PIOS_INCLUDE_USB_HID
|
||||
#define PIOS_INCLUDE_USB_CDC
|
||||
#define PIOS_INCLUDE_USB_RCTX
|
||||
|
||||
/* PIOS sensor interfaces */
|
||||
#define PIOS_INCLUDE_ADXL345
|
||||
/* #define PIOS_INCLUDE_BMA180 */
|
||||
/* #define PIOS_INCLUDE_L3GD20 */
|
||||
#define PIOS_INCLUDE_MPU6000
|
||||
#define PIOS_MPU6000_ACCEL
|
||||
/* #define PIOS_INCLUDE_HMC5843 */
|
||||
/* #define PIOS_INCLUDE_HMC5X83 */
|
||||
/* #define PIOS_HMC5883_HAS_GPIOS */
|
||||
/* #define PIOS_INCLUDE_BMP085 */
|
||||
/* #define PIOS_INCLUDE_MS5611 */
|
||||
/* #define PIOS_INCLUDE_MPXV */
|
||||
/* #define PIOS_INCLUDE_ETASV3 */
|
||||
/* #define PIOS_INCLUDE_HCSR04 */
|
||||
|
||||
#define PIOS_SENSOR_RATE 500.0f
|
||||
|
||||
/* PIOS receiver drivers */
|
||||
#define PIOS_INCLUDE_PWM
|
||||
#define PIOS_INCLUDE_PPM
|
||||
#define PIOS_INCLUDE_PPM_FLEXI
|
||||
#define PIOS_INCLUDE_DSM
|
||||
#define PIOS_INCLUDE_SBUS
|
||||
/* #define PIOS_INCLUDE_GCSRCVR */
|
||||
/* #define PIOS_INCLUDE_OPLINKRCVR */
|
||||
|
||||
/* PIOS abstract receiver interface */
|
||||
#define PIOS_INCLUDE_RCVR
|
||||
|
||||
/* PIOS common peripherals */
|
||||
#define PIOS_INCLUDE_LED
|
||||
#define PIOS_INCLUDE_IAP
|
||||
#define PIOS_INCLUDE_SERVO
|
||||
/* #define PIOS_INCLUDE_I2C_ESC */
|
||||
/* #define PIOS_INCLUDE_OVERO */
|
||||
/* #define PIOS_OVERO_SPI */
|
||||
/* #define PIOS_INCLUDE_SDCARD */
|
||||
/* #define LOG_FILENAME "startup.log" */
|
||||
#define PIOS_INCLUDE_FLASH
|
||||
#define PIOS_INCLUDE_FLASH_LOGFS_SETTINGS
|
||||
/* #define FLASH_FREERTOS */
|
||||
/* #define PIOS_INCLUDE_FLASH_EEPROM */
|
||||
/* #define PIOS_INCLUDE_FLASH_INTERNAL */
|
||||
|
||||
/* PIOS radio modules */
|
||||
/* #define PIOS_INCLUDE_RFM22B */
|
||||
/* #define PIOS_INCLUDE_RFM22B_COM */
|
||||
/* #define PIOS_INCLUDE_PPM_OUT */
|
||||
/* #define PIOS_RFM22B_DEBUG_ON_TELEM */
|
||||
|
||||
/* PIOS misc peripherals */
|
||||
/* #define PIOS_INCLUDE_VIDEO */
|
||||
/* #define PIOS_INCLUDE_WAVE */
|
||||
/* #define PIOS_INCLUDE_UDP */
|
||||
|
||||
/* PIOS abstract comms interface with options */
|
||||
#define PIOS_INCLUDE_COM
|
||||
/* #define PIOS_INCLUDE_COM_MSG */
|
||||
#define PIOS_INCLUDE_TELEMETRY_RF
|
||||
/* #define PIOS_INCLUDE_COM_TELEM */
|
||||
/* #define PIOS_INCLUDE_COM_FLEXI */
|
||||
/* #define PIOS_INCLUDE_COM_AUX */
|
||||
/* #define PIOS_TELEM_PRIORITY_QUEUE */
|
||||
#define PIOS_INCLUDE_GPS
|
||||
#define PIOS_GPS_MINIMAL
|
||||
/* #define PIOS_INCLUDE_GPS_NMEA_PARSER */
|
||||
#define PIOS_INCLUDE_GPS_UBX_PARSER
|
||||
/* #define PIOS_GPS_SETS_HOMELOCATION */
|
||||
|
||||
/* Stabilization options */
|
||||
/* #define PIOS_QUATERNION_STABILIZATION */
|
||||
#define PIOS_EXCLUDE_ADVANCED_FEATURES
|
||||
/* Performance counters */
|
||||
#define IDLE_COUNTS_PER_SEC_AT_NO_LOAD 1995998
|
||||
|
||||
/* Alarm Thresholds */
|
||||
#define HEAP_LIMIT_WARNING 220
|
||||
#define HEAP_LIMIT_CRITICAL 40
|
||||
#define IRQSTACK_LIMIT_WARNING 100
|
||||
#define IRQSTACK_LIMIT_CRITICAL 60
|
||||
#define CPULOAD_LIMIT_WARNING 85
|
||||
#define CPULOAD_LIMIT_CRITICAL 95
|
||||
|
||||
/* Task stack sizes */
|
||||
#define PIOS_ACTUATOR_STACK_SIZE 820
|
||||
#define PIOS_MANUAL_STACK_SIZE 735
|
||||
#define PIOS_RECEIVER_STACK_SIZE 620
|
||||
#define PIOS_STABILIZATION_STACK_SIZE 400
|
||||
|
||||
#ifdef DIAG_TASKS
|
||||
#define PIOS_SYSTEM_STACK_SIZE 740
|
||||
#else
|
||||
#define PIOS_SYSTEM_STACK_SIZE 660
|
||||
#endif
|
||||
#define PIOS_TELEM_RX_STACK_SIZE 410
|
||||
#define PIOS_TELEM_TX_STACK_SIZE 560
|
||||
#define PIOS_EVENTDISPATCHER_STACK_SIZE 95
|
||||
|
||||
/* This can't be too high to stop eventdispatcher thread overflowing */
|
||||
#define PIOS_EVENTDISAPTCHER_QUEUE 10
|
||||
|
||||
/* Revolution series */
|
||||
/* #define REVOLUTION */
|
||||
|
||||
#endif /* PIOS_CONFIG_H */
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
@ -0,0 +1,48 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file pios_config.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @brief PiOS configuration header.
|
||||
* Central compile time config for the project.
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
*
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* This program is free software; you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation; either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful, but
|
||||
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
|
||||
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
|
||||
* for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License along
|
||||
* with this program; if not, write to the Free Software Foundation, Inc.,
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
|
||||
|
||||
#ifndef PIOS_CONFIG_POSIX_H
|
||||
#define PIOS_CONFIG_POSIX_H
|
||||
|
||||
|
||||
/* Enable/Disable PiOS Modules */
|
||||
#define PIOS_INCLUDE_SYS
|
||||
#define PIOS_INCLUDE_DELAY
|
||||
#define PIOS_INCLUDE_LED
|
||||
#define PIOS_INCLUDE_FREERTOS
|
||||
#define PIOS_INCLUDE_CALLBACKSCHEDULER
|
||||
#define PIOS_INCLUDE_TASK_MONITOR
|
||||
#define PIOS_INCLUDE_COM
|
||||
#define PIOS_INCLUDE_UDP
|
||||
#define PIOS_INCLUDE_SERVO
|
||||
|
||||
|
||||
/* Defaults for Logging */
|
||||
#define LOG_FILENAME "PIOS.LOG"
|
||||
#define STARTUP_LOG_ENABLED 1
|
||||
|
||||
#endif /* PIOS_CONFIG_POSIX_H */
|
@ -0,0 +1,47 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup PIOS PIOS Core hardware abstraction layer
|
||||
* @{
|
||||
* @addtogroup PIOS_USB_BOARD Board specific USB definitions
|
||||
* @brief Board specific USB definitions
|
||||
* @{
|
||||
*
|
||||
* @file pios_usb_board_data.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @brief Board specific USB definitions
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
*
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* This program is free software; you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation; either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful, but
|
||||
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
|
||||
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
|
||||
* for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License along
|
||||
* with this program; if not, write to the Free Software Foundation, Inc.,
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
|
||||
#ifndef PIOS_USB_BOARD_DATA_H
|
||||
#define PIOS_USB_BOARD_DATA_H
|
||||
|
||||
// Note : changing below length will require changes to the USB buffer setup
|
||||
#define PIOS_USB_BOARD_CDC_DATA_LENGTH 64
|
||||
#define PIOS_USB_BOARD_CDC_MGMT_LENGTH 32
|
||||
#define PIOS_USB_BOARD_HID_DATA_LENGTH 64
|
||||
|
||||
#define PIOS_USB_BOARD_EP_NUM 4
|
||||
|
||||
#include <pios_usb_defs.h> /* USB_* macros */
|
||||
|
||||
#define PIOS_USB_BOARD_PRODUCT_ID USB_PRODUCT_ID_COPTERCONTROL
|
||||
#define PIOS_USB_BOARD_DEVICE_VER USB_OP_DEVICE_VER(USB_OP_BOARD_ID_COPTERCONTROL, USB_OP_BOARD_MODE_FW)
|
||||
#define PIOS_USB_BOARD_SN_SUFFIX "+FW"
|
||||
|
||||
#endif /* PIOS_USB_BOARD_DATA_H */
|
920
flight/targets/boards/coptercontrol/firmware/pios_board.c
Normal file
@ -0,0 +1,920 @@
|
||||
/**
|
||||
*****************************************************************************
|
||||
* @file pios_board.c
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @author PhoenixPilot, http://github.com/PhoenixPilot, Copyright (C) 2012
|
||||
* @addtogroup OpenPilotSystem OpenPilot System
|
||||
* @{
|
||||
* @addtogroup OpenPilotCore OpenPilot Core
|
||||
* @{
|
||||
* @brief Defines board specific static initializers for hardware for the CopterControl board.
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* This program is free software; you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation; either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful, but
|
||||
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
|
||||
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
|
||||
* for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License along
|
||||
* with this program; if not, write to the Free Software Foundation, Inc.,
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
|
||||
#include "inc/openpilot.h"
|
||||
#include <pios_board_info.h>
|
||||
#include <uavobjectsinit.h>
|
||||
#include <hwsettings.h>
|
||||
#include <manualcontrolsettings.h>
|
||||
#include <gcsreceiver.h>
|
||||
#include <taskinfo.h>
|
||||
#include <sanitycheck.h>
|
||||
#include <actuatorsettings.h>
|
||||
|
||||
#ifdef PIOS_INCLUDE_INSTRUMENTATION
|
||||
#include <pios_instrumentation.h>
|
||||
#endif
|
||||
#if defined(PIOS_INCLUDE_ADXL345)
|
||||
#include <pios_adxl345.h>
|
||||
#endif
|
||||
|
||||
/*
|
||||
* Pull in the board-specific static HW definitions.
|
||||
* Including .c files is a bit ugly but this allows all of
|
||||
* the HW definitions to be const and static to limit their
|
||||
* scope.
|
||||
*
|
||||
* NOTE: THIS IS THE ONLY PLACE THAT SHOULD EVER INCLUDE THIS FILE
|
||||
*/
|
||||
#include "../board_hw_defs.c"
|
||||
|
||||
/* One slot per selectable receiver group.
|
||||
* eg. PWM, PPM, GCS, DSMMAINPORT, DSMFLEXIPORT, SBUS
|
||||
* NOTE: No slot in this map for NONE.
|
||||
*/
|
||||
uint32_t pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_NONE];
|
||||
|
||||
static SystemAlarmsExtendedAlarmStatusOptions CopterControlConfigHook();
|
||||
static void ActuatorSettingsUpdatedCb(UAVObjEvent *ev);
|
||||
|
||||
#define PIOS_COM_TELEM_RF_RX_BUF_LEN 32
|
||||
#define PIOS_COM_TELEM_RF_TX_BUF_LEN 12
|
||||
|
||||
#define PIOS_COM_GPS_RX_BUF_LEN 32
|
||||
|
||||
#define PIOS_COM_TELEM_USB_RX_BUF_LEN 65
|
||||
#define PIOS_COM_TELEM_USB_TX_BUF_LEN 65
|
||||
|
||||
#define PIOS_COM_BRIDGE_RX_BUF_LEN 65
|
||||
#define PIOS_COM_BRIDGE_TX_BUF_LEN 12
|
||||
|
||||
#define PIOS_COM_HKOSD_TX_BUF_LEN 22
|
||||
|
||||
#if defined(PIOS_INCLUDE_DEBUG_CONSOLE)
|
||||
#define PIOS_COM_DEBUGCONSOLE_TX_BUF_LEN 40
|
||||
uint32_t pios_com_debug_id;
|
||||
#endif /* PIOS_INCLUDE_DEBUG_CONSOLE */
|
||||
|
||||
uint32_t pios_com_telem_rf_id;
|
||||
uint32_t pios_com_telem_usb_id;
|
||||
uint32_t pios_com_vcp_id;
|
||||
uint32_t pios_com_gps_id;
|
||||
uint32_t pios_com_bridge_id;
|
||||
uint32_t pios_com_hkosd_id;
|
||||
|
||||
uint32_t pios_usb_rctx_id;
|
||||
|
||||
uintptr_t pios_uavo_settings_fs_id;
|
||||
uintptr_t pios_user_fs_id = 0;
|
||||
/**
|
||||
* Configuration for MPU6000 chip
|
||||
*/
|
||||
#if defined(PIOS_INCLUDE_MPU6000)
|
||||
#include "pios_mpu6000.h"
|
||||
#include "pios_mpu6000_config.h"
|
||||
static const struct pios_exti_cfg pios_exti_mpu6000_cfg __exti_config = {
|
||||
.vector = PIOS_MPU6000_IRQHandler,
|
||||
.line = EXTI_Line3,
|
||||
.pin = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_3,
|
||||
.GPIO_Speed = GPIO_Speed_10MHz,
|
||||
.GPIO_Mode = GPIO_Mode_IN_FLOATING,
|
||||
},
|
||||
},
|
||||
.irq = {
|
||||
.init = {
|
||||
.NVIC_IRQChannel = EXTI3_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
.exti = {
|
||||
.init = {
|
||||
.EXTI_Line = EXTI_Line3, // matches above GPIO pin
|
||||
.EXTI_Mode = EXTI_Mode_Interrupt,
|
||||
.EXTI_Trigger = EXTI_Trigger_Rising,
|
||||
.EXTI_LineCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
static const struct pios_mpu6000_cfg pios_mpu6000_cfg = {
|
||||
.exti_cfg = &pios_exti_mpu6000_cfg,
|
||||
.Fifo_store = PIOS_MPU6000_FIFO_TEMP_OUT | PIOS_MPU6000_FIFO_GYRO_X_OUT | PIOS_MPU6000_FIFO_GYRO_Y_OUT | PIOS_MPU6000_FIFO_GYRO_Z_OUT,
|
||||
// Clock at 8 khz, downsampled by 8 for 1000 Hz
|
||||
.Smpl_rate_div_no_dlp = 7,
|
||||
// Clock at 1 khz, downsampled by 1 for 1000 Hz
|
||||
.Smpl_rate_div_dlp = 0,
|
||||
.interrupt_cfg = PIOS_MPU6000_INT_CLR_ANYRD,
|
||||
.interrupt_en = PIOS_MPU6000_INTEN_DATA_RDY,
|
||||
.User_ctl = PIOS_MPU6000_USERCTL_DIS_I2C,
|
||||
.Pwr_mgmt_clk = PIOS_MPU6000_PWRMGMT_PLL_X_CLK,
|
||||
.accel_range = PIOS_MPU6000_ACCEL_8G,
|
||||
.gyro_range = PIOS_MPU6000_SCALE_2000_DEG,
|
||||
.filter = PIOS_MPU6000_LOWPASS_256_HZ,
|
||||
.orientation = PIOS_MPU6000_TOP_180DEG,
|
||||
.fast_prescaler = PIOS_SPI_PRESCALER_4,
|
||||
.std_prescaler = PIOS_SPI_PRESCALER_64,
|
||||
.max_downsample = 2
|
||||
};
|
||||
#endif /* PIOS_INCLUDE_MPU6000 */
|
||||
|
||||
/**
|
||||
* PIOS_Board_Init()
|
||||
* initializes all the core subsystems on this specific hardware
|
||||
* called from System/openpilot.c
|
||||
*/
|
||||
int32_t init_test;
|
||||
void PIOS_Board_Init(void)
|
||||
{
|
||||
/* Delay system */
|
||||
PIOS_DELAY_Init();
|
||||
|
||||
const struct pios_board_info *bdinfo = &pios_board_info_blob;
|
||||
|
||||
#if defined(PIOS_INCLUDE_LED)
|
||||
const struct pios_gpio_cfg *led_cfg = PIOS_BOARD_HW_DEFS_GetLedCfg(bdinfo->board_rev);
|
||||
PIOS_Assert(led_cfg);
|
||||
PIOS_LED_Init(led_cfg);
|
||||
#endif /* PIOS_INCLUDE_LED */
|
||||
|
||||
#ifdef PIOS_INCLUDE_INSTRUMENTATION
|
||||
PIOS_Instrumentation_Init(PIOS_INSTRUMENTATION_MAX_COUNTERS);
|
||||
#endif
|
||||
|
||||
#if defined(PIOS_INCLUDE_SPI)
|
||||
/* Set up the SPI interface to the serial flash */
|
||||
|
||||
switch (bdinfo->board_rev) {
|
||||
case BOARD_REVISION_CC:
|
||||
if (PIOS_SPI_Init(&pios_spi_flash_accel_id, &pios_spi_flash_accel_cfg_cc)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
break;
|
||||
case BOARD_REVISION_CC3D:
|
||||
if (PIOS_SPI_Init(&pios_spi_flash_accel_id, &pios_spi_flash_accel_cfg_cc3d)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
break;
|
||||
default:
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
uintptr_t flash_id;
|
||||
switch (bdinfo->board_rev) {
|
||||
case BOARD_REVISION_CC:
|
||||
if (PIOS_Flash_Jedec_Init(&flash_id, pios_spi_flash_accel_id, 1)) {
|
||||
PIOS_DEBUG_Assert(0);
|
||||
}
|
||||
if (PIOS_FLASHFS_Logfs_Init(&pios_uavo_settings_fs_id, &flashfs_w25x_cfg, &pios_jedec_flash_driver, flash_id)) {
|
||||
PIOS_DEBUG_Assert(0);
|
||||
}
|
||||
break;
|
||||
case BOARD_REVISION_CC3D:
|
||||
if (PIOS_Flash_Jedec_Init(&flash_id, pios_spi_flash_accel_id, 0)) {
|
||||
PIOS_DEBUG_Assert(0);
|
||||
}
|
||||
if (PIOS_FLASHFS_Logfs_Init(&pios_uavo_settings_fs_id, &flashfs_m25p_cfg, &pios_jedec_flash_driver, flash_id)) {
|
||||
PIOS_DEBUG_Assert(0);
|
||||
}
|
||||
break;
|
||||
default:
|
||||
PIOS_DEBUG_Assert(0);
|
||||
}
|
||||
|
||||
/* Initialize the task monitor */
|
||||
if (PIOS_TASK_MONITOR_Initialize(TASKINFO_RUNNING_NUMELEM)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
|
||||
/* Initialize the delayed callback library */
|
||||
PIOS_CALLBACKSCHEDULER_Initialize();
|
||||
|
||||
/* Initialize UAVObject libraries */
|
||||
EventDispatcherInitialize();
|
||||
UAVObjInitialize();
|
||||
|
||||
#if defined(PIOS_INCLUDE_RTC)
|
||||
/* Initialize the real-time clock and its associated tick */
|
||||
PIOS_RTC_Init(&pios_rtc_main_cfg);
|
||||
#endif
|
||||
PIOS_IAP_Init();
|
||||
// check for safe mode commands from gcs
|
||||
if (PIOS_IAP_ReadBootCmd(0) == PIOS_IAP_CLEAR_FLASH_CMD_0 &&
|
||||
PIOS_IAP_ReadBootCmd(1) == PIOS_IAP_CLEAR_FLASH_CMD_1 &&
|
||||
PIOS_IAP_ReadBootCmd(2) == PIOS_IAP_CLEAR_FLASH_CMD_2) {
|
||||
PIOS_FLASHFS_Format(pios_uavo_settings_fs_id);
|
||||
PIOS_IAP_WriteBootCmd(0, 0);
|
||||
PIOS_IAP_WriteBootCmd(1, 0);
|
||||
PIOS_IAP_WriteBootCmd(2, 0);
|
||||
}
|
||||
|
||||
HwSettingsInitialize();
|
||||
|
||||
#ifndef ERASE_FLASH
|
||||
#ifdef PIOS_INCLUDE_WDG
|
||||
/* Initialize watchdog as early as possible to catch faults during init */
|
||||
PIOS_WDG_Init();
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/* Initialize the alarms library */
|
||||
AlarmsInitialize();
|
||||
|
||||
/* Check for repeated boot failures */
|
||||
uint16_t boot_count = PIOS_IAP_ReadBootCount();
|
||||
if (boot_count < 3) {
|
||||
PIOS_IAP_WriteBootCount(++boot_count);
|
||||
AlarmsClear(SYSTEMALARMS_ALARM_BOOTFAULT);
|
||||
} else {
|
||||
/* Too many failed boot attempts, force hwsettings to defaults */
|
||||
HwSettingsSetDefaults(HwSettingsHandle(), 0);
|
||||
AlarmsSet(SYSTEMALARMS_ALARM_BOOTFAULT, SYSTEMALARMS_ALARM_CRITICAL);
|
||||
}
|
||||
|
||||
/* Set up pulse timers */
|
||||
PIOS_TIM_InitClock(&tim_1_cfg);
|
||||
PIOS_TIM_InitClock(&tim_2_cfg);
|
||||
PIOS_TIM_InitClock(&tim_3_cfg);
|
||||
PIOS_TIM_InitClock(&tim_4_cfg);
|
||||
|
||||
#if defined(PIOS_INCLUDE_USB)
|
||||
/* Initialize board specific USB data */
|
||||
PIOS_USB_BOARD_DATA_Init();
|
||||
|
||||
|
||||
/* Flags to determine if various USB interfaces are advertised */
|
||||
bool usb_hid_present = false;
|
||||
bool usb_cdc_present = false;
|
||||
|
||||
#if defined(PIOS_INCLUDE_USB_CDC)
|
||||
if (PIOS_USB_DESC_HID_CDC_Init()) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
usb_hid_present = true;
|
||||
usb_cdc_present = true;
|
||||
#else
|
||||
if (PIOS_USB_DESC_HID_ONLY_Init()) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
usb_hid_present = true;
|
||||
#endif
|
||||
|
||||
uint32_t pios_usb_id;
|
||||
|
||||
switch (bdinfo->board_rev) {
|
||||
case BOARD_REVISION_CC:
|
||||
PIOS_USB_Init(&pios_usb_id, &pios_usb_main_cfg_cc);
|
||||
break;
|
||||
case BOARD_REVISION_CC3D:
|
||||
PIOS_USB_Init(&pios_usb_id, &pios_usb_main_cfg_cc3d);
|
||||
break;
|
||||
default:
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
|
||||
#if defined(PIOS_INCLUDE_USB_CDC)
|
||||
|
||||
uint8_t hwsettings_usb_vcpport;
|
||||
/* Configure the USB VCP port */
|
||||
HwSettingsUSB_VCPPortGet(&hwsettings_usb_vcpport);
|
||||
|
||||
if (!usb_cdc_present) {
|
||||
/* Force VCP port function to disabled if we haven't advertised VCP in our USB descriptor */
|
||||
hwsettings_usb_vcpport = HWSETTINGS_USB_VCPPORT_DISABLED;
|
||||
}
|
||||
|
||||
switch (hwsettings_usb_vcpport) {
|
||||
case HWSETTINGS_USB_VCPPORT_DISABLED:
|
||||
break;
|
||||
case HWSETTINGS_USB_VCPPORT_USBTELEMETRY:
|
||||
#if defined(PIOS_INCLUDE_COM)
|
||||
{
|
||||
uint32_t pios_usb_cdc_id;
|
||||
if (PIOS_USB_CDC_Init(&pios_usb_cdc_id, &pios_usb_cdc_cfg, pios_usb_id)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
uint8_t *rx_buffer = (uint8_t *)pios_malloc(PIOS_COM_TELEM_USB_RX_BUF_LEN);
|
||||
uint8_t *tx_buffer = (uint8_t *)pios_malloc(PIOS_COM_TELEM_USB_TX_BUF_LEN);
|
||||
PIOS_Assert(rx_buffer);
|
||||
PIOS_Assert(tx_buffer);
|
||||
if (PIOS_COM_Init(&pios_com_telem_usb_id, &pios_usb_cdc_com_driver, pios_usb_cdc_id,
|
||||
rx_buffer, PIOS_COM_TELEM_USB_RX_BUF_LEN,
|
||||
tx_buffer, PIOS_COM_TELEM_USB_TX_BUF_LEN)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_COM */
|
||||
break;
|
||||
case HWSETTINGS_USB_VCPPORT_COMBRIDGE:
|
||||
#if defined(PIOS_INCLUDE_COM)
|
||||
{
|
||||
uint32_t pios_usb_cdc_id;
|
||||
if (PIOS_USB_CDC_Init(&pios_usb_cdc_id, &pios_usb_cdc_cfg, pios_usb_id)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
uint8_t *rx_buffer = (uint8_t *)pios_malloc(PIOS_COM_BRIDGE_RX_BUF_LEN);
|
||||
uint8_t *tx_buffer = (uint8_t *)pios_malloc(PIOS_COM_BRIDGE_TX_BUF_LEN);
|
||||
PIOS_Assert(rx_buffer);
|
||||
PIOS_Assert(tx_buffer);
|
||||
if (PIOS_COM_Init(&pios_com_vcp_id, &pios_usb_cdc_com_driver, pios_usb_cdc_id,
|
||||
rx_buffer, PIOS_COM_BRIDGE_RX_BUF_LEN,
|
||||
tx_buffer, PIOS_COM_BRIDGE_TX_BUF_LEN)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_COM */
|
||||
break;
|
||||
case HWSETTINGS_USB_VCPPORT_DEBUGCONSOLE:
|
||||
#if defined(PIOS_INCLUDE_COM)
|
||||
#if defined(PIOS_INCLUDE_DEBUG_CONSOLE)
|
||||
{
|
||||
uint32_t pios_usb_cdc_id;
|
||||
if (PIOS_USB_CDC_Init(&pios_usb_cdc_id, &pios_usb_cdc_cfg, pios_usb_id)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
uint8_t *tx_buffer = (uint8_t *)pios_malloc(PIOS_COM_DEBUGCONSOLE_TX_BUF_LEN);
|
||||
PIOS_Assert(tx_buffer);
|
||||
if (PIOS_COM_Init(&pios_com_debug_id, &pios_usb_cdc_com_driver, pios_usb_cdc_id,
|
||||
NULL, 0,
|
||||
tx_buffer, PIOS_COM_DEBUGCONSOLE_TX_BUF_LEN)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_DEBUG_CONSOLE */
|
||||
#endif /* PIOS_INCLUDE_COM */
|
||||
break;
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_USB_CDC */
|
||||
|
||||
#if defined(PIOS_INCLUDE_USB_HID)
|
||||
/* Configure the usb HID port */
|
||||
uint8_t hwsettings_usb_hidport;
|
||||
HwSettingsUSB_HIDPortGet(&hwsettings_usb_hidport);
|
||||
|
||||
if (!usb_hid_present) {
|
||||
/* Force HID port function to disabled if we haven't advertised HID in our USB descriptor */
|
||||
hwsettings_usb_hidport = HWSETTINGS_USB_HIDPORT_DISABLED;
|
||||
}
|
||||
|
||||
switch (hwsettings_usb_hidport) {
|
||||
case HWSETTINGS_USB_HIDPORT_DISABLED:
|
||||
break;
|
||||
case HWSETTINGS_USB_HIDPORT_USBTELEMETRY:
|
||||
#if defined(PIOS_INCLUDE_COM)
|
||||
{
|
||||
uint32_t pios_usb_hid_id;
|
||||
if (PIOS_USB_HID_Init(&pios_usb_hid_id, &pios_usb_hid_cfg, pios_usb_id)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
uint8_t *rx_buffer = (uint8_t *)pios_malloc(PIOS_COM_TELEM_USB_RX_BUF_LEN);
|
||||
uint8_t *tx_buffer = (uint8_t *)pios_malloc(PIOS_COM_TELEM_USB_TX_BUF_LEN);
|
||||
PIOS_Assert(rx_buffer);
|
||||
PIOS_Assert(tx_buffer);
|
||||
if (PIOS_COM_Init(&pios_com_telem_usb_id, &pios_usb_hid_com_driver, pios_usb_hid_id,
|
||||
rx_buffer, PIOS_COM_TELEM_USB_RX_BUF_LEN,
|
||||
tx_buffer, PIOS_COM_TELEM_USB_TX_BUF_LEN)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_COM */
|
||||
break;
|
||||
case HWSETTINGS_USB_HIDPORT_RCTRANSMITTER:
|
||||
#if defined(PIOS_INCLUDE_USB_RCTX)
|
||||
{
|
||||
if (PIOS_USB_RCTX_Init(&pios_usb_rctx_id, &pios_usb_rctx_cfg, pios_usb_id)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_USB_RCTX */
|
||||
break;
|
||||
}
|
||||
|
||||
#endif /* PIOS_INCLUDE_USB_HID */
|
||||
|
||||
#endif /* PIOS_INCLUDE_USB */
|
||||
|
||||
/* Configure the main IO port */
|
||||
uint8_t hwsettings_DSMxBind;
|
||||
HwSettingsDSMxBindGet(&hwsettings_DSMxBind);
|
||||
uint8_t hwsettings_cc_mainport;
|
||||
HwSettingsCC_MainPortGet(&hwsettings_cc_mainport);
|
||||
|
||||
switch (hwsettings_cc_mainport) {
|
||||
case HWSETTINGS_CC_MAINPORT_DISABLED:
|
||||
break;
|
||||
case HWSETTINGS_CC_MAINPORT_TELEMETRY:
|
||||
#if defined(PIOS_INCLUDE_TELEMETRY_RF)
|
||||
{
|
||||
uint32_t pios_usart_generic_id;
|
||||
if (PIOS_USART_Init(&pios_usart_generic_id, &pios_usart_generic_main_cfg)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
|
||||
uint8_t *rx_buffer = (uint8_t *)pios_malloc(PIOS_COM_TELEM_RF_RX_BUF_LEN);
|
||||
uint8_t *tx_buffer = (uint8_t *)pios_malloc(PIOS_COM_TELEM_RF_TX_BUF_LEN);
|
||||
PIOS_Assert(rx_buffer);
|
||||
PIOS_Assert(tx_buffer);
|
||||
if (PIOS_COM_Init(&pios_com_telem_rf_id, &pios_usart_com_driver, pios_usart_generic_id,
|
||||
rx_buffer, PIOS_COM_TELEM_RF_RX_BUF_LEN,
|
||||
tx_buffer, PIOS_COM_TELEM_RF_TX_BUF_LEN)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_TELEMETRY_RF */
|
||||
break;
|
||||
case HWSETTINGS_CC_MAINPORT_SBUS:
|
||||
#if defined(PIOS_INCLUDE_SBUS)
|
||||
{
|
||||
uint32_t pios_usart_sbus_id;
|
||||
if (PIOS_USART_Init(&pios_usart_sbus_id, &pios_usart_sbus_main_cfg)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
|
||||
uint32_t pios_sbus_id;
|
||||
if (PIOS_SBus_Init(&pios_sbus_id, &pios_sbus_cfg, &pios_usart_com_driver, pios_usart_sbus_id)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
|
||||
uint32_t pios_sbus_rcvr_id;
|
||||
if (PIOS_RCVR_Init(&pios_sbus_rcvr_id, &pios_sbus_rcvr_driver, pios_sbus_id)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_SBUS] = pios_sbus_rcvr_id;
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_SBUS */
|
||||
break;
|
||||
case HWSETTINGS_CC_MAINPORT_GPS:
|
||||
#if defined(PIOS_INCLUDE_GPS)
|
||||
{
|
||||
uint32_t pios_usart_generic_id;
|
||||
if (PIOS_USART_Init(&pios_usart_generic_id, &pios_usart_generic_main_cfg)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
|
||||
uint8_t *rx_buffer = (uint8_t *)pios_malloc(PIOS_COM_GPS_RX_BUF_LEN);
|
||||
PIOS_Assert(rx_buffer);
|
||||
if (PIOS_COM_Init(&pios_com_gps_id, &pios_usart_com_driver, pios_usart_generic_id,
|
||||
rx_buffer, PIOS_COM_GPS_RX_BUF_LEN,
|
||||
NULL, 0)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_GPS */
|
||||
break;
|
||||
case HWSETTINGS_CC_MAINPORT_DSM:
|
||||
#if defined(PIOS_INCLUDE_DSM)
|
||||
{
|
||||
uint32_t pios_usart_dsm_id;
|
||||
if (PIOS_USART_Init(&pios_usart_dsm_id, &pios_usart_dsm_main_cfg)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
|
||||
uint32_t pios_dsm_id;
|
||||
if (PIOS_DSM_Init(&pios_dsm_id,
|
||||
&pios_dsm_main_cfg,
|
||||
&pios_usart_com_driver,
|
||||
pios_usart_dsm_id,
|
||||
0)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
|
||||
uint32_t pios_dsm_rcvr_id;
|
||||
if (PIOS_RCVR_Init(&pios_dsm_rcvr_id, &pios_dsm_rcvr_driver, pios_dsm_id)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_DSMMAINPORT] = pios_dsm_rcvr_id;
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_DSM */
|
||||
break;
|
||||
case HWSETTINGS_CC_MAINPORT_DEBUGCONSOLE:
|
||||
#if defined(PIOS_INCLUDE_COM)
|
||||
#if defined(PIOS_INCLUDE_DEBUG_CONSOLE)
|
||||
{
|
||||
uint32_t pios_usart_generic_id;
|
||||
if (PIOS_USART_Init(&pios_usart_generic_id, &pios_usart_generic_main_cfg)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
|
||||
uint8_t *tx_buffer = (uint8_t *)pios_malloc(PIOS_COM_DEBUGCONSOLE_TX_BUF_LEN);
|
||||
PIOS_Assert(tx_buffer);
|
||||
if (PIOS_COM_Init(&pios_com_debug_id, &pios_usart_com_driver, pios_usart_generic_id,
|
||||
NULL, 0,
|
||||
tx_buffer, PIOS_COM_DEBUGCONSOLE_TX_BUF_LEN)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_DEBUG_CONSOLE */
|
||||
#endif /* PIOS_INCLUDE_COM */
|
||||
break;
|
||||
case HWSETTINGS_CC_MAINPORT_COMBRIDGE:
|
||||
{
|
||||
uint32_t pios_usart_generic_id;
|
||||
if (PIOS_USART_Init(&pios_usart_generic_id, &pios_usart_generic_main_cfg)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
|
||||
uint8_t *rx_buffer = (uint8_t *)pios_malloc(PIOS_COM_BRIDGE_RX_BUF_LEN);
|
||||
PIOS_Assert(rx_buffer);
|
||||
uint8_t *tx_buffer = (uint8_t *)pios_malloc(PIOS_COM_BRIDGE_TX_BUF_LEN);
|
||||
PIOS_Assert(tx_buffer);
|
||||
if (PIOS_COM_Init(&pios_com_bridge_id, &pios_usart_com_driver, pios_usart_generic_id,
|
||||
rx_buffer, PIOS_COM_BRIDGE_RX_BUF_LEN,
|
||||
tx_buffer, PIOS_COM_BRIDGE_TX_BUF_LEN)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
}
|
||||
break;
|
||||
case HWSETTINGS_CC_MAINPORT_OSDHK:
|
||||
{
|
||||
uint32_t pios_usart_hkosd_id;
|
||||
if (PIOS_USART_Init(&pios_usart_hkosd_id, &pios_usart_hkosd_main_cfg)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
|
||||
uint8_t *tx_buffer = (uint8_t *)pios_malloc(PIOS_COM_HKOSD_TX_BUF_LEN);
|
||||
PIOS_Assert(tx_buffer);
|
||||
if (PIOS_COM_Init(&pios_com_hkosd_id, &pios_usart_com_driver, pios_usart_hkosd_id,
|
||||
NULL, 0,
|
||||
tx_buffer, PIOS_COM_HKOSD_TX_BUF_LEN)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
}
|
||||
break;
|
||||
}
|
||||
|
||||
/* Configure the flexi port */
|
||||
uint8_t hwsettings_cc_flexiport;
|
||||
HwSettingsCC_FlexiPortGet(&hwsettings_cc_flexiport);
|
||||
|
||||
switch (hwsettings_cc_flexiport) {
|
||||
case HWSETTINGS_CC_FLEXIPORT_DISABLED:
|
||||
break;
|
||||
case HWSETTINGS_CC_FLEXIPORT_TELEMETRY:
|
||||
#if defined(PIOS_INCLUDE_TELEMETRY_RF)
|
||||
{
|
||||
uint32_t pios_usart_generic_id;
|
||||
if (PIOS_USART_Init(&pios_usart_generic_id, &pios_usart_generic_flexi_cfg)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
uint8_t *rx_buffer = (uint8_t *)pios_malloc(PIOS_COM_TELEM_RF_RX_BUF_LEN);
|
||||
uint8_t *tx_buffer = (uint8_t *)pios_malloc(PIOS_COM_TELEM_RF_TX_BUF_LEN);
|
||||
PIOS_Assert(rx_buffer);
|
||||
PIOS_Assert(tx_buffer);
|
||||
if (PIOS_COM_Init(&pios_com_telem_rf_id, &pios_usart_com_driver, pios_usart_generic_id,
|
||||
rx_buffer, PIOS_COM_TELEM_RF_RX_BUF_LEN,
|
||||
tx_buffer, PIOS_COM_TELEM_RF_TX_BUF_LEN)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_TELEMETRY_RF */
|
||||
break;
|
||||
case HWSETTINGS_CC_FLEXIPORT_COMBRIDGE:
|
||||
{
|
||||
uint32_t pios_usart_generic_id;
|
||||
if (PIOS_USART_Init(&pios_usart_generic_id, &pios_usart_generic_flexi_cfg)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
|
||||
uint8_t *rx_buffer = (uint8_t *)pios_malloc(PIOS_COM_BRIDGE_RX_BUF_LEN);
|
||||
uint8_t *tx_buffer = (uint8_t *)pios_malloc(PIOS_COM_BRIDGE_TX_BUF_LEN);
|
||||
PIOS_Assert(rx_buffer);
|
||||
PIOS_Assert(tx_buffer);
|
||||
if (PIOS_COM_Init(&pios_com_bridge_id, &pios_usart_com_driver, pios_usart_generic_id,
|
||||
rx_buffer, PIOS_COM_BRIDGE_RX_BUF_LEN,
|
||||
tx_buffer, PIOS_COM_BRIDGE_TX_BUF_LEN)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
}
|
||||
break;
|
||||
case HWSETTINGS_CC_FLEXIPORT_GPS:
|
||||
#if defined(PIOS_INCLUDE_GPS)
|
||||
{
|
||||
uint32_t pios_usart_generic_id;
|
||||
if (PIOS_USART_Init(&pios_usart_generic_id, &pios_usart_generic_flexi_cfg)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
uint8_t *rx_buffer = (uint8_t *)pios_malloc(PIOS_COM_GPS_RX_BUF_LEN);
|
||||
PIOS_Assert(rx_buffer);
|
||||
if (PIOS_COM_Init(&pios_com_gps_id, &pios_usart_com_driver, pios_usart_generic_id,
|
||||
rx_buffer, PIOS_COM_GPS_RX_BUF_LEN,
|
||||
NULL, 0)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_GPS */
|
||||
break;
|
||||
case HWSETTINGS_CC_FLEXIPORT_PPM:
|
||||
#if defined(PIOS_INCLUDE_PPM_FLEXI)
|
||||
{
|
||||
uint32_t pios_ppm_id;
|
||||
PIOS_PPM_Init(&pios_ppm_id, &pios_ppm_flexi_cfg);
|
||||
|
||||
uint32_t pios_ppm_rcvr_id;
|
||||
if (PIOS_RCVR_Init(&pios_ppm_rcvr_id, &pios_ppm_rcvr_driver, pios_ppm_id)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_PPM] = pios_ppm_rcvr_id;
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_PPM_FLEXI */
|
||||
break;
|
||||
case HWSETTINGS_CC_FLEXIPORT_DSM:
|
||||
#if defined(PIOS_INCLUDE_DSM)
|
||||
{
|
||||
uint32_t pios_usart_dsm_id;
|
||||
if (PIOS_USART_Init(&pios_usart_dsm_id, &pios_usart_dsm_flexi_cfg)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
|
||||
uint32_t pios_dsm_id;
|
||||
if (PIOS_DSM_Init(&pios_dsm_id,
|
||||
&pios_dsm_flexi_cfg,
|
||||
&pios_usart_com_driver,
|
||||
pios_usart_dsm_id,
|
||||
hwsettings_DSMxBind)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
|
||||
uint32_t pios_dsm_rcvr_id;
|
||||
if (PIOS_RCVR_Init(&pios_dsm_rcvr_id, &pios_dsm_rcvr_driver, pios_dsm_id)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_DSMFLEXIPORT] = pios_dsm_rcvr_id;
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_DSM */
|
||||
break;
|
||||
case HWSETTINGS_CC_FLEXIPORT_DEBUGCONSOLE:
|
||||
#if defined(PIOS_INCLUDE_COM)
|
||||
#if defined(PIOS_INCLUDE_DEBUG_CONSOLE)
|
||||
{
|
||||
uint32_t pios_usart_generic_id;
|
||||
if (PIOS_USART_Init(&pios_usart_generic_id, &pios_usart_generic_flexi_cfg)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
|
||||
uint8_t *tx_buffer = (uint8_t *)pios_malloc(PIOS_COM_DEBUGCONSOLE_TX_BUF_LEN);
|
||||
PIOS_Assert(tx_buffer);
|
||||
if (PIOS_COM_Init(&pios_com_debug_id, &pios_usart_com_driver, pios_usart_generic_id,
|
||||
NULL, 0,
|
||||
tx_buffer, PIOS_COM_DEBUGCONSOLE_TX_BUF_LEN)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_DEBUG_CONSOLE */
|
||||
#endif /* PIOS_INCLUDE_COM */
|
||||
break;
|
||||
case HWSETTINGS_CC_FLEXIPORT_I2C:
|
||||
#if defined(PIOS_INCLUDE_I2C)
|
||||
{
|
||||
if (PIOS_I2C_Init(&pios_i2c_flexi_adapter_id, &pios_i2c_flexi_adapter_cfg)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_I2C */
|
||||
break;
|
||||
case HWSETTINGS_CC_FLEXIPORT_OSDHK:
|
||||
{
|
||||
uint32_t pios_usart_hkosd_id;
|
||||
if (PIOS_USART_Init(&pios_usart_hkosd_id, &pios_usart_hkosd_flexi_cfg)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
|
||||
uint8_t *tx_buffer = (uint8_t *)pios_malloc(PIOS_COM_HKOSD_TX_BUF_LEN);
|
||||
PIOS_Assert(tx_buffer);
|
||||
if (PIOS_COM_Init(&pios_com_hkosd_id, &pios_usart_com_driver, pios_usart_hkosd_id,
|
||||
NULL, 0,
|
||||
tx_buffer, PIOS_COM_HKOSD_TX_BUF_LEN)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
}
|
||||
break;
|
||||
}
|
||||
|
||||
/* Configure the rcvr port */
|
||||
uint8_t hwsettings_rcvrport;
|
||||
HwSettingsCC_RcvrPortGet(&hwsettings_rcvrport);
|
||||
|
||||
switch ((HwSettingsCC_RcvrPortOptions)hwsettings_rcvrport) {
|
||||
case HWSETTINGS_CC_RCVRPORT_DISABLEDONESHOT:
|
||||
#if defined(PIOS_INCLUDE_HCSR04)
|
||||
{
|
||||
uint32_t pios_hcsr04_id;
|
||||
PIOS_HCSR04_Init(&pios_hcsr04_id, &pios_hcsr04_cfg);
|
||||
}
|
||||
#endif
|
||||
break;
|
||||
case HWSETTINGS_CC_RCVRPORT_PWMNOONESHOT:
|
||||
#if defined(PIOS_INCLUDE_PWM)
|
||||
{
|
||||
uint32_t pios_pwm_id;
|
||||
PIOS_PWM_Init(&pios_pwm_id, &pios_pwm_cfg);
|
||||
|
||||
uint32_t pios_pwm_rcvr_id;
|
||||
if (PIOS_RCVR_Init(&pios_pwm_rcvr_id, &pios_pwm_rcvr_driver, pios_pwm_id)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_PWM] = pios_pwm_rcvr_id;
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_PWM */
|
||||
break;
|
||||
case HWSETTINGS_CC_RCVRPORT_PPMNOONESHOT:
|
||||
case HWSETTINGS_CC_RCVRPORT_PPMOUTPUTSNOONESHOT:
|
||||
case HWSETTINGS_CC_RCVRPORT_PPM_PIN8ONESHOT:
|
||||
#if defined(PIOS_INCLUDE_PPM)
|
||||
{
|
||||
uint32_t pios_ppm_id;
|
||||
if (hwsettings_rcvrport == HWSETTINGS_CC_RCVRPORT_PPM_PIN8ONESHOT) {
|
||||
PIOS_PPM_Init(&pios_ppm_id, &pios_ppm_pin8_cfg);
|
||||
} else {
|
||||
PIOS_PPM_Init(&pios_ppm_id, &pios_ppm_cfg);
|
||||
}
|
||||
|
||||
uint32_t pios_ppm_rcvr_id;
|
||||
if (PIOS_RCVR_Init(&pios_ppm_rcvr_id, &pios_ppm_rcvr_driver, pios_ppm_id)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_PPM] = pios_ppm_rcvr_id;
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_PPM */
|
||||
break;
|
||||
case HWSETTINGS_CC_RCVRPORT_PPMPWMNOONESHOT:
|
||||
/* This is a combination of PPM and PWM inputs */
|
||||
#if defined(PIOS_INCLUDE_PPM)
|
||||
{
|
||||
uint32_t pios_ppm_id;
|
||||
PIOS_PPM_Init(&pios_ppm_id, &pios_ppm_cfg);
|
||||
|
||||
uint32_t pios_ppm_rcvr_id;
|
||||
if (PIOS_RCVR_Init(&pios_ppm_rcvr_id, &pios_ppm_rcvr_driver, pios_ppm_id)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_PPM] = pios_ppm_rcvr_id;
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_PPM */
|
||||
#if defined(PIOS_INCLUDE_PWM)
|
||||
{
|
||||
uint32_t pios_pwm_id;
|
||||
PIOS_PWM_Init(&pios_pwm_id, &pios_pwm_with_ppm_cfg);
|
||||
|
||||
uint32_t pios_pwm_rcvr_id;
|
||||
if (PIOS_RCVR_Init(&pios_pwm_rcvr_id, &pios_pwm_rcvr_driver, pios_pwm_id)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_PWM] = pios_pwm_rcvr_id;
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_PWM */
|
||||
break;
|
||||
case HWSETTINGS_CC_RCVRPORT_OUTPUTSONESHOT:
|
||||
break;
|
||||
}
|
||||
|
||||
#if defined(PIOS_INCLUDE_GCSRCVR)
|
||||
GCSReceiverInitialize();
|
||||
uint32_t pios_gcsrcvr_id;
|
||||
PIOS_GCSRCVR_Init(&pios_gcsrcvr_id);
|
||||
uint32_t pios_gcsrcvr_rcvr_id;
|
||||
if (PIOS_RCVR_Init(&pios_gcsrcvr_rcvr_id, &pios_gcsrcvr_rcvr_driver, pios_gcsrcvr_id)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_GCS] = pios_gcsrcvr_rcvr_id;
|
||||
#endif /* PIOS_INCLUDE_GCSRCVR */
|
||||
|
||||
/* Remap AFIO pin for PB4 (Servo 5 Out)*/
|
||||
GPIO_PinRemapConfig(GPIO_Remap_SWJ_NoJTRST, ENABLE);
|
||||
|
||||
#ifndef PIOS_ENABLE_DEBUG_PINS
|
||||
switch ((HwSettingsCC_RcvrPortOptions)hwsettings_rcvrport) {
|
||||
case HWSETTINGS_CC_RCVRPORT_DISABLEDONESHOT:
|
||||
case HWSETTINGS_CC_RCVRPORT_PWMNOONESHOT:
|
||||
case HWSETTINGS_CC_RCVRPORT_PPMNOONESHOT:
|
||||
case HWSETTINGS_CC_RCVRPORT_PPMPWMNOONESHOT:
|
||||
case HWSETTINGS_CC_RCVRPORT_PPM_PIN8ONESHOT:
|
||||
PIOS_Servo_Init(&pios_servo_cfg);
|
||||
break;
|
||||
case HWSETTINGS_CC_RCVRPORT_PPMOUTPUTSNOONESHOT:
|
||||
case HWSETTINGS_CC_RCVRPORT_OUTPUTSONESHOT:
|
||||
PIOS_Servo_Init(&pios_servo_rcvr_cfg);
|
||||
break;
|
||||
}
|
||||
#else
|
||||
PIOS_DEBUG_Init(pios_tim_servoport_all_pins, NELEMENTS(pios_tim_servoport_all_pins));
|
||||
#endif /* PIOS_ENABLE_DEBUG_PINS */
|
||||
|
||||
switch (bdinfo->board_rev) {
|
||||
case BOARD_REVISION_CC:
|
||||
// Revision 1 with invensense gyros, start the ADC
|
||||
#if defined(PIOS_INCLUDE_ADC)
|
||||
PIOS_ADC_Init(&pios_adc_cfg);
|
||||
#endif
|
||||
#if defined(PIOS_INCLUDE_ADXL345)
|
||||
PIOS_ADXL345_Init(pios_spi_flash_accel_id, 0);
|
||||
#endif
|
||||
break;
|
||||
case BOARD_REVISION_CC3D:
|
||||
// Revision 2 with MPU6000 gyros, start a SPI interface and connect to it
|
||||
GPIO_PinRemapConfig(GPIO_Remap_SWJ_JTAGDisable, ENABLE);
|
||||
|
||||
#if defined(PIOS_INCLUDE_MPU6000)
|
||||
// Set up the SPI interface to the serial flash
|
||||
if (PIOS_SPI_Init(&pios_spi_gyro_id, &pios_spi_gyro_cfg)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
PIOS_MPU6000_Init(pios_spi_gyro_id, 0, &pios_mpu6000_cfg);
|
||||
PIOS_MPU6000_CONFIG_Configure();
|
||||
init_test = !PIOS_MPU6000_Driver.test(0);
|
||||
#endif /* PIOS_INCLUDE_MPU6000 */
|
||||
|
||||
break;
|
||||
default:
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
|
||||
/* Make sure we have at least one telemetry link configured or else fail initialization */
|
||||
PIOS_Assert(pios_com_telem_rf_id || pios_com_telem_usb_id);
|
||||
|
||||
// Attach the board config check hook
|
||||
SANITYCHECK_AttachHook(&CopterControlConfigHook);
|
||||
// trigger a config check if actuatorsettings are updated
|
||||
ActuatorSettingsInitialize();
|
||||
ActuatorSettingsConnectCallback(ActuatorSettingsUpdatedCb);
|
||||
}
|
||||
|
||||
SystemAlarmsExtendedAlarmStatusOptions CopterControlConfigHook()
|
||||
{
|
||||
// inhibit usage of oneshot for non supported RECEIVER port modes
|
||||
uint8_t recmode;
|
||||
|
||||
HwSettingsCC_RcvrPortGet(&recmode);
|
||||
uint8_t flexiMode;
|
||||
uint8_t modes[ACTUATORSETTINGS_BANKMODE_NUMELEM];
|
||||
ActuatorSettingsBankModeGet(modes);
|
||||
HwSettingsCC_FlexiPortGet(&flexiMode);
|
||||
|
||||
switch ((HwSettingsCC_RcvrPortOptions)recmode) {
|
||||
// Those modes allows oneshot usage
|
||||
case HWSETTINGS_CC_RCVRPORT_DISABLEDONESHOT:
|
||||
case HWSETTINGS_CC_RCVRPORT_OUTPUTSONESHOT:
|
||||
case HWSETTINGS_CC_RCVRPORT_PPM_PIN8ONESHOT:
|
||||
if ((recmode == HWSETTINGS_CC_RCVRPORT_PPM_PIN8ONESHOT ||
|
||||
flexiMode == HWSETTINGS_CC_FLEXIPORT_PPM) &&
|
||||
(modes[3] == ACTUATORSETTINGS_BANKMODE_PWMSYNC ||
|
||||
modes[3] == ACTUATORSETTINGS_BANKMODE_ONESHOT125)) {
|
||||
return SYSTEMALARMS_EXTENDEDALARMSTATUS_UNSUPPORTEDCONFIG_ONESHOT;
|
||||
} else {
|
||||
return SYSTEMALARMS_EXTENDEDALARMSTATUS_NONE;
|
||||
}
|
||||
|
||||
// inhibit oneshot for the following modes
|
||||
case HWSETTINGS_CC_RCVRPORT_PPMNOONESHOT:
|
||||
case HWSETTINGS_CC_RCVRPORT_PPMOUTPUTSNOONESHOT:
|
||||
case HWSETTINGS_CC_RCVRPORT_PPMPWMNOONESHOT:
|
||||
case HWSETTINGS_CC_RCVRPORT_PWMNOONESHOT:
|
||||
for (uint8_t i = 0; i < ACTUATORSETTINGS_BANKMODE_NUMELEM; i++) {
|
||||
if (modes[i] == ACTUATORSETTINGS_BANKMODE_PWMSYNC ||
|
||||
modes[i] == ACTUATORSETTINGS_BANKMODE_ONESHOT125) {
|
||||
return SYSTEMALARMS_EXTENDEDALARMSTATUS_UNSUPPORTEDCONFIG_ONESHOT;;
|
||||
}
|
||||
|
||||
return SYSTEMALARMS_EXTENDEDALARMSTATUS_NONE;
|
||||
}
|
||||
}
|
||||
return SYSTEMALARMS_EXTENDEDALARMSTATUS_UNSUPPORTEDCONFIG_ONESHOT;;
|
||||
}
|
||||
// trigger a configuration check if ActuatorSettings are changed.
|
||||
void ActuatorSettingsUpdatedCb(__attribute__((unused)) UAVObjEvent *ev)
|
||||
{
|
||||
configuration_check();
|
||||
}
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
145
flight/targets/boards/coptercontrol/firmware/pios_board_posix.c
Normal file
@ -0,0 +1,145 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file pios_board.c
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @brief Defines board specific static initializers for hardware for the OpenPilot board.
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
*
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* This program is free software; you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation; either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful, but
|
||||
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
|
||||
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
|
||||
* for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License along
|
||||
* with this program; if not, write to the Free Software Foundation, Inc.,
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
|
||||
#include "inc/openpilot.h"
|
||||
#include <pios_udp_priv.h>
|
||||
#include <pios_com_priv.h>
|
||||
#include <uavobjectsinit.h>
|
||||
|
||||
/**
|
||||
* PIOS_Board_Init()
|
||||
* initializes all the core systems on this specific hardware
|
||||
* called from System/openpilot.c
|
||||
*/
|
||||
void PIOS_Board_Init(void)
|
||||
{
|
||||
/* Delay system */
|
||||
PIOS_DELAY_Init();
|
||||
|
||||
/* Initialize the delayed callback library */
|
||||
PIOS_CALLBACKSCHEDULER_Initialize();
|
||||
|
||||
/* Initialize UAVObject libraries */
|
||||
EventDispatcherInitialize();
|
||||
UAVObjInitialize();
|
||||
|
||||
/* Initialize the alarms library */
|
||||
AlarmsInitialize();
|
||||
|
||||
/* Initialize the task monitor */
|
||||
if (PIOS_TASK_MONITOR_Initialize(TASKINFO_RUNNING_NUMELEM)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
|
||||
/* Initialize the PiOS library */
|
||||
PIOS_COM_Init();
|
||||
}
|
||||
|
||||
|
||||
const struct pios_udp_cfg pios_udp0_cfg = {
|
||||
.ip = "0.0.0.0",
|
||||
.port = 9000,
|
||||
};
|
||||
const struct pios_udp_cfg pios_udp1_cfg = {
|
||||
.ip = "0.0.0.0",
|
||||
.port = 9001,
|
||||
};
|
||||
const struct pios_udp_cfg pios_udp2_cfg = {
|
||||
.ip = "0.0.0.0",
|
||||
.port = 9002,
|
||||
};
|
||||
|
||||
#ifdef PIOS_COM_AUX
|
||||
/*
|
||||
* AUX USART
|
||||
*/
|
||||
const struct pios_udp_cfg pios_udp3_cfg = {
|
||||
.ip = "0.0.0.0",
|
||||
.port = 9003,
|
||||
};
|
||||
#endif
|
||||
|
||||
/*
|
||||
* Board specific number of devices.
|
||||
*/
|
||||
struct pios_udp_dev pios_udp_devs[] = {
|
||||
#define PIOS_UDP_TELEM 0
|
||||
{
|
||||
.cfg = &pios_udp0_cfg,
|
||||
},
|
||||
#define PIOS_UDP_GPS 1
|
||||
{
|
||||
.cfg = &pios_udp1_cfg,
|
||||
},
|
||||
#define PIOS_UDP_LOCAL 2
|
||||
{
|
||||
.cfg = &pios_udp2_cfg,
|
||||
},
|
||||
#ifdef PIOS_COM_AUX
|
||||
#define PIOS_UDP_AUX 3
|
||||
{
|
||||
.cfg = &pios_udp3_cfg,
|
||||
},
|
||||
#endif
|
||||
};
|
||||
|
||||
uint8_t pios_udp_num_devices = NELEMENTS(pios_udp_devs);
|
||||
|
||||
/*
|
||||
* COM devices
|
||||
*/
|
||||
|
||||
/*
|
||||
* Board specific number of devices.
|
||||
*/
|
||||
extern const struct pios_com_driver pios_serial_com_driver;
|
||||
extern const struct pios_com_driver pios_udp_com_driver;
|
||||
|
||||
struct pios_com_dev pios_com_devs[] = {
|
||||
{
|
||||
.id = PIOS_UDP_TELEM,
|
||||
.driver = &pios_udp_com_driver,
|
||||
},
|
||||
{
|
||||
.id = PIOS_UDP_GPS,
|
||||
.driver = &pios_udp_com_driver,
|
||||
},
|
||||
{
|
||||
.id = PIOS_UDP_LOCAL,
|
||||
.driver = &pios_udp_com_driver,
|
||||
},
|
||||
#ifdef PIOS_COM_AUX
|
||||
{
|
||||
.id = PIOS_UDP_AUX,
|
||||
.driver = &pios_udp_com_driver,
|
||||
},
|
||||
#endif
|
||||
};
|
||||
|
||||
const uint8_t pios_com_num_devices = NELEMENTS(pios_com_devs);
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
279
flight/targets/boards/coptercontrol/pios_board.h
Normal file
@ -0,0 +1,279 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file pios_board.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @brief Defines board hardware for the OpenPilot Version 1.1 hardware.
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
*
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* This program is free software; you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation; either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful, but
|
||||
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
|
||||
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
|
||||
* for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License along
|
||||
* with this program; if not, write to the Free Software Foundation, Inc.,
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
|
||||
#ifndef PIOS_BOARD_H
|
||||
#define PIOS_BOARD_H
|
||||
// ------------------------
|
||||
// Timers and Channels Used
|
||||
// ------------------------
|
||||
/*
|
||||
Timer | Channel 1 | Channel 2 | Channel 3 | Channel 4
|
||||
------+-----------+-----------+-----------+----------
|
||||
TIM1 | Servo 4 | | |
|
||||
TIM2 | RC In 5 | RC In 6 | Servo 6 |
|
||||
TIM3 | Servo 5 | RC In 2 | RC In 3 | RC In 4
|
||||
TIM4 | RC In 1 | Servo 3 | Servo 2 | Servo 1
|
||||
------+-----------+-----------+-----------+----------
|
||||
*/
|
||||
|
||||
// ------------------------
|
||||
// DMA Channels Used
|
||||
// ------------------------
|
||||
/* Channel 1 - */
|
||||
/* Channel 2 - */
|
||||
/* Channel 3 - */
|
||||
/* Channel 4 - */
|
||||
/* Channel 5 - */
|
||||
/* Channel 6 - */
|
||||
/* Channel 7 - */
|
||||
/* Channel 8 - */
|
||||
/* Channel 9 - */
|
||||
/* Channel 10 - */
|
||||
/* Channel 11 - */
|
||||
/* Channel 12 - */
|
||||
|
||||
// ------------------------
|
||||
// BOOTLOADER_SETTINGS
|
||||
// ------------------------
|
||||
#define BOARD_READABLE TRUE
|
||||
#define BOARD_WRITABLE TRUE
|
||||
#define MAX_DEL_RETRYS 3
|
||||
|
||||
// ------------------------
|
||||
// WATCHDOG_SETTINGS
|
||||
// ------------------------
|
||||
#define PIOS_WATCHDOG_TIMEOUT 250
|
||||
#define PIOS_WDG_REGISTER BKP_DR4
|
||||
#define PIOS_WDG_ACTUATOR 0x0001
|
||||
#define PIOS_WDG_STABILIZATION 0x0002
|
||||
#define PIOS_WDG_ATTITUDE 0x0004
|
||||
#define PIOS_WDG_MANUAL 0x0008
|
||||
#define PIOS_WDG_AUTOTUNE 0x0010
|
||||
|
||||
// ------------------------
|
||||
// TELEMETRY
|
||||
// ------------------------
|
||||
#define TELEM_QUEUE_SIZE 10
|
||||
|
||||
// ------------------------
|
||||
// PIOS_LED
|
||||
// ------------------------
|
||||
#define PIOS_LED_HEARTBEAT 0
|
||||
|
||||
// -------------------------
|
||||
// System Settings
|
||||
// -------------------------
|
||||
#define PIOS_MASTER_CLOCK 72000000
|
||||
#define PIOS_PERIPHERAL_CLOCK (PIOS_MASTER_CLOCK / 2)
|
||||
|
||||
// -------------------------
|
||||
// Interrupt Priorities
|
||||
// -------------------------
|
||||
#define PIOS_IRQ_PRIO_LOW 12 // lower than RTOS
|
||||
#define PIOS_IRQ_PRIO_MID 8 // higher than RTOS
|
||||
#define PIOS_IRQ_PRIO_HIGH 5 // for SPI, ADC, I2C etc...
|
||||
#define PIOS_IRQ_PRIO_HIGHEST 4 // for USART etc...
|
||||
// ------------------------
|
||||
// PIOS_I2C
|
||||
// See also pios_board.c
|
||||
// ------------------------
|
||||
#define PIOS_I2C_MAX_DEVS 1
|
||||
extern uint32_t pios_i2c_flexi_adapter_id;
|
||||
#define PIOS_I2C_MAIN_ADAPTER (pios_i2c_flexi_adapter_id)
|
||||
#define PIOS_I2C_ESC_ADAPTER (pios_i2c_flexi_adapter_id)
|
||||
#define PIOS_I2C_BMP085_ADAPTER (pios_i2c_flexi_adapter_id)
|
||||
|
||||
// ------------------------
|
||||
// PIOS_BMP085
|
||||
// ------------------------
|
||||
#define PIOS_BMP085_OVERSAMPLING 3
|
||||
|
||||
// -------------------------
|
||||
// SPI
|
||||
//
|
||||
// See also pios_board.c
|
||||
// -------------------------
|
||||
#define PIOS_SPI_MAX_DEVS 2
|
||||
|
||||
// -------------------------
|
||||
// PIOS_USART
|
||||
// -------------------------
|
||||
#define PIOS_USART_MAX_DEVS 2
|
||||
|
||||
// -------------------------
|
||||
// PIOS_COM
|
||||
//
|
||||
// See also pios_board.c
|
||||
// -------------------------
|
||||
#define PIOS_COM_MAX_DEVS 3
|
||||
|
||||
extern uint32_t pios_com_telem_rf_id;
|
||||
#define PIOS_COM_TELEM_RF (pios_com_telem_rf_id)
|
||||
|
||||
#if defined(PIOS_INCLUDE_GPS)
|
||||
extern uint32_t pios_com_gps_id;
|
||||
#define PIOS_COM_GPS (pios_com_gps_id)
|
||||
#endif /* PIOS_INCLUDE_GPS */
|
||||
|
||||
extern uint32_t pios_com_bridge_id;
|
||||
#define PIOS_COM_BRIDGE (pios_com_bridge_id)
|
||||
|
||||
extern uint32_t pios_com_vcp_id;
|
||||
#define PIOS_COM_VCP (pios_com_vcp_id)
|
||||
|
||||
extern uint32_t pios_com_telem_usb_id;
|
||||
#define PIOS_COM_TELEM_USB (pios_com_telem_usb_id)
|
||||
|
||||
#if defined(PIOS_INCLUDE_DEBUG_CONSOLE)
|
||||
extern uint32_t pios_com_debug_id;
|
||||
#define PIOS_COM_DEBUG (pios_com_debug_id)
|
||||
#endif /* PIOS_INCLUDE_DEBUG_CONSOLE */
|
||||
|
||||
extern uint32_t pios_com_hkosd_id;
|
||||
#define PIOS_COM_OSDHK (pios_com_hkosd_id)
|
||||
|
||||
// -------------------------
|
||||
// ADC
|
||||
// PIOS_ADC_PinGet(0) = Gyro Z
|
||||
// PIOS_ADC_PinGet(1) = Gyro Y
|
||||
// PIOS_ADC_PinGet(2) = Gyro X
|
||||
// -------------------------
|
||||
// #define PIOS_ADC_OVERSAMPLING_RATE 1
|
||||
#define PIOS_ADC_USE_TEMP_SENSOR 1
|
||||
#define PIOS_ADC_TEMP_SENSOR_ADC ADC1
|
||||
#define PIOS_ADC_TEMP_SENSOR_ADC_CHANNEL 1
|
||||
|
||||
#define PIOS_ADC_PIN1_GPIO_PORT GPIOA // PA4 (Gyro X)
|
||||
#define PIOS_ADC_PIN1_GPIO_PIN GPIO_Pin_4 // ADC12_IN4
|
||||
#define PIOS_ADC_PIN1_GPIO_CHANNEL ADC_Channel_4
|
||||
#define PIOS_ADC_PIN1_ADC ADC2
|
||||
#define PIOS_ADC_PIN1_ADC_NUMBER 1
|
||||
|
||||
#define PIOS_ADC_PIN2_GPIO_PORT GPIOA // PA5 (Gyro Y)
|
||||
#define PIOS_ADC_PIN2_GPIO_PIN GPIO_Pin_5 // ADC123_IN5
|
||||
#define PIOS_ADC_PIN2_GPIO_CHANNEL ADC_Channel_5
|
||||
#define PIOS_ADC_PIN2_ADC ADC1
|
||||
#define PIOS_ADC_PIN2_ADC_NUMBER 2
|
||||
|
||||
#define PIOS_ADC_PIN3_GPIO_PORT GPIOA // PA3 (Gyro Z)
|
||||
#define PIOS_ADC_PIN3_GPIO_PIN GPIO_Pin_3 // ADC12_IN3
|
||||
#define PIOS_ADC_PIN3_GPIO_CHANNEL ADC_Channel_3
|
||||
#define PIOS_ADC_PIN3_ADC ADC2
|
||||
#define PIOS_ADC_PIN3_ADC_NUMBER 2
|
||||
|
||||
#define PIOS_ADC_NUM_PINS 3
|
||||
|
||||
#define PIOS_ADC_PORTS { PIOS_ADC_PIN1_GPIO_PORT, PIOS_ADC_PIN2_GPIO_PORT, PIOS_ADC_PIN3_GPIO_PORT }
|
||||
#define PIOS_ADC_PINS { PIOS_ADC_PIN1_GPIO_PIN, PIOS_ADC_PIN2_GPIO_PIN, PIOS_ADC_PIN3_GPIO_PIN }
|
||||
#define PIOS_ADC_CHANNELS { PIOS_ADC_PIN1_GPIO_CHANNEL, PIOS_ADC_PIN2_GPIO_CHANNEL, PIOS_ADC_PIN3_GPIO_CHANNEL }
|
||||
#define PIOS_ADC_MAPPING { PIOS_ADC_PIN1_ADC, PIOS_ADC_PIN2_ADC, PIOS_ADC_PIN3_ADC }
|
||||
#define PIOS_ADC_CHANNEL_MAPPING { PIOS_ADC_PIN1_ADC_NUMBER, PIOS_ADC_PIN2_ADC_NUMBER, PIOS_ADC_PIN3_ADC_NUMBER }
|
||||
#define PIOS_ADC_NUM_CHANNELS (PIOS_ADC_NUM_PINS + PIOS_ADC_USE_TEMP_SENSOR)
|
||||
#define PIOS_ADC_NUM_ADC_CHANNELS 2
|
||||
#define PIOS_ADC_USE_ADC2 1
|
||||
#define PIOS_ADC_CLOCK_FUNCTION RCC_APB2PeriphClockCmd(RCC_APB2Periph_ADC1 | RCC_APB2Periph_ADC2, ENABLE)
|
||||
#define PIOS_ADC_ADCCLK RCC_PCLK2_Div8
|
||||
/* RCC_PCLK2_Div2: ADC clock = PCLK2/2 */
|
||||
/* RCC_PCLK2_Div4: ADC clock = PCLK2/4 */
|
||||
/* RCC_PCLK2_Div6: ADC clock = PCLK2/6 */
|
||||
/* RCC_PCLK2_Div8: ADC clock = PCLK2/8 */
|
||||
#define PIOS_ADC_SAMPLE_TIME ADC_SampleTime_239Cycles5
|
||||
/* Sample time: */
|
||||
/* With an ADCCLK = 14 MHz and a sampling time of 239.5 cycles: */
|
||||
/* Tconv = 239.5 + 12.5 = 252 cycles = 18<31>s */
|
||||
/* (1 / (ADCCLK / CYCLES)) = Sample Time (<28>S) */
|
||||
#define PIOS_ADC_IRQ_PRIO PIOS_IRQ_PRIO_LOW
|
||||
|
||||
// Currently analog acquistion hard coded at 480 Hz
|
||||
// PCKL2 = HCLK / 16
|
||||
// ADCCLK = PCLK2 / 2
|
||||
#define PIOS_ADC_RATE (72.0e6f / 1.0f / 8.0f / 252.0f / (PIOS_ADC_NUM_CHANNELS >> PIOS_ADC_USE_ADC2))
|
||||
#define PIOS_ADC_MAX_OVERSAMPLING 48
|
||||
|
||||
#define PIOS_ADC_TEMPERATURE_PIN 0
|
||||
|
||||
// ------------------------
|
||||
// PIOS_RCVR
|
||||
// See also pios_board.c
|
||||
// ------------------------
|
||||
#define PIOS_RCVR_MAX_DEVS 3
|
||||
#define PIOS_RCVR_MAX_CHANNELS 12
|
||||
#define PIOS_GCSRCVR_TIMEOUT_MS 100
|
||||
|
||||
// -------------------------
|
||||
// Receiver PPM input
|
||||
// -------------------------
|
||||
#define PIOS_PPM_MAX_DEVS 1
|
||||
#define PIOS_PPM_NUM_INPUTS 12
|
||||
|
||||
// -------------------------
|
||||
// Receiver PWM input
|
||||
// -------------------------
|
||||
#define PIOS_PWM_MAX_DEVS 1
|
||||
#define PIOS_PWM_NUM_INPUTS 6
|
||||
|
||||
// -------------------------
|
||||
// Receiver DSM input
|
||||
// -------------------------
|
||||
#define PIOS_DSM_MAX_DEVS 2
|
||||
#define PIOS_DSM_NUM_INPUTS 12
|
||||
|
||||
// -------------------------
|
||||
// Receiver S.Bus input
|
||||
// -------------------------
|
||||
#define PIOS_SBUS_MAX_DEVS 1
|
||||
#define PIOS_SBUS_NUM_INPUTS (16 + 2)
|
||||
|
||||
// -------------------------
|
||||
// Servo outputs
|
||||
// -------------------------
|
||||
#define PIOS_SERVO_UPDATE_HZ 50
|
||||
#define PIOS_SERVOS_INITIAL_POSITION 0 /* dont want to start motors, have no pulse till settings loaded */
|
||||
#define PIOS_SERVO_BANKS 6
|
||||
|
||||
// --------------------------
|
||||
// Timer controller settings
|
||||
// --------------------------
|
||||
#define PIOS_TIM_MAX_DEVS 3
|
||||
|
||||
// -------------------------
|
||||
// GPIO
|
||||
// -------------------------
|
||||
#define PIOS_GPIO_PORTS {}
|
||||
#define PIOS_GPIO_PINS {}
|
||||
#define PIOS_GPIO_CLKS {}
|
||||
#define PIOS_GPIO_NUM 0
|
||||
|
||||
// -------------------------
|
||||
// USB
|
||||
// -------------------------
|
||||
#define PIOS_USB_HID_MAX_DEVS 1
|
||||
|
||||
#define PIOS_USB_ENABLED 1
|
||||
#define PIOS_USB_DETECT_GPIO_PORT GPIOC
|
||||
#define PIOS_USB_MAX_DEVS 1
|
||||
#define PIOS_USB_DETECT_GPIO_PIN GPIO_Pin_15
|
||||
|
||||
#endif /* PIOS_BOARD_H */
|
102
flight/targets/boards/coptercontrol/pios_usb_board_data.c
Normal file
@ -0,0 +1,102 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup PIOS PIOS Core hardware abstraction layer
|
||||
* @{
|
||||
* @addtogroup PIOS_USB_BOARD Board specific USB definitions
|
||||
* @brief Board specific USB definitions
|
||||
* @{
|
||||
*
|
||||
* @file pios_usb_board_data.c
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @brief Board specific USB definitions
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
*
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* This program is free software; you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation; either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful, but
|
||||
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
|
||||
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
|
||||
* for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License along
|
||||
* with this program; if not, write to the Free Software Foundation, Inc.,
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
|
||||
#include "inc/pios_usb_board_data.h" /* struct usb_*, USB_* */
|
||||
#include <pios_sys.h> /* PIOS_SYS_SerialNumberGet */
|
||||
#include <pios_usbhook.h> /* PIOS_USBHOOK_* */
|
||||
#include <pios_usb_util.h> /* PIOS_USB_UTIL_AsciiToUtf8 */
|
||||
|
||||
static const uint8_t usb_product_id[28] = {
|
||||
sizeof(usb_product_id),
|
||||
USB_DESC_TYPE_STRING,
|
||||
'C', 0,
|
||||
'o', 0,
|
||||
'p', 0,
|
||||
't', 0,
|
||||
'e', 0,
|
||||
'r', 0,
|
||||
'C', 0,
|
||||
'o', 0,
|
||||
'n', 0,
|
||||
't', 0,
|
||||
'r', 0,
|
||||
'o', 0,
|
||||
'l', 0,
|
||||
};
|
||||
|
||||
static uint8_t usb_serial_number[2 + PIOS_SYS_SERIAL_NUM_ASCII_LEN * 2 + (sizeof(PIOS_USB_BOARD_SN_SUFFIX) - 1) * 2] = {
|
||||
sizeof(usb_serial_number),
|
||||
USB_DESC_TYPE_STRING,
|
||||
};
|
||||
|
||||
static const struct usb_string_langid usb_lang_id = {
|
||||
.bLength = sizeof(usb_lang_id),
|
||||
.bDescriptorType = USB_DESC_TYPE_STRING,
|
||||
.bLangID = htousbs(USB_LANGID_ENGLISH_US),
|
||||
};
|
||||
|
||||
static const uint8_t usb_vendor_id[28] = {
|
||||
sizeof(usb_vendor_id),
|
||||
USB_DESC_TYPE_STRING,
|
||||
'o', 0,
|
||||
'p', 0,
|
||||
'e', 0,
|
||||
'n', 0,
|
||||
'p', 0,
|
||||
'i', 0,
|
||||
'l', 0,
|
||||
'o', 0,
|
||||
't', 0,
|
||||
'.', 0,
|
||||
'o', 0,
|
||||
'r', 0,
|
||||
'g', 0
|
||||
};
|
||||
|
||||
int32_t PIOS_USB_BOARD_DATA_Init(void)
|
||||
{
|
||||
/* Load device serial number into serial number string */
|
||||
uint8_t sn[PIOS_SYS_SERIAL_NUM_ASCII_LEN + 1];
|
||||
|
||||
PIOS_SYS_SerialNumberGet((char *)sn);
|
||||
|
||||
/* Concatenate the device serial number and the appropriate suffix ("+BL" or "+FW") into the USB serial number */
|
||||
uint8_t *utf8 = &(usb_serial_number[2]);
|
||||
utf8 = PIOS_USB_UTIL_AsciiToUtf8(utf8, sn, PIOS_SYS_SERIAL_NUM_ASCII_LEN);
|
||||
utf8 = PIOS_USB_UTIL_AsciiToUtf8(utf8, (uint8_t *)PIOS_USB_BOARD_SN_SUFFIX, sizeof(PIOS_USB_BOARD_SN_SUFFIX) - 1);
|
||||
|
||||
PIOS_USBHOOK_RegisterString(USB_STRING_DESC_PRODUCT, (uint8_t *)&usb_product_id, sizeof(usb_product_id));
|
||||
PIOS_USBHOOK_RegisterString(USB_STRING_DESC_SERIAL, (uint8_t *)&usb_serial_number, sizeof(usb_serial_number));
|
||||
|
||||
PIOS_USBHOOK_RegisterString(USB_STRING_DESC_LANG, (uint8_t *)&usb_lang_id, sizeof(usb_lang_id));
|
||||
PIOS_USBHOOK_RegisterString(USB_STRING_DESC_VENDOR, (uint8_t *)&usb_vendor_id, sizeof(usb_vendor_id));
|
||||
|
||||
return 0;
|
||||
}
|
658
ground/openpilotgcs/src/plugins/config/cc_hw_settings.ui
Normal file
@ -0,0 +1,658 @@
|
||||
<?xml version="1.0" encoding="UTF-8"?>
|
||||
<ui version="4.0">
|
||||
<class>CC_HW_Widget</class>
|
||||
<widget class="QWidget" name="CC_HW_Widget">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>0</x>
|
||||
<y>0</y>
|
||||
<width>646</width>
|
||||
<height>596</height>
|
||||
</rect>
|
||||
</property>
|
||||
<property name="windowTitle">
|
||||
<string>Form</string>
|
||||
</property>
|
||||
<layout class="QVBoxLayout" name="verticalLayout">
|
||||
<item>
|
||||
<widget class="QTabWidget" name="tabWidget">
|
||||
<property name="currentIndex">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<widget class="QWidget" name="tab">
|
||||
<attribute name="title">
|
||||
<string>HW settings</string>
|
||||
</attribute>
|
||||
<layout class="QVBoxLayout" name="verticalLayout_3">
|
||||
<property name="leftMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="topMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="rightMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="bottomMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<item>
|
||||
<widget class="QScrollArea" name="scrollArea">
|
||||
<property name="palette">
|
||||
<palette>
|
||||
<active>
|
||||
<colorrole role="Base">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>255</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Window">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="0">
|
||||
<red>232</red>
|
||||
<green>232</green>
|
||||
<blue>232</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
</active>
|
||||
<inactive>
|
||||
<colorrole role="Base">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>255</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Window">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="0">
|
||||
<red>232</red>
|
||||
<green>232</green>
|
||||
<blue>232</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
</inactive>
|
||||
<disabled>
|
||||
<colorrole role="Base">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="0">
|
||||
<red>232</red>
|
||||
<green>232</green>
|
||||
<blue>232</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Window">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="0">
|
||||
<red>232</red>
|
||||
<green>232</green>
|
||||
<blue>232</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
</disabled>
|
||||
</palette>
|
||||
</property>
|
||||
<property name="frameShape">
|
||||
<enum>QFrame::NoFrame</enum>
|
||||
</property>
|
||||
<property name="frameShadow">
|
||||
<enum>QFrame::Plain</enum>
|
||||
</property>
|
||||
<property name="widgetResizable">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<widget class="QWidget" name="scrollAreaWidgetContents">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>0</x>
|
||||
<y>0</y>
|
||||
<width>624</width>
|
||||
<height>510</height>
|
||||
</rect>
|
||||
</property>
|
||||
<layout class="QGridLayout" name="gridLayout_3">
|
||||
<property name="leftMargin">
|
||||
<number>12</number>
|
||||
</property>
|
||||
<property name="topMargin">
|
||||
<number>12</number>
|
||||
</property>
|
||||
<property name="rightMargin">
|
||||
<number>12</number>
|
||||
</property>
|
||||
<property name="bottomMargin">
|
||||
<number>12</number>
|
||||
</property>
|
||||
<item row="6" column="0" colspan="3">
|
||||
<widget class="QGroupBox" name="groupBox_2">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Minimum">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>50</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="title">
|
||||
<string>Messages</string>
|
||||
</property>
|
||||
<layout class="QHBoxLayout" name="horizontalLayout_3">
|
||||
<item>
|
||||
<widget class="QLabel" name="problems">
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>75</weight>
|
||||
<bold>true</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string/>
|
||||
</property>
|
||||
<property name="textFormat">
|
||||
<enum>Qt::AutoText</enum>
|
||||
</property>
|
||||
<property name="wordWrap">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="1">
|
||||
<widget class="QLabel" name="label_6">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Preferred">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>500</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>500</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>75</weight>
|
||||
<bold>true</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Changes on this page only take effect after board reset or power cycle</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
<property name="wordWrap">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="5" column="1">
|
||||
<spacer name="verticalSpacer">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Vertical</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>20</width>
|
||||
<height>25</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item row="3" column="1">
|
||||
<layout class="QHBoxLayout" name="horizontalLayout">
|
||||
<item>
|
||||
<layout class="QGridLayout" name="gridLayout_2">
|
||||
<item row="0" column="1">
|
||||
<widget class="QComboBox" name="telemetrySpeed">
|
||||
<property name="toolTip">
|
||||
<string>Select the speed here.</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="0">
|
||||
<widget class="QLabel" name="GpsSpeedLabel">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>55</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>GPS speed:</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="0">
|
||||
<widget class="QLabel" name="telemetrySpeedLabel">
|
||||
<property name="text">
|
||||
<string>Telemetry speed:</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="1">
|
||||
<widget class="QComboBox" name="comUsbBridgeSpeed">
|
||||
<property name="toolTip">
|
||||
<string>Select the speed here.</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="1">
|
||||
<widget class="QComboBox" name="gpsSpeed">
|
||||
<property name="toolTip">
|
||||
<string>Select the speed here.</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="0">
|
||||
<widget class="QLabel" name="ComUsbBridgeSpeedLabel">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>55</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>ComUsbBridge speed:</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="0">
|
||||
<widget class="QLabel" name="GpsProtocolLabel">
|
||||
<property name="text">
|
||||
<string>GPS protocol :</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="1">
|
||||
<widget class="QComboBox" name="gpsProtocol"/>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
<item>
|
||||
<spacer name="horizontalSpacer_3">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>40</width>
|
||||
<height>20</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
<item row="2" column="1">
|
||||
<layout class="QGridLayout" name="gridLayout" rowstretch="0,0,0,0,0,0,0,0">
|
||||
<item row="4" column="0">
|
||||
<widget class="QComboBox" name="cbFlexi"/>
|
||||
</item>
|
||||
<item row="6" column="0">
|
||||
<widget class="QComboBox" name="cbTele"/>
|
||||
</item>
|
||||
<item row="3" column="3">
|
||||
<widget class="QLabel" name="label_8">
|
||||
<property name="text">
|
||||
<string>USB HID Port</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignBottom|Qt::AlignLeading|Qt::AlignLeft</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="7" column="0">
|
||||
<widget class="QLabel" name="label_4">
|
||||
<property name="text">
|
||||
<string/>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="5" column="3">
|
||||
<widget class="QLabel" name="label_9">
|
||||
<property name="text">
|
||||
<string>USB VCP Port</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignBottom|Qt::AlignLeading|Qt::AlignLeft</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="1" rowspan="5" colspan="2">
|
||||
<widget class="QLabel" name="label_2">
|
||||
<property name="text">
|
||||
<string/>
|
||||
</property>
|
||||
<property name="scaledContents">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="5" column="0">
|
||||
<widget class="QLabel" name="label_3">
|
||||
<property name="text">
|
||||
<string>Main Port</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignBottom|Qt::AlignLeading|Qt::AlignLeft</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="0">
|
||||
<widget class="QLabel" name="label_5">
|
||||
<property name="text">
|
||||
<string>Flexi Port</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignBottom|Qt::AlignLeading|Qt::AlignLeft</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="4" column="3">
|
||||
<widget class="QComboBox" name="cbUsbHid"/>
|
||||
</item>
|
||||
<item row="4" column="4">
|
||||
<spacer name="horizontalSpacer_2">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>40</width>
|
||||
<height>20</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item row="6" column="3">
|
||||
<widget class="QComboBox" name="cbUsbVcp"/>
|
||||
</item>
|
||||
<item row="2" column="1" colspan="2" alignment="Qt::AlignLeft">
|
||||
<widget class="QComboBox" name="cbRcvr"/>
|
||||
</item>
|
||||
<item row="1" column="1" colspan="2" alignment="Qt::AlignLeft">
|
||||
<widget class="QLabel" name="label_7">
|
||||
<property name="text">
|
||||
<string>Receiver Port</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
<item row="2" column="0">
|
||||
<spacer name="horizontalSpacer_4">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>40</width>
|
||||
<height>20</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item row="2" column="2">
|
||||
<spacer name="horizontalSpacer_5">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>40</width>
|
||||
<height>20</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item row="1" column="1">
|
||||
<spacer name="verticalSpacer_2">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Vertical</enum>
|
||||
</property>
|
||||
<property name="sizeType">
|
||||
<enum>QSizePolicy::Fixed</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>20</width>
|
||||
<height>10</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<layout class="QHBoxLayout" name="horizontalLayout_2">
|
||||
<property name="spacing">
|
||||
<number>4</number>
|
||||
</property>
|
||||
<item>
|
||||
<spacer name="horizontalSpacer">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>369</width>
|
||||
<height>20</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QPushButton" name="cchwHelp">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Fixed" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>25</width>
|
||||
<height>25</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>25</width>
|
||||
<height>25</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Takes you to the wiki page</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string/>
|
||||
</property>
|
||||
<property name="icon">
|
||||
<iconset resource="../coreplugin/core.qrc">
|
||||
<normaloff>:/core/images/helpicon.svg</normaloff>:/core/images/helpicon.svg</iconset>
|
||||
</property>
|
||||
<property name="iconSize">
|
||||
<size>
|
||||
<width>25</width>
|
||||
<height>25</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="flat">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QPushButton" name="saveTelemetryToRAM">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>16777215</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="palette">
|
||||
<palette>
|
||||
<active>
|
||||
<colorrole role="Base">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="0">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>255</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Window">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>232</red>
|
||||
<green>232</green>
|
||||
<blue>232</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
</active>
|
||||
<inactive>
|
||||
<colorrole role="Base">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="0">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>255</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Window">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>232</red>
|
||||
<green>232</green>
|
||||
<blue>232</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
</inactive>
|
||||
<disabled>
|
||||
<colorrole role="Base">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>232</red>
|
||||
<green>232</green>
|
||||
<blue>232</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Window">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>232</red>
|
||||
<green>232</green>
|
||||
<blue>232</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
</disabled>
|
||||
</palette>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Send to OpenPilot but don't write in SD.
|
||||
Beware of not locking yourself out!</string>
|
||||
</property>
|
||||
<property name="autoFillBackground">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true"/>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Apply</string>
|
||||
</property>
|
||||
<property name="iconSize">
|
||||
<size>
|
||||
<width>16</width>
|
||||
<height>16</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="checkable">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QPushButton" name="saveTelemetryToSD">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>16777215</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Applies and Saves all settings to SD.
|
||||
Beware of not locking yourself out!</string>
|
||||
</property>
|
||||
<property name="autoFillBackground">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true"/>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Save</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
<resources>
|
||||
<include location="../coreplugin/core.qrc"/>
|
||||
</resources>
|
||||
<connections/>
|
||||
</ui>
|
597
ground/openpilotgcs/src/plugins/config/ccattitude.ui
Normal file
@ -0,0 +1,597 @@
|
||||
<?xml version="1.0" encoding="UTF-8"?>
|
||||
<ui version="4.0">
|
||||
<class>ccattitude</class>
|
||||
<widget class="QWidget" name="ccattitude">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>0</x>
|
||||
<y>0</y>
|
||||
<width>780</width>
|
||||
<height>566</height>
|
||||
</rect>
|
||||
</property>
|
||||
<property name="windowTitle">
|
||||
<string>Form</string>
|
||||
</property>
|
||||
<layout class="QVBoxLayout" name="verticalLayout_5">
|
||||
<item>
|
||||
<widget class="QTabWidget" name="tabWidget">
|
||||
<property name="currentIndex">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<widget class="QWidget" name="Attitude">
|
||||
<attribute name="title">
|
||||
<string>Attitude</string>
|
||||
</attribute>
|
||||
<layout class="QVBoxLayout" name="verticalLayout_3">
|
||||
<property name="leftMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="topMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="rightMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="bottomMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<item>
|
||||
<widget class="QScrollArea" name="scrollArea">
|
||||
<property name="palette">
|
||||
<palette>
|
||||
<active>
|
||||
<colorrole role="Base">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>255</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Window">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="0">
|
||||
<red>232</red>
|
||||
<green>232</green>
|
||||
<blue>232</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
</active>
|
||||
<inactive>
|
||||
<colorrole role="Base">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>255</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Window">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="0">
|
||||
<red>232</red>
|
||||
<green>232</green>
|
||||
<blue>232</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
</inactive>
|
||||
<disabled>
|
||||
<colorrole role="Base">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="0">
|
||||
<red>232</red>
|
||||
<green>232</green>
|
||||
<blue>232</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Window">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="0">
|
||||
<red>232</red>
|
||||
<green>232</green>
|
||||
<blue>232</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
</disabled>
|
||||
</palette>
|
||||
</property>
|
||||
<property name="frameShape">
|
||||
<enum>QFrame::NoFrame</enum>
|
||||
</property>
|
||||
<property name="frameShadow">
|
||||
<enum>QFrame::Plain</enum>
|
||||
</property>
|
||||
<property name="widgetResizable">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<widget class="QWidget" name="scrollAreaWidgetContents">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>0</x>
|
||||
<y>0</y>
|
||||
<width>758</width>
|
||||
<height>486</height>
|
||||
</rect>
|
||||
</property>
|
||||
<layout class="QVBoxLayout" name="verticalLayout">
|
||||
<property name="leftMargin">
|
||||
<number>12</number>
|
||||
</property>
|
||||
<property name="topMargin">
|
||||
<number>12</number>
|
||||
</property>
|
||||
<property name="rightMargin">
|
||||
<number>12</number>
|
||||
</property>
|
||||
<property name="bottomMargin">
|
||||
<number>12</number>
|
||||
</property>
|
||||
<item>
|
||||
<widget class="QGroupBox" name="groupBox">
|
||||
<property name="title">
|
||||
<string>Rotate virtual attitude relative to board</string>
|
||||
</property>
|
||||
<layout class="QGridLayout" name="gridLayout" columnstretch="0,1,0,1,0,1,0">
|
||||
<item row="0" column="1">
|
||||
<widget class="QLabel" name="label_2">
|
||||
<property name="styleSheet">
|
||||
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
|
||||
color: rgb(255, 255, 255);
|
||||
border-radius: 5;
|
||||
margin:1px;
|
||||
font:bold;</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Roll</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="1">
|
||||
<widget class="QSpinBox" name="rollBias">
|
||||
<property name="minimum">
|
||||
<number>-180</number>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>180</number>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="4">
|
||||
<spacer name="horizontalSpacer_9">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>40</width>
|
||||
<height>20</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item row="1" column="5">
|
||||
<widget class="QSpinBox" name="yawBias">
|
||||
<property name="minimum">
|
||||
<number>-180</number>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>180</number>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="5">
|
||||
<widget class="QLabel" name="label_4">
|
||||
<property name="styleSheet">
|
||||
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
|
||||
color: rgb(255, 255, 255);
|
||||
border-radius: 5;
|
||||
margin:1px;
|
||||
font:bold;</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Yaw</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="2">
|
||||
<spacer name="horizontalSpacer_8">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>40</width>
|
||||
<height>20</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item row="0" column="3">
|
||||
<widget class="QLabel" name="label_3">
|
||||
<property name="styleSheet">
|
||||
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
|
||||
color: rgb(255, 255, 255);
|
||||
border-radius: 5;
|
||||
margin:1px;
|
||||
font:bold;</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Pitch</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="3">
|
||||
<widget class="QSpinBox" name="pitchBias">
|
||||
<property name="minimum">
|
||||
<number>-90</number>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>90</number>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="0">
|
||||
<spacer name="horizontalSpacer_7">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>40</width>
|
||||
<height>20</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item row="1" column="6">
|
||||
<spacer name="horizontalSpacer_10">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>40</width>
|
||||
<height>20</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QGroupBox" name="groupBox_2">
|
||||
<property name="title">
|
||||
<string>Calibration</string>
|
||||
</property>
|
||||
<layout class="QGridLayout" name="gridLayout_2">
|
||||
<item row="0" column="0" colspan="3">
|
||||
<layout class="QHBoxLayout" name="horizontalLayout_2">
|
||||
<item>
|
||||
<spacer name="horizontalSpacer_2">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>40</width>
|
||||
<height>20</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QLabel" name="label">
|
||||
<property name="text">
|
||||
<string>Place aircraft very flat, and then click level to compute the accelerometer and gyro bias</string>
|
||||
</property>
|
||||
<property name="wordWrap">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<spacer name="horizontalSpacer_3">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>40</width>
|
||||
<height>20</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
<item row="1" column="0">
|
||||
<widget class="QPushButton" name="zeroBias">
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>500</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Launch horizontal calibration.</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Level</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="1">
|
||||
<spacer name="horizontalSpacer_4">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="sizeType">
|
||||
<enum>QSizePolicy::Fixed</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>10</width>
|
||||
<height>20</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item row="1" column="2">
|
||||
<widget class="QProgressBar" name="zeroBiasProgress">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>300</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="value">
|
||||
<number>0</number>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="0" colspan="3">
|
||||
<layout class="QHBoxLayout" name="horizontalLayout_3">
|
||||
<item>
|
||||
<widget class="QCheckBox" name="zeroGyroBiasOnArming">
|
||||
<property name="toolTip">
|
||||
<string>If enabled, a fast recalibration of gyro zero point will be done
|
||||
whenever the frame is armed. Do not move the airframe while
|
||||
arming it in that case!</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Zero gyros while arming aircraft</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<spacer name="horizontalSpacer_6">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>40</width>
|
||||
<height>20</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QGroupBox" name="groupBox_3">
|
||||
<property name="title">
|
||||
<string>Filtering</string>
|
||||
</property>
|
||||
<layout class="QHBoxLayout" name="horizontalLayout_5">
|
||||
<item>
|
||||
<widget class="QLabel" name="label_5">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string/>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Accelerometers</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<spacer name="horizontalSpacer_12">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="sizeType">
|
||||
<enum>QSizePolicy::Fixed</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>10</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QDoubleSpinBox" name="accelTauSpinbox">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>60</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Accelerometer filtering.
|
||||
|
||||
Sets the amount of lowpass filtering of accelerometer data
|
||||
for the attitude estimation. Higher values apply a stronger
|
||||
filter, which may help with drifting in attitude mode.
|
||||
|
||||
Range: 0.00 - 0.20, Good starting value: 0.05 - 0.10
|
||||
Start low and raise until drift stops.
|
||||
|
||||
A setting of 0.00 disables the filter.</string>
|
||||
</property>
|
||||
<property name="decimals">
|
||||
<number>2</number>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<double>0.200000000000000</double>
|
||||
</property>
|
||||
<property name="singleStep">
|
||||
<double>0.010000000000000</double>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<spacer name="horizontalSpacer_5">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>40</width>
|
||||
<height>20</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<spacer name="verticalSpacer_2">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Vertical</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>20</width>
|
||||
<height>10</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<layout class="QHBoxLayout" name="horizontalLayout">
|
||||
<property name="spacing">
|
||||
<number>4</number>
|
||||
</property>
|
||||
<item>
|
||||
<spacer name="horizontalSpacer">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>380</width>
|
||||
<height>20</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QPushButton" name="ccAttitudeHelp">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Fixed" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>25</width>
|
||||
<height>25</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Takes you to the wiki page</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string/>
|
||||
</property>
|
||||
<property name="icon">
|
||||
<iconset resource="../coreplugin/core.qrc">
|
||||
<normaloff>:/core/images/helpicon.svg</normaloff>:/core/images/helpicon.svg</iconset>
|
||||
</property>
|
||||
<property name="iconSize">
|
||||
<size>
|
||||
<width>25</width>
|
||||
<height>25</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="flat">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QPushButton" name="applyButton">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Apply</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QPushButton" name="saveButton">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Click to permanently save the accel bias in the CopterControl Flash.</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Save</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
<resources>
|
||||
<include location="../coreplugin/core.qrc"/>
|
||||
</resources>
|
||||
<connections/>
|
||||
</ui>
|
@ -21,6 +21,8 @@ HEADERS += \
|
||||
configinputwidget.h \
|
||||
configoutputwidget.h \
|
||||
configvehicletypewidget.h \
|
||||
config_cc_hw_widget.h \
|
||||
configccattitudewidget.h \
|
||||
configstabilizationwidget.h \
|
||||
assertions.h \
|
||||
defaultattitudewidget.h \
|
||||
@ -67,6 +69,8 @@ SOURCES += \
|
||||
configinputwidget.cpp \
|
||||
configoutputwidget.cpp \
|
||||
configvehicletypewidget.cpp \
|
||||
config_cc_hw_widget.cpp \
|
||||
configccattitudewidget.cpp \
|
||||
configstabilizationwidget.cpp \
|
||||
defaultattitudewidget.cpp \
|
||||
defaulthwsettingswidget.cpp \
|
||||
@ -104,10 +108,12 @@ FORMS += \
|
||||
airframe_ground.ui \
|
||||
airframe_multirotor.ui \
|
||||
airframe_custom.ui \
|
||||
cc_hw_settings.ui \
|
||||
stabilization.ui \
|
||||
input.ui \
|
||||
input_wizard.ui \
|
||||
output.ui \
|
||||
ccattitude.ui \
|
||||
defaultattitude.ui \
|
||||
defaulthwsettings.ui \
|
||||
inputchannelform.ui \
|
||||
|
156
ground/openpilotgcs/src/plugins/config/config_cc_hw_widget.cpp
Normal file
@ -0,0 +1,156 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file configtelemetrywidget.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @addtogroup GCSPlugins GCS Plugins
|
||||
* @{
|
||||
* @addtogroup ConfigPlugin Config Plugin
|
||||
* @{
|
||||
* @brief The Configuration Gadget used to update settings in the firmware
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* 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 "config_cc_hw_widget.h"
|
||||
#include "hwsettings.h"
|
||||
#include <QDebug>
|
||||
#include <QStringList>
|
||||
#include <QWidget>
|
||||
#include <QTextEdit>
|
||||
#include <QVBoxLayout>
|
||||
#include <QPushButton>
|
||||
#include <QDesktopServices>
|
||||
#include <QUrl>
|
||||
#include <extensionsystem/pluginmanager.h>
|
||||
#include <coreplugin/generalsettings.h>
|
||||
|
||||
|
||||
ConfigCCHWWidget::ConfigCCHWWidget(QWidget *parent) : ConfigTaskWidget(parent)
|
||||
{
|
||||
m_telemetry = new Ui_CC_HW_Widget();
|
||||
m_telemetry->setupUi(this);
|
||||
|
||||
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
|
||||
Core::Internal::GeneralSettings *settings = pm->getObject<Core::Internal::GeneralSettings>();
|
||||
if (!settings->useExpertMode()) {
|
||||
m_telemetry->saveTelemetryToRAM->setVisible(false);
|
||||
}
|
||||
|
||||
|
||||
UAVObjectUtilManager *utilMngr = pm->getObject<UAVObjectUtilManager>();
|
||||
int id = utilMngr->getBoardModel();
|
||||
|
||||
switch (id) {
|
||||
case 0x0101:
|
||||
m_telemetry->label_2->setPixmap(QPixmap(":/uploader/images/deviceID-0101.svg"));
|
||||
break;
|
||||
case 0x0301:
|
||||
m_telemetry->label_2->setPixmap(QPixmap(":/uploader/images/deviceID-0301.svg"));
|
||||
break;
|
||||
case 0x0401:
|
||||
m_telemetry->label_2->setPixmap(QPixmap(":/configgadget/images/coptercontrol.svg"));
|
||||
break;
|
||||
case 0x0402:
|
||||
m_telemetry->label_2->setPixmap(QPixmap(":/configgadget/images/coptercontrol.svg"));
|
||||
break;
|
||||
case 0x0201:
|
||||
m_telemetry->label_2->setPixmap(QPixmap(":/uploader/images/deviceID-0201.svg"));
|
||||
break;
|
||||
default:
|
||||
m_telemetry->label_2->setPixmap(QPixmap(":/configgadget/images/coptercontrol.svg"));
|
||||
break;
|
||||
}
|
||||
addApplySaveButtons(m_telemetry->saveTelemetryToRAM, m_telemetry->saveTelemetryToSD);
|
||||
addWidgetBinding("HwSettings", "CC_FlexiPort", m_telemetry->cbFlexi);
|
||||
addWidgetBinding("HwSettings", "CC_MainPort", m_telemetry->cbTele);
|
||||
addWidgetBinding("HwSettings", "CC_RcvrPort", m_telemetry->cbRcvr);
|
||||
addWidgetBinding("HwSettings", "USB_HIDPort", m_telemetry->cbUsbHid);
|
||||
addWidgetBinding("HwSettings", "USB_VCPPort", m_telemetry->cbUsbVcp);
|
||||
addWidgetBinding("HwSettings", "TelemetrySpeed", m_telemetry->telemetrySpeed);
|
||||
addWidgetBinding("HwSettings", "GPSSpeed", m_telemetry->gpsSpeed);
|
||||
// Add Gps protocol configuration
|
||||
|
||||
HwSettings *hwSettings = HwSettings::GetInstance(getObjectManager());
|
||||
HwSettings::DataFields hwSettingsData = hwSettings->getData();
|
||||
|
||||
if (hwSettingsData.OptionalModules[HwSettings::OPTIONALMODULES_GPS] != HwSettings::OPTIONALMODULES_ENABLED) {
|
||||
m_telemetry->gpsProtocol->setEnabled(false);
|
||||
m_telemetry->gpsProtocol->setToolTip(tr("Enable GPS module and reboot the board to be able to select GPS protocol"));
|
||||
} else {
|
||||
addWidgetBinding("GPSSettings", "DataProtocol", m_telemetry->gpsProtocol);
|
||||
}
|
||||
|
||||
addWidgetBinding("HwSettings", "ComUsbBridgeSpeed", m_telemetry->comUsbBridgeSpeed);
|
||||
connect(m_telemetry->cchwHelp, SIGNAL(clicked()), this, SLOT(openHelp()));
|
||||
enableSaveButtons(false);
|
||||
populateWidgets();
|
||||
refreshWidgetsValues();
|
||||
forceConnectedState();
|
||||
}
|
||||
|
||||
ConfigCCHWWidget::~ConfigCCHWWidget()
|
||||
{
|
||||
// Do nothing
|
||||
}
|
||||
|
||||
void ConfigCCHWWidget::refreshValues()
|
||||
{}
|
||||
|
||||
void ConfigCCHWWidget::widgetsContentsChanged()
|
||||
{
|
||||
ConfigTaskWidget::widgetsContentsChanged();
|
||||
|
||||
if (((m_telemetry->cbTele->currentIndex() == HwSettings::CC_MAINPORT_DEBUGCONSOLE) &&
|
||||
(m_telemetry->cbFlexi->currentIndex() == HwSettings::CC_FLEXIPORT_DEBUGCONSOLE)) ||
|
||||
((m_telemetry->cbFlexi->currentIndex() == HwSettings::CC_FLEXIPORT_DEBUGCONSOLE) &&
|
||||
(m_telemetry->cbUsbVcp->currentIndex() == HwSettings::USB_VCPPORT_DEBUGCONSOLE)) ||
|
||||
((m_telemetry->cbUsbVcp->currentIndex() == HwSettings::USB_VCPPORT_DEBUGCONSOLE) &&
|
||||
(m_telemetry->cbTele->currentIndex() == HwSettings::CC_MAINPORT_DEBUGCONSOLE))) {
|
||||
enableSaveButtons(false);
|
||||
m_telemetry->problems->setText(tr("Warning: you have configured more than one DebugConsole, this currently is not supported"));
|
||||
} else if (((m_telemetry->cbTele->currentIndex() == HwSettings::CC_MAINPORT_TELEMETRY) && (m_telemetry->cbFlexi->currentIndex() == HwSettings::CC_FLEXIPORT_TELEMETRY)) ||
|
||||
((m_telemetry->cbTele->currentIndex() == HwSettings::CC_MAINPORT_GPS) && (m_telemetry->cbFlexi->currentIndex() == HwSettings::CC_FLEXIPORT_GPS)) ||
|
||||
((m_telemetry->cbTele->currentIndex() == HwSettings::CC_MAINPORT_DEBUGCONSOLE) && (m_telemetry->cbFlexi->currentIndex() == HwSettings::CC_FLEXIPORT_DEBUGCONSOLE)) ||
|
||||
((m_telemetry->cbTele->currentIndex() == HwSettings::CC_MAINPORT_COMBRIDGE) && (m_telemetry->cbFlexi->currentIndex() == HwSettings::CC_FLEXIPORT_COMBRIDGE))) {
|
||||
enableSaveButtons(false);
|
||||
m_telemetry->problems->setText(tr("Warning: you have configured both MainPort and FlexiPort for the same function, this currently is not supported"));
|
||||
} else if ((m_telemetry->cbUsbHid->currentIndex() == HwSettings::USB_HIDPORT_USBTELEMETRY) && (m_telemetry->cbUsbVcp->currentIndex() == HwSettings::USB_VCPPORT_USBTELEMETRY)) {
|
||||
enableSaveButtons(false);
|
||||
m_telemetry->problems->setText(tr("Warning: you have configured both USB HID Port and USB VCP Port for the same function, this currently is not supported"));
|
||||
} else if ((m_telemetry->cbUsbHid->currentIndex() != HwSettings::USB_HIDPORT_USBTELEMETRY) && (m_telemetry->cbUsbVcp->currentIndex() != HwSettings::USB_VCPPORT_USBTELEMETRY)) {
|
||||
enableSaveButtons(false);
|
||||
m_telemetry->problems->setText(tr("Warning: you have disabled USB Telemetry on both USB HID Port and USB VCP Port, this currently is not supported"));
|
||||
} else {
|
||||
m_telemetry->problems->setText("");
|
||||
enableSaveButtons(true);
|
||||
}
|
||||
}
|
||||
|
||||
void ConfigCCHWWidget::enableSaveButtons(bool enable)
|
||||
{
|
||||
m_telemetry->saveTelemetryToRAM->setEnabled(enable);
|
||||
m_telemetry->saveTelemetryToSD->setEnabled(enable);
|
||||
}
|
||||
|
||||
void ConfigCCHWWidget::openHelp()
|
||||
{
|
||||
QDesktopServices::openUrl(QUrl(tr("http://wiki.openpilot.org/x/D4AUAQ"), QUrl::StrictMode));
|
||||
}
|
||||
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
56
ground/openpilotgcs/src/plugins/config/config_cc_hw_widget.h
Normal file
@ -0,0 +1,56 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file configtelemetrytwidget.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @addtogroup GCSPlugins GCS Plugins
|
||||
* @{
|
||||
* @addtogroup ConfigPlugin Config Plugin
|
||||
* @{
|
||||
* @brief Telemetry configuration panel
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* 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 CONFIGCCHWWIDGET_H
|
||||
#define CONFIGCCHWWIDGET_H
|
||||
|
||||
#include "ui_cc_hw_settings.h"
|
||||
#include "../uavobjectwidgetutils/configtaskwidget.h"
|
||||
#include "extensionsystem/pluginmanager.h"
|
||||
#include "uavobjectmanager.h"
|
||||
#include "uavobject.h"
|
||||
#include <QWidget>
|
||||
#include <QList>
|
||||
#include "smartsavebutton.h"
|
||||
|
||||
class ConfigCCHWWidget : public ConfigTaskWidget {
|
||||
Q_OBJECT
|
||||
|
||||
public:
|
||||
ConfigCCHWWidget(QWidget *parent = 0);
|
||||
~ConfigCCHWWidget();
|
||||
private slots:
|
||||
void openHelp();
|
||||
void refreshValues();
|
||||
void widgetsContentsChanged();
|
||||
void enableSaveButtons(bool enable);
|
||||
|
||||
private:
|
||||
Ui_CC_HW_Widget *m_telemetry;
|
||||
QSvgRenderer *m_renderer;
|
||||
};
|
||||
|
||||
#endif // CONFIGCCHWWIDGET_H
|
@ -0,0 +1,239 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file configccattitudewidget.cpp
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @addtogroup GCSPlugins GCS Plugins
|
||||
* @{
|
||||
* @addtogroup ConfigPlugin Config Plugin
|
||||
* @{
|
||||
* @brief Configure Attitude module on CopterControl
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* 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 "configccattitudewidget.h"
|
||||
#include "ui_ccattitude.h"
|
||||
#include "utils/coordinateconversions.h"
|
||||
#include "attitudesettings.h"
|
||||
#include <QMutexLocker>
|
||||
#include <QMessageBox>
|
||||
#include <QDebug>
|
||||
#include <QDesktopServices>
|
||||
#include <QUrl>
|
||||
#include "accelstate.h"
|
||||
#include "accelgyrosettings.h"
|
||||
#include "gyrostate.h"
|
||||
#include <extensionsystem/pluginmanager.h>
|
||||
#include <coreplugin/generalsettings.h>
|
||||
#include <calibration/calibrationutils.h>
|
||||
ConfigCCAttitudeWidget::ConfigCCAttitudeWidget(QWidget *parent) :
|
||||
ConfigTaskWidget(parent),
|
||||
ui(new Ui_ccattitude)
|
||||
{
|
||||
ui->setupUi(this);
|
||||
connect(ui->zeroBias, SIGNAL(clicked()), this, SLOT(startAccelCalibration()));
|
||||
|
||||
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
|
||||
Core::Internal::GeneralSettings *settings = pm->getObject<Core::Internal::GeneralSettings>();
|
||||
if (!settings->useExpertMode()) {
|
||||
ui->applyButton->setVisible(false);
|
||||
}
|
||||
|
||||
addApplySaveButtons(ui->applyButton, ui->saveButton);
|
||||
addUAVObject("AttitudeSettings");
|
||||
addUAVObject("AccelGyroSettings");
|
||||
|
||||
// Connect the help button
|
||||
connect(ui->ccAttitudeHelp, SIGNAL(clicked()), this, SLOT(openHelp()));
|
||||
|
||||
addWidgetBinding("AttitudeSettings", "ZeroDuringArming", ui->zeroGyroBiasOnArming);
|
||||
addWidgetBinding("AttitudeSettings", "AccelTau", ui->accelTauSpinbox);
|
||||
|
||||
addWidgetBinding("AttitudeSettings", "BoardRotation", ui->rollBias, AttitudeSettings::BOARDROTATION_ROLL);
|
||||
addWidgetBinding("AttitudeSettings", "BoardRotation", ui->pitchBias, AttitudeSettings::BOARDROTATION_PITCH);
|
||||
addWidgetBinding("AttitudeSettings", "BoardRotation", ui->yawBias, AttitudeSettings::BOARDROTATION_YAW);
|
||||
addWidget(ui->zeroBias);
|
||||
populateWidgets();
|
||||
refreshWidgetsValues();
|
||||
forceConnectedState();
|
||||
}
|
||||
|
||||
ConfigCCAttitudeWidget::~ConfigCCAttitudeWidget()
|
||||
{
|
||||
delete ui;
|
||||
}
|
||||
|
||||
void ConfigCCAttitudeWidget::sensorsUpdated(UAVObject *obj)
|
||||
{
|
||||
if (!timer.isActive()) {
|
||||
// ignore updates that come in after the timer has expired
|
||||
return;
|
||||
}
|
||||
|
||||
AccelState *accelState = AccelState::GetInstance(getObjectManager());
|
||||
GyroState *gyroState = GyroState::GetInstance(getObjectManager());
|
||||
|
||||
// Accumulate samples until we have _at least_ NUM_SENSOR_UPDATES samples
|
||||
// for both gyros and accels.
|
||||
// Note that, at present, we stash the samples and then compute the bias
|
||||
// at the end, even though the mean could be accumulated as we go.
|
||||
// In future, a better algorithm could be used.
|
||||
if (obj->getObjID() == AccelState::OBJID) {
|
||||
accelUpdates++;
|
||||
AccelState::DataFields accelStateData = accelState->getData();
|
||||
x_accum.append(accelStateData.x);
|
||||
y_accum.append(accelStateData.y);
|
||||
z_accum.append(accelStateData.z);
|
||||
} else if (obj->getObjID() == GyroState::OBJID) {
|
||||
gyroUpdates++;
|
||||
GyroState::DataFields gyroStateData = gyroState->getData();
|
||||
x_gyro_accum.append(gyroStateData.x);
|
||||
y_gyro_accum.append(gyroStateData.y);
|
||||
z_gyro_accum.append(gyroStateData.z);
|
||||
}
|
||||
|
||||
// update the progress indicator
|
||||
ui->zeroBiasProgress->setValue((float)qMin(accelUpdates, gyroUpdates) / NUM_SENSOR_UPDATES * 100);
|
||||
|
||||
// If we have enough samples, then stop sampling and compute the biases
|
||||
if (accelUpdates >= NUM_SENSOR_UPDATES && gyroUpdates >= NUM_SENSOR_UPDATES) {
|
||||
timer.stop();
|
||||
disconnect(obj, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(sensorsUpdated(UAVObject *)));
|
||||
disconnect(&timer, SIGNAL(timeout()), this, SLOT(timeout()));
|
||||
|
||||
float x_bias = OpenPilot::CalibrationUtils::listMean(x_accum);
|
||||
float y_bias = OpenPilot::CalibrationUtils::listMean(y_accum);
|
||||
float z_bias = OpenPilot::CalibrationUtils::listMean(z_accum) + 9.81;
|
||||
|
||||
float x_gyro_bias = OpenPilot::CalibrationUtils::listMean(x_gyro_accum);
|
||||
float y_gyro_bias = OpenPilot::CalibrationUtils::listMean(y_gyro_accum);
|
||||
float z_gyro_bias = OpenPilot::CalibrationUtils::listMean(z_gyro_accum);
|
||||
accelState->setMetadata(initialAccelStateMdata);
|
||||
gyroState->setMetadata(initialGyroStateMdata);
|
||||
|
||||
AccelGyroSettings::DataFields accelGyroSettingsData = AccelGyroSettings::GetInstance(getObjectManager())->getData();
|
||||
AttitudeSettings::DataFields attitudeSettingsData = AttitudeSettings::GetInstance(getObjectManager())->getData();
|
||||
// We offset the gyro bias by current bias to help precision
|
||||
accelGyroSettingsData.accel_bias[0] += x_bias;
|
||||
accelGyroSettingsData.accel_bias[1] += y_bias;
|
||||
accelGyroSettingsData.accel_bias[2] += z_bias;
|
||||
accelGyroSettingsData.gyro_bias[0] = -x_gyro_bias;
|
||||
accelGyroSettingsData.gyro_bias[1] = -y_gyro_bias;
|
||||
accelGyroSettingsData.gyro_bias[2] = -z_gyro_bias;
|
||||
attitudeSettingsData.BiasCorrectGyro = AttitudeSettings::BIASCORRECTGYRO_TRUE;
|
||||
AttitudeSettings::GetInstance(getObjectManager())->setData(attitudeSettingsData);
|
||||
AccelGyroSettings::GetInstance(getObjectManager())->setData(accelGyroSettingsData);
|
||||
this->setDirty(true);
|
||||
|
||||
// reenable controls
|
||||
enableControls(true);
|
||||
}
|
||||
}
|
||||
|
||||
void ConfigCCAttitudeWidget::timeout()
|
||||
{
|
||||
UAVDataObject *obj = AccelState::GetInstance(getObjectManager());
|
||||
|
||||
disconnect(obj, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(sensorsUpdated(UAVObject *)));
|
||||
disconnect(&timer, SIGNAL(timeout()), this, SLOT(timeout()));
|
||||
|
||||
AccelState *accelState = AccelState::GetInstance(getObjectManager());
|
||||
GyroState *gyroState = GyroState::GetInstance(getObjectManager());
|
||||
accelState->setMetadata(initialAccelStateMdata);
|
||||
gyroState->setMetadata(initialGyroStateMdata);
|
||||
|
||||
QMessageBox msgBox;
|
||||
msgBox.setText(tr("Calibration timed out before receiving required updates."));
|
||||
msgBox.setStandardButtons(QMessageBox::Ok);
|
||||
msgBox.setDefaultButton(QMessageBox::Ok);
|
||||
msgBox.exec();
|
||||
|
||||
// reset progress indicator
|
||||
ui->zeroBiasProgress->setValue(0);
|
||||
// reenable controls
|
||||
enableControls(true);
|
||||
}
|
||||
|
||||
void ConfigCCAttitudeWidget::startAccelCalibration()
|
||||
{
|
||||
// disable controls during sampling
|
||||
enableControls(false);
|
||||
|
||||
accelUpdates = 0;
|
||||
gyroUpdates = 0;
|
||||
x_accum.clear();
|
||||
y_accum.clear();
|
||||
z_accum.clear();
|
||||
x_gyro_accum.clear();
|
||||
y_gyro_accum.clear();
|
||||
z_gyro_accum.clear();
|
||||
|
||||
// Disable gyro bias correction to see raw data
|
||||
AttitudeSettings::DataFields attitudeSettingsData = AttitudeSettings::GetInstance(getObjectManager())->getData();
|
||||
attitudeSettingsData.BiasCorrectGyro = AttitudeSettings::BIASCORRECTGYRO_FALSE;
|
||||
AttitudeSettings::GetInstance(getObjectManager())->setData(attitudeSettingsData);
|
||||
|
||||
// Set up to receive updates
|
||||
UAVDataObject *accelState = AccelState::GetInstance(getObjectManager());
|
||||
UAVDataObject *gyroState = GyroState::GetInstance(getObjectManager());
|
||||
connect(accelState, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(sensorsUpdated(UAVObject *)));
|
||||
connect(gyroState, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(sensorsUpdated(UAVObject *)));
|
||||
|
||||
// Speed up updates
|
||||
initialAccelStateMdata = accelState->getMetadata();
|
||||
UAVObject::Metadata accelStateMdata = initialAccelStateMdata;
|
||||
UAVObject::SetFlightTelemetryUpdateMode(accelStateMdata, UAVObject::UPDATEMODE_PERIODIC);
|
||||
accelStateMdata.flightTelemetryUpdatePeriod = 30; // ms
|
||||
accelState->setMetadata(accelStateMdata);
|
||||
|
||||
initialGyroStateMdata = gyroState->getMetadata();
|
||||
UAVObject::Metadata gyroStateMdata = initialGyroStateMdata;
|
||||
UAVObject::SetFlightTelemetryUpdateMode(gyroStateMdata, UAVObject::UPDATEMODE_PERIODIC);
|
||||
gyroStateMdata.flightTelemetryUpdatePeriod = 30; // ms
|
||||
gyroState->setMetadata(gyroStateMdata);
|
||||
|
||||
// Set up timeout timer
|
||||
timer.setSingleShot(true);
|
||||
timer.start(5000 + (NUM_SENSOR_UPDATES * qMax(accelStateMdata.flightTelemetryUpdatePeriod,
|
||||
gyroStateMdata.flightTelemetryUpdatePeriod)));
|
||||
connect(&timer, SIGNAL(timeout()), this, SLOT(timeout()));
|
||||
}
|
||||
|
||||
void ConfigCCAttitudeWidget::openHelp()
|
||||
{
|
||||
QDesktopServices::openUrl(QUrl(tr("http://wiki.openpilot.org/x/44Cf"), QUrl::StrictMode));
|
||||
}
|
||||
|
||||
void ConfigCCAttitudeWidget::setAccelFiltering(bool active)
|
||||
{
|
||||
Q_UNUSED(active);
|
||||
setDirty(true);
|
||||
}
|
||||
|
||||
void ConfigCCAttitudeWidget::enableControls(bool enable)
|
||||
{
|
||||
ui->zeroBias->setEnabled(enable);
|
||||
ui->zeroGyroBiasOnArming->setEnabled(enable);
|
||||
ui->accelTauSpinbox->setEnabled(enable);
|
||||
ConfigTaskWidget::enableControls(enable);
|
||||
}
|
||||
|
||||
void ConfigCCAttitudeWidget::updateObjectsFromWidgets()
|
||||
{
|
||||
ConfigTaskWidget::updateObjectsFromWidgets();
|
||||
|
||||
ui->zeroBiasProgress->setValue(0);
|
||||
}
|
@ -0,0 +1,74 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file configccattitudewidget.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @addtogroup GCSPlugins GCS Plugins
|
||||
* @{
|
||||
* @addtogroup ConfigPlugin Config Plugin
|
||||
* @{
|
||||
* @brief Configure the properties of the attitude module in CopterControl
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* 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 CCATTITUDEWIDGET_H
|
||||
#define CCATTITUDEWIDGET_H
|
||||
|
||||
#include "ui_ccattitude.h"
|
||||
#include "../uavobjectwidgetutils/configtaskwidget.h"
|
||||
#include "extensionsystem/pluginmanager.h"
|
||||
#include "uavobjectmanager.h"
|
||||
#include "uavobject.h"
|
||||
#include <QWidget>
|
||||
#include <QTimer>
|
||||
|
||||
class Ui_Widget;
|
||||
|
||||
class ConfigCCAttitudeWidget : public ConfigTaskWidget {
|
||||
Q_OBJECT
|
||||
|
||||
public:
|
||||
explicit ConfigCCAttitudeWidget(QWidget *parent = 0);
|
||||
~ConfigCCAttitudeWidget();
|
||||
|
||||
virtual void updateObjectsFromWidgets();
|
||||
|
||||
private slots:
|
||||
void sensorsUpdated(UAVObject *obj);
|
||||
void timeout();
|
||||
void startAccelCalibration();
|
||||
void openHelp();
|
||||
void setAccelFiltering(bool active);
|
||||
|
||||
private:
|
||||
Ui_ccattitude *ui;
|
||||
QTimer timer;
|
||||
UAVObject::Metadata initialAccelStateMdata;
|
||||
UAVObject::Metadata initialGyroStateMdata;
|
||||
|
||||
int accelUpdates;
|
||||
int gyroUpdates;
|
||||
|
||||
QList<double> x_accum, y_accum, z_accum;
|
||||
QList<double> x_gyro_accum, y_gyro_accum, z_gyro_accum;
|
||||
|
||||
static const float DEFAULT_ENABLED_ACCEL_TAU = 0.1;
|
||||
static const int NUM_SENSOR_UPDATES = 300;
|
||||
protected:
|
||||
virtual void enableControls(bool enable);
|
||||
};
|
||||
|
||||
#endif // CCATTITUDEWIDGET_H
|
@ -12,7 +12,9 @@
|
||||
<file>images/fixedwing-shapes.svg</file>
|
||||
<file>images/ground-shapes.svg</file>
|
||||
<file>images/ccpm_setup.svg</file>
|
||||
<file>images/PipXtreme.png</file>
|
||||
<file>images/help.png</file>
|
||||
<file>images/coptercontrol.svg</file>
|
||||
<file>images/TX2.svg</file>
|
||||
<file>images/output_selected.png</file>
|
||||
<file>images/output_normal.png</file>
|
||||
|
@ -28,12 +28,14 @@
|
||||
#include "configgadgetwidget.h"
|
||||
|
||||
#include "configvehicletypewidget.h"
|
||||
#include "configccattitudewidget.h"
|
||||
#include "configinputwidget.h"
|
||||
#include "configoutputwidget.h"
|
||||
#include "configstabilizationwidget.h"
|
||||
#include "configcamerastabilizationwidget.h"
|
||||
#include "configtxpidwidget.h"
|
||||
#include "configrevohwwidget.h"
|
||||
#include "config_cc_hw_widget.h"
|
||||
#include "configoplinkwidget.h"
|
||||
#include "configrevowidget.h"
|
||||
#include "configrevonanohwwidget.h"
|
||||
@ -182,13 +184,18 @@ void ConfigGadgetWidget::onAutopilotConnect()
|
||||
UAVObjectUtilManager *utilMngr = pm->getObject<UAVObjectUtilManager>();
|
||||
if (utilMngr) {
|
||||
int board = utilMngr->getBoardModel();
|
||||
if ((board & 0xff00) == 0x0900) {
|
||||
if ((board & 0xff00) == 0x0400) {
|
||||
// CopterControl family
|
||||
QWidget *qwd = new ConfigCCAttitudeWidget(this);
|
||||
stackWidget->replaceTab(ConfigGadgetWidget::sensors, qwd);
|
||||
qwd = new ConfigCCHWWidget(this);
|
||||
stackWidget->replaceTab(ConfigGadgetWidget::hardware, qwd);
|
||||
} else if ((board & 0xff00) == 0x0900) {
|
||||
// Revolution family
|
||||
QWidget *qwd = new ConfigRevoWidget(this);
|
||||
stackWidget->replaceTab(ConfigGadgetWidget::sensors, qwd);
|
||||
if (board == 0x0903) {
|
||||
qwd = new ConfigRevoHWWidget(this);
|
||||
} else if (board == 0x0905) {
|
||||
qwd = new ConfigRevoHWWidget(this);
|
||||
if (board == 0x0905) {
|
||||
qwd = new ConfigRevoNanoHWWidget(this);
|
||||
}
|
||||
stackWidget->replaceTab(ConfigGadgetWidget::hardware, qwd);
|
||||
|
@ -354,7 +354,11 @@ void ConfigOutputWidget::refreshWidgetsValues(UAVObject *obj)
|
||||
if (utilMngr) {
|
||||
int board = utilMngr->getBoardModel();
|
||||
// Setup labels and combos for banks according to board type
|
||||
if (board == 0x0903) {
|
||||
if ((board & 0xff00) == 0x0400) {
|
||||
// Coptercontrol family of boards 4 timer banks
|
||||
bankLabels << "1 (1-3)" << "2 (4)" << "3 (5,7-8)" << "4 (6,9-10)";
|
||||
channelBanks << 1 << 1 << 1 << 2 << 3 << 4 << 3 << 3 << 4 << 4;
|
||||
} else if (board == 0x0903) {
|
||||
// Revolution family of boards 6 timer banks
|
||||
bankLabels << "1 (1-2)" << "2 (3)" << "3 (4)" << "4 (5-6)" << "5 (7,12)" << "6 (8-11)";
|
||||
channelBanks << 1 << 1 << 2 << 3 << 4 << 4 << 5 << 6 << 6 << 6 << 6 << 5;
|
||||
@ -472,7 +476,10 @@ void ConfigOutputWidget::updateWarnings(UAVObject *)
|
||||
if (systemAlarms.Alarm[SystemAlarms::ALARM_SYSTEMCONFIGURATION] > SystemAlarms::ALARM_WARNING) {
|
||||
switch (systemAlarms.ExtendedAlarmStatus[SystemAlarms::EXTENDEDALARMSTATUS_SYSTEMCONFIGURATION]) {
|
||||
case SystemAlarms::EXTENDEDALARMSTATUS_UNSUPPORTEDCONFIG_ONESHOT:
|
||||
setWarning(tr("OneShot and PWMSync output DO NOT work with Receiver Port is 'PWM'<br>"));
|
||||
setWarning(tr("OneShot and PWMSync output only works with Receiver Port settings marked with '+OneShot'<br>"
|
||||
"When using Receiver Port setting 'PPM_PIN8+OneShot' "
|
||||
"<b><font color='%1'>Bank %2</font></b> must be set to PWM")
|
||||
.arg(m_banks.at(3).color().name()).arg(m_banks.at(3).label()->text()));
|
||||
return;
|
||||
}
|
||||
}
|
||||
|
BIN
ground/openpilotgcs/src/plugins/config/images/PipXtreme.png
Normal file
After Width: | Height: | Size: 77 KiB |
2647
ground/openpilotgcs/src/plugins/config/images/coptercontrol.svg
Normal file
@ -0,0 +1,2647 @@
|
||||
<?xml version="1.0" encoding="UTF-8" standalone="no"?>
|
||||
<!-- Created with Inkscape (http://www.inkscape.org/) -->
|
||||
|
||||
<svg
|
||||
xmlns:dc="http://purl.org/dc/elements/1.1/"
|
||||
xmlns:cc="http://creativecommons.org/ns#"
|
||||
xmlns:rdf="http://www.w3.org/1999/02/22-rdf-syntax-ns#"
|
||||
xmlns:svg="http://www.w3.org/2000/svg"
|
||||
xmlns="http://www.w3.org/2000/svg"
|
||||
xmlns:sodipodi="http://sodipodi.sourceforge.net/DTD/sodipodi-0.dtd"
|
||||
xmlns:inkscape="http://www.inkscape.org/namespaces/inkscape"
|
||||
id="svg3578"
|
||||
version="1.1"
|
||||
inkscape:version="0.48.1 "
|
||||
width="217.16675"
|
||||
height="212.0625"
|
||||
xml:space="preserve"
|
||||
sodipodi:docname="deviceID-0401.svg"><metadata
|
||||
id="metadata3584"><rdf:RDF><cc:Work
|
||||
rdf:about=""><dc:format>image/svg+xml</dc:format><dc:type
|
||||
rdf:resource="http://purl.org/dc/dcmitype/StillImage" /><dc:title></dc:title></cc:Work></rdf:RDF></metadata><defs
|
||||
id="defs3582"><clipPath
|
||||
clipPathUnits="userSpaceOnUse"
|
||||
id="clipPath3596"><path
|
||||
d="M 0,0 662,0 662,675 0,675 0,0 z"
|
||||
id="path3598"
|
||||
inkscape:connector-curvature="0" /></clipPath></defs><sodipodi:namedview
|
||||
pagecolor="#ffffff"
|
||||
bordercolor="#666666"
|
||||
borderopacity="1"
|
||||
objecttolerance="10"
|
||||
gridtolerance="10"
|
||||
guidetolerance="10"
|
||||
inkscape:pageopacity="0"
|
||||
inkscape:pageshadow="2"
|
||||
inkscape:window-width="1280"
|
||||
inkscape:window-height="738"
|
||||
id="namedview3580"
|
||||
showgrid="false"
|
||||
inkscape:zoom="1.4596704"
|
||||
inkscape:cx="74.195835"
|
||||
inkscape:cy="113.87434"
|
||||
inkscape:window-x="-8"
|
||||
inkscape:window-y="-8"
|
||||
inkscape:window-maximized="1"
|
||||
inkscape:current-layer="layer2"
|
||||
fit-margin-top="0"
|
||||
fit-margin-left="0"
|
||||
fit-margin-right="0"
|
||||
fit-margin-bottom="0" /><g
|
||||
inkscape:groupmode="layer"
|
||||
id="layer2"
|
||||
inkscape:label="Rendering#1"
|
||||
style="display:inline"
|
||||
transform="translate(-40.177007,-31.1875)"><g
|
||||
id="device"
|
||||
inkscape:label="#g15334"
|
||||
transform="matrix(0,1,-1,0,285.97623,-11.53961)"><rect
|
||||
rx="13.079585"
|
||||
ry="10"
|
||||
y="32.199471"
|
||||
x="46.668976"
|
||||
height="210.03767"
|
||||
width="209.67079"
|
||||
id="rect9798"
|
||||
style="fill:#171717;fill-opacity:1;stroke:#000000;stroke-width:2;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><g
|
||||
transform="translate(-311.74173,-199.45)"
|
||||
id="g4318"
|
||||
style="display:inline"><rect
|
||||
y="365.75504"
|
||||
x="422.11606"
|
||||
height="5.0892859"
|
||||
width="6.5178571"
|
||||
id="rect4320"
|
||||
style="fill:#312d29;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect4322"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="428.58929"
|
||||
y="365.75504" /><rect
|
||||
y="365.75504"
|
||||
x="418.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect4324"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /></g><g
|
||||
transform="matrix(0,-1,1,0,-158.96398,620.23853)"
|
||||
id="g4406"
|
||||
style="display:inline"><rect
|
||||
y="365.75504"
|
||||
x="422.11606"
|
||||
height="5.0892859"
|
||||
width="6.5178571"
|
||||
id="rect4408"
|
||||
style="fill:#312d29;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect4410"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="428.58929"
|
||||
y="365.75504" /><rect
|
||||
y="365.75504"
|
||||
x="418.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect4412"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /></g><g
|
||||
style="display:inline"
|
||||
id="g10505"
|
||||
transform="translate(-238.1085,-287.13166)"><rect
|
||||
style="fill:#312d29;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect10507"
|
||||
width="6.5178571"
|
||||
height="5.0892859"
|
||||
x="422.11606"
|
||||
y="365.75504" /><rect
|
||||
y="365.75504"
|
||||
x="428.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect10509"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect10511"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="418.58929"
|
||||
y="365.75504" /></g><g
|
||||
transform="translate(-297.20885,-185.40155)"
|
||||
id="g10513"
|
||||
style="display:inline"><rect
|
||||
y="365.75504"
|
||||
x="422.11606"
|
||||
height="5.0892859"
|
||||
width="6.5178571"
|
||||
id="rect10515"
|
||||
style="fill:#312d29;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect10517"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="428.58929"
|
||||
y="365.75504" /><rect
|
||||
y="365.75504"
|
||||
x="418.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect10519"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /></g><g
|
||||
id="g4225"
|
||||
style="display:inline"
|
||||
transform="translate(-324.12933,-188.57649)"><rect
|
||||
style="fill:#bc781e;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect4219"
|
||||
width="6.5178571"
|
||||
height="5.0892859"
|
||||
x="422.11606"
|
||||
y="365.75504" /><rect
|
||||
y="365.75504"
|
||||
x="428.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect4221"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect4223"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="418.58929"
|
||||
y="365.75504" /></g><g
|
||||
transform="translate(-229.42344,-179.37234)"
|
||||
style="display:inline"
|
||||
id="g10548"><rect
|
||||
y="365.75504"
|
||||
x="422.11606"
|
||||
height="5.0892859"
|
||||
width="6.5178571"
|
||||
id="rect10550"
|
||||
style="fill:#bc781e;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect10552"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="428.58929"
|
||||
y="365.75504" /><rect
|
||||
y="365.75504"
|
||||
x="418.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect10554"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /></g><g
|
||||
id="g10556"
|
||||
style="display:inline"
|
||||
transform="translate(-230.15008,-167.50383)"><rect
|
||||
style="fill:#bc781e;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect10558"
|
||||
width="6.5178571"
|
||||
height="5.0892859"
|
||||
x="422.11606"
|
||||
y="365.75504" /><rect
|
||||
y="365.75504"
|
||||
x="428.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect10560"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect10562"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="418.58929"
|
||||
y="365.75504" /></g><g
|
||||
transform="translate(-235.23659,-253.7322)"
|
||||
style="display:inline"
|
||||
id="g10564"><rect
|
||||
y="365.75504"
|
||||
x="422.11606"
|
||||
height="5.0892859"
|
||||
width="6.5178571"
|
||||
id="rect10566"
|
||||
style="fill:#bc781e;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect10568"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="428.58929"
|
||||
y="365.75504" /><rect
|
||||
y="365.75504"
|
||||
x="418.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect10570"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /></g><g
|
||||
id="g10572"
|
||||
style="display:inline"
|
||||
transform="translate(-214.16393,-327.60763)"><rect
|
||||
style="fill:#bc781e;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect10574"
|
||||
width="6.5178571"
|
||||
height="5.0892859"
|
||||
x="422.11606"
|
||||
y="365.75504" /><rect
|
||||
y="365.75504"
|
||||
x="428.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect10576"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect10578"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="418.58929"
|
||||
y="365.75504" /></g><g
|
||||
id="g4414"
|
||||
transform="translate(-365.77251,-288.34483)"
|
||||
style="display:inline"><rect
|
||||
style="fill:#0052ff;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect4416"
|
||||
width="6.5178571"
|
||||
height="5.0892859"
|
||||
x="422.11606"
|
||||
y="365.75504" /><rect
|
||||
y="365.75504"
|
||||
x="428.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect4418"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect4420"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="418.58929"
|
||||
y="365.75504" /></g><g
|
||||
id="g10667"
|
||||
style="display:inline"
|
||||
transform="translate(-466.1013,-470.16522)"><rect
|
||||
style="fill:#ff7900;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect4432"
|
||||
width="6.5178571"
|
||||
height="5.0892859"
|
||||
x="522.11609"
|
||||
y="559.755" /><rect
|
||||
y="559.755"
|
||||
x="528.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect4434"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect4436"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="518.58929"
|
||||
y="559.755" /></g><g
|
||||
transform="matrix(0,1,-1,0,476.81179,-372.57224)"
|
||||
id="g4278"
|
||||
style="display:inline"><rect
|
||||
y="365.75504"
|
||||
x="422.11606"
|
||||
height="5.0892859"
|
||||
width="6.5178571"
|
||||
id="rect4280"
|
||||
style="fill:#bc781e;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect4282"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="428.58929"
|
||||
y="365.75504" /><rect
|
||||
y="365.75504"
|
||||
x="418.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect4284"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /></g><g
|
||||
style="display:inline"
|
||||
id="g10761"
|
||||
transform="matrix(0,1,-1,0,476.81179,-340.57224)"><rect
|
||||
style="fill:#bc781e;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect10763"
|
||||
width="6.5178571"
|
||||
height="5.0892859"
|
||||
x="422.11606"
|
||||
y="365.75504" /><rect
|
||||
y="365.75504"
|
||||
x="428.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect10765"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect10767"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="418.58929"
|
||||
y="365.75504" /></g><g
|
||||
transform="matrix(0,1,-1,0,531.29622,-332.15009)"
|
||||
id="g10769"
|
||||
style="display:inline"><rect
|
||||
y="365.75504"
|
||||
x="422.11606"
|
||||
height="5.0892859"
|
||||
width="6.5178571"
|
||||
id="rect10771"
|
||||
style="fill:#bc781e;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect10773"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="428.58929"
|
||||
y="365.75504" /><rect
|
||||
y="365.75504"
|
||||
x="418.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect10775"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /></g><g
|
||||
style="display:inline"
|
||||
id="g10777"
|
||||
transform="matrix(0,1,-1,0,453.06093,-235.02206)"><rect
|
||||
style="fill:#bc781e;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect10779"
|
||||
width="6.5178571"
|
||||
height="5.0892859"
|
||||
x="422.11606"
|
||||
y="365.75504" /><rect
|
||||
y="365.75504"
|
||||
x="428.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect10781"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect10783"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="418.58929"
|
||||
y="365.75504" /></g><g
|
||||
transform="matrix(0,1,-1,0,453.06093,-213.9494)"
|
||||
id="g10785"
|
||||
style="display:inline"><rect
|
||||
y="365.75504"
|
||||
x="422.11606"
|
||||
height="5.0892859"
|
||||
width="6.5178571"
|
||||
id="rect10787"
|
||||
style="fill:#bc781e;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect10789"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="428.58929"
|
||||
y="365.75504" /><rect
|
||||
y="365.75504"
|
||||
x="418.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect10791"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /></g><g
|
||||
style="display:inline"
|
||||
id="g10793"
|
||||
transform="matrix(0,1,-1,0,497.6284,-222.66912)"><rect
|
||||
style="fill:#bc781e;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect10795"
|
||||
width="6.5178571"
|
||||
height="5.0892859"
|
||||
x="422.11606"
|
||||
y="365.75504" /><rect
|
||||
y="365.75504"
|
||||
x="428.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect10797"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect10799"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="418.58929"
|
||||
y="365.75504" /></g><g
|
||||
style="display:inline"
|
||||
id="g10801"
|
||||
transform="matrix(0,-1,1,0,-252.45879,579.30427)"><rect
|
||||
style="fill:#312d29;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect10803"
|
||||
width="6.5178571"
|
||||
height="5.0892859"
|
||||
x="422.11606"
|
||||
y="365.75504" /><rect
|
||||
y="365.75504"
|
||||
x="428.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect10805"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect10807"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="418.58929"
|
||||
y="365.75504" /></g><g
|
||||
transform="matrix(0,-1,1,0,-263.11623,579.54648)"
|
||||
id="g10809"
|
||||
style="display:inline"><rect
|
||||
y="365.75504"
|
||||
x="422.11606"
|
||||
height="5.0892859"
|
||||
width="6.5178571"
|
||||
id="rect10811"
|
||||
style="fill:#312d29;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect10813"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="428.58929"
|
||||
y="365.75504" /><rect
|
||||
y="365.75504"
|
||||
x="418.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect10815"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /></g><g
|
||||
style="display:inline"
|
||||
id="g10817"
|
||||
transform="matrix(0,-1,1,0,-273.53145,580.27312)"><rect
|
||||
style="fill:#312d29;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect10819"
|
||||
width="6.5178571"
|
||||
height="5.0892859"
|
||||
x="422.11606"
|
||||
y="365.75504" /><rect
|
||||
y="365.75504"
|
||||
x="428.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect10821"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect10823"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="418.58929"
|
||||
y="365.75504" /></g><g
|
||||
transform="matrix(0,-1,1,0,-272.56259,546.12087)"
|
||||
id="g10825"
|
||||
style="display:inline"><rect
|
||||
y="365.75504"
|
||||
x="422.11606"
|
||||
height="5.0892859"
|
||||
width="6.5178571"
|
||||
id="rect10827"
|
||||
style="fill:#312d29;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect10829"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="428.58929"
|
||||
y="365.75504" /><rect
|
||||
y="365.75504"
|
||||
x="418.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect10831"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /></g><g
|
||||
style="display:inline"
|
||||
id="g10833"
|
||||
transform="matrix(0,-1,1,0,-257.06086,546.36308)"><rect
|
||||
style="fill:#312d29;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect10835"
|
||||
width="6.5178571"
|
||||
height="5.0892859"
|
||||
x="422.11606"
|
||||
y="365.75504" /><rect
|
||||
y="365.75504"
|
||||
x="428.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect10837"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect10839"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="418.58929"
|
||||
y="365.75504" /></g><g
|
||||
id="g10887"><path
|
||||
sodipodi:type="arc"
|
||||
style="fill:none;stroke:#f2edda;stroke-width:1.5;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="path4550"
|
||||
sodipodi:cx="225.89285"
|
||||
sodipodi:cy="542.54077"
|
||||
sodipodi:rx="5.1785712"
|
||||
sodipodi:ry="5.1785712"
|
||||
d="m 231.07142,542.54077 c 0,2.86005 -2.31852,5.17857 -5.17857,5.17857 -2.86004,0 -5.17857,-2.31852 -5.17857,-5.17857 0,-2.86004 2.31853,-5.17857 5.17857,-5.17857 2.86005,0 5.17857,2.31853 5.17857,5.17857 z"
|
||||
transform="translate(20.6651,-466.48541)" /><path
|
||||
sodipodi:type="arc"
|
||||
style="fill:none;stroke:#f2edda;stroke-width:1.5;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="path4554"
|
||||
sodipodi:cx="225.89285"
|
||||
sodipodi:cy="542.54077"
|
||||
sodipodi:rx="5.1785712"
|
||||
sodipodi:ry="5.1785712"
|
||||
d="m 231.07142,542.54077 c 0,2.86005 -2.31852,5.17857 -5.17857,5.17857 -2.86004,0 -5.17857,-2.31852 -5.17857,-5.17857 0,-2.86004 2.31853,-5.17857 5.17857,-5.17857 2.86005,0 5.17857,2.31853 5.17857,5.17857 z"
|
||||
transform="translate(4.6651,-466.48541)" /><rect
|
||||
y="71.519623"
|
||||
x="210.81711"
|
||||
height="8.5714283"
|
||||
width="9.6428576"
|
||||
id="rect4556"
|
||||
style="fill:none;stroke:#f2edda;stroke-width:1.5;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" /></g><g
|
||||
transform="translate(0,14)"
|
||||
id="g10892"><path
|
||||
transform="translate(20.6651,-466.48541)"
|
||||
d="m 231.07142,542.54077 c 0,2.86005 -2.31852,5.17857 -5.17857,5.17857 -2.86004,0 -5.17857,-2.31852 -5.17857,-5.17857 0,-2.86004 2.31853,-5.17857 5.17857,-5.17857 2.86005,0 5.17857,2.31853 5.17857,5.17857 z"
|
||||
sodipodi:ry="5.1785712"
|
||||
sodipodi:rx="5.1785712"
|
||||
sodipodi:cy="542.54077"
|
||||
sodipodi:cx="225.89285"
|
||||
id="path10894"
|
||||
style="fill:none;stroke:#f2edda;stroke-width:1.5;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
sodipodi:type="arc" /><path
|
||||
transform="translate(4.6651,-466.48541)"
|
||||
d="m 231.07142,542.54077 c 0,2.86005 -2.31852,5.17857 -5.17857,5.17857 -2.86004,0 -5.17857,-2.31852 -5.17857,-5.17857 0,-2.86004 2.31853,-5.17857 5.17857,-5.17857 2.86005,0 5.17857,2.31853 5.17857,5.17857 z"
|
||||
sodipodi:ry="5.1785712"
|
||||
sodipodi:rx="5.1785712"
|
||||
sodipodi:cy="542.54077"
|
||||
sodipodi:cx="225.89285"
|
||||
id="path10896"
|
||||
style="fill:none;stroke:#f2edda;stroke-width:1.5;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
sodipodi:type="arc" /><rect
|
||||
style="fill:none;stroke:#f2edda;stroke-width:1.5;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="rect10898"
|
||||
width="9.6428576"
|
||||
height="8.5714283"
|
||||
x="210.81711"
|
||||
y="71.519623" /></g><g
|
||||
id="g10900"
|
||||
transform="translate(0,30)"><path
|
||||
sodipodi:type="arc"
|
||||
style="fill:none;stroke:#f2edda;stroke-width:1.5;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="path10902"
|
||||
sodipodi:cx="225.89285"
|
||||
sodipodi:cy="542.54077"
|
||||
sodipodi:rx="5.1785712"
|
||||
sodipodi:ry="5.1785712"
|
||||
d="m 231.07142,542.54077 c 0,2.86005 -2.31852,5.17857 -5.17857,5.17857 -2.86004,0 -5.17857,-2.31852 -5.17857,-5.17857 0,-2.86004 2.31853,-5.17857 5.17857,-5.17857 2.86005,0 5.17857,2.31853 5.17857,5.17857 z"
|
||||
transform="translate(20.6651,-466.48541)" /><path
|
||||
sodipodi:type="arc"
|
||||
style="fill:none;stroke:#f2edda;stroke-width:1.5;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="path10904"
|
||||
sodipodi:cx="225.89285"
|
||||
sodipodi:cy="542.54077"
|
||||
sodipodi:rx="5.1785712"
|
||||
sodipodi:ry="5.1785712"
|
||||
d="m 231.07142,542.54077 c 0,2.86005 -2.31852,5.17857 -5.17857,5.17857 -2.86004,0 -5.17857,-2.31852 -5.17857,-5.17857 0,-2.86004 2.31853,-5.17857 5.17857,-5.17857 2.86005,0 5.17857,2.31853 5.17857,5.17857 z"
|
||||
transform="translate(4.6651,-466.48541)" /><rect
|
||||
y="71.519623"
|
||||
x="210.81711"
|
||||
height="8.5714283"
|
||||
width="9.6428576"
|
||||
id="rect10906"
|
||||
style="fill:none;stroke:#f2edda;stroke-width:1.5;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" /></g><g
|
||||
transform="translate(0,46)"
|
||||
id="g10908"><path
|
||||
transform="translate(20.6651,-466.48541)"
|
||||
d="m 231.07142,542.54077 c 0,2.86005 -2.31852,5.17857 -5.17857,5.17857 -2.86004,0 -5.17857,-2.31852 -5.17857,-5.17857 0,-2.86004 2.31853,-5.17857 5.17857,-5.17857 2.86005,0 5.17857,2.31853 5.17857,5.17857 z"
|
||||
sodipodi:ry="5.1785712"
|
||||
sodipodi:rx="5.1785712"
|
||||
sodipodi:cy="542.54077"
|
||||
sodipodi:cx="225.89285"
|
||||
id="path10910"
|
||||
style="fill:none;stroke:#f2edda;stroke-width:1.5;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
sodipodi:type="arc" /><path
|
||||
transform="translate(4.6651,-466.48541)"
|
||||
d="m 231.07142,542.54077 c 0,2.86005 -2.31852,5.17857 -5.17857,5.17857 -2.86004,0 -5.17857,-2.31852 -5.17857,-5.17857 0,-2.86004 2.31853,-5.17857 5.17857,-5.17857 2.86005,0 5.17857,2.31853 5.17857,5.17857 z"
|
||||
sodipodi:ry="5.1785712"
|
||||
sodipodi:rx="5.1785712"
|
||||
sodipodi:cy="542.54077"
|
||||
sodipodi:cx="225.89285"
|
||||
id="path10912"
|
||||
style="fill:none;stroke:#f2edda;stroke-width:1.5;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
sodipodi:type="arc" /><rect
|
||||
style="fill:none;stroke:#f2edda;stroke-width:1.5;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="rect10914"
|
||||
width="9.6428576"
|
||||
height="8.5714283"
|
||||
x="210.81711"
|
||||
y="71.519623" /></g><g
|
||||
id="g10916"
|
||||
transform="translate(0,62)"><path
|
||||
sodipodi:type="arc"
|
||||
style="fill:none;stroke:#f2edda;stroke-width:1.5;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="path10918"
|
||||
sodipodi:cx="225.89285"
|
||||
sodipodi:cy="542.54077"
|
||||
sodipodi:rx="5.1785712"
|
||||
sodipodi:ry="5.1785712"
|
||||
d="m 231.07142,542.54077 c 0,2.86005 -2.31852,5.17857 -5.17857,5.17857 -2.86004,0 -5.17857,-2.31852 -5.17857,-5.17857 0,-2.86004 2.31853,-5.17857 5.17857,-5.17857 2.86005,0 5.17857,2.31853 5.17857,5.17857 z"
|
||||
transform="translate(20.6651,-466.48541)" /><path
|
||||
sodipodi:type="arc"
|
||||
style="fill:none;stroke:#f2edda;stroke-width:1.5;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="path10920"
|
||||
sodipodi:cx="225.89285"
|
||||
sodipodi:cy="542.54077"
|
||||
sodipodi:rx="5.1785712"
|
||||
sodipodi:ry="5.1785712"
|
||||
d="m 231.07142,542.54077 c 0,2.86005 -2.31852,5.17857 -5.17857,5.17857 -2.86004,0 -5.17857,-2.31852 -5.17857,-5.17857 0,-2.86004 2.31853,-5.17857 5.17857,-5.17857 2.86005,0 5.17857,2.31853 5.17857,5.17857 z"
|
||||
transform="translate(4.6651,-466.48541)" /><rect
|
||||
y="71.519623"
|
||||
x="210.81711"
|
||||
height="8.5714283"
|
||||
width="9.6428576"
|
||||
id="rect10922"
|
||||
style="fill:none;stroke:#f2edda;stroke-width:1.5;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" /></g><g
|
||||
transform="translate(0,76)"
|
||||
id="g10924"><path
|
||||
transform="translate(20.6651,-466.48541)"
|
||||
d="m 231.07142,542.54077 c 0,2.86005 -2.31852,5.17857 -5.17857,5.17857 -2.86004,0 -5.17857,-2.31852 -5.17857,-5.17857 0,-2.86004 2.31853,-5.17857 5.17857,-5.17857 2.86005,0 5.17857,2.31853 5.17857,5.17857 z"
|
||||
sodipodi:ry="5.1785712"
|
||||
sodipodi:rx="5.1785712"
|
||||
sodipodi:cy="542.54077"
|
||||
sodipodi:cx="225.89285"
|
||||
id="path10926"
|
||||
style="fill:none;stroke:#f2edda;stroke-width:1.5;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
sodipodi:type="arc" /><path
|
||||
transform="translate(4.6651,-466.48541)"
|
||||
d="m 231.07142,542.54077 c 0,2.86005 -2.31852,5.17857 -5.17857,5.17857 -2.86004,0 -5.17857,-2.31852 -5.17857,-5.17857 0,-2.86004 2.31853,-5.17857 5.17857,-5.17857 2.86005,0 5.17857,2.31853 5.17857,5.17857 z"
|
||||
sodipodi:ry="5.1785712"
|
||||
sodipodi:rx="5.1785712"
|
||||
sodipodi:cy="542.54077"
|
||||
sodipodi:cx="225.89285"
|
||||
id="path10928"
|
||||
style="fill:none;stroke:#f2edda;stroke-width:1.5;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
sodipodi:type="arc" /><rect
|
||||
style="fill:none;stroke:#f2edda;stroke-width:1.5;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="rect10930"
|
||||
width="9.6428576"
|
||||
height="8.5714283"
|
||||
x="210.81711"
|
||||
y="71.519623" /></g><g
|
||||
style="display:inline"
|
||||
transform="matrix(0,1.2406633,-1.7870765,0,753.06413,-443.20477)"
|
||||
id="g4788"><rect
|
||||
y="365.75504"
|
||||
x="422.11606"
|
||||
height="5.0892859"
|
||||
width="6.5178571"
|
||||
id="rect4790"
|
||||
style="fill:#a9814d;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect4792"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="428.58929"
|
||||
y="365.75504" /><rect
|
||||
y="365.75504"
|
||||
x="418.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect4794"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /></g><g
|
||||
id="g12054"
|
||||
transform="matrix(0,1.2406633,-1.7870765,0,753.06413,-475.20477)"
|
||||
style="display:inline"><rect
|
||||
style="fill:#a9814d;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect12056"
|
||||
width="6.5178571"
|
||||
height="5.0892859"
|
||||
x="422.11606"
|
||||
y="365.75504" /><rect
|
||||
y="365.75504"
|
||||
x="428.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect12058"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect12060"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="418.58929"
|
||||
y="365.75504" /></g><g
|
||||
style="display:inline"
|
||||
transform="matrix(1.2406633,0,0,1.7870765,-460.86273,-457.63731)"
|
||||
id="g12062"><rect
|
||||
y="365.75504"
|
||||
x="422.11606"
|
||||
height="5.0892859"
|
||||
width="6.5178571"
|
||||
id="rect12064"
|
||||
style="fill:#a9814d;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect12066"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="428.58929"
|
||||
y="365.75504" /><rect
|
||||
y="365.75504"
|
||||
x="418.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect12068"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /></g><g
|
||||
id="g12070"
|
||||
transform="matrix(1.2406633,0,0,1.7870765,-426.86273,-457.63731)"
|
||||
style="display:inline"><rect
|
||||
style="fill:#a9814d;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect12072"
|
||||
width="6.5178571"
|
||||
height="5.0892859"
|
||||
x="422.11606"
|
||||
y="365.75504" /><rect
|
||||
y="365.75504"
|
||||
x="428.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect12074"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect12076"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="418.58929"
|
||||
y="365.75504" /></g><g
|
||||
id="g12796"><g
|
||||
transform="translate(-0.3633218,-0.12110727)"
|
||||
id="g12766"><path
|
||||
d="m 133.77917,39.752694 0,-2.686385"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path5376"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 130.94256,39.752694 0,-2.686385"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path5378"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 145.57351,39.752694 0,-2.686385"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path5386"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 142.58758,39.752694 0,-2.686385"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path5388"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 139.75097,39.752694 0,-2.686385"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path5390"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 130.94256,69.7503 0,-2.686344"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path5454"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 133.77917,69.7503 0,-2.686344"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path5456"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 139.75097,69.7503 0,-2.686344"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path5466"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 142.58758,69.7503 0,-2.686344"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path5468"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 145.57351,69.7503 0,-2.686344"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path5470"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 124.82147,57.810942 2.6873,0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path5612"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 124.82147,60.64656 2.6873,0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path5614"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 124.82147,63.63141 2.6873,0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path5616"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 149.0073,63.63141 2.53802,0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path5618"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 149.0073,60.64656 2.53802,0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path5620"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 149.0073,57.810942 2.53802,0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path5622"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 124.82147,46.020858 2.6873,0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path5624"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 124.82147,49.005667 2.6873,0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path5626"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 124.82147,51.841284 2.6873,0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path5628"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 149.0073,51.841284 2.53802,0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path5630"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 149.0073,49.005667 2.53802,0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path5632"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 149.0073,46.020858 2.53802,0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path5634"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 136.76509,39.752694 0,-2.686385"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path5636"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 124.82147,54.826134 2.6873,0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path5726"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 136.76509,69.7503 0,-2.686344"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path5728"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 149.0073,54.826134 2.53802,0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path5730"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 124.82147,43.036008 2.6873,0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path5738"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 149.0073,43.036008 2.53802,0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path5740"
|
||||
inkscape:connector-curvature="0" /></g><rect
|
||||
style="fill:#6a6a6a;fill-opacity:1;stroke:#000000;stroke-width:0.69999999;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="rect4974"
|
||||
width="24.34742"
|
||||
height="31.192205"
|
||||
x="125.66183"
|
||||
y="37.711323" /></g><g
|
||||
id="g12828"><g
|
||||
id="g12830"
|
||||
transform="translate(-0.3633218,-0.12110727)"><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path12832"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
d="m 133.77917,39.752694 0,-2.686385" /><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path12834"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
d="m 130.94256,39.752694 0,-2.686385" /><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path12836"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
d="m 145.57351,39.752694 0,-2.686385" /><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path12838"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
d="m 142.58758,39.752694 0,-2.686385" /><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path12840"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
d="m 139.75097,39.752694 0,-2.686385" /><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path12842"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
d="m 130.94256,69.7503 0,-2.686344" /><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path12844"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
d="m 133.77917,69.7503 0,-2.686344" /><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path12846"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
d="m 139.75097,69.7503 0,-2.686344" /><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path12848"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
d="m 142.58758,69.7503 0,-2.686344" /><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path12850"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
d="m 145.57351,69.7503 0,-2.686344" /><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path12852"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
d="m 124.82147,57.810942 2.6873,0" /><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path12854"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
d="m 124.82147,60.64656 2.6873,0" /><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path12856"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
d="m 124.82147,63.63141 2.6873,0" /><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path12858"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
d="m 149.0073,63.63141 2.53802,0" /><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path12860"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
d="m 149.0073,60.64656 2.53802,0" /><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path12862"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
d="m 149.0073,57.810942 2.53802,0" /><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path12864"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
d="m 124.82147,46.020858 2.6873,0" /><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path12866"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
d="m 124.82147,49.005667 2.6873,0" /><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path12868"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
d="m 124.82147,51.841284 2.6873,0" /><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path12870"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
d="m 149.0073,51.841284 2.53802,0" /><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path12872"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
d="m 149.0073,49.005667 2.53802,0" /><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path12874"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
d="m 149.0073,46.020858 2.53802,0" /><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path12876"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
d="m 136.76509,39.752694 0,-2.686385" /><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path12878"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
d="m 124.82147,54.826134 2.6873,0" /><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path12880"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
d="m 136.76509,69.7503 0,-2.686344" /><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path12882"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
d="m 149.0073,54.826134 2.53802,0" /><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path12884"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
d="m 124.82147,43.036008 2.6873,0" /><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path12886"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
d="m 149.0073,43.036008 2.53802,0" /></g><rect
|
||||
y="37.711323"
|
||||
x="125.66183"
|
||||
height="31.192205"
|
||||
width="24.34742"
|
||||
id="rect12888"
|
||||
style="fill:#6a6a6a;fill-opacity:1;stroke:#000000;stroke-width:0.69999999;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" /></g><g
|
||||
transform="translate(0.68508616,38.685086)"
|
||||
id="g12890"><g
|
||||
transform="translate(-0.3633218,-0.12110727)"
|
||||
id="g12892"><path
|
||||
d="m 133.77917,39.752694 0,-2.686385"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path12894"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 130.94256,39.752694 0,-2.686385"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path12896"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 145.57351,39.752694 0,-2.686385"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path12898"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 142.58758,39.752694 0,-2.686385"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path12900"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 139.75097,39.752694 0,-2.686385"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path12902"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 130.94256,69.7503 0,-2.686344"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path12904"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 133.77917,69.7503 0,-2.686344"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path12906"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 139.75097,69.7503 0,-2.686344"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path12908"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 142.58758,69.7503 0,-2.686344"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path12910"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 145.57351,69.7503 0,-2.686344"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path12912"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 124.82147,57.810942 2.6873,0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path12914"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 124.82147,60.64656 2.6873,0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path12916"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 124.82147,63.63141 2.6873,0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path12918"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 149.0073,63.63141 2.53802,0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path12920"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 149.0073,60.64656 2.53802,0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path12922"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 149.0073,57.810942 2.53802,0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path12924"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 124.82147,46.020858 2.6873,0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path12926"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 124.82147,49.005667 2.6873,0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path12928"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 124.82147,51.841284 2.6873,0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path12930"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 149.0073,51.841284 2.53802,0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path12932"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 149.0073,49.005667 2.53802,0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path12934"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 149.0073,46.020858 2.53802,0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path12936"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 136.76509,39.752694 0,-2.686385"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path12938"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 124.82147,54.826134 2.6873,0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path12940"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 136.76509,69.7503 0,-2.686344"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path12942"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 149.0073,54.826134 2.53802,0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path12944"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 124.82147,43.036008 2.6873,0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path12946"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 149.0073,43.036008 2.53802,0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path12948"
|
||||
inkscape:connector-curvature="0" /></g><rect
|
||||
style="fill:#6a6a6a;fill-opacity:1;stroke:#000000;stroke-width:0.69999999;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="rect12950"
|
||||
width="24.34742"
|
||||
height="31.192205"
|
||||
x="125.66183"
|
||||
y="37.711323" /></g><g
|
||||
id="g12952"
|
||||
style="display:inline"
|
||||
transform="matrix(0.55313316,0,0,0.55313316,202.151,-66.0335)"><rect
|
||||
style="fill:#6a6a6a;fill-opacity:1;stroke:#000000;stroke-width:3.61576581;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect3773"
|
||||
width="76.428574"
|
||||
height="76.785713"
|
||||
x="-104.28571"
|
||||
y="358.43362"
|
||||
ry="2.5" /><g
|
||||
id="g3875"
|
||||
transform="translate(-520,-37.142857)"><g
|
||||
transform="matrix(1.4970318,0,0,1,-211.28069,0.21205357)"
|
||||
id="g3781"><path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path3777"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path3779"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" /></g><g
|
||||
id="g3785"
|
||||
transform="matrix(1.4970318,0,0,1,-207.28069,0.21205357)"><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3787"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3789"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
|
||||
transform="matrix(1.4970318,0,0,1,-203.28069,0.21205357)"
|
||||
id="g3791"><path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path3793"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path3795"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" /></g><g
|
||||
id="g3797"
|
||||
transform="matrix(1.4970318,0,0,1,-199.28069,0.21205357)"><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3799"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3801"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
|
||||
transform="matrix(1.4970318,0,0,1,-195.28069,0.21205357)"
|
||||
id="g3803"><path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path3805"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path3807"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" /></g><g
|
||||
id="g3809"
|
||||
transform="matrix(1.4970318,0,0,1,-191.28069,0.21205357)"><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3811"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3813"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
|
||||
transform="matrix(1.4970318,0,0,1,-187.28069,0.21205357)"
|
||||
id="g3815"><path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path3817"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path3819"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" /></g><g
|
||||
id="g3821"
|
||||
transform="matrix(1.4970318,0,0,1,-183.28069,0.21205357)"><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3823"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3825"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
|
||||
transform="matrix(1.4970318,0,0,1,-179.28069,0.21205357)"
|
||||
id="g3827"><path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path3829"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path3831"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" /></g><g
|
||||
id="g3833"
|
||||
transform="matrix(1.4970318,0,0,1,-175.28069,0.21205357)"><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3835"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3837"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
|
||||
transform="matrix(1.4970318,0,0,1,-171.28069,0.21205357)"
|
||||
id="g3839"><path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path3841"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path3843"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" /></g><g
|
||||
id="g3845"
|
||||
transform="matrix(1.4970318,0,0,1,-167.28069,0.21205357)"><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3847"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3849"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
|
||||
transform="matrix(1.4970318,0,0,1,-163.28069,0.21205357)"
|
||||
id="g3851"><path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path3853"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path3855"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" /></g><g
|
||||
id="g3857"
|
||||
transform="matrix(1.4970318,0,0,1,-159.28069,0.21205357)"><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3859"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3861"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
|
||||
transform="matrix(1.4970318,0,0,1,-155.28069,0.21205357)"
|
||||
id="g3863"><path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path3865"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path3867"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" /></g><g
|
||||
id="g3869"
|
||||
transform="matrix(1.4970318,0,0,1,-151.28069,0.21205357)"><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3871"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3873"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g></g><g
|
||||
id="g3925"
|
||||
transform="matrix(0,1,-1,0,367.93406,-54.993437)"><g
|
||||
id="g3927"
|
||||
transform="matrix(1.4970318,0,0,1,-211.28069,0.21205357)"><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3929"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3931"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
|
||||
transform="matrix(1.4970318,0,0,1,-207.28069,0.21205357)"
|
||||
id="g3933"><path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path3935"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path3937"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" /></g><g
|
||||
id="g3939"
|
||||
transform="matrix(1.4970318,0,0,1,-203.28069,0.21205357)"><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3941"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3943"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
|
||||
transform="matrix(1.4970318,0,0,1,-199.28069,0.21205357)"
|
||||
id="g3945"><path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path3947"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path3949"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" /></g><g
|
||||
id="g3951"
|
||||
transform="matrix(1.4970318,0,0,1,-195.28069,0.21205357)"><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3953"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3955"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
|
||||
transform="matrix(1.4970318,0,0,1,-191.28069,0.21205357)"
|
||||
id="g3957"><path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path3959"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path3961"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" /></g><g
|
||||
id="g3963"
|
||||
transform="matrix(1.4970318,0,0,1,-187.28069,0.21205357)"><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3965"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3967"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
|
||||
transform="matrix(1.4970318,0,0,1,-183.28069,0.21205357)"
|
||||
id="g3969"><path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path3971"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path3973"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" /></g><g
|
||||
id="g3975"
|
||||
transform="matrix(1.4970318,0,0,1,-179.28069,0.21205357)"><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3977"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3979"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
|
||||
transform="matrix(1.4970318,0,0,1,-175.28069,0.21205357)"
|
||||
id="g3981"><path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path3983"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path3985"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" /></g><g
|
||||
id="g3987"
|
||||
transform="matrix(1.4970318,0,0,1,-171.28069,0.21205357)"><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3989"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3991"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
|
||||
transform="matrix(1.4970318,0,0,1,-167.28069,0.21205357)"
|
||||
id="g3993"><path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path3995"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path3997"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" /></g><g
|
||||
id="g3999"
|
||||
transform="matrix(1.4970318,0,0,1,-163.28069,0.21205357)"><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4001"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4003"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
|
||||
transform="matrix(1.4970318,0,0,1,-159.28069,0.21205357)"
|
||||
id="g4005"><path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path4007"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path4009"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" /></g><g
|
||||
id="g4011"
|
||||
transform="matrix(1.4970318,0,0,1,-155.28069,0.21205357)"><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4013"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4015"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
|
||||
transform="matrix(1.4970318,0,0,1,-151.28069,0.21205357)"
|
||||
id="g4017"><path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path4019"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path4021"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" /></g></g><g
|
||||
transform="matrix(0,1,1,0,-500.02315,-54.993437)"
|
||||
id="g4023"><g
|
||||
transform="matrix(1.4970318,0,0,1,-211.28069,0.21205357)"
|
||||
id="g4025"><path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path4027"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path4029"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" /></g><g
|
||||
id="g4031"
|
||||
transform="matrix(1.4970318,0,0,1,-207.28069,0.21205357)"><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4033"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4035"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
|
||||
transform="matrix(1.4970318,0,0,1,-203.28069,0.21205357)"
|
||||
id="g4037"><path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path4039"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path4041"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" /></g><g
|
||||
id="g4043"
|
||||
transform="matrix(1.4970318,0,0,1,-199.28069,0.21205357)"><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4045"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4047"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
|
||||
transform="matrix(1.4970318,0,0,1,-195.28069,0.21205357)"
|
||||
id="g4049"><path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path4051"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path4053"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" /></g><g
|
||||
id="g4055"
|
||||
transform="matrix(1.4970318,0,0,1,-191.28069,0.21205357)"><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4057"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4059"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
|
||||
transform="matrix(1.4970318,0,0,1,-187.28069,0.21205357)"
|
||||
id="g4061"><path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path4063"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path4065"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" /></g><g
|
||||
id="g4067"
|
||||
transform="matrix(1.4970318,0,0,1,-183.28069,0.21205357)"><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4069"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4071"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
|
||||
transform="matrix(1.4970318,0,0,1,-179.28069,0.21205357)"
|
||||
id="g4073"><path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path4075"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path4077"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" /></g><g
|
||||
id="g4079"
|
||||
transform="matrix(1.4970318,0,0,1,-175.28069,0.21205357)"><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4081"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4083"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
|
||||
transform="matrix(1.4970318,0,0,1,-171.28069,0.21205357)"
|
||||
id="g4085"><path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path4087"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path4089"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" /></g><g
|
||||
id="g4091"
|
||||
transform="matrix(1.4970318,0,0,1,-167.28069,0.21205357)"><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4093"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4095"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
|
||||
transform="matrix(1.4970318,0,0,1,-163.28069,0.21205357)"
|
||||
id="g4097"><path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path4099"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path4101"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" /></g><g
|
||||
id="g4103"
|
||||
transform="matrix(1.4970318,0,0,1,-159.28069,0.21205357)"><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4105"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4107"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
|
||||
transform="matrix(1.4970318,0,0,1,-155.28069,0.21205357)"
|
||||
id="g4109"><path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path4111"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path4113"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" /></g><g
|
||||
id="g4115"
|
||||
transform="matrix(1.4970318,0,0,1,-151.28069,0.21205357)"><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4117"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4119"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g></g><g
|
||||
id="g4121"
|
||||
transform="matrix(1,0,0,-1,-520,830.07704)"><g
|
||||
id="g4123"
|
||||
transform="matrix(1.4970318,0,0,1,-211.28069,0.21205357)"><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4125"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4127"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
|
||||
transform="matrix(1.4970318,0,0,1,-207.28069,0.21205357)"
|
||||
id="g4129"><path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path4131"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path4133"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" /></g><g
|
||||
id="g4135"
|
||||
transform="matrix(1.4970318,0,0,1,-203.28069,0.21205357)"><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4137"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4139"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
|
||||
transform="matrix(1.4970318,0,0,1,-199.28069,0.21205357)"
|
||||
id="g4141"><path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path4143"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path4145"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" /></g><g
|
||||
id="g4147"
|
||||
transform="matrix(1.4970318,0,0,1,-195.28069,0.21205357)"><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4149"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4151"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
|
||||
transform="matrix(1.4970318,0,0,1,-191.28069,0.21205357)"
|
||||
id="g4153"><path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path4155"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path4157"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" /></g><g
|
||||
id="g4159"
|
||||
transform="matrix(1.4970318,0,0,1,-187.28069,0.21205357)"><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4161"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4163"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
|
||||
transform="matrix(1.4970318,0,0,1,-183.28069,0.21205357)"
|
||||
id="g4165"><path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path4167"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path4169"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" /></g><g
|
||||
id="g4171"
|
||||
transform="matrix(1.4970318,0,0,1,-179.28069,0.21205357)"><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4173"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4175"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
|
||||
transform="matrix(1.4970318,0,0,1,-175.28069,0.21205357)"
|
||||
id="g4177"><path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path4179"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path4181"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" /></g><g
|
||||
id="g4183"
|
||||
transform="matrix(1.4970318,0,0,1,-171.28069,0.21205357)"><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4185"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4187"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
|
||||
transform="matrix(1.4970318,0,0,1,-167.28069,0.21205357)"
|
||||
id="g4189"><path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path4191"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path4193"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" /></g><g
|
||||
id="g4195"
|
||||
transform="matrix(1.4970318,0,0,1,-163.28069,0.21205357)"><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4197"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4199"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
|
||||
transform="matrix(1.4970318,0,0,1,-159.28069,0.21205357)"
|
||||
id="g4201"><path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path4203"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path4205"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" /></g><g
|
||||
id="g4207"
|
||||
transform="matrix(1.4970318,0,0,1,-155.28069,0.21205357)"><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4209"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4211"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
|
||||
transform="matrix(1.4970318,0,0,1,-151.28069,0.21205357)"
|
||||
id="g4213"><path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path4215"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path4217"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" /></g></g></g><g
|
||||
style="display:inline"
|
||||
id="g4920"
|
||||
transform="matrix(0.41419929,0,0,0.41419929,-10.368172,-50.871127)"><g
|
||||
transform="matrix(0,1.4970318,-1,0,849.26635,-33.0226)"
|
||||
id="g4871"
|
||||
style="display:inline"><rect
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none"
|
||||
id="rect4867"
|
||||
width="10.985409"
|
||||
height="4.0486217"
|
||||
x="-386.60983"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-383.45309"
|
||||
height="4.0486217"
|
||||
width="2.5253813"
|
||||
id="rect4869"
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none" /></g><g
|
||||
id="g4875"
|
||||
transform="matrix(0,1.4970318,-1,0,849.26635,-23.0226)"
|
||||
style="display:inline"><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-386.60983"
|
||||
height="4.0486217"
|
||||
width="10.985409"
|
||||
id="rect4877"
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none" /><rect
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none"
|
||||
id="rect4879"
|
||||
width="2.5253813"
|
||||
height="4.0486217"
|
||||
x="-383.45309"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /></g><g
|
||||
transform="matrix(0,1.4970318,-1,0,849.26635,-13.0226)"
|
||||
id="g4881"
|
||||
style="display:inline"><rect
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none"
|
||||
id="rect4883"
|
||||
width="10.985409"
|
||||
height="4.0486217"
|
||||
x="-386.60983"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-383.45309"
|
||||
height="4.0486217"
|
||||
width="2.5253813"
|
||||
id="rect4885"
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none" /></g><g
|
||||
id="g4887"
|
||||
transform="matrix(0,1.4970318,1,0,55.91598,-13.0226)"
|
||||
style="display:inline"><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-386.60983"
|
||||
height="4.0486217"
|
||||
width="10.985409"
|
||||
id="rect4889"
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none" /><rect
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none"
|
||||
id="rect4891"
|
||||
width="2.5253813"
|
||||
height="4.0486217"
|
||||
x="-383.45309"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /></g><g
|
||||
transform="matrix(0,1.4970318,1,0,55.91598,-33.0226)"
|
||||
id="g4899"
|
||||
style="display:inline"><rect
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none"
|
||||
id="rect4901"
|
||||
width="10.985409"
|
||||
height="4.0486217"
|
||||
x="-386.60983"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-383.45309"
|
||||
height="4.0486217"
|
||||
width="2.5253813"
|
||||
id="rect4903"
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none" /></g><rect
|
||||
ry="1.5"
|
||||
y="590.15265"
|
||||
x="443.12988"
|
||||
height="31.819805"
|
||||
width="18.687822"
|
||||
id="rect4841"
|
||||
style="fill:#6a6a6a;fill-opacity:1;stroke:#000000;stroke-width:2.41429687;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /></g><g
|
||||
transform="matrix(0,0.41419929,-0.41419929,0,462.12545,-133.30339)"
|
||||
id="g13877"
|
||||
style="display:inline"><g
|
||||
style="display:inline"
|
||||
id="g13879"
|
||||
transform="matrix(0,1.4970318,-1,0,849.26635,-33.0226)"><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-386.60983"
|
||||
height="4.0486217"
|
||||
width="10.985409"
|
||||
id="rect13881"
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none" /><rect
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none"
|
||||
id="rect13883"
|
||||
width="2.5253813"
|
||||
height="4.0486217"
|
||||
x="-383.45309"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /></g><g
|
||||
style="display:inline"
|
||||
transform="matrix(0,1.4970318,-1,0,849.26635,-23.0226)"
|
||||
id="g13885"><rect
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none"
|
||||
id="rect13887"
|
||||
width="10.985409"
|
||||
height="4.0486217"
|
||||
x="-386.60983"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-383.45309"
|
||||
height="4.0486217"
|
||||
width="2.5253813"
|
||||
id="rect13889"
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none" /></g><g
|
||||
style="display:inline"
|
||||
id="g13891"
|
||||
transform="matrix(0,1.4970318,-1,0,849.26635,-13.0226)"><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-386.60983"
|
||||
height="4.0486217"
|
||||
width="10.985409"
|
||||
id="rect13893"
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none" /><rect
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none"
|
||||
id="rect13895"
|
||||
width="2.5253813"
|
||||
height="4.0486217"
|
||||
x="-383.45309"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /></g><g
|
||||
style="display:inline"
|
||||
transform="matrix(0,1.4970318,1,0,55.91598,-13.0226)"
|
||||
id="g13897"><rect
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none"
|
||||
id="rect13899"
|
||||
width="10.985409"
|
||||
height="4.0486217"
|
||||
x="-386.60983"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-383.45309"
|
||||
height="4.0486217"
|
||||
width="2.5253813"
|
||||
id="rect13901"
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none" /></g><g
|
||||
style="display:inline"
|
||||
id="g13903"
|
||||
transform="matrix(0,1.4970318,1,0,55.91598,-33.0226)"><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-386.60983"
|
||||
height="4.0486217"
|
||||
width="10.985409"
|
||||
id="rect13905"
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none" /><rect
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none"
|
||||
id="rect13907"
|
||||
width="2.5253813"
|
||||
height="4.0486217"
|
||||
x="-383.45309"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /></g><rect
|
||||
style="fill:#6a6a6a;fill-opacity:1;stroke:#000000;stroke-width:2.41429687;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect13909"
|
||||
width="18.687822"
|
||||
height="31.819805"
|
||||
x="443.12988"
|
||||
y="590.15265"
|
||||
ry="1.5" /></g><g
|
||||
id="g13760"
|
||||
style="display:inline"
|
||||
transform="matrix(0,0.61819183,-0.61819183,0,444.94676,-97.125819)"><rect
|
||||
transform="translate(188.57143,331.57648)"
|
||||
y="269.42856"
|
||||
x="140.71428"
|
||||
height="52.142857"
|
||||
width="89.285713"
|
||||
id="rect5020"
|
||||
style="fill:#fffcfc;fill-opacity:1;stroke:#828282;stroke-width:3.23524165;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" /><g
|
||||
transform="matrix(-1.4970318,0,0,1,971.39158,213.03078)"
|
||||
id="g4964-3"
|
||||
style="display:inline"><rect
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none"
|
||||
id="rect4966-2"
|
||||
width="10.985409"
|
||||
height="4.0486217"
|
||||
x="-386.60983"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-383.45309"
|
||||
height="4.0486217"
|
||||
width="2.5253813"
|
||||
id="rect4968-1"
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none" /></g><g
|
||||
style="display:inline"
|
||||
id="g5046"
|
||||
transform="matrix(-1.4970318,0,0,1,981.39158,213.03078)"><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-386.60983"
|
||||
height="4.0486217"
|
||||
width="10.985409"
|
||||
id="rect5048"
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none" /><rect
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none"
|
||||
id="rect5050"
|
||||
width="2.5253813"
|
||||
height="4.0486217"
|
||||
x="-383.45309"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /></g><g
|
||||
transform="matrix(-1.4970318,0,0,1,991.39158,213.03078)"
|
||||
id="g5052"
|
||||
style="display:inline"><rect
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none"
|
||||
id="rect5054"
|
||||
width="10.985409"
|
||||
height="4.0486217"
|
||||
x="-386.60983"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-383.45309"
|
||||
height="4.0486217"
|
||||
width="2.5253813"
|
||||
id="rect5056"
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none" /></g><g
|
||||
style="display:inline"
|
||||
id="g5058"
|
||||
transform="matrix(-1.4970318,0,0,1,1001.3916,213.03078)"><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-386.60983"
|
||||
height="4.0486217"
|
||||
width="10.985409"
|
||||
id="rect5060"
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none" /><rect
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none"
|
||||
id="rect5062"
|
||||
width="2.5253813"
|
||||
height="4.0486217"
|
||||
x="-383.45309"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /></g><g
|
||||
transform="matrix(-1.4970318,0,0,1,1011.3916,213.03078)"
|
||||
id="g5064"
|
||||
style="display:inline"><rect
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none"
|
||||
id="rect5066"
|
||||
width="10.985409"
|
||||
height="4.0486217"
|
||||
x="-386.60983"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-383.45309"
|
||||
height="4.0486217"
|
||||
width="2.5253813"
|
||||
id="rect5068"
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none" /></g><g
|
||||
style="display:inline"
|
||||
id="g5070"
|
||||
transform="matrix(-1.4970318,0,0,1,1021.3916,213.03078)"><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-386.60983"
|
||||
height="4.0486217"
|
||||
width="10.985409"
|
||||
id="rect5072"
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none" /><rect
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none"
|
||||
id="rect5074"
|
||||
width="2.5253813"
|
||||
height="4.0486217"
|
||||
x="-383.45309"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /></g><g
|
||||
style="display:inline"
|
||||
id="g13998"
|
||||
transform="matrix(-1.4970318,0,0,1,1031.0972,213.03078)"><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-386.60983"
|
||||
height="4.0486217"
|
||||
width="10.985409"
|
||||
id="rect14000"
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none" /><rect
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none"
|
||||
id="rect14002"
|
||||
width="2.5253813"
|
||||
height="4.0486217"
|
||||
x="-383.45309"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /></g><g
|
||||
transform="matrix(-1.4970318,0,0,1,1040.8028,213.03078)"
|
||||
id="g14004"
|
||||
style="display:inline"><rect
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none"
|
||||
id="rect14006"
|
||||
width="10.985409"
|
||||
height="4.0486217"
|
||||
x="-386.60983"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-383.45309"
|
||||
height="4.0486217"
|
||||
width="2.5253813"
|
||||
id="rect14008"
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none" /></g></g><g
|
||||
style="display:inline"
|
||||
id="g4920-2"
|
||||
transform="matrix(-0.48222043,0,0,-0.59728256,285.82656,546.58597)"><g
|
||||
transform="matrix(0,1.4970318,-1,0,849.26635,-33.0226)"
|
||||
id="g4871-7"
|
||||
style="display:inline"><rect
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none"
|
||||
id="rect4867-0"
|
||||
width="10.985409"
|
||||
height="4.0486217"
|
||||
x="-386.60983"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-383.45309"
|
||||
height="4.0486217"
|
||||
width="2.5253813"
|
||||
id="rect4869-4"
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none" /></g><g
|
||||
id="g4875-1"
|
||||
transform="matrix(0,1.4970318,-1,0,849.26635,-23.0226)"
|
||||
style="display:inline"><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-386.60983"
|
||||
height="4.0486217"
|
||||
width="10.985409"
|
||||
id="rect4877-3"
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none" /><rect
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none"
|
||||
id="rect4879-4"
|
||||
width="2.5253813"
|
||||
height="4.0486217"
|
||||
x="-383.45309"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /></g><g
|
||||
transform="matrix(0,1.4970318,-1,0,849.26635,-13.0226)"
|
||||
id="g4881-9"
|
||||
style="display:inline"><rect
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none"
|
||||
id="rect4883-6"
|
||||
width="10.985409"
|
||||
height="4.0486217"
|
||||
x="-386.60983"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-383.45309"
|
||||
height="4.0486217"
|
||||
width="2.5253813"
|
||||
id="rect4885-2"
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none" /></g><g
|
||||
id="g4887-8"
|
||||
transform="matrix(0,1.4970318,1,0,55.91598,-13.0226)"
|
||||
style="display:inline"><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-386.60983"
|
||||
height="4.0486217"
|
||||
width="10.985409"
|
||||
id="rect4889-3"
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none" /><rect
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none"
|
||||
id="rect4891-3"
|
||||
width="2.5253813"
|
||||
height="4.0486217"
|
||||
x="-383.45309"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /></g><g
|
||||
transform="matrix(0,1.4970318,1,0,55.91598,-33.0226)"
|
||||
id="g4899-7"
|
||||
style="display:inline"><rect
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none"
|
||||
id="rect4901-7"
|
||||
width="10.985409"
|
||||
height="4.0486217"
|
||||
x="-386.60983"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-383.45309"
|
||||
height="4.0486217"
|
||||
width="2.5253813"
|
||||
id="rect4903-8"
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none" /></g><rect
|
||||
ry="1.5"
|
||||
y="590.15265"
|
||||
x="443.12988"
|
||||
height="31.819805"
|
||||
width="18.687822"
|
||||
id="rect4841-1"
|
||||
style="fill:#6a6a6a;fill-opacity:1;stroke:#000000;stroke-width:1.86331928;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /></g><g
|
||||
style="display:inline"
|
||||
id="g14076"
|
||||
transform="matrix(0,-1,1,0,-150.96398,652.23853)"><rect
|
||||
y="365.75504"
|
||||
x="426.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect14080"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect14082"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="418.58929"
|
||||
y="365.75504" /></g><g
|
||||
transform="matrix(0.61819183,0,0,0.48347584,-108.7519,-76.23362)"
|
||||
style="display:inline"
|
||||
id="g14084"><rect
|
||||
style="fill:#fffcfc;fill-opacity:1;stroke:#828282;stroke-width:3.65831399;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="rect14086"
|
||||
width="53.268898"
|
||||
height="52.142857"
|
||||
x="329.28571"
|
||||
y="601.00507" /><g
|
||||
style="display:inline"
|
||||
id="g14088"
|
||||
transform="matrix(-1.4970318,0,0,1,971.39158,213.03078)"><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-386.60983"
|
||||
height="4.0486217"
|
||||
width="10.985409"
|
||||
id="rect14090"
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none" /><rect
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none"
|
||||
id="rect14092"
|
||||
width="2.5253813"
|
||||
height="4.0486217"
|
||||
x="-383.45309"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /></g><g
|
||||
transform="matrix(-1.4970318,0,0,1,981.39158,213.03078)"
|
||||
id="g14094"
|
||||
style="display:inline"><rect
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none"
|
||||
id="rect14096"
|
||||
width="10.985409"
|
||||
height="4.0486217"
|
||||
x="-386.60983"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-383.45309"
|
||||
height="4.0486217"
|
||||
width="2.5253813"
|
||||
id="rect14098"
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none" /></g><g
|
||||
style="display:inline"
|
||||
id="g14100"
|
||||
transform="matrix(-1.4970318,0,0,1,991.39158,213.03078)"><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-386.60983"
|
||||
height="4.0486217"
|
||||
width="10.985409"
|
||||
id="rect14102"
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none" /><rect
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none"
|
||||
id="rect14104"
|
||||
width="2.5253813"
|
||||
height="4.0486217"
|
||||
x="-383.45309"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /></g><g
|
||||
transform="matrix(-1.4970318,0,0,1,1001.3916,213.03078)"
|
||||
id="g14106"
|
||||
style="display:inline"><rect
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none"
|
||||
id="rect14108"
|
||||
width="10.985409"
|
||||
height="4.0486217"
|
||||
x="-386.60983"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-383.45309"
|
||||
height="4.0486217"
|
||||
width="2.5253813"
|
||||
id="rect14110"
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none" /></g></g><g
|
||||
id="g14136"
|
||||
style="display:inline"
|
||||
transform="matrix(0.61819183,0,0,0.48347584,-30.7519,-76.23362)"><rect
|
||||
y="601.00507"
|
||||
x="329.28571"
|
||||
height="52.142857"
|
||||
width="53.268898"
|
||||
id="rect14138"
|
||||
style="fill:#fffcfc;fill-opacity:1;stroke:#828282;stroke-width:3.65831399;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" /><g
|
||||
transform="matrix(-1.4970318,0,0,1,971.39158,213.03078)"
|
||||
id="g14140"
|
||||
style="display:inline"><rect
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none"
|
||||
id="rect14142"
|
||||
width="10.985409"
|
||||
height="4.0486217"
|
||||
x="-386.60983"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-383.45309"
|
||||
height="4.0486217"
|
||||
width="2.5253813"
|
||||
id="rect14144"
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none" /></g><g
|
||||
style="display:inline"
|
||||
id="g14146"
|
||||
transform="matrix(-1.4970318,0,0,1,981.39158,213.03078)"><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-386.60983"
|
||||
height="4.0486217"
|
||||
width="10.985409"
|
||||
id="rect14148"
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none" /><rect
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none"
|
||||
id="rect14150"
|
||||
width="2.5253813"
|
||||
height="4.0486217"
|
||||
x="-383.45309"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /></g><g
|
||||
transform="matrix(-1.4970318,0,0,1,991.39158,213.03078)"
|
||||
id="g14152"
|
||||
style="display:inline"><rect
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none"
|
||||
id="rect14154"
|
||||
width="10.985409"
|
||||
height="4.0486217"
|
||||
x="-386.60983"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-383.45309"
|
||||
height="4.0486217"
|
||||
width="2.5253813"
|
||||
id="rect14156"
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none" /></g><g
|
||||
style="display:inline"
|
||||
id="g14158"
|
||||
transform="matrix(-1.4970318,0,0,1,1001.3916,213.03078)"><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-386.60983"
|
||||
height="4.0486217"
|
||||
width="10.985409"
|
||||
id="rect14160"
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none" /><rect
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none"
|
||||
id="rect14162"
|
||||
width="2.5253813"
|
||||
height="4.0486217"
|
||||
x="-383.45309"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /></g></g><g
|
||||
style="display:inline"
|
||||
transform="matrix(2.4017041,0,0,3.9408912,-788.51882,-1271.7817)"
|
||||
id="g14164"><rect
|
||||
y="365.75504"
|
||||
x="422.11606"
|
||||
height="5.0892859"
|
||||
width="6.5178571"
|
||||
id="rect14166"
|
||||
style="fill:#00440d;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect14168"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="428.58929"
|
||||
y="365.75504" /><rect
|
||||
y="365.75504"
|
||||
x="418.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect14170"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /></g><rect
|
||||
style="fill:#6a6a6a;fill-opacity:1;stroke:#000000;stroke-width:0.69999999;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="rect14172"
|
||||
width="18.524187"
|
||||
height="28.45186"
|
||||
x="174.85481"
|
||||
y="44.491241" /><g
|
||||
style="display:inline"
|
||||
id="g14192"
|
||||
transform="translate(-342.57061,-300.15766)"><rect
|
||||
style="fill:#312d29;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect14194"
|
||||
width="6.5178571"
|
||||
height="5.0892859"
|
||||
x="422.11606"
|
||||
y="365.75504" /><rect
|
||||
y="365.75504"
|
||||
x="428.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect14196"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect14198"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="418.58929"
|
||||
y="365.75504" /></g><g
|
||||
style="display:inline"
|
||||
id="g14200"
|
||||
transform="matrix(0,0.63857044,-0.6183842,0,527.83252,-72.180508)"><g
|
||||
transform="matrix(0,1.4970318,-1,0,852.39835,-33.0226)"
|
||||
id="g14202"
|
||||
style="display:inline"><rect
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none"
|
||||
id="rect14204"
|
||||
width="10.985409"
|
||||
height="4.0486217"
|
||||
x="-386.60983"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-383.45309"
|
||||
height="4.0486217"
|
||||
width="2.5253813"
|
||||
id="rect14206"
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none" /></g><g
|
||||
id="g14208"
|
||||
transform="matrix(0,1.4970318,-1,0,852.39835,-23.0226)"
|
||||
style="display:inline"><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-386.60983"
|
||||
height="4.0486217"
|
||||
width="10.985409"
|
||||
id="rect14210"
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none" /><rect
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none"
|
||||
id="rect14212"
|
||||
width="2.5253813"
|
||||
height="4.0486217"
|
||||
x="-383.45309"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /></g><g
|
||||
transform="matrix(0,1.4970318,-1,0,852.39835,-13.0226)"
|
||||
id="g14214"
|
||||
style="display:inline"><rect
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none"
|
||||
id="rect14216"
|
||||
width="10.985409"
|
||||
height="4.0486217"
|
||||
x="-386.60983"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-383.45309"
|
||||
height="4.0486217"
|
||||
width="2.5253813"
|
||||
id="rect14218"
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none" /></g><g
|
||||
id="g14220"
|
||||
transform="matrix(0,1.4970318,1,0,46.519992,-13.0226)"
|
||||
style="display:inline"><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-386.60983"
|
||||
height="4.0486217"
|
||||
width="10.985409"
|
||||
id="rect14222"
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none" /><rect
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none"
|
||||
id="rect14224"
|
||||
width="2.5253813"
|
||||
height="4.0486217"
|
||||
x="-383.45309"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /></g><g
|
||||
transform="matrix(0,1.4970318,1,0,46.519992,-33.0226)"
|
||||
id="g14226"
|
||||
style="display:inline"><rect
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none"
|
||||
id="rect14228"
|
||||
width="10.985409"
|
||||
height="4.0486217"
|
||||
x="-386.60983"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-383.45309"
|
||||
height="4.0486217"
|
||||
width="2.5253813"
|
||||
id="rect14230"
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none" /></g><g
|
||||
style="display:inline"
|
||||
transform="matrix(0,1.4970318,1,0,46.519992,-22.679788)"
|
||||
id="g14240"><rect
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none"
|
||||
id="rect14242"
|
||||
width="10.985409"
|
||||
height="4.0486217"
|
||||
x="-386.60983"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-383.45309"
|
||||
height="4.0486217"
|
||||
width="2.5253813"
|
||||
id="rect14244"
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none" /></g><g
|
||||
style="display:inline"
|
||||
transform="matrix(0,1.4970318,1,0,46.519992,-3.365413)"
|
||||
id="g14246"><rect
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none"
|
||||
id="rect14248"
|
||||
width="10.985409"
|
||||
height="4.0486217"
|
||||
x="-386.60983"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-383.45309"
|
||||
height="4.0486217"
|
||||
width="2.5253813"
|
||||
id="rect14250"
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none" /></g><g
|
||||
style="display:inline"
|
||||
id="g14252"
|
||||
transform="matrix(0,1.4970318,-1,0,852.39835,-3.365413)"><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-386.60983"
|
||||
height="4.0486217"
|
||||
width="10.985409"
|
||||
id="rect14254"
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none" /><rect
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none"
|
||||
id="rect14256"
|
||||
width="2.5253813"
|
||||
height="4.0486217"
|
||||
x="-383.45309"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /></g><rect
|
||||
ry="1.9272836"
|
||||
y="590.15265"
|
||||
x="432.12994"
|
||||
height="40.883862"
|
||||
width="34.998043"
|
||||
id="rect14232"
|
||||
style="fill:#6a6a6a;fill-opacity:1;stroke:#000000;stroke-width:1.59135258;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /></g></g></g></svg>
|
After Width: | Height: | Size: 139 KiB |
@ -89,8 +89,6 @@ void ConnectionManager::init()
|
||||
// new connection object from plugins
|
||||
QObject::connect(ExtensionSystem::PluginManager::instance(), SIGNAL(objectAdded(QObject *)), this, SLOT(objectAdded(QObject *)));
|
||||
QObject::connect(ExtensionSystem::PluginManager::instance(), SIGNAL(aboutToRemoveObject(QObject *)), this, SLOT(aboutToRemoveObject(QObject *)));
|
||||
|
||||
ccWarningClosed = true;
|
||||
}
|
||||
|
||||
|
||||
@ -437,23 +435,16 @@ void ConnectionManager::devChanged(IConnection *connection)
|
||||
}
|
||||
// clear device list combobox
|
||||
m_availableDevList->clear();
|
||||
ccFound = false;
|
||||
|
||||
// remove registered devices of this IConnection from the list
|
||||
updateConnectionList(connection);
|
||||
|
||||
updateConnectionDropdown();
|
||||
|
||||
if (ccFound && ccWarningClosed) {
|
||||
ccWarningClosed = false;
|
||||
QMessageBox::information(this, tr("CopterControl Not Supported"),
|
||||
tr("This version of OpenPilot GCS does not support CC and CC3D boards.\n\nPlease use OpenPilot GCS version 15.02.xx instead"));
|
||||
ccWarningClosed = true;
|
||||
}
|
||||
|
||||
qDebug() << "# devices " << m_devList.count();
|
||||
emit availableDevicesChanged(m_devList);
|
||||
|
||||
|
||||
// disable connection button if the liNameif (m_availableDevList->count() > 0)
|
||||
if (m_availableDevList->count() > 0) {
|
||||
m_connectBtn->setEnabled(true);
|
||||
@ -466,21 +457,17 @@ void ConnectionManager::updateConnectionDropdown()
|
||||
{
|
||||
// add all the list again to the combobox
|
||||
foreach(DevListItem d, m_devList) {
|
||||
if (!d.getConName().contains("CopterControl")) {
|
||||
m_availableDevList->addItem(d.getConName());
|
||||
m_availableDevList->setItemData(m_availableDevList->count() - 1, d.getConName(), Qt::ToolTipRole);
|
||||
if (!m_ioDev && d.getConName().startsWith("USB")) {
|
||||
if (m_mainWindow->generalSettings()->autoConnect() || m_mainWindow->generalSettings()->autoSelect()) {
|
||||
m_availableDevList->setCurrentIndex(m_availableDevList->count() - 1);
|
||||
}
|
||||
if (m_mainWindow->generalSettings()->autoConnect() && polling) {
|
||||
qDebug() << "Automatically opening device";
|
||||
connectDevice(d);
|
||||
qDebug() << "ConnectionManager::updateConnectionDropdown autoconnected USB device";
|
||||
}
|
||||
m_availableDevList->addItem(d.getConName());
|
||||
m_availableDevList->setItemData(m_availableDevList->count() - 1, d.getConName(), Qt::ToolTipRole);
|
||||
if (!m_ioDev && d.getConName().startsWith("USB")) {
|
||||
if (m_mainWindow->generalSettings()->autoConnect() || m_mainWindow->generalSettings()->autoSelect()) {
|
||||
m_availableDevList->setCurrentIndex(m_availableDevList->count() - 1);
|
||||
}
|
||||
if (m_mainWindow->generalSettings()->autoConnect() && polling) {
|
||||
qDebug() << "Automatically opening device";
|
||||
connectDevice(d);
|
||||
qDebug() << "ConnectionManager::updateConnectionDropdown autoconnected USB device";
|
||||
}
|
||||
} else {
|
||||
ccFound = true;
|
||||
}
|
||||
}
|
||||
if (m_ioDev) {
|
||||
|
@ -38,7 +38,6 @@
|
||||
#include <QtCore/QLinkedList>
|
||||
#include <QPushButton>
|
||||
#include <QComboBox>
|
||||
#include <QMessageBox>
|
||||
|
||||
#include "core_global.h"
|
||||
#include <QTimer>
|
||||
@ -150,8 +149,6 @@ protected:
|
||||
private:
|
||||
bool connectDevice();
|
||||
bool polling;
|
||||
bool ccFound;
|
||||
bool ccWarningClosed;
|
||||
Internal::MainWindow *m_mainWindow;
|
||||
QList <IConnection *> connectionBackup;
|
||||
QTimer *reconnect;
|
||||
|
@ -135,9 +135,10 @@ public:
|
||||
};
|
||||
|
||||
enum USBConstants {
|
||||
idVendor_OpenPilot = 0x20a0,
|
||||
idProduct_OpenPilot = 0x415a,
|
||||
idProduct_OPLinkMini = 0x415c
|
||||
idVendor_OpenPilot = 0x20a0,
|
||||
idProduct_OpenPilot = 0x415a,
|
||||
idProduct_CopterControl = 0x415b,
|
||||
idProduct_OPLinkMini = 0x415c
|
||||
};
|
||||
|
||||
static USBMonitor *instance();
|
||||
|
@ -81,6 +81,10 @@ void ConnectionDiagram::setupGraphicsScene()
|
||||
QList<QString> elementsToShow;
|
||||
|
||||
switch (m_configSource->getControllerType()) {
|
||||
case VehicleConfigurationSource::CONTROLLER_CC:
|
||||
case VehicleConfigurationSource::CONTROLLER_CC3D:
|
||||
elementsToShow << "controller-cc";
|
||||
break;
|
||||
case VehicleConfigurationSource::CONTROLLER_REVO:
|
||||
elementsToShow << "controller-revo";
|
||||
break;
|
||||
@ -160,6 +164,14 @@ void ConnectionDiagram::setupGraphicsScene()
|
||||
QString prefix = "";
|
||||
QString suffix = "";
|
||||
switch (m_configSource->getControllerType()) {
|
||||
case VehicleConfigurationSource::CONTROLLER_CC:
|
||||
case VehicleConfigurationSource::CONTROLLER_CC3D:
|
||||
prefix = "cc-";
|
||||
if (m_configSource->getEscType() == VehicleConfigurationSource::ESC_ONESHOT ||
|
||||
m_configSource->getEscType() == VehicleConfigurationSource::ESC_SYNCHED) {
|
||||
suffix = "-oneshot";
|
||||
}
|
||||
break;
|
||||
case VehicleConfigurationSource::CONTROLLER_REVO:
|
||||
prefix = "revo-";
|
||||
break;
|
||||
|
@ -80,6 +80,9 @@ bool ControllerPage::isComplete() const
|
||||
bool ControllerPage::validatePage()
|
||||
{
|
||||
getWizard()->setControllerType((SetupWizard::CONTROLLER_TYPE)ui->boardTypeCombo->itemData(ui->boardTypeCombo->currentIndex()).toInt());
|
||||
if (getWizard()->getControllerType() == SetupWizard::CONTROLLER_CC || getWizard()->getControllerType() == SetupWizard::CONTROLLER_CC3D) {
|
||||
getWizard()->setGpsType(SetupWizard::GPS_DISABLED);
|
||||
}
|
||||
return true;
|
||||
}
|
||||
|
||||
@ -98,6 +101,12 @@ SetupWizard::CONTROLLER_TYPE ControllerPage::getControllerType()
|
||||
case 0x0301:
|
||||
return SetupWizard::CONTROLLER_OPLINK;
|
||||
|
||||
case 0x0401:
|
||||
return SetupWizard::CONTROLLER_CC;
|
||||
|
||||
case 0x0402:
|
||||
return SetupWizard::CONTROLLER_CC3D;
|
||||
|
||||
case 0x0903:
|
||||
return SetupWizard::CONTROLLER_REVO;
|
||||
|
||||
@ -123,6 +132,8 @@ void ControllerPage::setupBoardTypes()
|
||||
QVariant v(0);
|
||||
|
||||
ui->boardTypeCombo->addItem(tr("<Unknown>"), SetupWizard::CONTROLLER_UNKNOWN);
|
||||
ui->boardTypeCombo->addItem(tr("OpenPilot CopterControl"), SetupWizard::CONTROLLER_CC);
|
||||
ui->boardTypeCombo->addItem(tr("OpenPilot CopterControl 3D"), SetupWizard::CONTROLLER_CC3D);
|
||||
ui->boardTypeCombo->addItem(tr("OpenPilot Revolution"), SetupWizard::CONTROLLER_REVO);
|
||||
ui->boardTypeCombo->addItem(tr("OpenPilot OPLink Radio Modem"), SetupWizard::CONTROLLER_OPLINK);
|
||||
ui->boardTypeCombo->addItem(tr("OpenPilot DiscoveryF4"), SetupWizard::CONTROLLER_DISCOVERYF4);
|
||||
|
@ -77,9 +77,10 @@ bool EscPage::isSynchOrOneShotAvailable()
|
||||
|
||||
switch (getWizard()->getControllerType()) {
|
||||
case SetupWizard::CONTROLLER_NANO:
|
||||
case SetupWizard::CONTROLLER_CC:
|
||||
case SetupWizard::CONTROLLER_CC3D:
|
||||
available = getWizard()->getInputType() != SetupWizard::INPUT_PWM;
|
||||
break;
|
||||
|
||||
default:
|
||||
break;
|
||||
}
|
||||
|
@ -74,6 +74,27 @@ bool InputPage::restartNeeded(VehicleConfigurationSource::INPUT_TYPE selectedTyp
|
||||
HwSettings *hwSettings = HwSettings::GetInstance(uavoManager);
|
||||
HwSettings::DataFields data = hwSettings->getData();
|
||||
switch (getWizard()->getControllerType()) {
|
||||
case SetupWizard::CONTROLLER_CC:
|
||||
case SetupWizard::CONTROLLER_CC3D:
|
||||
{
|
||||
switch (selectedType) {
|
||||
case VehicleConfigurationSource::INPUT_PWM:
|
||||
return data.CC_RcvrPort != HwSettings::CC_RCVRPORT_PWMNOONESHOT;
|
||||
|
||||
case VehicleConfigurationSource::INPUT_PPM:
|
||||
return data.CC_RcvrPort != HwSettings::CC_RCVRPORT_PPMNOONESHOT;
|
||||
|
||||
case VehicleConfigurationSource::INPUT_SBUS:
|
||||
return data.CC_MainPort != HwSettings::CC_MAINPORT_SBUS;
|
||||
|
||||
case VehicleConfigurationSource::INPUT_DSM:
|
||||
// TODO: Handle all of the DSM types ?? Which is most common?
|
||||
return data.CC_MainPort != HwSettings::CC_MAINPORT_DSM;
|
||||
|
||||
default: return true;
|
||||
}
|
||||
break;
|
||||
}
|
||||
case SetupWizard::CONTROLLER_REVO:
|
||||
case SetupWizard::CONTROLLER_DISCOVERYF4:
|
||||
case SetupWizard::CONTROLLER_NANO:
|
||||
|
@ -30,13 +30,13 @@
|
||||
inkscape:window-height="928"
|
||||
id="namedview4616"
|
||||
showgrid="false"
|
||||
inkscape:zoom="1.1114784"
|
||||
inkscape:cx="996.21691"
|
||||
inkscape:cy="488.50335"
|
||||
inkscape:zoom="3.1437357"
|
||||
inkscape:cx="491.77294"
|
||||
inkscape:cy="464.53459"
|
||||
inkscape:window-x="0"
|
||||
inkscape:window-y="27"
|
||||
inkscape:window-maximized="1"
|
||||
inkscape:current-layer="1234"
|
||||
inkscape:current-layer="layer51"
|
||||
fit-margin-top="15"
|
||||
fit-margin-left="15"
|
||||
fit-margin-right="15"
|
||||
@ -17771,6 +17771,46 @@
|
||||
y1="1450"
|
||||
x2="1490"
|
||||
y2="1450" />
|
||||
<linearGradient
|
||||
inkscape:collect="always"
|
||||
xlink:href="#linearGradient6587-8-2"
|
||||
id="linearGradient38671"
|
||||
gradientUnits="userSpaceOnUse"
|
||||
gradientTransform="translate(-240,-90)"
|
||||
x1="1250"
|
||||
y1="1450"
|
||||
x2="1490"
|
||||
y2="1450" />
|
||||
<linearGradient
|
||||
inkscape:collect="always"
|
||||
xlink:href="#linearGradient6587-8-2-7"
|
||||
id="linearGradient38759"
|
||||
gradientUnits="userSpaceOnUse"
|
||||
gradientTransform="translate(-151.00134,-881.62884)"
|
||||
x1="1250"
|
||||
y1="1450"
|
||||
x2="1490"
|
||||
y2="1450" />
|
||||
<linearGradient
|
||||
inkscape:collect="always"
|
||||
xlink:href="#linearGradient6587-9"
|
||||
id="linearGradient38819"
|
||||
gradientUnits="userSpaceOnUse"
|
||||
gradientTransform="translate(225,-95)"
|
||||
x1="1250"
|
||||
y1="1450"
|
||||
x2="1490"
|
||||
y2="1450" />
|
||||
<linearGradient
|
||||
inkscape:collect="always"
|
||||
xlink:href="#linearGradient6595-2-8-7-7"
|
||||
id="linearGradient39211"
|
||||
gradientUnits="userSpaceOnUse"
|
||||
gradientTransform="matrix(0.4,0,0,0.4,-14.566438,-107.34458)"
|
||||
x1="401"
|
||||
y1="1060"
|
||||
x2="843"
|
||||
y2="669" />
|
||||
</defs>
|
||||
<metadata
|
||||
id="metadata12656">
|
||||
@ -17810,15 +17850,563 @@
|
||||
transform="translate(-32.46875,315.85439)">
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="layer16"
|
||||
inkscape:label="revo-srxl"
|
||||
id="layer52"
|
||||
inkscape:label="cc-pwm"
|
||||
style="display:none"
|
||||
sodipodi:insensitive="true">
|
||||
<g
|
||||
style="display:inline"
|
||||
id="cc-pwm"
|
||||
transform="translate(0.99999976,-1.9999999)">
|
||||
<path
|
||||
id="path8856-1-8-4"
|
||||
d="m 309.08544,189.42619 l 121.38331,-0.484"
|
||||
inkscape:connector-curvature="0"
|
||||
style="display:inline;fill:none;stroke:#ec1d00;stroke-width:5.61390018;stroke-linecap:butt;stroke-linejoin:miter"
|
||||
sodipodi:nodetypes="cc" />
|
||||
<path
|
||||
id="path8856-1-5-8-4"
|
||||
d="m 309.08544,183.82619 l 121.38331,-0.2056"
|
||||
inkscape:connector-curvature="0"
|
||||
style="display:inline;fill:none;stroke:#000000;stroke-width:5.61390018;stroke-linecap:butt;stroke-linejoin:miter"
|
||||
sodipodi:nodetypes="cc" />
|
||||
<path
|
||||
id="path8856-1-3-1-3"
|
||||
d="m 309.08544,195.62619 l 121.38331,-0.412"
|
||||
inkscape:connector-curvature="0"
|
||||
style="display:inline;fill:none;stroke:#ffffff;stroke-width:5.17476749;stroke-linecap:butt;stroke-linejoin:miter"
|
||||
sodipodi:nodetypes="cc" />
|
||||
<path
|
||||
sodipodi:nodetypes="cccc"
|
||||
style="fill:none;stroke:#1f4697;stroke-width:5.61390018;stroke-linecap:butt;stroke-linejoin:round"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 303.76407,219.75113 l 75.17593,-0.0948 l 0,-16.06759 l 51.4,-0.1488"
|
||||
id="path8856-5" />
|
||||
<path
|
||||
sodipodi:nodetypes="cccc"
|
||||
style="fill:none;stroke:#fac204;stroke-width:5.61399984;stroke-linecap:butt;stroke-linejoin:round;stroke-miterlimit:4;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 303.76407,244.51434 l 84.7,0 l -0.3,-33 l 42.4,0"
|
||||
id="path8856-5-1" />
|
||||
<path
|
||||
sodipodi:nodetypes="cccc"
|
||||
style="fill:none;stroke:#32a304;stroke-width:5.61399984;stroke-linecap:butt;stroke-linejoin:round;stroke-miterlimit:4;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 303.76407,271.55113 l 92.03993,0.0311 l 4.7e-4,-52.06489 l 34.6,-0.006"
|
||||
id="path8856-5-1-7" />
|
||||
<path
|
||||
sodipodi:nodetypes="cccc"
|
||||
style="fill:none;stroke:#ec6004;stroke-width:5.61390018;stroke-linecap:butt;stroke-linejoin:round"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 320.88407,294.27993 l 82.39993,-0.2524 l 0,-67.51319 l 27.43487,0"
|
||||
id="path8856-5-1-7-1" />
|
||||
<path
|
||||
style="display:inline;fill:none;stroke:#777777;stroke-width:5.80000019;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="M 131.51628,280.89645 C 99.179438,276.41438 56.116118,293.77498 44.942858,345.61434"
|
||||
id="path9857-3-9" />
|
||||
<path
|
||||
style="display:inline;fill:none;stroke:#6b6b6b;stroke-width:1.21428466;stroke-linecap:butt;stroke-linejoin:miter"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 309.08544,198.82619 l 121.38331,-0.278"
|
||||
id="path8856-4-4"
|
||||
sodipodi:nodetypes="cc" />
|
||||
<path
|
||||
sodipodi:nodetypes="sssccccssssss"
|
||||
inkscape:connector-curvature="0"
|
||||
id="rect8853-0-8"
|
||||
d="m 136.31357,163.05542 l 187.03999,0 c 3.58992,0 6.48,2.89008 6.48,6.48 l 0,8.84015 l -6,0 l 0,122.36001 l 6.00044,0 l -4.4e-4,10.23984 c -1.5e-4,3.58992 -2.89008,6.48 -6.48,6.48 l -187.03999,0 c -3.58993,0 -6.48001,-2.89008 -6.48001,-6.48 l 0,-141.44 c 0,-3.58992 2.89008,-6.48 6.48001,-6.48 z"
|
||||
style="color:#000000;display:inline;fill:url(#linearGradient39211);fill-rule:nonzero;stroke:#000000;stroke-width:3.09599996;stroke-miterlimit:4;stroke-dasharray:none;enable-background:accumulate" />
|
||||
<g
|
||||
style="font-style:normal;font-variant:normal;font-weight:bold;font-stretch:normal;font-size:22.39999962px;line-height:125%;font-family:Sans;text-align:start;letter-spacing:0px;word-spacing:0px;writing-mode:lr-tb;text-anchor:start;fill:#ffffff"
|
||||
id="text9734"
|
||||
transform="translate(0,31)">
|
||||
<path
|
||||
d="m 218.29909,148.86051 l 15.05,0 l 0,3.18282 l -5.41407,0 l 0,13.14687 l -4.21093,0 l 0,-13.14687 l -5.425,0 l 0,-3.18282"
|
||||
id="path13625"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
d="m 247.65534,157.73083 l 0,7.45937 l -3.9375,0 l 0,-1.21406 l 0,-4.47344 c -1e-5,-1.07187 -0.0255,-1.80832 -0.0766,-2.20937 c -0.0438,-0.40104 -0.12397,-0.69635 -0.24063,-0.88594 c -0.15313,-0.2552 -0.36095,-0.45208 -0.62344,-0.59063 c -0.26251,-0.14582 -0.56146,-0.21874 -0.89687,-0.21875 c -0.81668,1e-5 -1.45834,0.3172 -1.925,0.95157 c -0.46668,0.62709 -0.70001,1.49844 -0.7,2.61406 l 0,6.02656 l -3.91563,0 l 0,-17.01875 l 3.91563,0 l 0,6.5625 c 0.59062,-0.71457 1.2177,-1.23957 1.88125,-1.575 c 0.66353,-0.34269 1.39634,-0.51405 2.19844,-0.51406 c 1.41457,1e-5 2.48644,0.43386 3.21562,1.30156 c 0.73644,0.86772 1.10467,2.12918 1.10469,3.78438"
|
||||
id="path13627"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
d="m 260.40846,156.27614 c -0.34272,-0.16041 -0.68543,-0.27708 -1.02812,-0.35 c -0.33543,-0.0802 -0.67449,-0.1203 -1.01719,-0.12031 c -1.00626,1e-5 -1.78282,0.32448 -2.32969,0.97343 c -0.53959,0.64168 -0.80938,1.56407 -0.80937,2.76719 l 0,5.64375 l -3.91563,0 l 0,-12.25 l 3.91563,0 l 0,2.0125 c 0.50312,-0.80207 1.07916,-1.3854 1.72812,-1.75 c 0.65624,-0.37186 1.4401,-0.5578 2.35156,-0.55781 c 0.13124,1e-5 0.27343,0.007 0.42657,0.0219 c 0.15311,0.007 0.37551,0.0292 0.66718,0.0656 l 0.0109,3.54375"
|
||||
id="path13629"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
d="m 268.2069,155.44489 c -0.86771,1e-5 -1.53125,0.31355 -1.99062,0.94062 c -0.45209,0.6198 -0.67813,1.51668 -0.67813,2.69063 c 0,1.17396 0.22604,2.07448 0.67813,2.70156 c 0.45937,0.6198 1.12291,0.92969 1.99062,0.92969 c 0.85312,0 1.50572,-0.30989 1.95781,-0.92969 c 0.45208,-0.62708 0.67812,-1.5276 0.67813,-2.70156 c -1e-5,-1.17395 -0.22605,-2.07083 -0.67813,-2.69063 c -0.45209,-0.62707 -1.10469,-0.94061 -1.95781,-0.94062 m 0,-2.8 c 2.10728,1e-5 3.75155,0.56876 4.93281,1.70625 c 1.18853,1.13751 1.7828,2.71251 1.78282,4.725 c -2e-5,2.0125 -0.59429,3.5875 -1.78282,4.725 c -1.18126,1.1375 -2.82553,1.70625 -4.93281,1.70625 c -2.11459,0 -3.76979,-0.56875 -4.96562,-1.70625 c -1.18855,-1.1375 -1.78282,-2.7125 -1.78282,-4.725 c 0,-2.01249 0.59427,-3.58749 1.78282,-4.725 c 1.19583,-1.13749 2.85103,-1.70624 4.96562,-1.70625"
|
||||
id="path13631"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
d="m 282.05377,149.46208 l 0,3.47812 l 4.03594,0 l 0,2.8 l -4.03594,0 l 0,5.19531 c 0,0.56876 0.11302,0.95521 0.33907,1.15938 c 0.22603,0.19688 0.67447,0.29531 1.34531,0.29531 l 2.0125,0 l 0,2.8 l -3.35781,0 c -1.54584,0 -2.64324,-0.32083 -3.29219,-0.9625 c -0.64167,-0.64896 -0.9625,-1.74635 -0.9625,-3.29219 l 0,-5.19531 l -1.94688,0 l 0,-2.8 l 1.94688,0 l 0,-3.47812 l 3.91562,0"
|
||||
id="path13633"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
d="m 292.77253,149.46208 l 0,3.47812 l 4.03594,0 l 0,2.8 l -4.03594,0 l 0,5.19531 c -1e-5,0.56876 0.11301,0.95521 0.33906,1.15938 c 0.22604,0.19688 0.67447,0.29531 1.34531,0.29531 l 2.0125,0 l 0,2.8 l -3.35781,0 c -1.54584,0 -2.64323,-0.32083 -3.29219,-0.9625 c -0.64167,-0.64896 -0.9625,-1.74635 -0.9625,-3.29219 l 0,-5.19531 l -1.94687,0 l 0,-2.8 l 1.94687,0 l 0,-3.47812 l 3.91563,0"
|
||||
id="path13635"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
d="m 299.21472,148.17145 l 3.91562,0 l 0,17.01875 l -3.91562,0 l 0,-17.01875"
|
||||
id="path13637"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
d="m 319.14284,159.03239 l 0,1.11562 l -9.15469,0 c 0.0948,0.91876 0.42656,1.60782 0.99531,2.06719 c 0.56875,0.45938 1.36354,0.68907 2.38438,0.68906 c 0.82395,1e-5 1.66613,-0.12031 2.52656,-0.36093 c 0.8677,-0.24792 1.75728,-0.61979 2.66875,-1.11563 l 0,3.01875 c -0.92605,0.35 -1.8521,0.6125 -2.77813,0.7875 c -0.92605,0.18229 -1.85209,0.27344 -2.77812,0.27344 c -2.21667,0 -3.94115,-0.56146 -5.17344,-1.68438 c -1.225,-1.1302 -1.8375,-2.71249 -1.8375,-4.74687 c 0,-1.99791 0.60156,-3.56926 1.80469,-4.71406 c 1.21041,-1.14478 2.87291,-1.71718 4.9875,-1.71719 c 1.92499,1e-5 3.46353,0.5797 4.61562,1.73906 c 1.15937,1.15939 1.73905,2.70886 1.73907,4.64844 m -4.025,-1.30156 c -10e-6,-0.74375 -0.21876,-1.34166 -0.65625,-1.79375 c -0.43022,-0.45937 -0.99532,-0.68906 -1.69532,-0.68907 c -0.75834,1e-5 -1.37448,0.21512 -1.84843,0.64532 c -0.47397,0.42292 -0.76928,1.03542 -0.88594,1.8375 l 5.08594,0"
|
||||
id="path13639"
|
||||
inkscape:connector-curvature="0" />
|
||||
</g>
|
||||
<g
|
||||
style="font-style:normal;font-variant:normal;font-weight:bold;font-stretch:normal;font-size:22.39999962px;line-height:125%;font-family:Sans;text-align:start;letter-spacing:0px;word-spacing:0px;writing-mode:lr-tb;text-anchor:start;fill:#488eff"
|
||||
id="text9734-2"
|
||||
transform="translate(0,31)">
|
||||
<path
|
||||
d="m 276.62875,182.50113 c 0.88229,1e-5 1.51301,-0.16405 1.89219,-0.49219 c 0.38645,-0.32811 0.57968,-0.86769 0.57969,-1.61875 c -1e-5,-0.74373 -0.19324,-1.27602 -0.57969,-1.59687 c -0.37918,-0.32082 -1.0099,-0.48124 -1.89219,-0.48125 l -1.77187,0 l 0,4.18906 l 1.77187,0 m -1.77187,2.90938 l 0,6.17968 l -4.21094,0 l 0,-16.32968 l 6.43125,0 c 2.15103,1e-5 3.72603,0.36095 4.725,1.08281 c 1.00624,0.72189 1.50936,1.86303 1.50938,3.42344 c -2e-5,1.07917 -0.26252,1.96511 -0.7875,2.65781 c -0.51773,0.69272 -1.30158,1.20313 -2.35157,1.53125 c 0.57603,0.13126 1.09009,0.43022 1.54219,0.89687 c 0.45936,0.45939 0.92238,1.15939 1.38906,2.1 l 2.28594,4.6375 l -4.48437,0 l -1.99063,-4.05781 c -0.40105,-0.81666 -0.80938,-1.37447 -1.225,-1.67344 c -0.40834,-0.29895 -0.95522,-0.44843 -1.64062,-0.44843 l -1.19219,0"
|
||||
id="path13616"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
d="m 293.53813,181.84488 c -0.86772,1e-5 -1.53126,0.31355 -1.99063,0.94063 c -0.45209,0.6198 -0.67813,1.51667 -0.67812,2.69062 c -10e-6,1.17397 0.22603,2.07449 0.67812,2.70156 c 0.45937,0.6198 1.12291,0.92969 1.99063,0.92969 c 0.85311,0 1.50572,-0.30989 1.95781,-0.92969 c 0.45207,-0.62707 0.67811,-1.52759 0.67813,-2.70156 c -2e-5,-1.17395 -0.22606,-2.07082 -0.67813,-2.69062 c -0.45209,-0.62708 -1.1047,-0.94062 -1.95781,-0.94063 m 0,-2.8 c 2.10728,1e-5 3.75155,0.56876 4.93281,1.70625 c 1.18853,1.13751 1.7828,2.71251 1.78281,4.725 c -1e-5,2.01251 -0.59428,3.5875 -1.78281,4.725 c -1.18126,1.1375 -2.82553,1.70625 -4.93281,1.70625 c -2.11459,0 -3.7698,-0.56875 -4.96563,-1.70625 c -1.18854,-1.1375 -1.78281,-2.71249 -1.78281,-4.725 c 0,-2.01249 0.59427,-3.58749 1.78281,-4.725 c 1.19583,-1.13749 2.85104,-1.70624 4.96563,-1.70625"
|
||||
id="path13618"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
d="m 303.10844,174.57144 l 3.91562,0 l 0,17.01875 l -3.91562,0 l 0,-17.01875"
|
||||
id="path13620"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
d="m 310.80844,174.57144 l 3.91562,0 l 0,17.01875 l -3.91562,0 l 0,-17.01875"
|
||||
id="path13622"
|
||||
inkscape:connector-curvature="0" />
|
||||
</g>
|
||||
<g
|
||||
style="font-style:normal;font-variant:normal;font-weight:bold;font-stretch:normal;font-size:22.39999962px;line-height:125%;font-family:Sans;text-align:start;letter-spacing:0px;word-spacing:0px;writing-mode:lr-tb;text-anchor:start;fill:#ffdc00"
|
||||
id="text9734-2-6"
|
||||
transform="translate(0,31)">
|
||||
<path
|
||||
d="m 259.44596,202.46052 l 6.98906,0 c 2.07812,2e-5 3.67134,0.46304 4.77969,1.38906 c 1.11561,0.91877 1.67342,2.23126 1.67344,3.9375 c -2e-5,1.71355 -0.55783,3.03334 -1.67344,3.95938 c -1.10835,0.91875 -2.70157,1.37813 -4.77969,1.37812 l -2.77812,0 l 0,5.66563 l -4.21094,0 l 0,-16.32969 m 4.21094,3.05156 l 0,4.56094 l 2.32968,0 c 0.81666,10e-6 1.44739,-0.19687 1.89219,-0.59063 c 0.44478,-0.40103 0.66718,-0.96613 0.66719,-1.69531 c -10e-6,-0.72915 -0.22241,-1.29061 -0.66719,-1.68437 c -0.4448,-0.39374 -1.07553,-0.59061 -1.89219,-0.59063 l -2.32968,0"
|
||||
id="path13605"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
d="m 275.67721,206.54021 l 3.91562,0 l 0,12.25 l -3.91562,0 l 0,-12.25 m 0,-4.76875 l 3.91562,0 l 0,3.19375 l -3.91562,0 l 0,-3.19375"
|
||||
id="path13607"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
d="m 287.65377,203.06208 l 0,3.47813 l 4.03594,0 l 0,2.8 l -4.03594,0 l 0,5.19531 c 0,0.56875 0.11302,0.95521 0.33907,1.15937 c 0.22603,0.19688 0.67447,0.29532 1.34531,0.29532 l 2.0125,0 l 0,2.8 l -3.35781,0 c -1.54584,0 -2.64324,-0.32084 -3.29219,-0.9625 c -0.64167,-0.64896 -0.9625,-1.74635 -0.9625,-3.29219 l 0,-5.19531 l -1.94688,0 l 0,-2.8 l 1.94688,0 l 0,-3.47813 l 3.91562,0"
|
||||
id="path13609"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
d="m 303.9944,206.92302 l 0,3.19375 c -0.53231,-0.36457 -1.06824,-0.63437 -1.60781,-0.80938 c -0.53231,-0.17499 -1.08647,-0.26249 -1.6625,-0.2625 c -1.09376,1e-5 -1.94689,0.32085 -2.55938,0.9625 c -0.60521,0.63439 -0.90782,1.52397 -0.90781,2.66875 c -10e-6,1.1448 0.3026,2.03803 0.90781,2.67969 c 0.61249,0.63438 1.46562,0.95157 2.55938,0.95156 c 0.61249,1e-5 1.19217,-0.0911 1.73906,-0.27343 c 0.55415,-0.18229 1.06457,-0.45208 1.53125,-0.80938 l 0,3.20469 c -0.61251,0.22604 -1.23595,0.39375 -1.87031,0.50312 c -0.6271,0.11667 -1.25783,0.175 -1.89219,0.175 c -2.20938,0 -3.93751,-0.5651 -5.18438,-1.69531 c -1.24687,-1.1375 -1.87031,-2.71614 -1.87031,-4.73594 c 0,-2.01978 0.62344,-3.59478 1.87031,-4.725 c 1.24687,-1.13748 2.975,-1.70623 5.18438,-1.70625 c 0.64166,2e-5 1.27238,0.0583 1.89219,0.175 c 0.62707,0.10939 1.2505,0.2771 1.87031,0.50313"
|
||||
id="path13611"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
d="m 319.71158,211.33083 l 0,7.45938 l -3.9375,0 l 0,-1.21407 l 0,-4.47343 c -1e-5,-1.07187 -0.0255,-1.80833 -0.0766,-2.20938 c -0.0438,-0.40103 -0.12397,-0.69634 -0.24062,-0.88594 c -0.15314,-0.25519 -0.36095,-0.45207 -0.62344,-0.59062 c -0.26251,-0.14582 -0.56147,-0.21874 -0.89688,-0.21875 c -0.81667,10e-6 -1.45834,0.3172 -1.925,0.95156 c -0.46667,0.62709 -0.7,1.49845 -0.7,2.61406 l 0,6.02657 l -3.91562,0 l 0,-17.01875 l 3.91562,0 l 0,6.5625 c 0.59062,-0.71458 1.21771,-1.23957 1.88125,-1.575 c 0.66354,-0.3427 1.39635,-0.51405 2.19844,-0.51407 c 1.41457,2e-5 2.48645,0.43387 3.21563,1.30157 c 0.73644,0.86772 1.10467,2.12917 1.10468,3.78437"
|
||||
id="path13613"
|
||||
inkscape:connector-curvature="0" />
|
||||
</g>
|
||||
<g
|
||||
style="color:#000000;font-style:normal;font-variant:normal;font-weight:bold;font-stretch:normal;font-size:22.39999962px;line-height:125%;font-family:Sans;text-indent:0;text-align:start;text-decoration:none;text-decoration-line:none;letter-spacing:0px;word-spacing:0px;text-transform:none;direction:ltr;block-progression:tb;writing-mode:lr-tb;baseline-shift:baseline;text-anchor:start;fill:#73ff00;fill-rule:nonzero;enable-background:accumulate"
|
||||
id="text9734-2-6-4"
|
||||
transform="translate(0,31)">
|
||||
<path
|
||||
d="m 264.37094,228.86053 l 4.60469,0 l 3.71875,5.81875 l 3.71875,-5.81875 l 4.61562,0 l -6.22343,9.45 l 0,6.87969 l -4.21094,0 l 0,-6.87969 l -6.22344,-9.45"
|
||||
id="path13598"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
d="m 286.13657,239.67772 c -0.81668,0 -1.43282,0.13854 -1.84844,0.41562 c -0.40834,0.27709 -0.61251,0.68542 -0.6125,1.225 c -1e-5,0.49584 0.16406,0.88594 0.49219,1.17031 c 0.33541,0.27709 0.79843,0.41563 1.38906,0.41563 c 0.73645,0 1.35624,-0.2625 1.85937,-0.7875 c 0.50312,-0.53229 0.75468,-1.19583 0.75469,-1.99063 l 0,-0.44843 l -2.03437,0 m 5.98281,-1.47657 l 0,6.98907 l -3.94844,0 l 0,-1.81563 c -0.52501,0.74375 -1.11563,1.28698 -1.77187,1.62969 c -0.65626,0.33542 -1.4547,0.50312 -2.39532,0.50312 c -1.26875,0 -2.30052,-0.36823 -3.09531,-1.10468 c -0.7875,-0.74375 -1.18125,-1.70625 -1.18125,-2.8875 c 0,-1.43646 0.49219,-2.4901 1.47656,-3.16094 c 0.99167,-0.67083 2.54479,-1.00624 4.65938,-1.00625 l 2.30781,0 l 0,-0.30625 c -10e-6,-0.61978 -0.24428,-1.07187 -0.73281,-1.35625 c -0.48855,-0.29166 -1.25053,-0.43749 -2.28594,-0.4375 c -0.83855,1e-5 -1.61875,0.0839 -2.34062,0.25156 c -0.72188,0.16772 -1.39271,0.41928 -2.0125,0.75469 l 0,-2.98594 c 0.83854,-0.20415 1.68072,-0.35728 2.52656,-0.45937 c 0.84583,-0.10937 1.69166,-0.16405 2.5375,-0.16407 c 2.20936,2e-5 3.80259,0.43752 4.77969,1.3125 c 0.98436,0.86772 1.47655,2.2823 1.47656,4.24375"
|
||||
id="path13600"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
d="m 294.68969,232.94022 l 3.80625,0 l 2.05625,8.44375 l 2.06719,-8.44375 l 3.27031,0 l 2.05625,8.35625 l 2.06719,-8.35625 l 3.80625,0 l -3.22656,12.25 l -4.27657,0 l -2.06718,-8.42188 l -2.05625,8.42188 l -4.27657,0 l -3.22656,-12.25"
|
||||
id="path13602"
|
||||
inkscape:connector-curvature="0" />
|
||||
</g>
|
||||
<g
|
||||
style="color:#000000;font-style:normal;font-variant:normal;font-weight:bold;font-stretch:normal;font-size:22.39999962px;line-height:125%;font-family:Sans;text-indent:0;text-align:end;text-decoration:none;text-decoration-line:none;letter-spacing:0px;word-spacing:0px;text-transform:none;direction:ltr;block-progression:tb;writing-mode:lr-tb;baseline-shift:baseline;text-anchor:end;fill:#ff7e00;fill-rule:nonzero;enable-background:accumulate"
|
||||
id="text9734-2-6-4-2"
|
||||
transform="translate(0,31)">
|
||||
<path
|
||||
d="m 162.89598,252.86053 l 11.36406,0 l 0,3.18281 l -7.15312,0 l 0,3.04063 l 6.72656,0 l 0,3.18281 l -6.72656,0 l 0,6.92344 l -4.21094,0 l 0,-16.32969"
|
||||
id="path13577"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
d="m 178.03348,252.17147 l 3.91563,0 l 0,17.01875 l -3.91563,0 l 0,-17.01875"
|
||||
id="path13579"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
d="m 185.73348,256.94022 l 3.91563,0 l 0,12.25 l -3.91563,0 l 0,-12.25 m 0,-4.76875 l 3.91563,0 l 0,3.19375 l -3.91563,0 l 0,-3.19375"
|
||||
id="path13581"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
d="m 201.76785,267.11209 c -0.53959,0.71459 -1.13386,1.23959 -1.78281,1.575 c -0.64896,0.33542 -1.4,0.50313 -2.25312,0.50313 c -1.4948,0 -2.73074,-0.58698 -3.70782,-1.76094 c -0.97708,-1.18125 -1.46562,-2.68333 -1.46562,-4.50625 c 0,-1.8302 0.48854,-3.32864 1.46562,-4.49531 c 0.97708,-1.17395 2.21302,-1.76093 3.70782,-1.76094 c 0.85312,10e-6 1.60416,0.16772 2.25312,0.50312 c 0.64895,0.33543 1.24322,0.86408 1.78281,1.58594 l 0,-1.81562 l 3.9375,0 l 0,11.01406 c -1e-5,1.96875 -0.62345,3.47083 -1.87031,4.50625 c -1.23959,1.0427 -3.04063,1.56406 -5.40312,1.56406 c -0.76563,0 -1.50574,-0.0583 -2.22032,-0.175 c -0.71458,-0.11667 -1.43281,-0.29532 -2.15468,-0.53594 l 0,-3.05156 c 0.68541,0.39375 1.35624,0.68542 2.0125,0.875 c 0.65624,0.19687 1.31614,0.29531 1.97968,0.29531 c 1.28333,0 2.22395,-0.28073 2.82188,-0.84218 c 0.59791,-0.56146 0.89686,-1.44011 0.89687,-2.63594 l 0,-0.84219 m -2.58125,-7.62344 c -0.80938,10e-6 -1.44011,0.29897 -1.89218,0.89688 c -0.45209,0.59792 -0.67813,1.44376 -0.67813,2.5375 c 0,1.12292 0.21875,1.97604 0.65625,2.55937 c 0.4375,0.57605 1.07552,0.86407 1.91406,0.86407 c 0.81666,0 1.45104,-0.29896 1.90313,-0.89688 c 0.45207,-0.59791 0.67811,-1.4401 0.67812,-2.52656 c -1e-5,-1.09374 -0.22605,-1.93958 -0.67812,-2.5375 c -0.45209,-0.59791 -1.08647,-0.89687 -1.90313,-0.89688"
|
||||
id="path13583"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
d="m 221.80535,261.73084 l 0,7.45938 l -3.9375,0 l 0,-1.21407 l 0,-4.47343 c -1e-5,-1.07187 -0.0255,-1.80833 -0.0766,-2.20938 c -0.0438,-0.40103 -0.12397,-0.69634 -0.24062,-0.88594 c -0.15314,-0.2552 -0.36095,-0.45207 -0.62344,-0.59062 c -0.26251,-0.14583 -0.56147,-0.21874 -0.89688,-0.21875 c -0.81667,1e-5 -1.45834,0.3172 -1.925,0.95156 c -0.46667,0.62709 -0.7,1.49845 -0.7,2.61406 l 0,6.02657 l -3.91562,0 l 0,-17.01875 l 3.91562,0 l 0,6.5625 c 0.59062,-0.71458 1.21771,-1.23958 1.88125,-1.575 c 0.66354,-0.3427 1.39635,-0.51405 2.19844,-0.51407 c 1.41457,2e-5 2.48645,0.43387 3.21563,1.30157 c 0.73644,0.86771 1.10467,2.12917 1.10468,3.78437"
|
||||
id="path13585"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
d="m 229.73504,253.46209 l 0,3.47813 l 4.03594,0 l 0,2.8 l -4.03594,0 l 0,5.19531 c 0,0.56875 0.11302,0.95521 0.33906,1.15937 c 0.22604,0.19688 0.67448,0.29532 1.34532,0.29532 l 2.0125,0 l 0,2.8 l -3.35782,0 c -1.54583,0 -2.64323,-0.32084 -3.29218,-0.9625 c -0.64167,-0.64896 -0.96251,-1.74636 -0.9625,-3.29219 l 0,-5.19531 l -1.94688,0 l 0,-2.8 l 1.94688,0 l 0,-3.47813 l 3.91562,0"
|
||||
id="path13587"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
d="m 244.13973,252.86053 l 5.35938,0 l 3.71875,8.73906 l 3.74062,-8.73906 l 5.34844,0 l 0,16.32969 l -3.98125,0 l 0,-11.94375 l -3.7625,8.80468 l -2.66875,0 l -3.7625,-8.80468 l 0,11.94375 l -3.99219,0 l 0,-16.32969"
|
||||
id="path13589"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
d="m 272.10692,259.4449 c -0.86772,10e-6 -1.53126,0.31355 -1.99063,0.94063 c -0.45208,0.6198 -0.67813,1.51667 -0.67812,2.69062 c -1e-5,1.17397 0.22604,2.07449 0.67812,2.70157 c 0.45937,0.61979 1.12291,0.92969 1.99063,0.92968 c 0.85312,10e-6 1.50572,-0.30989 1.95781,-0.92968 c 0.45207,-0.62708 0.67812,-1.5276 0.67813,-2.70157 c -1e-5,-1.17395 -0.22606,-2.07082 -0.67813,-2.69062 c -0.45209,-0.62708 -1.10469,-0.94062 -1.95781,-0.94063 m 0,-2.8 c 2.10728,2e-5 3.75155,0.56877 4.93281,1.70625 c 1.18853,1.13751 1.7828,2.71251 1.78281,4.725 c -1e-5,2.01251 -0.59428,3.58751 -1.78281,4.725 c -1.18126,1.1375 -2.82553,1.70625 -4.93281,1.70625 c -2.11459,0 -3.7698,-0.56875 -4.96563,-1.70625 c -1.18854,-1.13749 -1.78281,-2.71249 -1.78281,-4.725 c 0,-2.01249 0.59427,-3.58749 1.78281,-4.725 c 1.19583,-1.13748 2.85104,-1.70623 4.96563,-1.70625"
|
||||
id="path13591"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
d="m 290.0116,258.73397 l 0,-6.5625 l 3.9375,0 l 0,17.01875 l -3.9375,0 l 0,-1.77188 c -0.53959,0.72188 -1.13386,1.25052 -1.78281,1.58594 c -0.64897,0.33542 -1.40001,0.50312 -2.25313,0.50312 c -1.50938,0 -2.74896,-0.59791 -3.71875,-1.79375 c -0.96979,-1.20312 -1.45469,-2.74895 -1.45468,-4.6375 c -1e-5,-1.88853 0.48489,-3.43072 1.45468,-4.62656 c 0.96979,-1.20311 2.20937,-1.80467 3.71875,-1.80469 c 0.84583,2e-5 1.59322,0.17137 2.24219,0.51407 c 0.65624,0.33542 1.25416,0.86042 1.79375,1.575 m -2.58125,7.92968 c 0.83853,10e-6 1.47655,-0.30624 1.91406,-0.91875 c 0.44478,-0.61249 0.66718,-1.50207 0.66719,-2.66875 c -10e-6,-1.16666 -0.22241,-2.05624 -0.66719,-2.66875 c -0.43751,-0.61249 -1.07553,-0.91874 -1.91406,-0.91875 c -0.83126,10e-6 -1.46928,0.30626 -1.91406,0.91875 c -0.43751,0.61251 -0.65626,1.50209 -0.65625,2.66875 c -1e-5,1.16668 0.21874,2.05626 0.65625,2.66875 c 0.44478,0.61251 1.0828,0.91876 1.91406,0.91875"
|
||||
id="path13593"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
d="m 309.9616,263.0324 l 0,1.11563 l -9.15469,0 c 0.0948,0.91875 0.42656,1.60781 0.99532,2.06719 c 0.56874,0.45937 1.36353,0.68906 2.38437,0.68906 c 0.82395,0 1.66614,-0.12031 2.52656,-0.36094 c 0.8677,-0.24791 1.75728,-0.61979 2.66875,-1.11562 l 0,3.01875 c -0.92605,0.35 -1.85209,0.6125 -2.77812,0.7875 c -0.92605,0.18229 -1.85209,0.27343 -2.77813,0.27343 c -2.21667,0 -3.94115,-0.56145 -5.17343,-1.68437 c -1.225,-1.13021 -1.8375,-2.7125 -1.8375,-4.74688 c 0,-1.9979 0.60156,-3.56926 1.80468,-4.71406 c 1.21042,-1.14478 2.87292,-1.71717 4.9875,-1.71719 c 1.92499,2e-5 3.46354,0.5797 4.61563,1.73907 c 1.15936,1.15938 1.73905,2.70886 1.73906,4.64843 m -4.025,-1.30156 c -10e-6,-0.74374 -0.21876,-1.34166 -0.65625,-1.79375 c -0.43022,-0.45936 -0.99532,-0.68905 -1.69531,-0.68906 c -0.75834,10e-6 -1.37449,0.21511 -1.84844,0.64531 c -0.47396,0.42293 -0.76927,1.03543 -0.88594,1.8375 l 5.08594,0"
|
||||
id="path13595"
|
||||
inkscape:connector-curvature="0" />
|
||||
</g>
|
||||
<path
|
||||
id="path22050-6"
|
||||
d="m 371.284,309.51434 l 39.35872,-0.5 l 0.35872,-75.5 l 19.71743,0"
|
||||
inkscape:connector-curvature="0"
|
||||
style="display:inline;fill:none;stroke:#7a00ff;stroke-width:5.61390018;stroke-linecap:butt;stroke-linejoin:round;stroke-opacity:1"
|
||||
sodipodi:nodetypes="cccc" />
|
||||
</g>
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="layer51"
|
||||
inkscape:label="cc-ppm-oneshot"
|
||||
style="display:inline">
|
||||
<g
|
||||
style="display:inline"
|
||||
id="revo-srxl"
|
||||
id="cc-ppm-oneshot"
|
||||
transform="translate(0.99999976,-1.9999999)">
|
||||
<path
|
||||
id="path8856-1-8-4-3"
|
||||
d="m 309.08575,189.42619 l 121.383,-0.484"
|
||||
inkscape:connector-curvature="0"
|
||||
style="display:inline;fill:none;stroke:#ec1d00;stroke-width:5.61390018;stroke-linecap:butt;stroke-linejoin:miter"
|
||||
sodipodi:nodetypes="cc" />
|
||||
<path
|
||||
id="path8856-1-5-8-4-6"
|
||||
d="m 309.08544,183.82619 l 121.38331,-0.2056"
|
||||
inkscape:connector-curvature="0"
|
||||
style="display:inline;fill:none;stroke:#000000;stroke-width:5.61390018;stroke-linecap:butt;stroke-linejoin:miter"
|
||||
sodipodi:nodetypes="cc" />
|
||||
<path
|
||||
id="path8856-1-3-1-3-7"
|
||||
d="m 389.08544,195.62619 l 41.38331,-0.412"
|
||||
inkscape:connector-curvature="0"
|
||||
style="display:inline;fill:none;stroke:#ffffff;stroke-width:5.17476749;stroke-linecap:butt;stroke-linejoin:miter"
|
||||
sodipodi:nodetypes="cc" />
|
||||
<path
|
||||
sodipodi:nodetypes="cc"
|
||||
style="fill:none;stroke:#1f4697;stroke-width:5.61390018;stroke-linecap:butt;stroke-linejoin:round"
|
||||
inkscape:connector-curvature="0"
|
||||
d="M 387.93975,203.58874 L 430.34,203.43994"
|
||||
id="path8856-5-47" />
|
||||
<path
|
||||
id="path22050"
|
||||
d="m 309.08575,195.51434 l 52.383,0 l 0,38 l 38.84184,0 l 30.40828,0"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#7a00ff;stroke-width:5.61390018;stroke-linecap:butt;stroke-linejoin:round;stroke-opacity:1"
|
||||
sodipodi:nodetypes="ccccc" />
|
||||
<path
|
||||
sodipodi:nodetypes="cc"
|
||||
style="fill:none;stroke:#fac204;stroke-width:5.61399984;stroke-linecap:butt;stroke-linejoin:round;stroke-miterlimit:4;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 387.93975,211.51434 l 42.62432,0"
|
||||
id="path8856-5-1-4" />
|
||||
<path
|
||||
sodipodi:nodetypes="cc"
|
||||
style="fill:none;stroke:#32a304;stroke-width:5.61399984;stroke-linecap:butt;stroke-linejoin:round;stroke-miterlimit:4;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 387.93975,218.51734 l 42.46472,-0.006"
|
||||
id="path8856-5-1-7-5" />
|
||||
<path
|
||||
sodipodi:nodetypes="cc"
|
||||
style="fill:none;stroke:#ec6004;stroke-width:5.61390018;stroke-linecap:butt;stroke-linejoin:round"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 387.93975,226.51434 l 42.77912,0"
|
||||
id="path8856-5-1-7-1-7" />
|
||||
<path
|
||||
style="display:inline;fill:none;stroke:#777777;stroke-width:5.80000019;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="M 131.51628,280.89645 C 99.179438,276.41438 56.116118,293.77498 44.942858,345.61434"
|
||||
id="path9857-3-9-8" />
|
||||
<path
|
||||
style="display:inline;fill:none;stroke:#6b6b6b;stroke-width:1.21428466;stroke-linecap:butt;stroke-linejoin:miter"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 388.78672,192.76858 l -0.01,5.91861 l 41.69166,-0.139"
|
||||
id="path8856-4-4-4"
|
||||
sodipodi:nodetypes="ccc" />
|
||||
<path
|
||||
sodipodi:nodetypes="sssccccssssss"
|
||||
inkscape:connector-curvature="0"
|
||||
id="rect8853-0-8-5"
|
||||
d="m 136.31357,163.05542 l 187.03999,0 c 3.58992,0 6.48,2.89008 6.48,6.48 l 0,8.84015 l -6,0 l 0,122.36001 l 6.00044,0 l -4.4e-4,10.23984 c -1.5e-4,3.58992 -2.89008,6.48 -6.48,6.48 l -187.03999,0 c -3.58993,0 -6.48001,-2.89008 -6.48001,-6.48 l 0,-141.44 c 0,-3.58992 2.89008,-6.48 6.48001,-6.48 z"
|
||||
style="color:#000000;display:inline;fill:url(#linearGradient13565);fill-rule:nonzero;stroke:#000000;stroke-width:3.09599996;stroke-miterlimit:4;stroke-dasharray:none;enable-background:accumulate" />
|
||||
<g
|
||||
transform="translate(-95.14393,-124.01573)"
|
||||
id="text9734-24-8-2"
|
||||
style="font-style:normal;font-variant:normal;font-weight:bold;font-stretch:normal;font-size:22.39999962px;line-height:125%;font-family:Sans;text-align:start;letter-spacing:0px;word-spacing:0px;writing-mode:lr-tb;text-anchor:start;display:inline;fill:#ffffff">
|
||||
<path
|
||||
id="path13900-3"
|
||||
d="m 268.82831,303.23718 l 6.98907,0 c 2.07811,10e-6 3.67134,0.46303 4.77968,1.38906 c 1.11561,0.91876 1.67343,2.23126 1.67344,3.9375 c -1e-5,1.71355 -0.55783,3.03334 -1.67344,3.95937 c -1.10834,0.91876 -2.70157,1.37813 -4.77968,1.37813 l -2.77813,0 l 0,5.66562 l -4.21094,0 l 0,-16.32968 m 4.21094,3.05156 l 0,4.56094 l 2.32969,0 c 0.81666,1e-5 1.44738,-0.19687 1.89219,-0.59063 c 0.44478,-0.40103 0.66717,-0.96613 0.66718,-1.69531 c -1e-5,-0.72916 -0.2224,-1.29061 -0.66718,-1.68438 c -0.44481,-0.39373 -1.07553,-0.59061 -1.89219,-0.59062 l -2.32969,0"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
id="path13902-9"
|
||||
d="m 285.23456,303.23718 l 6.98907,0 c 2.07811,10e-6 3.67134,0.46303 4.77968,1.38906 c 1.11561,0.91876 1.67343,2.23126 1.67344,3.9375 c -1e-5,1.71355 -0.55783,3.03334 -1.67344,3.95937 c -1.10834,0.91876 -2.70157,1.37813 -4.77968,1.37813 l -2.77813,0 l 0,5.66562 l -4.21094,0 l 0,-16.32968 m 4.21094,3.05156 l 0,4.56094 l 2.32969,0 c 0.81666,1e-5 1.44738,-0.19687 1.89219,-0.59063 c 0.44478,-0.40103 0.66717,-0.96613 0.66718,-1.69531 c -1e-5,-0.72916 -0.2224,-1.29061 -0.66718,-1.68438 c -0.44481,-0.39373 -1.07553,-0.59061 -1.89219,-0.59062 l -2.32969,0"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
id="path13904-1"
|
||||
d="m 301.64081,303.23718 l 5.35938,0 l 3.71875,8.73906 l 3.74062,-8.73906 l 5.34844,0 l 0,16.32968 l -3.98125,0 l 0,-11.94375 l -3.7625,8.80469 l -2.66875,0 l -3.7625,-8.80469 l 0,11.94375 l -3.99219,0 l 0,-16.32968"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
id="path13906-1"
|
||||
d="m 343.10487,303.75124 l 0,3.45625 c -0.89688,-0.40103 -1.77188,-0.70363 -2.625,-0.90781 c -0.85313,-0.20416 -1.65886,-0.30624 -2.41718,-0.30625 c -1.00626,1e-5 -1.75001,0.13855 -2.23125,0.41562 c -0.48126,0.2771 -0.72188,0.70731 -0.72188,1.29063 c 0,0.43751 0.16041,0.78022 0.48125,1.02812 c 0.32812,0.24064 0.91875,0.44845 1.77188,0.62344 l 1.79375,0.36094 c 1.81561,0.36459 3.10623,0.91876 3.87187,1.6625 c 0.76561,0.74375 1.14843,1.80104 1.14844,3.17187 c -1e-5,1.80105 -0.53595,3.14271 -1.60781,4.025 c -1.0646,0.875 -2.69428,1.3125 -4.88906,1.3125 c -1.03543,0 -2.07449,-0.0984 -3.11719,-0.29531 c -1.04271,-0.19688 -2.08542,-0.48854 -3.12813,-0.875 l 0,-3.55469 c 1.04271,0.55417 2.04896,0.97344 3.01875,1.25781 c 0.97708,0.27709 1.9177,0.41563 2.82188,0.41563 c 0.91874,0 1.62238,-0.15312 2.11094,-0.45938 c 0.48853,-0.30624 0.7328,-0.74374 0.73281,-1.3125 c -1e-5,-0.51041 -0.16772,-0.90416 -0.50313,-1.18125 c -0.32813,-0.27707 -0.98803,-0.52499 -1.97968,-0.74375 l -1.62969,-0.36093 c -1.63334,-0.35 -2.82917,-0.90781 -3.5875,-1.67344 c -0.75105,-0.76562 -1.12657,-1.79739 -1.12656,-3.09531 c -10e-6,-1.62603 0.52499,-2.87655 1.575,-3.75157 c 1.04999,-0.87498 2.55936,-1.31248 4.52812,-1.3125 c 0.89687,2e-5 1.81926,0.0693 2.76719,0.20782 c 0.9479,0.13126 1.92863,0.33178 2.94218,0.60156"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
id="path13908-3"
|
||||
d="m 347.70957,307.31686 l 3.91562,0 l 0,12.25 l -3.91562,0 l 0,-12.25 m 0,-4.76875 l 3.91562,0 l 0,3.19375 l -3.91562,0 l 0,-3.19375"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
id="path13910-5"
|
||||
d="m 363.74394,317.48874 c -0.5396,0.71458 -1.13387,1.23958 -1.78281,1.575 c -0.64897,0.33542 -1.40001,0.50312 -2.25313,0.50312 c -1.4948,0 -2.73073,-0.58697 -3.70781,-1.76093 c -0.97709,-1.18125 -1.46563,-2.68333 -1.46563,-4.50625 c 0,-1.8302 0.48854,-3.32864 1.46563,-4.49532 c 0.97708,-1.17394 2.21301,-1.76092 3.70781,-1.76093 c 0.85312,10e-6 1.60416,0.16772 2.25313,0.50312 c 0.64894,0.33543 1.24321,0.86408 1.78281,1.58594 l 0,-1.81563 l 3.9375,0 l 0,11.01407 c -2e-5,1.96875 -0.62345,3.47083 -1.87032,4.50625 c -1.23959,1.0427 -3.04063,1.56405 -5.40312,1.56406 c -0.76563,-10e-6 -1.50573,-0.0583 -2.22031,-0.175 c -0.71459,-0.11667 -1.43282,-0.29532 -2.15469,-0.53594 l 0,-3.05156 c 0.68541,0.39375 1.35625,0.68541 2.0125,0.875 c 0.65624,0.19687 1.31614,0.29531 1.97969,0.29531 c 1.28332,0 2.22395,-0.28073 2.82187,-0.84219 c 0.59791,-0.56146 0.89687,-1.4401 0.89688,-2.63593 l 0,-0.84219 m -2.58125,-7.62344 c -0.80938,1e-5 -1.44011,0.29897 -1.89219,0.89688 c -0.45209,0.59792 -0.67813,1.44375 -0.67812,2.5375 c -10e-6,1.12292 0.21874,1.97604 0.65625,2.55937 c 0.43749,0.57605 1.07551,0.86407 1.91406,0.86406 c 0.81666,10e-6 1.45103,-0.29895 1.90312,-0.89687 c 0.45208,-0.59791 0.67812,-1.4401 0.67813,-2.52656 c -1e-5,-1.09375 -0.22605,-1.93958 -0.67813,-2.5375 c -0.45209,-0.59791 -1.08646,-0.89687 -1.90312,-0.89688"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
id="path13912-3"
|
||||
d="m 383.78144,312.10749 l 0,7.45937 l -3.9375,0 l 0,-1.21406 l 0,-4.49531 c -10e-6,-1.05729 -0.0255,-1.78645 -0.0766,-2.1875 c -0.0438,-0.40103 -0.12397,-0.69635 -0.24063,-0.88594 c -0.15313,-0.2552 -0.36095,-0.45207 -0.62344,-0.59062 c -0.26251,-0.14583 -0.56146,-0.21874 -0.89687,-0.21875 c -0.81668,1e-5 -1.45834,0.31719 -1.925,0.95156 c -0.46667,0.62709 -0.70001,1.49844 -0.7,2.61406 l 0,6.02656 l -3.91563,0 l 0,-12.25 l 3.91563,0 l 0,1.79375 c 0.59062,-0.71457 1.2177,-1.23957 1.88125,-1.575 c 0.66353,-0.34269 1.39634,-0.51405 2.19844,-0.51406 c 1.41457,1e-5 2.48644,0.43387 3.21562,1.30156 c 0.73645,0.86772 1.10467,2.12918 1.10469,3.78438"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
id="path13914-2"
|
||||
d="m 392.92519,314.05436 c -0.81667,1e-5 -1.43282,0.13855 -1.84844,0.41563 c -0.40834,0.27709 -0.6125,0.68542 -0.6125,1.225 c 0,0.49584 0.16406,0.88594 0.49219,1.17031 c 0.33541,0.27709 0.79843,0.41563 1.38906,0.41563 c 0.73645,0 1.35624,-0.2625 1.85938,-0.7875 c 0.50311,-0.53229 0.75467,-1.19583 0.75468,-1.99063 l 0,-0.44844 l -2.03437,0 m 5.98281,-1.47656 l 0,6.98906 l -3.94844,0 l 0,-1.81562 c -0.525,0.74375 -1.11563,1.28698 -1.77187,1.62969 c -0.65626,0.33541 -1.45469,0.50312 -2.39531,0.50312 c -1.26876,0 -2.30053,-0.36823 -3.09532,-1.10469 c -0.7875,-0.74374 -1.18125,-1.70624 -1.18125,-2.8875 c 0,-1.43645 0.49219,-2.49009 1.47657,-3.16093 c 0.99166,-0.67083 2.54478,-1.00625 4.65937,-1.00625 l 2.30781,0 l 0,-0.30625 c -1e-5,-0.61979 -0.24428,-1.07187 -0.73281,-1.35625 c -0.48855,-0.29166 -1.25053,-0.43749 -2.28594,-0.4375 c -0.83854,10e-6 -1.61875,0.0839 -2.34062,0.25156 c -0.72188,0.16772 -1.39271,0.41928 -2.0125,0.75469 l 0,-2.98594 c 0.83854,-0.20416 1.68072,-0.35728 2.52656,-0.45938 c 0.84583,-0.10936 1.69166,-0.16405 2.5375,-0.16406 c 2.20937,1e-5 3.80259,0.43751 4.77969,1.3125 c 0.98436,0.86772 1.47655,2.2823 1.47656,4.24375"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
id="path13916-6"
|
||||
d="m 402.57206,302.54811 l 3.91563,0 l 0,17.01875 l -3.91563,0 l 0,-17.01875"
|
||||
inkscape:connector-curvature="0" />
|
||||
</g>
|
||||
<g
|
||||
style="font-style:normal;font-variant:normal;font-weight:bold;font-stretch:condensed;font-size:21.83368874px;line-height:125%;font-family:'Arial Narrow';-inkscape-font-specification:'Arial Narrow Bold Condensed';letter-spacing:0px;word-spacing:0px;fill:#7a00ff;fill-opacity:1;stroke:none"
|
||||
id="text12471">
|
||||
<path
|
||||
d="m 360.43582,244.43796 l 0,-2.77185 l 2.46269,0 l 0,2.77185 l -2.46269,0 m 0,12.85714 l 0,-11.32196 l 2.46269,0 l 0,11.32196 l -2.46269,0"
|
||||
style="fill:#7a00ff;fill-opacity:1"
|
||||
id="path12476"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
d="m 373.86866,257.2951 l -2.46269,0 l 0,-5.77825 c -1e-5,-1.15848 -0.0462,-1.92963 -0.13859,-2.31343 c -0.0924,-0.38379 -0.26653,-0.67874 -0.52239,-0.88486 c -0.24876,-0.2061 -0.53305,-0.30916 -0.85288,-0.30917 c -0.41223,1e-5 -0.78536,0.13505 -1.1194,0.40512 c -0.33405,0.26298 -0.56859,0.629 -0.70363,1.09808 c -0.13504,0.46909 -0.20256,1.35395 -0.20255,2.65458 l 0,5.12793 l -2.46269,0 l 0,-11.32196 l 2.28145,0 l 0,1.66312 c 0.40511,-0.63965 0.85998,-1.1194 1.3646,-1.43924 c 0.51173,-0.31981 1.07676,-0.47973 1.6951,-0.47974 c 0.71783,1e-5 1.32195,0.18836 1.81237,0.56503 c 0.4975,0.36959 0.83865,0.84934 1.02345,1.43923 c 0.19189,0.58281 0.28784,1.42858 0.28785,2.53732 l 0,7.03624"
|
||||
style="fill:#7a00ff;fill-opacity:1"
|
||||
id="path12478"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
d="m 376.31002,245.97314 l 2.29211,0 l 0,1.66312 c 0.31272,-0.59701 0.72495,-1.06609 1.23668,-1.40725 c 0.51172,-0.34114 1.06254,-0.51172 1.65245,-0.51173 c 1.05898,1e-5 1.96872,0.50463 2.72921,1.51386 c 0.76758,1.00925 1.15138,2.44137 1.15139,4.29637 c -1e-5,1.94741 -0.38381,3.43995 -1.15139,4.47762 c -0.7676,1.03056 -1.68089,1.54584 -2.73987,1.54584 c -0.49041,0 -0.94883,-0.11727 -1.37527,-0.35181 c -0.41934,-0.24165 -0.86354,-0.6752 -1.33262,-1.30064 l 0,5.70362 l -2.46269,0 l 0,-15.629 m 2.43071,5.46909 c -10e-6,1.27932 0.2061,2.22104 0.61833,2.82516 c 0.41933,0.60412 0.92395,0.90618 1.51386,0.90618 c 0.56147,0 1.03411,-0.27718 1.41791,-0.83156 c 0.38379,-0.56147 0.57569,-1.47476 0.5757,-2.73987 c -1e-5,-1.20113 -0.19902,-2.08599 -0.59702,-2.65458 c -0.39091,-0.57569 -0.87065,-0.86353 -1.43923,-0.86354 c -0.59702,1e-5 -1.09453,0.28075 -1.49254,0.84222 c -0.39801,0.55437 -0.59702,1.39304 -0.59701,2.51599"
|
||||
style="fill:#7a00ff;fill-opacity:1"
|
||||
id="path12480"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
d="m 393.44222,257.2951 l 0,-1.69509 c -0.34116,0.61123 -0.78892,1.09097 -1.34329,1.43923 c -0.55437,0.34115 -1.13362,0.51173 -1.73774,0.51173 c -0.61123,0 -1.15849,-0.15992 -1.64179,-0.47975 c -0.4833,-0.31982 -0.84577,-0.77469 -1.08742,-1.3646 c -0.23454,-0.58991 -0.35181,-1.44634 -0.35181,-2.5693 l 0,-7.16418 l 2.46269,0 l 0,5.20256 c -1e-5,1.48544 0.0355,2.43071 0.10661,2.83582 c 0.0782,0.39802 0.24519,0.70718 0.50106,0.92751 c 0.25586,0.22033 0.56503,0.33049 0.92751,0.33049 c 0.41222,0 0.79246,-0.14215 1.14072,-0.42644 c 0.34825,-0.2914 0.57569,-0.66098 0.68231,-1.10874 c 0.11371,-0.45487 0.17056,-1.44989 0.17057,-2.98508 l 0,-4.77612 l 2.45203,0 l 0,11.32196 l -2.28145,0"
|
||||
style="fill:#7a00ff;fill-opacity:1"
|
||||
id="path12482"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
d="m 402.54669,245.97314 l 0,2.38806 l -1.67377,0 l 0,4.5629 c 0,0.98792 0.0249,1.56006 0.0746,1.71642 c 0.0995,0.2843 0.30205,0.42644 0.60767,0.42644 c 0.22743,0 0.55437,-0.0959 0.98081,-0.28785 l 0.21322,2.3241 c -0.56859,0.2985 -1.2118,0.44776 -1.92963,0.44776 c -0.62545,0 -1.12652,-0.14926 -1.5032,-0.44776 c -0.37669,-0.29851 -0.629,-0.7285 -0.75693,-1.28998 c -0.0995,-0.41222 -0.14926,-1.25089 -0.14926,-2.51599 l 0,-4.93604 l -1.13006,0 l 0,-2.38806 l 1.13006,0 l 0,-2.24946 l 2.46269,-1.7484 l 0,3.99786 l 1.67377,0"
|
||||
style="fill:#7a00ff;fill-opacity:1"
|
||||
id="path12484"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
d="m 412.06695,245.4934 l -2.3774,0.31983 c -0.11372,-1.16559 -0.57925,-1.74839 -1.39659,-1.7484 c -0.53305,1e-5 -0.97726,0.29141 -1.33262,0.8742 c -0.34826,0.58281 -0.56859,1.75907 -0.66098,3.52878 c 0.30561,-0.44064 0.64676,-0.77113 1.02345,-0.99147 c 0.37669,-0.22032 0.79247,-0.33048 1.24734,-0.33049 c 1.00212,1e-5 1.87632,0.46909 2.6226,1.40725 c 0.74626,0.93107 1.11939,2.17129 1.1194,3.72068 c -10e-6,1.6489 -0.39446,2.94244 -1.18337,3.8806 c -0.78892,0.93817 -1.76617,1.40725 -2.93177,1.40725 c -1.27932,0 -2.34186,-0.60768 -3.18763,-1.82303 c -0.83866,-1.22245 -1.25799,-3.24449 -1.25799,-6.0661 c 0,-2.86424 0.43709,-4.92536 1.3113,-6.18337 c 0.87419,-1.25798 1.99715,-1.88697 3.36887,-1.88699 c 0.94526,2e-5 1.74128,0.3234 2.38806,0.97015 c 0.65386,0.63967 1.06964,1.61338 1.24733,2.92111 m -5.55437,6.53518 c 0,0.98792 0.18123,1.74485 0.54371,2.27079 c 0.36958,0.51884 0.78891,0.77825 1.258,0.77825 c 0.45486,0 0.83155,-0.21677 1.13006,-0.65032 c 0.30561,-0.43354 0.45841,-1.14427 0.45842,-2.1322 c -10e-6,-1.02344 -0.16347,-1.76971 -0.4904,-2.2388 c -0.32695,-0.46908 -0.73206,-0.70362 -1.21536,-0.70363 c -0.46908,1e-5 -0.86709,0.22389 -1.19403,0.67165 c -0.32694,0.44776 -0.4904,1.11585 -0.4904,2.00426"
|
||||
style="fill:#7a00ff;fill-opacity:1"
|
||||
id="path12486"
|
||||
inkscape:connector-curvature="0" />
|
||||
</g>
|
||||
<g
|
||||
style="font-style:normal;font-variant:normal;font-weight:bold;font-stretch:condensed;font-size:21.31113434px;line-height:125%;font-family:'Arial Narrow';-inkscape-font-specification:'Arial Narrow Bold Condensed';letter-spacing:0px;word-spacing:0px;fill:#7a00ff;fill-opacity:1;stroke:none"
|
||||
id="text11303"
|
||||
transform="translate(-2,0)">
|
||||
<path
|
||||
d="m 368.60892,284.29186 l -1.64412,0 c -0.86022,-1.56088 -1.52272,-3.21194 -1.98752,-4.95318 c -0.45785,-1.74817 -0.68678,-3.44085 -0.68678,-5.07804 c 0,-1.76898 0.2324,-3.49288 0.69719,-5.1717 c 0.46479,-1.68573 1.13423,-3.28476 2.00832,-4.79708 l 1.63372,0 c -0.79778,2.16442 -1.33889,3.97503 -1.62331,5.43184 c -0.27749,1.45682 -0.41624,2.99688 -0.41623,4.62019 c -1e-5,1.67881 0.1977,3.45473 0.59313,5.32778 c 0.27748,1.31807 0.75268,2.85813 1.4256,4.62019"
|
||||
style="fill:#7a00ff;fill-opacity:1"
|
||||
id="path11308"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
d="m 370.39872,268.75596 l 2.23725,0 l 0,1.62331 c 0.30524,-0.58272 0.7076,-1.04058 1.20708,-1.37357 c 0.49947,-0.33298 1.03711,-0.49947 1.6129,-0.49948 c 1.03364,1e-5 1.9216,0.49255 2.66389,1.47762 c 0.74921,0.9851 1.12382,2.38295 1.12383,4.19355 c -1e-5,1.9008 -0.37462,3.35762 -1.12383,4.37045 c -0.74922,1.0059 -1.64065,1.50885 -2.67429,1.50885 c -0.47868,0 -0.92613,-0.11447 -1.34235,-0.3434 c -0.40931,-0.23586 -0.84288,-0.65903 -1.30073,-1.26951 l 0,5.56712 l -2.40375,0 l 0,-15.25494 m 2.37253,5.33819 c 0,1.2487 0.20117,2.16788 0.60354,2.75754 c 0.40929,0.58967 0.90183,0.8845 1.47762,0.8845 c 0.54804,0 1.00936,-0.27055 1.38398,-0.81166 c 0.3746,-0.54804 0.56191,-1.43947 0.56191,-2.6743 c 0,-1.17238 -0.19425,-2.03606 -0.58272,-2.59105 c -0.38156,-0.5619 -0.84982,-0.84286 -1.40479,-0.84287 c -0.58273,1e-5 -1.06833,0.27403 -1.45681,0.82206 c -0.38849,0.54111 -0.58273,1.3597 -0.58273,2.45578"
|
||||
style="fill:#7a00ff;fill-opacity:1"
|
||||
id="path11310"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
d="m 381.16875,267.25752 l 0,-2.70552 l 2.40375,0 l 0,2.70552 l -2.40375,0 m 0,12.54943 l 0,-11.05099 l 2.40375,0 l 0,11.05099 l -2.40375,0"
|
||||
style="fill:#7a00ff;fill-opacity:1"
|
||||
id="path11312"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
d="m 394.28009,279.80695 l -2.40374,0 l 0,-5.63996 c -10e-6,-1.13076 -0.0451,-1.88345 -0.13528,-2.25807 c -0.0902,-0.3746 -0.26015,-0.66249 -0.50988,-0.86368 c -0.24281,-0.20117 -0.5203,-0.30176 -0.83247,-0.30177 c -0.40236,10e-6 -0.76657,0.13182 -1.09261,0.39542 c -0.32606,0.25669 -0.55498,0.61395 -0.68679,1.0718 c -0.13181,0.45787 -0.19771,1.32155 -0.19771,2.59105 l 0,5.00521 l -2.40374,0 l 0,-11.05099 l 2.22684,0 l 0,1.62331 c 0.39542,-0.62434 0.8394,-1.09261 1.33195,-1.40479 c 0.49947,-0.31216 1.05098,-0.46825 1.65453,-0.46826 c 0.70065,1e-5 1.29031,0.18384 1.76899,0.55151 c 0.48559,0.36074 0.81858,0.829 0.99896,1.40478 c 0.18729,0.56886 0.28094,1.39439 0.28095,2.47659 l 0,6.86785"
|
||||
style="fill:#7a00ff;fill-opacity:1"
|
||||
id="path11314"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
d="m 398.28634,271.57594 c -0.58967,-0.30523 -1.03365,-0.72147 -1.33195,-1.2487 c -0.2983,-0.52722 -0.44745,-1.16198 -0.44745,-1.90427 c 0,-1.20013 0.33992,-2.15399 1.01977,-2.8616 c 0.67985,-0.71452 1.59556,-1.07179 2.74714,-1.0718 c 1.22095,10e-6 2.15053,0.38156 2.78876,1.14464 c 0.63822,0.75617 0.95733,1.67882 0.95734,2.76795 c -10e-6,0.74229 -0.1561,1.38745 -0.46826,1.93548 c -0.30525,0.54111 -0.72495,0.95388 -1.25911,1.2383 c 0.71453,0.34687 1.24869,0.83594 1.6025,1.46722 c 0.35379,0.62435 0.53069,1.39438 0.5307,2.31009 c -10e-6,0.94347 -0.17691,1.77593 -0.5307,2.4974 c -0.34687,0.72147 -0.82901,1.27298 -1.44641,1.65453 c -0.61742,0.38154 -1.31114,0.57232 -2.08117,0.57232 c -1.20708,0 -2.20603,-0.41624 -2.99687,-1.2487 c -0.78391,-0.8394 -1.17586,-1.9667 -1.17586,-3.3819 c 0,-0.9157 0.18036,-1.70308 0.5411,-2.36212 c 0.36073,-0.65903 0.87756,-1.16197 1.55047,-1.50884 m 0.48907,-2.94485 c 0,0.59661 0.13874,1.05446 0.41624,1.37357 c 0.28442,0.31912 0.64168,0.47867 1.0718,0.47866 c 0.43703,1e-5 0.79777,-0.15954 1.0822,-0.47866 c 0.28442,-0.31911 0.42663,-0.77696 0.42664,-1.37357 c -10e-6,-0.57578 -0.14222,-1.02323 -0.42664,-1.34235 c -0.27749,-0.3191 -0.62782,-0.47866 -1.05099,-0.47867 c -0.44398,1e-5 -0.80819,0.16303 -1.09261,0.48907 c -0.28443,0.31913 -0.42664,0.76311 -0.42664,1.33195 m -0.21852,6.53486 c 0,0.81859 0.17343,1.44988 0.52029,1.89386 c 0.34686,0.44398 0.76309,0.66597 1.2487,0.66597 c 0.4856,0 0.89143,-0.21158 1.21748,-0.63476 c 0.33298,-0.42316 0.49948,-1.05792 0.49948,-1.90426 c 0,-0.7284 -0.16997,-1.30419 -0.50988,-1.72737 c -0.333,-0.42316 -0.74576,-0.63475 -1.2383,-0.63475 c -0.48561,0 -0.89837,0.21506 -1.23829,0.64516 c -0.33299,0.42317 -0.49948,0.98856 -0.49948,1.69615"
|
||||
style="fill:#7a00ff;fill-opacity:1"
|
||||
id="path11316"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
d="m 405.80975,284.29186 c 0.67291,-1.74818 1.14464,-3.2709 1.41519,-4.56816 c 0.40236,-1.88692 0.60354,-3.68019 0.60354,-5.37981 c 0,-1.62331 -0.14222,-3.16337 -0.42664,-4.62019 c -0.27749,-1.45681 -0.81512,-3.26742 -1.6129,-5.43184 l 1.63371,0 c 0.8949,1.56782 1.56781,3.18419 2.01873,4.84911 c 0.45786,1.66494 0.68678,3.32641 0.68679,4.98439 c -1e-5,1.66494 -0.22547,3.37843 -0.67638,5.14048 c -0.45092,1.75512 -1.1169,3.43045 -1.99792,5.02602 l -1.64412,0"
|
||||
style="fill:#7a00ff;fill-opacity:1"
|
||||
id="path11318"
|
||||
inkscape:connector-curvature="0" />
|
||||
</g>
|
||||
</g>
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="layer22"
|
||||
inkscape:label="cc-ppm"
|
||||
style="display:none"
|
||||
sodipodi:insensitive="true">
|
||||
<g
|
||||
style="display:inline"
|
||||
id="cc-ppm"
|
||||
transform="translate(-2.3935318e-7,-1.9999999)">
|
||||
<path
|
||||
id="path8856-1-8"
|
||||
d="m 309.08544,189.42619 l 121.38331,-0.484"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#ec1d00;stroke-width:5.61390018;stroke-linecap:butt;stroke-linejoin:miter"
|
||||
sodipodi:nodetypes="cc" />
|
||||
<path
|
||||
id="path8856-1-5-8"
|
||||
d="m 309.08544,183.82619 l 121.38331,-0.2056"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#000000;stroke-width:5.61390018;stroke-linecap:butt;stroke-linejoin:miter"
|
||||
sodipodi:nodetypes="cc" />
|
||||
<path
|
||||
id="path8856-1-3-1"
|
||||
d="m 309.08544,195.62619 l 121.38331,-0.412"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#ffffff;stroke-width:5.17476749;stroke-linecap:butt;stroke-linejoin:miter"
|
||||
sodipodi:nodetypes="cc" />
|
||||
<path
|
||||
style="fill:none;stroke:#6b6b6b;stroke-width:1.21428466;stroke-linecap:butt;stroke-linejoin:miter"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 309.08544,198.82619 l 121.38331,-0.278"
|
||||
id="path8856-4"
|
||||
sodipodi:nodetypes="cc" />
|
||||
<path
|
||||
style="display:inline;fill:none;stroke:#777777;stroke-width:5.80000019;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 136.89023,281.28139 c -32.33684,-4.48207 -75.400154,12.87853 -86.573414,64.71789"
|
||||
id="path9857-3" />
|
||||
<path
|
||||
sodipodi:nodetypes="sssccccssssss"
|
||||
inkscape:connector-curvature="0"
|
||||
id="rect8853-0"
|
||||
d="m 141.68752,163.44036 l 187.04,0 c 3.58992,0 6.48,2.89008 6.48,6.48 l 0,8.84015 l -6,0 l 0,122.36001 l 6.00044,0 l -4.4e-4,10.23984 c -1.6e-4,3.58992 -2.89008,6.48 -6.48,6.48 l -187.04,0 c -3.58992,0 -6.48,-2.89008 -6.48,-6.48 l 0,-141.44 c 0,-3.58992 2.89008,-6.48 6.48,-6.48 z"
|
||||
style="color:#000000;display:inline;fill:url(#linearGradient13497);fill-rule:nonzero;stroke:#000000;stroke-width:3.09599996;stroke-miterlimit:4;stroke-dasharray:none;enable-background:accumulate" />
|
||||
<g
|
||||
style="font-style:normal;font-variant:normal;font-weight:bold;font-stretch:normal;font-size:22.39999962px;line-height:125%;font-family:Sans;text-align:start;letter-spacing:0px;word-spacing:0px;writing-mode:lr-tb;text-anchor:start;fill:#ffffff"
|
||||
id="text9734-24"
|
||||
transform="translate(0,11)">
|
||||
<path
|
||||
d="m 174.20226,166.62213 l 6.98906,0 c 2.07812,1e-5 3.67135,0.46303 4.77969,1.38906 c 1.11561,0.91876 1.67342,2.23126 1.67344,3.9375 c -2e-5,1.71355 -0.55783,3.03334 -1.67344,3.95937 c -1.10834,0.91876 -2.70157,1.37813 -4.77969,1.37813 l -2.77812,0 l 0,5.66562 l -4.21094,0 l 0,-16.32968 m 4.21094,3.05156 l 0,4.56094 l 2.32969,0 c 0.81665,0 1.44738,-0.19687 1.89218,-0.59063 c 0.44478,-0.40103 0.66718,-0.96614 0.66719,-1.69531 c -1e-5,-0.72916 -0.22241,-1.29061 -0.66719,-1.68438 c -0.4448,-0.39373 -1.07553,-0.59061 -1.89218,-0.59062 l -2.32969,0"
|
||||
id="path13536"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
d="m 190.60851,166.62213 l 6.98906,0 c 2.07812,1e-5 3.67135,0.46303 4.77969,1.38906 c 1.11561,0.91876 1.67342,2.23126 1.67344,3.9375 c -2e-5,1.71355 -0.55783,3.03334 -1.67344,3.95937 c -1.10834,0.91876 -2.70157,1.37813 -4.77969,1.37813 l -2.77812,0 l 0,5.66562 l -4.21094,0 l 0,-16.32968 m 4.21094,3.05156 l 0,4.56094 l 2.32969,0 c 0.81665,0 1.44738,-0.19687 1.89218,-0.59063 c 0.44478,-0.40103 0.66718,-0.96614 0.66719,-1.69531 c -1e-5,-0.72916 -0.22241,-1.29061 -0.66719,-1.68438 c -0.4448,-0.39373 -1.07553,-0.59061 -1.89218,-0.59062 l -2.32969,0"
|
||||
id="path13538"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
d="m 207.01476,166.62213 l 5.35938,0 l 3.71875,8.73906 l 3.74062,-8.73906 l 5.34844,0 l 0,16.32968 l -3.98125,0 l 0,-11.94375 l -3.7625,8.80469 l -2.66875,0 l -3.7625,-8.80469 l 0,11.94375 l -3.99219,0 l 0,-16.32968"
|
||||
id="path13540"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
d="m 248.47882,167.13619 l 0,3.45625 c -0.89689,-0.40103 -1.77188,-0.70363 -2.625,-0.90781 c -0.85313,-0.20416 -1.65886,-0.30624 -2.41719,-0.30625 c -1.00625,1e-5 -1.75,0.13855 -2.23125,0.41562 c -0.48125,0.2771 -0.72188,0.7073 -0.72187,1.29063 c -1e-5,0.43751 0.16041,0.78021 0.48125,1.02812 c 0.32812,0.24064 0.91874,0.44845 1.77187,0.62344 l 1.79375,0.36094 c 1.81562,0.36459 3.10624,0.91875 3.87188,1.6625 c 0.76561,0.74375 1.14842,1.80104 1.14844,3.17187 c -2e-5,1.80105 -0.53595,3.14271 -1.60782,4.025 c -1.06459,0.875 -2.69428,1.3125 -4.88906,1.3125 c -1.03542,0 -2.07448,-0.0984 -3.11719,-0.29531 c -1.04271,-0.19688 -2.08541,-0.48854 -3.12812,-0.875 l 0,-3.55469 c 1.04271,0.55417 2.04895,0.97344 3.01875,1.25781 c 0.97708,0.27709 1.9177,0.41563 2.82187,0.41563 c 0.91875,0 1.62239,-0.15312 2.11094,-0.45938 c 0.48853,-0.30624 0.7328,-0.74374 0.73281,-1.3125 c -1e-5,-0.51041 -0.16771,-0.90416 -0.50312,-1.18125 c -0.32813,-0.27707 -0.98803,-0.52499 -1.97969,-0.74375 l -1.62969,-0.36093 c -1.63333,-0.35 -2.82917,-0.90781 -3.5875,-1.67344 c -0.75104,-0.76562 -1.12656,-1.79739 -1.12656,-3.09531 c 0,-1.62603 0.525,-2.87655 1.575,-3.75157 c 1.05,-0.87498 2.55937,-1.31248 4.52813,-1.3125 c 0.89686,2e-5 1.81926,0.0693 2.76718,0.20782 c 0.94791,0.13126 1.92864,0.33178 2.94219,0.60156"
|
||||
id="path13542"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
d="m 253.08351,170.70181 l 3.91563,0 l 0,12.25 l -3.91563,0 l 0,-12.25 m 0,-4.76875 l 3.91563,0 l 0,3.19375 l -3.91563,0 l 0,-3.19375"
|
||||
id="path13544"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
d="m 269.11788,180.87369 c -0.53959,0.71458 -1.13386,1.23958 -1.78281,1.575 c -0.64896,0.33541 -1.4,0.50312 -2.25312,0.50312 c -1.4948,0 -2.73074,-0.58698 -3.70782,-1.76093 c -0.97708,-1.18125 -1.46562,-2.68333 -1.46562,-4.50625 c 0,-1.8302 0.48854,-3.32864 1.46562,-4.49532 c 0.97708,-1.17394 2.21302,-1.76092 3.70782,-1.76093 c 0.85312,1e-5 1.60416,0.16772 2.25312,0.50312 c 0.64895,0.33543 1.24322,0.86407 1.78281,1.58594 l 0,-1.81563 l 3.9375,0 l 0,11.01407 c -1e-5,1.96874 -0.62345,3.47083 -1.87031,4.50625 c -1.23959,1.0427 -3.04063,1.56405 -5.40312,1.56406 c -0.76563,-1e-5 -1.50574,-0.0583 -2.22032,-0.175 c -0.71458,-0.11667 -1.43281,-0.29532 -2.15468,-0.53594 l 0,-3.05156 c 0.68541,0.39375 1.35624,0.68541 2.0125,0.875 c 0.65624,0.19687 1.31614,0.29531 1.97968,0.29531 c 1.28333,0 2.22395,-0.28073 2.82188,-0.84219 c 0.59791,-0.56146 0.89686,-1.4401 0.89687,-2.63593 l 0,-0.84219 m -2.58125,-7.62344 c -0.80938,1e-5 -1.44011,0.29897 -1.89218,0.89688 c -0.45209,0.59792 -0.67813,1.44375 -0.67813,2.5375 c 0,1.12292 0.21875,1.97604 0.65625,2.55937 c 0.4375,0.57605 1.07552,0.86407 1.91406,0.86406 c 0.81666,1e-5 1.45104,-0.29895 1.90313,-0.89687 c 0.45207,-0.59791 0.67811,-1.4401 0.67812,-2.52656 c -1e-5,-1.09375 -0.22605,-1.93958 -0.67812,-2.5375 c -0.45209,-0.59791 -1.08647,-0.89687 -1.90313,-0.89688"
|
||||
id="path13546"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
d="m 289.15539,175.49244 l 0,7.45937 l -3.9375,0 l 0,-1.21406 l 0,-4.49531 c -1e-5,-1.05729 -0.0255,-1.78645 -0.0766,-2.1875 c -0.0438,-0.40104 -0.12396,-0.69635 -0.24062,-0.88594 c -0.15314,-0.2552 -0.36095,-0.45207 -0.62344,-0.59062 c -0.26251,-0.14583 -0.56147,-0.21875 -0.89687,-0.21875 c -0.81668,0 -1.45834,0.31719 -1.925,0.95156 c -0.46668,0.62709 -0.70001,1.49844 -0.7,2.61406 l 0,6.02656 l -3.91563,0 l 0,-12.25 l 3.91563,0 l 0,1.79375 c 0.59061,-0.71457 1.2177,-1.23957 1.88125,-1.575 c 0.66353,-0.34269 1.39634,-0.51405 2.19843,-0.51406 c 1.41458,1e-5 2.48645,0.43387 3.21563,1.30156 c 0.73644,0.86772 1.10467,2.12918 1.10469,3.78438"
|
||||
id="path13548"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
d="m 298.29914,177.43931 c -0.81668,1e-5 -1.43282,0.13855 -1.84844,0.41563 c -0.40834,0.27709 -0.61251,0.68542 -0.6125,1.225 c -10e-6,0.49583 0.16406,0.88594 0.49219,1.17031 c 0.33541,0.27709 0.79843,0.41563 1.38906,0.41563 c 0.73645,0 1.35624,-0.2625 1.85937,-0.7875 c 0.50312,-0.53229 0.75468,-1.19583 0.75469,-1.99063 l 0,-0.44844 l -2.03437,0 m 5.98281,-1.47656 l 0,6.98906 l -3.94844,0 l 0,-1.81562 c -0.52501,0.74375 -1.11563,1.28698 -1.77187,1.62969 c -0.65626,0.33541 -1.4547,0.50312 -2.39532,0.50312 c -1.26875,0 -2.30052,-0.36823 -3.09531,-1.10469 c -0.7875,-0.74375 -1.18125,-1.70624 -1.18125,-2.8875 c 0,-1.43645 0.49219,-2.4901 1.47656,-3.16093 c 0.99167,-0.67083 2.54479,-1.00625 4.65938,-1.00625 l 2.30781,0 l 0,-0.30625 c -10e-6,-0.61979 -0.24428,-1.07187 -0.73281,-1.35625 c -0.48855,-0.29166 -1.25053,-0.43749 -2.28594,-0.4375 c -0.83855,1e-5 -1.61875,0.0839 -2.34062,0.25156 c -0.72188,0.16772 -1.39271,0.41928 -2.0125,0.75469 l 0,-2.98594 c 0.83854,-0.20416 1.68072,-0.35728 2.52656,-0.45938 c 0.84583,-0.10936 1.69166,-0.16405 2.5375,-0.16406 c 2.20936,1e-5 3.80259,0.43751 4.77969,1.3125 c 0.98436,0.86772 1.47655,2.2823 1.47656,4.24375"
|
||||
id="path13550"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
d="m 307.94601,165.93306 l 3.91562,0 l 0,17.01875 l -3.91562,0 l 0,-17.01875"
|
||||
id="path13552"
|
||||
inkscape:connector-curvature="0" />
|
||||
</g>
|
||||
<g
|
||||
style="font-style:normal;font-variant:normal;font-weight:bold;font-stretch:condensed;font-size:41px;line-height:125%;font-family:'Arial Narrow';-inkscape-font-specification:'Arial Narrow Bold Condensed';letter-spacing:0px;word-spacing:0px;display:inline;fill:#f4f6f8;fill-opacity:1;stroke:none"
|
||||
id="text21611"
|
||||
transform="matrix(0.66455533,0,0,0.66455533,105.60136,63.655516)">
|
||||
<path
|
||||
d="m 248.91997,211.60818 l 4.3042,0 l 0,3.12305 c 0.58723,-1.12107 1.36132,-2.00193 2.32226,-2.64258 c 0.96093,-0.6406 1.99527,-0.96091 3.10303,-0.96093 c 1.98859,2e-5 3.69692,0.94761 5.125,2.84277 c 1.44139,1.8952 2.16209,4.58449 2.16211,8.06787 c -2e-5,3.65691 -0.72072,6.45964 -2.16211,8.4082 c -1.44142,1.93523 -3.15643,2.90284 -5.14502,2.90284 c -0.92091,0 -1.78175,-0.22022 -2.58252,-0.66065 c -0.78744,-0.45377 -1.62159,-1.2679 -2.50244,-2.44238 l 0,10.71045 l -4.62451,0 l 0,-29.34864 m 4.56445,10.27002 c -1e-5,2.40236 0.38704,4.17075 1.16113,5.30518 c 0.78743,1.13444 1.73502,1.70166 2.84278,1.70166 c 1.05435,0 1.94188,-0.5205 2.66259,-1.56152 c 0.72069,-1.05436 1.08104,-2.76936 1.08106,-5.14502 c -2e-5,-2.25552 -0.37371,-3.91714 -1.12109,-4.98487 c -0.73407,-1.08103 -1.63494,-1.62156 -2.70264,-1.62158 c -1.1211,2e-5 -2.05535,0.5272 -2.80274,1.58154 c -0.7474,1.04104 -1.1211,2.6159 -1.12109,4.72461"
|
||||
id="path21616"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
d="m 269.64018,208.72537 l 0,-5.20508 l 4.62451,0 l 0,5.20508 l -4.62451,0 m 0,24.14356 l 0,-21.26075 l 4.62451,0 l 0,21.26075 l -4.62451,0"
|
||||
id="path21618"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
d="m 294.86479,232.86893 l -4.62451,0 l 0,-10.85059 c -10e-6,-2.17544 -0.0868,-3.62352 -0.26025,-4.34424 c -0.17352,-0.72068 -0.5005,-1.27456 -0.98096,-1.66162 c -0.46714,-0.38703 -1.00099,-0.58055 -1.60156,-0.58056 c -0.7741,1e-5 -1.47478,0.25359 -2.10205,0.76074 c -0.62729,0.49383 -1.06772,1.18117 -1.32129,2.06201 c -0.25359,0.88087 -0.38038,2.54249 -0.38037,4.98486 l 0,9.6294 l -4.62452,0 l 0,-21.26075 l 4.28418,0 l 0,3.12305 c 0.76074,-1.20115 1.6149,-2.10203 2.5625,-2.70264 c 0.96093,-0.60056 2.02197,-0.90085 3.18311,-0.90087 c 1.34797,2e-5 2.48241,0.3537 3.40332,1.06103 c 0.93423,0.69403 1.57485,1.59491 1.92187,2.70264 c 0.36034,1.09442 0.54051,2.68263 0.54053,4.76465 l 0,13.21289"
|
||||
id="path21620"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
d="m 298.42827,225.08133 l 4.46435,-0.66065 c 0.12012,1.38803 0.50049,2.44907 1.14112,3.18311 c 0.64061,0.73405 1.39468,1.10108 2.2622,1.10107 c 0.94759,1e-5 1.74837,-0.43375 2.40235,-1.30127 c 0.65396,-0.8675 0.98094,-2.06867 0.98095,-3.60351 c -10e-6,-1.42805 -0.31365,-2.54914 -0.94091,-3.36328 c -0.62729,-0.81412 -1.38803,-1.22118 -2.28223,-1.22119 c -0.58725,1e-5 -1.28793,0.14015 -2.10205,0.42041 l 0.50049,-4.58448 c 1.18781,0.0267 2.12873,-0.2936 2.82275,-0.96093 c 0.68065,-0.6673 1.02099,-1.60822 1.021,-2.82276 c -10e-6,-1.0143 -0.24692,-1.8084 -0.74072,-2.38232 c -0.49383,-0.57387 -1.12778,-0.86082 -1.90186,-0.86084 c -0.7741,2e-5 -1.44809,0.33368 -2.02197,1.00098 c -0.56056,0.65399 -0.89421,1.62827 -1.00098,2.92285 l -4.26416,-0.88086 c 0.44043,-2.6826 1.30127,-4.63116 2.58252,-5.84571 c 1.28124,-1.21449 2.89615,-1.82174 4.84473,-1.82177 c 2.18879,3e-5 3.92381,0.78079 5.20507,2.34228 c 1.29459,1.56155 1.94188,3.2899 1.9419,5.18506 c -2e-5,1.28127 -0.29364,2.43573 -0.88086,3.46338 c -0.57391,1.02769 -1.44142,1.92856 -2.60254,2.70264 c 1.34797,0.36036 2.44237,1.15447 3.2832,2.38232 c 0.85415,1.22788 1.28124,2.76271 1.28125,4.60449 c -1e-5,2.68263 -0.80079,4.90479 -2.40234,6.66651 c -1.58823,1.74837 -3.48341,2.62255 -5.68555,2.62256 c -2.10873,-1e-5 -3.89714,-0.74073 -5.36523,-2.22217 c -1.45476,-1.48144 -2.30225,-3.50342 -2.54248,-6.06592"
|
||||
id="path21622"
|
||||
inkscape:connector-curvature="0" />
|
||||
</g>
|
||||
<path
|
||||
sodipodi:nodetypes="cc"
|
||||
style="display:inline;fill:none;stroke:#1f4697;stroke-width:5.61390018;stroke-linecap:butt;stroke-linejoin:round"
|
||||
inkscape:connector-curvature="0"
|
||||
d="M 388.93975,203.58874 L 431.34,203.43994"
|
||||
id="path8856-5-47-7" />
|
||||
<path
|
||||
id="path22050-39"
|
||||
d="m 388.93975,233.51434 l 42.77912,0"
|
||||
inkscape:connector-curvature="0"
|
||||
style="display:inline;fill:none;stroke:#7a00ff;stroke-width:5.61390018;stroke-linecap:butt;stroke-linejoin:round;stroke-opacity:1"
|
||||
sodipodi:nodetypes="cc" />
|
||||
<path
|
||||
sodipodi:nodetypes="cc"
|
||||
style="display:inline;fill:none;stroke:#fac204;stroke-width:5.61399984;stroke-linecap:butt;stroke-linejoin:round;stroke-miterlimit:4;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 388.93975,211.51434 l 42.62432,0"
|
||||
id="path8856-5-1-4-3" />
|
||||
<path
|
||||
sodipodi:nodetypes="cc"
|
||||
style="display:inline;fill:none;stroke:#32a304;stroke-width:5.61399984;stroke-linecap:butt;stroke-linejoin:round;stroke-miterlimit:4;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 388.93975,218.51734 l 42.46472,-0.006"
|
||||
id="path8856-5-1-7-5-2" />
|
||||
<path
|
||||
sodipodi:nodetypes="cc"
|
||||
style="display:inline;fill:none;stroke:#ec6004;stroke-width:5.61390018;stroke-linecap:butt;stroke-linejoin:round"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 388.93975,226.51434 l 42.77912,0"
|
||||
id="path8856-5-1-7-1-7-2" />
|
||||
</g>
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="layer55"
|
||||
inkscape:label="cc-srxl"
|
||||
style="display:none"
|
||||
sodipodi:insensitive="true">
|
||||
<g
|
||||
style="display:inline"
|
||||
id="cc-srxl"
|
||||
transform="matrix(0,0.4,-0.4,0,929.4684,-117.45414)">
|
||||
<path
|
||||
id="path9857-8-8-1-1-4"
|
||||
id="path9857-8-8-1-1-4-0"
|
||||
d="m 1430.6302,1592 c -5.97,64.9 57.0596,195.8293 232.2275,97.9523"
|
||||
stroke-miterlimit="4"
|
||||
inkscape:connector-curvature="0"
|
||||
@ -17828,31 +18416,31 @@
|
||||
sodipodi:nodetypes="ccc"
|
||||
style="fill:none;stroke:#ec6004;stroke-width:15.29999924;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 1392.571,1323.8556 l 0,-286.8032 l -291.0357,0"
|
||||
id="path8856-5-1-7-1-9-5-4-3-7" />
|
||||
d="m 1392.571,1323.8556 l 0,-286.8032 l -283.5357,0"
|
||||
id="path8856-5-1-7-1-9-5-4-3-7-0" />
|
||||
<path
|
||||
sodipodi:nodetypes="ccc"
|
||||
style="fill:none;stroke:#d81900;stroke-width:15.29999924;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 1362.571,1323.8556 l -7e-4,-251.8944 l -261.035,0.1823"
|
||||
id="path8856-1-2-1-9-0-9" />
|
||||
d="m 1362.571,1323.8556 l -7e-4,-251.8944 l -253.535,0.1823"
|
||||
id="path8856-1-2-1-9-0-9-7" />
|
||||
<path
|
||||
sodipodi:nodetypes="ccc"
|
||||
style="fill:none;stroke:#000000;stroke-width:15.29999924;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 1347.571,1323.8556 l 0,-236.8032 l -246.0357,0"
|
||||
id="path8856-1-5-7-7-2-9-3" />
|
||||
d="m 1347.571,1323.8556 l 0,-236.8032 l -238.5357,0"
|
||||
id="path8856-1-5-7-7-2-9-3-2" />
|
||||
<path
|
||||
sodipodi:nodetypes="cc"
|
||||
style="fill:none;stroke:#777777;stroke-width:14.5;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
stroke-miterlimit="4"
|
||||
d="m 1308.744,1592 c 5.97,64.9 -57.0596,195.8293 -232.2275,97.9523"
|
||||
id="path21749-5" />
|
||||
id="path21749-5-7" />
|
||||
<rect
|
||||
rx="11.5"
|
||||
id="rect8853-6-8-6-6-4"
|
||||
style="color:#000000;fill:url(#linearGradient26963);fill-rule:nonzero;stroke:#000000;stroke-width:5.76999998;stroke-miterlimit:4;stroke-dasharray:none;enable-background:accumulate"
|
||||
id="rect8853-6-8-6-6-4-6"
|
||||
style="color:#000000;fill:url(#linearGradient38759);fill-rule:nonzero;stroke:#000000;stroke-width:5.76999998;stroke-miterlimit:4;stroke-dasharray:none;enable-background:accumulate"
|
||||
ry="11.5"
|
||||
height="272"
|
||||
width="237"
|
||||
@ -17861,201 +18449,248 @@
|
||||
x="1250" />
|
||||
<g
|
||||
style="font-style:normal;font-weight:normal;font-size:100px;line-height:125%;font-family:Sans;text-align:center;letter-spacing:0px;word-spacing:0px;text-anchor:middle;fill:#000000"
|
||||
id="text4849-5-9-2-5"
|
||||
id="text4849-5-9-2-5-5"
|
||||
transform="matrix(0,-1,1,0,-97.5,2824.5)">
|
||||
<path
|
||||
d="m 1337.2402,1484.8574 l 0,3.8477 q -2.2461,-1.0742 -4.2382,-1.6016 q -1.9922,-0.5273 -3.8477,-0.5273 q -3.2227,0 -4.9805,1.25 q -1.7383,1.25 -1.7383,3.5547 q 0,1.9336 1.1524,2.9296 q 1.1719,0.9766 4.4141,1.5821 l 2.3828,0.4883 q 4.414,0.8398 6.5039,2.9687 q 2.1093,2.1094 2.1093,5.6641 q 0,4.2383 -2.8515,6.4258 q -2.832,2.1875 -8.3203,2.1875 q -2.0703,0 -4.4141,-0.4688 q -2.3242,-0.4687 -4.8242,-1.3867 l 0,-4.0625 q 2.4023,1.3476 4.707,2.0312 q 2.3047,0.6836 4.5313,0.6836 q 3.3789,0 5.2148,-1.3281 q 1.836,-1.3281 1.836,-3.7891 q 0,-2.1484 -1.3282,-3.3593 q -1.3086,-1.211 -4.3164,-1.8164 l -2.4023,-0.4688 q -4.4141,-0.8789 -6.3867,-2.7539 q -1.9727,-1.875 -1.9727,-5.2148 q 0,-3.8672 2.7148,-6.0938 q 2.7344,-2.2266 7.5196,-2.2266 q 2.0508,0 4.1797,0.3711 q 2.1289,0.3711 4.3554,1.1133 z"
|
||||
style="font-size:40px;text-align:center;text-anchor:middle;fill:#ffffff"
|
||||
id="path21770-9"
|
||||
id="path21770-9-1"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
d="m 1358.9785,1499.3887 q 1.2695,0.4297 2.461,1.8359 q 1.2109,1.4063 2.4218,3.8672 l 4.0039,7.9687 l -4.2382,0 l -3.7305,-7.4804 q -1.4453,-2.9297 -2.8125,-3.8867 q -1.3477,-0.9571 -3.6914,-0.9571 l -4.2969,0 l 0,12.3242 l -3.9453,0 l 0,-29.1601 l 8.9062,0 q 5,0 7.461,2.0898 q 2.4609,2.0899 2.4609,6.3086 q 0,2.7539 -1.289,4.5703 q -1.2696,1.8164 -3.711,2.5196 z m -9.8828,-12.2461 l 0,10.3515 l 4.9609,0 q 2.8516,0 4.2969,-1.3086 q 1.4649,-1.3281 1.4649,-3.8867 q 0,-2.5586 -1.4649,-3.8476 q -1.4453,-1.3086 -4.2969,-1.3086 l -4.9609,0 z"
|
||||
style="font-size:40px;text-align:center;text-anchor:middle;fill:#ffffff"
|
||||
id="path21772-3"
|
||||
id="path21772-3-1"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
d="m 1371.5566,1483.9004 l 4.2383,0 l 7.2461,10.8398 l 7.2852,-10.8398 l 4.2383,0 l -9.375,14.0039 l 10,15.1562 l -4.2383,0 l -8.2032,-12.4023 l -8.2617,12.4023 l -4.2578,0 l 10.4102,-15.5664 l -9.0821,-13.5937 z"
|
||||
style="font-size:40px;text-align:center;text-anchor:middle;fill:#ffffff"
|
||||
id="path21774-4"
|
||||
id="path21774-4-7"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
d="m 1400.3848,1483.9004 l 3.9453,0 l 0,25.8398 l 14.1992,0 l 0,3.3203 l -18.1445,0 l 0,-29.1601 z"
|
||||
style="font-size:40px;text-align:center;text-anchor:middle;fill:#ffffff"
|
||||
id="path21776-8"
|
||||
id="path21776-8-9"
|
||||
inkscape:connector-curvature="0" />
|
||||
</g>
|
||||
<g
|
||||
style="font-style:normal;font-variant:normal;font-weight:bold;font-stretch:normal;font-size:37.7733078px;line-height:125%;font-family:Arial;-inkscape-font-specification:'Sans Bold';letter-spacing:0px;word-spacing:0px;display:inline;fill:#ffffff;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
id="text20525-8"
|
||||
id="text20525-8-7"
|
||||
transform="matrix(0,-1,1,0,-68.75,2824.5001)">
|
||||
<path
|
||||
d="m 1264.1993,1413.0389 l 0,-27.0389 l 8.1707,0 l 4.9061,18.444 l 4.8507,-18.444 l 8.1892,0 l 0,27.0389 l -5.0721,0 l 0,-21.2843 l -5.3672,21.2843 l -5.2566,0 l -5.3487,-21.2843 l 0,21.2843 l -5.0721,0 z"
|
||||
id="path21779-0"
|
||||
id="path21779-0-0"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
d="m 1295.7385,1386 l 5.4594,0 l 0,14.6446 q 0,3.4859 0.2029,4.5188 q 0.3505,1.6599 1.66,2.6743 q 1.328,0.996 3.615,0.996 q 2.324,0 3.5044,-0.9406 q 1.1804,-0.9591 1.4202,-2.3424 q 0.2397,-1.3833 0.2397,-4.5926 l 0,-14.9581 l 5.4595,0 l 0,14.2019 q 0,4.8692 -0.4427,6.8796 q -0.4427,2.0104 -1.6415,3.3937 q -1.1804,1.3833 -3.1724,2.2133 q -1.9919,0.8115 -5.2012,0.8115 q -3.8732,0 -5.8836,-0.8853 q -1.992,-0.9037 -3.154,-2.3239 q -1.1619,-1.4386 -1.5308,-3.0064 q -0.5349,-2.3239 -0.5349,-6.8612 l 0,-14.4232 z"
|
||||
id="path21781-9"
|
||||
id="path21781-9-0"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
d="m 1323.2201,1413.0389 l 0,-26.8175 l 5.4594,0 l 0,22.2619 l 13.5748,0 l 0,4.5556 l -19.0342,0 z"
|
||||
id="path21783-1"
|
||||
id="path21783-1-8"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
d="m 1349.4474,1413.0389 l 0,-22.4647 l -8.0231,0 l 0,-4.5742 l 21.4873,0 l 0,4.5742 l -8.0047,0 l 0,22.4647 l -5.4595,0 z"
|
||||
id="path21785-1"
|
||||
id="path21785-1-0"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
d="m 1366.213,1413.0389 l 0,-27.0389 l 5.4595,0 l 0,27.0389 l -5.4595,0 z"
|
||||
id="path21787-2"
|
||||
id="path21787-2-4"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
d="m 1376.8552,1413.0389 l 0,-27.0389 l 8.7609,0 q 4.9799,0 6.4923,0.4058 q 2.3239,0.6087 3.8917,2.6559 q 1.5677,2.0289 1.5677,5.2566 q 0,2.4899 -0.9037,4.1868 q -0.9038,1.6968 -2.3055,2.6743 q -1.3833,0.9591 -2.822,1.2727 q -1.955,0.3873 -5.6623,0.3873 l -3.5597,0 l 0,10.1995 l -5.4594,0 z m 5.4594,-22.4647 l 0,7.6727 l 2.988,0 q 3.2277,0 4.3159,-0.4243 q 1.0882,-0.4242 1.6968,-1.3279 q 0.6271,-0.9038 0.6271,-2.1026 q 0,-1.4756 -0.8669,-2.4346 q -0.8668,-0.9591 -2.1948,-1.1989 q -0.9775,-0.1844 -3.9286,-0.1844 l -2.6375,0 z"
|
||||
id="path21789-4"
|
||||
id="path21789-4-5"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
d="m 1402.2342,1413.0389 l 0,-26.8175 l 5.4594,0 l 0,22.2619 l 13.5748,0 l 0,4.5556 l -19.0342,0 z"
|
||||
id="path21791-4"
|
||||
id="path21791-4-3"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
d="m 1425.1785,1413.0389 l 0,-27.0389 l 20.0486,0 l 0,4.5742 l -14.5892,0 l 0,5.9943 l 13.5748,0 l 0,4.5556 l -13.5748,0 l 0,7.3592 l 15.1057,0 l 0,4.5556 l -20.5651,0 z"
|
||||
id="path21793-5"
|
||||
id="path21793-5-1"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
d="m 1447.6617,1413.0389 l 9.2405,-14.1096 L 1448.5286,1386 l 6.3816,0 l 5.4226,8.6872 l 5.3118,-8.6872 l 6.3263,0 l -8.4104,13.1322 l 9.2404,13.9067 l -6.5845,0 l -5.9943,-9.3511 l -6.0128,9.3511 l -6.5476,0 z"
|
||||
id="path21795-4"
|
||||
id="path21795-4-4"
|
||||
inkscape:connector-curvature="0" />
|
||||
</g>
|
||||
</g>
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="layer54"
|
||||
inkscape:label="revo-ppm"
|
||||
id="layer56"
|
||||
inkscape:label="cc-sbus"
|
||||
style="display:none"
|
||||
sodipodi:insensitive="true">
|
||||
<g
|
||||
transform="matrix(0.4,0,0,0.4,50.474996,-98.709115)"
|
||||
id="cc-sbus"
|
||||
style="display:inline">
|
||||
<path
|
||||
style="fill:none;stroke:#777777;stroke-width:14.5;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
stroke-miterlimit="4"
|
||||
d="m 1487.3483,1530 c 50.3,-1.09 115,5.3 155,36.6"
|
||||
id="path11327" />
|
||||
<path
|
||||
style="fill:none;stroke:#777777;stroke-width:14.5;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
stroke-miterlimit="4"
|
||||
d="m 1250,1530 c -64.9,-5.97 -121,14.3 -171,40.7"
|
||||
id="path11329" />
|
||||
<path
|
||||
id="path11331"
|
||||
d="m 1359.9896,1320.8001 l 0,-258.6274"
|
||||
inkscape:connector-curvature="0"
|
||||
style="display:inline;fill:none;stroke:#d81900;stroke-width:15.29999924;stroke-linecap:butt;stroke-linejoin:round;stroke-miterlimit:4;stroke-dasharray:none"
|
||||
sodipodi:nodetypes="cc" />
|
||||
<path
|
||||
id="path11333"
|
||||
d="m 1389.9896,1320.8001 l 0,-258.6274"
|
||||
inkscape:connector-curvature="0"
|
||||
style="display:inline;fill:none;stroke:#ec6004;stroke-width:15.29999924;stroke-linecap:butt;stroke-linejoin:round;stroke-miterlimit:4;stroke-dasharray:none"
|
||||
sodipodi:nodetypes="cc" />
|
||||
<path
|
||||
id="path11335"
|
||||
d="m 1346.2717,1320.8001 l 4e-4,-258.6274"
|
||||
inkscape:connector-curvature="0"
|
||||
style="display:inline;fill:none;stroke:#000000;stroke-width:15.29999924;stroke-linecap:butt;stroke-linejoin:round;stroke-miterlimit:4;stroke-dasharray:none"
|
||||
sodipodi:nodetypes="cc" />
|
||||
<rect
|
||||
x="1250"
|
||||
y="1320"
|
||||
stroke-miterlimit="4"
|
||||
width="237"
|
||||
height="272"
|
||||
ry="11.5"
|
||||
style="color:#000000;fill:url(#linearGradient38671);fill-rule:nonzero;stroke:#000000;stroke-width:5.76999998;stroke-miterlimit:4;stroke-dasharray:none;enable-background:accumulate"
|
||||
id="rect11337"
|
||||
rx="11.5" />
|
||||
<text
|
||||
sodipodi:linespacing="125%"
|
||||
xml:space="preserve"
|
||||
x="1367.399"
|
||||
y="1415.5746"
|
||||
font-style="normal"
|
||||
line-height="125%"
|
||||
font-size="40px"
|
||||
font-weight="normal"
|
||||
style="font-style:normal;font-weight:normal;font-size:40px;line-height:125%;font-family:Sans;text-align:center;letter-spacing:0px;word-spacing:0px;text-anchor:middle;fill:#ffffff"
|
||||
id="text11339"><tspan
|
||||
x="1367.399"
|
||||
y="1415.5746"
|
||||
id="tspan11341">Futaba</tspan></text>
|
||||
<text
|
||||
sodipodi:linespacing="125%"
|
||||
font-style="normal"
|
||||
x="1368.0533"
|
||||
y="1500.4048"
|
||||
line-height="125%"
|
||||
font-size="100px"
|
||||
xml:space="preserve"
|
||||
font-weight="normal"
|
||||
style="font-style:normal;font-weight:normal;font-size:100px;line-height:125%;font-family:Sans;text-align:center;letter-spacing:0px;word-spacing:0px;text-anchor:middle;fill:#000000"
|
||||
id="text11343"><tspan
|
||||
x="1368.0533"
|
||||
y="1500.4048"
|
||||
font-size="40px"
|
||||
style="font-size:40px;text-align:center;text-anchor:middle;fill:#ffffff"
|
||||
id="tspan11345">S-Bus</tspan></text>
|
||||
</g>
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="layer57"
|
||||
inkscape:label="cc-satellite"
|
||||
style="display:none"
|
||||
sodipodi:insensitive="true">
|
||||
<g
|
||||
style="display:inline"
|
||||
id="revo-ppm"
|
||||
transform="translate(1.0000001,-19)">
|
||||
id="cc-satellite"
|
||||
transform="matrix(0.4,0,0,0.4,-131.04473,-97.93132)">
|
||||
<path
|
||||
id="path8856-1-8-4-9-0"
|
||||
d="m 309.08544,189.42619 l 121.38331,-0.484"
|
||||
id="path9857-8"
|
||||
d="m 1250,1530 c -64.9,-5.97 -121,14.3 -171,40.7"
|
||||
stroke-miterlimit="4"
|
||||
inkscape:connector-curvature="0"
|
||||
style="display:inline;fill:none;stroke:#ec1d00;stroke-width:5.61390018;stroke-linecap:butt;stroke-linejoin:miter"
|
||||
sodipodi:nodetypes="cc" />
|
||||
style="fill:none;stroke:#777777;stroke-width:14.5;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none" />
|
||||
<path
|
||||
id="path8856-1-5-8-4-3-1"
|
||||
d="m 309.08544,183.82619 l 121.38331,-0.2056"
|
||||
id="path9857-8-5"
|
||||
d="m 1490,1530 c 50.3,-1.09 115,5.3 155,36.6"
|
||||
stroke-miterlimit="4"
|
||||
inkscape:connector-curvature="0"
|
||||
style="display:inline;fill:none;stroke:#000000;stroke-width:5.61390018;stroke-linecap:butt;stroke-linejoin:miter"
|
||||
sodipodi:nodetypes="cc" />
|
||||
style="fill:none;stroke:#777777;stroke-width:14.5;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none" />
|
||||
<path
|
||||
id="path8856-1-3-1-3-5-6"
|
||||
d="m 309.08544,195.62619 l 60.69165,-0.206 l 0.34583,16.897 l 60.34583,-0.103"
|
||||
sodipodi:nodetypes="cccc"
|
||||
style="fill:none;stroke:#1f4697;stroke-width:15.29999924;stroke-linecap:butt;stroke-linejoin:round;stroke-miterlimit:4;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
style="display:inline;fill:none;stroke:#ffffff;stroke-width:5.17476749;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
sodipodi:nodetypes="cccc" />
|
||||
d="m 1371.2889,1318.8556 l 0,-124.7594 l 225,0 l 0,-133.868"
|
||||
id="path8856-5-6" />
|
||||
<path
|
||||
sodipodi:nodetypes="cc"
|
||||
style="fill:none;stroke:#1f4697;stroke-width:5.61390018;stroke-linecap:butt;stroke-linejoin:round"
|
||||
sodipodi:nodetypes="cccc"
|
||||
style="fill:none;stroke:#d81900;stroke-width:15.29999924;stroke-linecap:butt;stroke-linejoin:round;stroke-miterlimit:4;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 394.76407,219.75113 l 35.79968,-0.0948"
|
||||
id="path8856-5-7-0" />
|
||||
d="m 1356.2889,1318.8556 l 0,-139.7594 l 225,0 l 0,-118.868"
|
||||
id="path8856-1-2" />
|
||||
<path
|
||||
sodipodi:nodetypes="cc"
|
||||
style="fill:none;stroke:#fac204;stroke-width:5.61399984;stroke-linecap:butt;stroke-linejoin:round;stroke-miterlimit:4;stroke-dasharray:none"
|
||||
sodipodi:nodetypes="cccc"
|
||||
style="fill:none;stroke:#ec6004;stroke-width:15.29999924;stroke-linecap:butt;stroke-linejoin:round;stroke-miterlimit:4;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 395.16407,226.51434 l 35.39968,0"
|
||||
id="path8856-5-1-81-9" />
|
||||
d="m 1386.2889,1318.8556 l 0,-109.7594 l 225.5,10e-5 l 0,-148.8681"
|
||||
id="path8856-5-1-7-1-9" />
|
||||
<path
|
||||
sodipodi:nodetypes="cc"
|
||||
style="fill:none;stroke:#32a304;stroke-width:5.61399984;stroke-linecap:butt;stroke-linejoin:round;stroke-miterlimit:4;stroke-dasharray:none"
|
||||
sodipodi:nodetypes="cccc"
|
||||
style="fill:none;stroke:#000000;stroke-width:15.30000019;stroke-linecap:butt;stroke-linejoin:round;stroke-miterlimit:4;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 395.80447,233.97173 l 34.6,-0.006"
|
||||
id="path8856-5-1-7-8-5" />
|
||||
<path
|
||||
sodipodi:nodetypes="cc"
|
||||
style="fill:none;stroke:#ec6004;stroke-width:5.61390018;stroke-linecap:butt;stroke-linejoin:round"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 396.284,241.51434 l 34.43487,0"
|
||||
id="path8856-5-1-7-1-5-2" />
|
||||
<path
|
||||
style="display:inline;fill:none;stroke:#777777;stroke-width:5.80000019;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="M 131.51628,280.89645 C 99.179438,276.41438 56.116118,293.77498 44.942858,345.61434"
|
||||
id="path9857-3-9-2-4" />
|
||||
<path
|
||||
style="display:inline;fill:none;stroke:#6b6b6b;stroke-width:1.21428466;stroke-linecap:butt;stroke-linejoin:miter"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 309.08544,198.82619 l 57.69165,-0.139 l 0.34583,16.9305 l 63.34583,-0.0695"
|
||||
id="path8856-4-4-3-0"
|
||||
sodipodi:nodetypes="cccc" />
|
||||
<path
|
||||
style="display:inline;fill:none;stroke:#6b6b6b;stroke-width:1.21428466;stroke-linecap:butt;stroke-linejoin:miter"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 309.08544,191.82619 l 63.69165,-0.139 l 0.34583,16.9305 l 57.34583,-0.0695"
|
||||
id="path8856-4-4-3-4-5"
|
||||
sodipodi:nodetypes="cccc" />
|
||||
<path
|
||||
sodipodi:nodetypes="sssccccssssss"
|
||||
inkscape:connector-curvature="0"
|
||||
id="rect8853-0-8-3-8"
|
||||
d="m 136.31357,163.05542 l 187.03999,0 c 3.58992,0 6.48,2.89008 6.48,6.48 l 0,8.84015 l -6,0 l 0,122.36001 l 6.00044,0 l -4.4e-4,10.23984 c -1.5e-4,3.58992 -2.89008,6.48 -6.48,6.48 l -187.03999,0 c -3.58993,0 -6.48001,-2.89008 -6.48001,-6.48 l 0,-141.44 c 0,-3.58992 2.89008,-6.48 6.48001,-6.48 z"
|
||||
style="color:#000000;display:inline;fill:url(#linearGradient13565-9-6);fill-rule:nonzero;stroke:#000000;stroke-width:3.09599996;stroke-miterlimit:4;stroke-dasharray:none;enable-background:accumulate" />
|
||||
<g
|
||||
transform="translate(-93.48662,-127.74067)"
|
||||
id="text9734-24-8-2-2"
|
||||
style="font-style:normal;font-variant:normal;font-weight:bold;font-stretch:normal;font-size:22.39999962px;line-height:125%;font-family:Sans;text-align:start;letter-spacing:0px;word-spacing:0px;writing-mode:lr-tb;text-anchor:start;display:inline;fill:#ffffff">
|
||||
<path
|
||||
id="path13900-3-4"
|
||||
d="m 268.82831,303.23718 l 6.98907,0 c 2.07811,10e-6 3.67134,0.46303 4.77968,1.38906 c 1.11561,0.91876 1.67343,2.23126 1.67344,3.9375 c -1e-5,1.71355 -0.55783,3.03334 -1.67344,3.95937 c -1.10834,0.91876 -2.70157,1.37813 -4.77968,1.37813 l -2.77813,0 l 0,5.66562 l -4.21094,0 l 0,-16.32968 m 4.21094,3.05156 l 0,4.56094 l 2.32969,0 c 0.81666,1e-5 1.44738,-0.19687 1.89219,-0.59063 c 0.44478,-0.40103 0.66717,-0.96613 0.66718,-1.69531 c -1e-5,-0.72916 -0.2224,-1.29061 -0.66718,-1.68438 c -0.44481,-0.39373 -1.07553,-0.59061 -1.89219,-0.59062 l -2.32969,0"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
id="path13902-9-6"
|
||||
d="m 285.23456,303.23718 l 6.98907,0 c 2.07811,10e-6 3.67134,0.46303 4.77968,1.38906 c 1.11561,0.91876 1.67343,2.23126 1.67344,3.9375 c -1e-5,1.71355 -0.55783,3.03334 -1.67344,3.95937 c -1.10834,0.91876 -2.70157,1.37813 -4.77968,1.37813 l -2.77813,0 l 0,5.66562 l -4.21094,0 l 0,-16.32968 m 4.21094,3.05156 l 0,4.56094 l 2.32969,0 c 0.81666,1e-5 1.44738,-0.19687 1.89219,-0.59063 c 0.44478,-0.40103 0.66717,-0.96613 0.66718,-1.69531 c -1e-5,-0.72916 -0.2224,-1.29061 -0.66718,-1.68438 c -0.44481,-0.39373 -1.07553,-0.59061 -1.89219,-0.59062 l -2.32969,0"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
id="path13904-1-3"
|
||||
d="m 301.64081,303.23718 l 5.35938,0 l 3.71875,8.73906 l 3.74062,-8.73906 l 5.34844,0 l 0,16.32968 l -3.98125,0 l 0,-11.94375 l -3.7625,8.80469 l -2.66875,0 l -3.7625,-8.80469 l 0,11.94375 l -3.99219,0 l 0,-16.32968"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
id="path13906-1-0"
|
||||
d="m 343.10487,303.75124 l 0,3.45625 c -0.89688,-0.40103 -1.77188,-0.70363 -2.625,-0.90781 c -0.85313,-0.20416 -1.65886,-0.30624 -2.41718,-0.30625 c -1.00626,1e-5 -1.75001,0.13855 -2.23125,0.41562 c -0.48126,0.2771 -0.72188,0.70731 -0.72188,1.29063 c 0,0.43751 0.16041,0.78022 0.48125,1.02812 c 0.32812,0.24064 0.91875,0.44845 1.77188,0.62344 l 1.79375,0.36094 c 1.81561,0.36459 3.10623,0.91876 3.87187,1.6625 c 0.76561,0.74375 1.14843,1.80104 1.14844,3.17187 c -1e-5,1.80105 -0.53595,3.14271 -1.60781,4.025 c -1.0646,0.875 -2.69428,1.3125 -4.88906,1.3125 c -1.03543,0 -2.07449,-0.0984 -3.11719,-0.29531 c -1.04271,-0.19688 -2.08542,-0.48854 -3.12813,-0.875 l 0,-3.55469 c 1.04271,0.55417 2.04896,0.97344 3.01875,1.25781 c 0.97708,0.27709 1.9177,0.41563 2.82188,0.41563 c 0.91874,0 1.62238,-0.15312 2.11094,-0.45938 c 0.48853,-0.30624 0.7328,-0.74374 0.73281,-1.3125 c -1e-5,-0.51041 -0.16772,-0.90416 -0.50313,-1.18125 c -0.32813,-0.27707 -0.98803,-0.52499 -1.97968,-0.74375 l -1.62969,-0.36093 c -1.63334,-0.35 -2.82917,-0.90781 -3.5875,-1.67344 c -0.75105,-0.76562 -1.12657,-1.79739 -1.12656,-3.09531 c -10e-6,-1.62603 0.52499,-2.87655 1.575,-3.75157 c 1.04999,-0.87498 2.55936,-1.31248 4.52812,-1.3125 c 0.89687,2e-5 1.81926,0.0693 2.76719,0.20782 c 0.9479,0.13126 1.92863,0.33178 2.94218,0.60156"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
id="path13908-3-7"
|
||||
d="m 347.70957,307.31686 l 3.91562,0 l 0,12.25 l -3.91562,0 l 0,-12.25 m 0,-4.76875 l 3.91562,0 l 0,3.19375 l -3.91562,0 l 0,-3.19375"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
id="path13910-5-7"
|
||||
d="m 363.74394,317.48874 c -0.5396,0.71458 -1.13387,1.23958 -1.78281,1.575 c -0.64897,0.33542 -1.40001,0.50312 -2.25313,0.50312 c -1.4948,0 -2.73073,-0.58697 -3.70781,-1.76093 c -0.97709,-1.18125 -1.46563,-2.68333 -1.46563,-4.50625 c 0,-1.8302 0.48854,-3.32864 1.46563,-4.49532 c 0.97708,-1.17394 2.21301,-1.76092 3.70781,-1.76093 c 0.85312,10e-6 1.60416,0.16772 2.25313,0.50312 c 0.64894,0.33543 1.24321,0.86408 1.78281,1.58594 l 0,-1.81563 l 3.9375,0 l 0,11.01407 c -2e-5,1.96875 -0.62345,3.47083 -1.87032,4.50625 c -1.23959,1.0427 -3.04063,1.56405 -5.40312,1.56406 c -0.76563,-10e-6 -1.50573,-0.0583 -2.22031,-0.175 c -0.71459,-0.11667 -1.43282,-0.29532 -2.15469,-0.53594 l 0,-3.05156 c 0.68541,0.39375 1.35625,0.68541 2.0125,0.875 c 0.65624,0.19687 1.31614,0.29531 1.97969,0.29531 c 1.28332,0 2.22395,-0.28073 2.82187,-0.84219 c 0.59791,-0.56146 0.89687,-1.4401 0.89688,-2.63593 l 0,-0.84219 m -2.58125,-7.62344 c -0.80938,1e-5 -1.44011,0.29897 -1.89219,0.89688 c -0.45209,0.59792 -0.67813,1.44375 -0.67812,2.5375 c -10e-6,1.12292 0.21874,1.97604 0.65625,2.55937 c 0.43749,0.57605 1.07551,0.86407 1.91406,0.86406 c 0.81666,10e-6 1.45103,-0.29895 1.90312,-0.89687 c 0.45208,-0.59791 0.67812,-1.4401 0.67813,-2.52656 c -1e-5,-1.09375 -0.22605,-1.93958 -0.67813,-2.5375 c -0.45209,-0.59791 -1.08646,-0.89687 -1.90312,-0.89688"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
id="path13912-3-0"
|
||||
d="m 383.78144,312.10749 l 0,7.45937 l -3.9375,0 l 0,-1.21406 l 0,-4.49531 c -10e-6,-1.05729 -0.0255,-1.78645 -0.0766,-2.1875 c -0.0438,-0.40103 -0.12397,-0.69635 -0.24063,-0.88594 c -0.15313,-0.2552 -0.36095,-0.45207 -0.62344,-0.59062 c -0.26251,-0.14583 -0.56146,-0.21874 -0.89687,-0.21875 c -0.81668,1e-5 -1.45834,0.31719 -1.925,0.95156 c -0.46667,0.62709 -0.70001,1.49844 -0.7,2.61406 l 0,6.02656 l -3.91563,0 l 0,-12.25 l 3.91563,0 l 0,1.79375 c 0.59062,-0.71457 1.2177,-1.23957 1.88125,-1.575 c 0.66353,-0.34269 1.39634,-0.51405 2.19844,-0.51406 c 1.41457,1e-5 2.48644,0.43387 3.21562,1.30156 c 0.73645,0.86772 1.10467,2.12918 1.10469,3.78438"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
id="path13914-2-8"
|
||||
d="m 392.92519,314.05436 c -0.81667,1e-5 -1.43282,0.13855 -1.84844,0.41563 c -0.40834,0.27709 -0.6125,0.68542 -0.6125,1.225 c 0,0.49584 0.16406,0.88594 0.49219,1.17031 c 0.33541,0.27709 0.79843,0.41563 1.38906,0.41563 c 0.73645,0 1.35624,-0.2625 1.85938,-0.7875 c 0.50311,-0.53229 0.75467,-1.19583 0.75468,-1.99063 l 0,-0.44844 l -2.03437,0 m 5.98281,-1.47656 l 0,6.98906 l -3.94844,0 l 0,-1.81562 c -0.525,0.74375 -1.11563,1.28698 -1.77187,1.62969 c -0.65626,0.33541 -1.45469,0.50312 -2.39531,0.50312 c -1.26876,0 -2.30053,-0.36823 -3.09532,-1.10469 c -0.7875,-0.74374 -1.18125,-1.70624 -1.18125,-2.8875 c 0,-1.43645 0.49219,-2.49009 1.47657,-3.16093 c 0.99166,-0.67083 2.54478,-1.00625 4.65937,-1.00625 l 2.30781,0 l 0,-0.30625 c -1e-5,-0.61979 -0.24428,-1.07187 -0.73281,-1.35625 c -0.48855,-0.29166 -1.25053,-0.43749 -2.28594,-0.4375 c -0.83854,10e-6 -1.61875,0.0839 -2.34062,0.25156 c -0.72188,0.16772 -1.39271,0.41928 -2.0125,0.75469 l 0,-2.98594 c 0.83854,-0.20416 1.68072,-0.35728 2.52656,-0.45938 c 0.84583,-0.10936 1.69166,-0.16405 2.5375,-0.16406 c 2.20937,1e-5 3.80259,0.43751 4.77969,1.3125 c 0.98436,0.86772 1.47655,2.2823 1.47656,4.24375"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
id="path13916-6-8"
|
||||
d="m 402.57206,302.54811 l 3.91563,0 l 0,17.01875 l -3.91563,0 l 0,-17.01875"
|
||||
inkscape:connector-curvature="0" />
|
||||
</g>
|
||||
<path
|
||||
id="path22050-3"
|
||||
d="m 397.284,248.51434 l 33.43487,0"
|
||||
inkscape:connector-curvature="0"
|
||||
style="display:inline;fill:none;stroke:#7a00ff;stroke-width:5.61390018;stroke-linecap:butt;stroke-linejoin:round;stroke-opacity:1"
|
||||
sodipodi:nodetypes="cc" />
|
||||
d="m 1342.571,1318.8556 l 0,-154.7594 l 223.7179,0 l 0,-103.868"
|
||||
id="path8856-1-5-7" />
|
||||
<rect
|
||||
rx="11.5"
|
||||
id="rect8853-6"
|
||||
style="color:#000000;fill:url(#linearGradient38819);fill-rule:nonzero;stroke:#000000;stroke-width:5.76999998;stroke-miterlimit:4;stroke-dasharray:none;enable-background:accumulate"
|
||||
ry="11.5"
|
||||
height="272"
|
||||
width="237"
|
||||
stroke-miterlimit="4"
|
||||
y="1320"
|
||||
x="1250" />
|
||||
<text
|
||||
id="text9963"
|
||||
style="font-style:normal;font-weight:normal;font-size:40px;line-height:125%;font-family:Sans;text-align:center;letter-spacing:0px;word-spacing:0px;text-anchor:middle;fill:#ffffff"
|
||||
font-weight="normal"
|
||||
font-size="40px"
|
||||
line-height="125%"
|
||||
font-style="normal"
|
||||
y="1415.5746"
|
||||
x="1368.6637"
|
||||
xml:space="preserve"
|
||||
sodipodi:linespacing="125%"><tspan
|
||||
id="tspan8153"
|
||||
y="1415.5746"
|
||||
x="1368.6637">Spectrum</tspan></text>
|
||||
<text
|
||||
id="text4849"
|
||||
style="font-style:normal;font-weight:normal;font-size:100px;line-height:125%;font-family:Sans;letter-spacing:0px;word-spacing:0px;fill:#000000"
|
||||
font-weight="normal"
|
||||
xml:space="preserve"
|
||||
font-size="100px"
|
||||
font-style="normal"
|
||||
y="1500.4048"
|
||||
x="1291.984"
|
||||
line-height="125%"
|
||||
sodipodi:linespacing="125%"><tspan
|
||||
id="tspan4851"
|
||||
font-size="40px"
|
||||
y="1500.4048"
|
||||
x="1291.984"
|
||||
style="font-size:40px;fill:#ffffff">Satellite</tspan></text>
|
||||
</g>
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="layer53"
|
||||
inkscape:label="revo-pwm"
|
||||
style="display:none">
|
||||
style="display:none"
|
||||
sodipodi:insensitive="true">
|
||||
<g
|
||||
style="display:inline"
|
||||
id="revo-pwm"
|
||||
@ -18278,6 +18913,250 @@
|
||||
sodipodi:nodetypes="cccc" />
|
||||
</g>
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="layer54"
|
||||
inkscape:label="revo-ppm"
|
||||
style="display:none"
|
||||
sodipodi:insensitive="true">
|
||||
<g
|
||||
style="display:inline"
|
||||
id="revo-ppm"
|
||||
transform="translate(1.0000001,-19)">
|
||||
<path
|
||||
id="path8856-1-8-4-9-0"
|
||||
d="m 309.08544,189.42619 l 121.38331,-0.484"
|
||||
inkscape:connector-curvature="0"
|
||||
style="display:inline;fill:none;stroke:#ec1d00;stroke-width:5.61390018;stroke-linecap:butt;stroke-linejoin:miter"
|
||||
sodipodi:nodetypes="cc" />
|
||||
<path
|
||||
id="path8856-1-5-8-4-3-1"
|
||||
d="m 309.08544,183.82619 l 121.38331,-0.2056"
|
||||
inkscape:connector-curvature="0"
|
||||
style="display:inline;fill:none;stroke:#000000;stroke-width:5.61390018;stroke-linecap:butt;stroke-linejoin:miter"
|
||||
sodipodi:nodetypes="cc" />
|
||||
<path
|
||||
id="path8856-1-3-1-3-5-6"
|
||||
d="m 309.08544,195.62619 l 60.69165,-0.206 l 0.34583,16.897 l 60.34583,-0.103"
|
||||
inkscape:connector-curvature="0"
|
||||
style="display:inline;fill:none;stroke:#ffffff;stroke-width:5.17476749;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
sodipodi:nodetypes="cccc" />
|
||||
<path
|
||||
sodipodi:nodetypes="cc"
|
||||
style="fill:none;stroke:#1f4697;stroke-width:5.61390018;stroke-linecap:butt;stroke-linejoin:round"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 394.76407,219.75113 l 35.79968,-0.0948"
|
||||
id="path8856-5-7-0" />
|
||||
<path
|
||||
sodipodi:nodetypes="cc"
|
||||
style="fill:none;stroke:#fac204;stroke-width:5.61399984;stroke-linecap:butt;stroke-linejoin:round;stroke-miterlimit:4;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 395.16407,226.51434 l 35.39968,0"
|
||||
id="path8856-5-1-81-9" />
|
||||
<path
|
||||
sodipodi:nodetypes="cc"
|
||||
style="fill:none;stroke:#32a304;stroke-width:5.61399984;stroke-linecap:butt;stroke-linejoin:round;stroke-miterlimit:4;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 395.80447,233.97173 l 34.6,-0.006"
|
||||
id="path8856-5-1-7-8-5" />
|
||||
<path
|
||||
sodipodi:nodetypes="cc"
|
||||
style="fill:none;stroke:#ec6004;stroke-width:5.61390018;stroke-linecap:butt;stroke-linejoin:round"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 396.284,241.51434 l 34.43487,0"
|
||||
id="path8856-5-1-7-1-5-2" />
|
||||
<path
|
||||
style="display:inline;fill:none;stroke:#777777;stroke-width:5.80000019;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="M 131.51628,280.89645 C 99.179438,276.41438 56.116118,293.77498 44.942858,345.61434"
|
||||
id="path9857-3-9-2-4" />
|
||||
<path
|
||||
style="display:inline;fill:none;stroke:#6b6b6b;stroke-width:1.21428466;stroke-linecap:butt;stroke-linejoin:miter"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 309.08544,198.82619 l 57.69165,-0.139 l 0.34583,16.9305 l 63.34583,-0.0695"
|
||||
id="path8856-4-4-3-0"
|
||||
sodipodi:nodetypes="cccc" />
|
||||
<path
|
||||
style="display:inline;fill:none;stroke:#6b6b6b;stroke-width:1.21428466;stroke-linecap:butt;stroke-linejoin:miter"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 309.08544,191.82619 l 63.69165,-0.139 l 0.34583,16.9305 l 57.34583,-0.0695"
|
||||
id="path8856-4-4-3-4-5"
|
||||
sodipodi:nodetypes="cccc" />
|
||||
<path
|
||||
sodipodi:nodetypes="sssccccssssss"
|
||||
inkscape:connector-curvature="0"
|
||||
id="rect8853-0-8-3-8"
|
||||
d="m 136.31357,163.05542 l 187.03999,0 c 3.58992,0 6.48,2.89008 6.48,6.48 l 0,8.84015 l -6,0 l 0,122.36001 l 6.00044,0 l -4.4e-4,10.23984 c -1.5e-4,3.58992 -2.89008,6.48 -6.48,6.48 l -187.03999,0 c -3.58993,0 -6.48001,-2.89008 -6.48001,-6.48 l 0,-141.44 c 0,-3.58992 2.89008,-6.48 6.48001,-6.48 z"
|
||||
style="color:#000000;display:inline;fill:url(#linearGradient13565-9-6);fill-rule:nonzero;stroke:#000000;stroke-width:3.09599996;stroke-miterlimit:4;stroke-dasharray:none;enable-background:accumulate" />
|
||||
<g
|
||||
transform="translate(-93.48662,-127.74067)"
|
||||
id="text9734-24-8-2-2"
|
||||
style="font-style:normal;font-variant:normal;font-weight:bold;font-stretch:normal;font-size:22.39999962px;line-height:125%;font-family:Sans;text-align:start;letter-spacing:0px;word-spacing:0px;writing-mode:lr-tb;text-anchor:start;display:inline;fill:#ffffff">
|
||||
<path
|
||||
id="path13900-3-4"
|
||||
d="m 268.82831,303.23718 l 6.98907,0 c 2.07811,10e-6 3.67134,0.46303 4.77968,1.38906 c 1.11561,0.91876 1.67343,2.23126 1.67344,3.9375 c -1e-5,1.71355 -0.55783,3.03334 -1.67344,3.95937 c -1.10834,0.91876 -2.70157,1.37813 -4.77968,1.37813 l -2.77813,0 l 0,5.66562 l -4.21094,0 l 0,-16.32968 m 4.21094,3.05156 l 0,4.56094 l 2.32969,0 c 0.81666,1e-5 1.44738,-0.19687 1.89219,-0.59063 c 0.44478,-0.40103 0.66717,-0.96613 0.66718,-1.69531 c -1e-5,-0.72916 -0.2224,-1.29061 -0.66718,-1.68438 c -0.44481,-0.39373 -1.07553,-0.59061 -1.89219,-0.59062 l -2.32969,0"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
id="path13902-9-6"
|
||||
d="m 285.23456,303.23718 l 6.98907,0 c 2.07811,10e-6 3.67134,0.46303 4.77968,1.38906 c 1.11561,0.91876 1.67343,2.23126 1.67344,3.9375 c -1e-5,1.71355 -0.55783,3.03334 -1.67344,3.95937 c -1.10834,0.91876 -2.70157,1.37813 -4.77968,1.37813 l -2.77813,0 l 0,5.66562 l -4.21094,0 l 0,-16.32968 m 4.21094,3.05156 l 0,4.56094 l 2.32969,0 c 0.81666,1e-5 1.44738,-0.19687 1.89219,-0.59063 c 0.44478,-0.40103 0.66717,-0.96613 0.66718,-1.69531 c -1e-5,-0.72916 -0.2224,-1.29061 -0.66718,-1.68438 c -0.44481,-0.39373 -1.07553,-0.59061 -1.89219,-0.59062 l -2.32969,0"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
id="path13904-1-3"
|
||||
d="m 301.64081,303.23718 l 5.35938,0 l 3.71875,8.73906 l 3.74062,-8.73906 l 5.34844,0 l 0,16.32968 l -3.98125,0 l 0,-11.94375 l -3.7625,8.80469 l -2.66875,0 l -3.7625,-8.80469 l 0,11.94375 l -3.99219,0 l 0,-16.32968"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
id="path13906-1-0"
|
||||
d="m 343.10487,303.75124 l 0,3.45625 c -0.89688,-0.40103 -1.77188,-0.70363 -2.625,-0.90781 c -0.85313,-0.20416 -1.65886,-0.30624 -2.41718,-0.30625 c -1.00626,1e-5 -1.75001,0.13855 -2.23125,0.41562 c -0.48126,0.2771 -0.72188,0.70731 -0.72188,1.29063 c 0,0.43751 0.16041,0.78022 0.48125,1.02812 c 0.32812,0.24064 0.91875,0.44845 1.77188,0.62344 l 1.79375,0.36094 c 1.81561,0.36459 3.10623,0.91876 3.87187,1.6625 c 0.76561,0.74375 1.14843,1.80104 1.14844,3.17187 c -1e-5,1.80105 -0.53595,3.14271 -1.60781,4.025 c -1.0646,0.875 -2.69428,1.3125 -4.88906,1.3125 c -1.03543,0 -2.07449,-0.0984 -3.11719,-0.29531 c -1.04271,-0.19688 -2.08542,-0.48854 -3.12813,-0.875 l 0,-3.55469 c 1.04271,0.55417 2.04896,0.97344 3.01875,1.25781 c 0.97708,0.27709 1.9177,0.41563 2.82188,0.41563 c 0.91874,0 1.62238,-0.15312 2.11094,-0.45938 c 0.48853,-0.30624 0.7328,-0.74374 0.73281,-1.3125 c -1e-5,-0.51041 -0.16772,-0.90416 -0.50313,-1.18125 c -0.32813,-0.27707 -0.98803,-0.52499 -1.97968,-0.74375 l -1.62969,-0.36093 c -1.63334,-0.35 -2.82917,-0.90781 -3.5875,-1.67344 c -0.75105,-0.76562 -1.12657,-1.79739 -1.12656,-3.09531 c -10e-6,-1.62603 0.52499,-2.87655 1.575,-3.75157 c 1.04999,-0.87498 2.55936,-1.31248 4.52812,-1.3125 c 0.89687,2e-5 1.81926,0.0693 2.76719,0.20782 c 0.9479,0.13126 1.92863,0.33178 2.94218,0.60156"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
id="path13908-3-7"
|
||||
d="m 347.70957,307.31686 l 3.91562,0 l 0,12.25 l -3.91562,0 l 0,-12.25 m 0,-4.76875 l 3.91562,0 l 0,3.19375 l -3.91562,0 l 0,-3.19375"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
id="path13910-5-7"
|
||||
d="m 363.74394,317.48874 c -0.5396,0.71458 -1.13387,1.23958 -1.78281,1.575 c -0.64897,0.33542 -1.40001,0.50312 -2.25313,0.50312 c -1.4948,0 -2.73073,-0.58697 -3.70781,-1.76093 c -0.97709,-1.18125 -1.46563,-2.68333 -1.46563,-4.50625 c 0,-1.8302 0.48854,-3.32864 1.46563,-4.49532 c 0.97708,-1.17394 2.21301,-1.76092 3.70781,-1.76093 c 0.85312,10e-6 1.60416,0.16772 2.25313,0.50312 c 0.64894,0.33543 1.24321,0.86408 1.78281,1.58594 l 0,-1.81563 l 3.9375,0 l 0,11.01407 c -2e-5,1.96875 -0.62345,3.47083 -1.87032,4.50625 c -1.23959,1.0427 -3.04063,1.56405 -5.40312,1.56406 c -0.76563,-10e-6 -1.50573,-0.0583 -2.22031,-0.175 c -0.71459,-0.11667 -1.43282,-0.29532 -2.15469,-0.53594 l 0,-3.05156 c 0.68541,0.39375 1.35625,0.68541 2.0125,0.875 c 0.65624,0.19687 1.31614,0.29531 1.97969,0.29531 c 1.28332,0 2.22395,-0.28073 2.82187,-0.84219 c 0.59791,-0.56146 0.89687,-1.4401 0.89688,-2.63593 l 0,-0.84219 m -2.58125,-7.62344 c -0.80938,1e-5 -1.44011,0.29897 -1.89219,0.89688 c -0.45209,0.59792 -0.67813,1.44375 -0.67812,2.5375 c -10e-6,1.12292 0.21874,1.97604 0.65625,2.55937 c 0.43749,0.57605 1.07551,0.86407 1.91406,0.86406 c 0.81666,10e-6 1.45103,-0.29895 1.90312,-0.89687 c 0.45208,-0.59791 0.67812,-1.4401 0.67813,-2.52656 c -1e-5,-1.09375 -0.22605,-1.93958 -0.67813,-2.5375 c -0.45209,-0.59791 -1.08646,-0.89687 -1.90312,-0.89688"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
id="path13912-3-0"
|
||||
d="m 383.78144,312.10749 l 0,7.45937 l -3.9375,0 l 0,-1.21406 l 0,-4.49531 c -10e-6,-1.05729 -0.0255,-1.78645 -0.0766,-2.1875 c -0.0438,-0.40103 -0.12397,-0.69635 -0.24063,-0.88594 c -0.15313,-0.2552 -0.36095,-0.45207 -0.62344,-0.59062 c -0.26251,-0.14583 -0.56146,-0.21874 -0.89687,-0.21875 c -0.81668,1e-5 -1.45834,0.31719 -1.925,0.95156 c -0.46667,0.62709 -0.70001,1.49844 -0.7,2.61406 l 0,6.02656 l -3.91563,0 l 0,-12.25 l 3.91563,0 l 0,1.79375 c 0.59062,-0.71457 1.2177,-1.23957 1.88125,-1.575 c 0.66353,-0.34269 1.39634,-0.51405 2.19844,-0.51406 c 1.41457,1e-5 2.48644,0.43387 3.21562,1.30156 c 0.73645,0.86772 1.10467,2.12918 1.10469,3.78438"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
id="path13914-2-8"
|
||||
d="m 392.92519,314.05436 c -0.81667,1e-5 -1.43282,0.13855 -1.84844,0.41563 c -0.40834,0.27709 -0.6125,0.68542 -0.6125,1.225 c 0,0.49584 0.16406,0.88594 0.49219,1.17031 c 0.33541,0.27709 0.79843,0.41563 1.38906,0.41563 c 0.73645,0 1.35624,-0.2625 1.85938,-0.7875 c 0.50311,-0.53229 0.75467,-1.19583 0.75468,-1.99063 l 0,-0.44844 l -2.03437,0 m 5.98281,-1.47656 l 0,6.98906 l -3.94844,0 l 0,-1.81562 c -0.525,0.74375 -1.11563,1.28698 -1.77187,1.62969 c -0.65626,0.33541 -1.45469,0.50312 -2.39531,0.50312 c -1.26876,0 -2.30053,-0.36823 -3.09532,-1.10469 c -0.7875,-0.74374 -1.18125,-1.70624 -1.18125,-2.8875 c 0,-1.43645 0.49219,-2.49009 1.47657,-3.16093 c 0.99166,-0.67083 2.54478,-1.00625 4.65937,-1.00625 l 2.30781,0 l 0,-0.30625 c -1e-5,-0.61979 -0.24428,-1.07187 -0.73281,-1.35625 c -0.48855,-0.29166 -1.25053,-0.43749 -2.28594,-0.4375 c -0.83854,10e-6 -1.61875,0.0839 -2.34062,0.25156 c -0.72188,0.16772 -1.39271,0.41928 -2.0125,0.75469 l 0,-2.98594 c 0.83854,-0.20416 1.68072,-0.35728 2.52656,-0.45938 c 0.84583,-0.10936 1.69166,-0.16405 2.5375,-0.16406 c 2.20937,1e-5 3.80259,0.43751 4.77969,1.3125 c 0.98436,0.86772 1.47655,2.2823 1.47656,4.24375"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
id="path13916-6-8"
|
||||
d="m 402.57206,302.54811 l 3.91563,0 l 0,17.01875 l -3.91563,0 l 0,-17.01875"
|
||||
inkscape:connector-curvature="0" />
|
||||
</g>
|
||||
<path
|
||||
id="path22050-3"
|
||||
d="m 397.284,248.51434 l 33.43487,0"
|
||||
inkscape:connector-curvature="0"
|
||||
style="display:inline;fill:none;stroke:#7a00ff;stroke-width:5.61390018;stroke-linecap:butt;stroke-linejoin:round;stroke-opacity:1"
|
||||
sodipodi:nodetypes="cc" />
|
||||
</g>
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="layer16"
|
||||
inkscape:label="revo-srxl"
|
||||
style="display:none"
|
||||
sodipodi:insensitive="true">
|
||||
<g
|
||||
style="display:inline"
|
||||
id="revo-srxl"
|
||||
transform="matrix(0,0.4,-0.4,0,929.4684,-117.45414)">
|
||||
<path
|
||||
id="path9857-8-8-1-1-4"
|
||||
d="m 1430.6302,1592 c -5.97,64.9 57.0596,195.8293 232.2275,97.9523"
|
||||
stroke-miterlimit="4"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#777777;stroke-width:14.5;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none"
|
||||
sodipodi:nodetypes="cc" />
|
||||
<path
|
||||
sodipodi:nodetypes="ccc"
|
||||
style="fill:none;stroke:#ec6004;stroke-width:15.29999924;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 1392.571,1323.8556 l 0,-286.8032 l -291.0357,0"
|
||||
id="path8856-5-1-7-1-9-5-4-3-7" />
|
||||
<path
|
||||
sodipodi:nodetypes="ccc"
|
||||
style="fill:none;stroke:#d81900;stroke-width:15.29999924;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 1362.571,1323.8556 l -7e-4,-251.8944 l -261.035,0.1823"
|
||||
id="path8856-1-2-1-9-0-9" />
|
||||
<path
|
||||
sodipodi:nodetypes="ccc"
|
||||
style="fill:none;stroke:#000000;stroke-width:15.29999924;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 1347.571,1323.8556 l 0,-236.8032 l -246.0357,0"
|
||||
id="path8856-1-5-7-7-2-9-3" />
|
||||
<path
|
||||
sodipodi:nodetypes="cc"
|
||||
style="fill:none;stroke:#777777;stroke-width:14.5;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
stroke-miterlimit="4"
|
||||
d="m 1308.744,1592 c 5.97,64.9 -57.0596,195.8293 -232.2275,97.9523"
|
||||
id="path21749-5" />
|
||||
<rect
|
||||
rx="11.5"
|
||||
id="rect8853-6-8-6-6-4"
|
||||
style="color:#000000;fill:url(#linearGradient26963);fill-rule:nonzero;stroke:#000000;stroke-width:5.76999998;stroke-miterlimit:4;stroke-dasharray:none;enable-background:accumulate"
|
||||
ry="11.5"
|
||||
height="272"
|
||||
width="237"
|
||||
stroke-miterlimit="4"
|
||||
y="1320"
|
||||
x="1250" />
|
||||
<g
|
||||
style="font-style:normal;font-weight:normal;font-size:100px;line-height:125%;font-family:Sans;text-align:center;letter-spacing:0px;word-spacing:0px;text-anchor:middle;fill:#000000"
|
||||
id="text4849-5-9-2-5"
|
||||
transform="matrix(0,-1,1,0,-97.5,2824.5)">
|
||||
<path
|
||||
d="m 1337.2402,1484.8574 l 0,3.8477 q -2.2461,-1.0742 -4.2382,-1.6016 q -1.9922,-0.5273 -3.8477,-0.5273 q -3.2227,0 -4.9805,1.25 q -1.7383,1.25 -1.7383,3.5547 q 0,1.9336 1.1524,2.9296 q 1.1719,0.9766 4.4141,1.5821 l 2.3828,0.4883 q 4.414,0.8398 6.5039,2.9687 q 2.1093,2.1094 2.1093,5.6641 q 0,4.2383 -2.8515,6.4258 q -2.832,2.1875 -8.3203,2.1875 q -2.0703,0 -4.4141,-0.4688 q -2.3242,-0.4687 -4.8242,-1.3867 l 0,-4.0625 q 2.4023,1.3476 4.707,2.0312 q 2.3047,0.6836 4.5313,0.6836 q 3.3789,0 5.2148,-1.3281 q 1.836,-1.3281 1.836,-3.7891 q 0,-2.1484 -1.3282,-3.3593 q -1.3086,-1.211 -4.3164,-1.8164 l -2.4023,-0.4688 q -4.4141,-0.8789 -6.3867,-2.7539 q -1.9727,-1.875 -1.9727,-5.2148 q 0,-3.8672 2.7148,-6.0938 q 2.7344,-2.2266 7.5196,-2.2266 q 2.0508,0 4.1797,0.3711 q 2.1289,0.3711 4.3554,1.1133 z"
|
||||
style="font-size:40px;text-align:center;text-anchor:middle;fill:#ffffff"
|
||||
id="path21770-9"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
d="m 1358.9785,1499.3887 q 1.2695,0.4297 2.461,1.8359 q 1.2109,1.4063 2.4218,3.8672 l 4.0039,7.9687 l -4.2382,0 l -3.7305,-7.4804 q -1.4453,-2.9297 -2.8125,-3.8867 q -1.3477,-0.9571 -3.6914,-0.9571 l -4.2969,0 l 0,12.3242 l -3.9453,0 l 0,-29.1601 l 8.9062,0 q 5,0 7.461,2.0898 q 2.4609,2.0899 2.4609,6.3086 q 0,2.7539 -1.289,4.5703 q -1.2696,1.8164 -3.711,2.5196 z m -9.8828,-12.2461 l 0,10.3515 l 4.9609,0 q 2.8516,0 4.2969,-1.3086 q 1.4649,-1.3281 1.4649,-3.8867 q 0,-2.5586 -1.4649,-3.8476 q -1.4453,-1.3086 -4.2969,-1.3086 l -4.9609,0 z"
|
||||
style="font-size:40px;text-align:center;text-anchor:middle;fill:#ffffff"
|
||||
id="path21772-3"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
d="m 1371.5566,1483.9004 l 4.2383,0 l 7.2461,10.8398 l 7.2852,-10.8398 l 4.2383,0 l -9.375,14.0039 l 10,15.1562 l -4.2383,0 l -8.2032,-12.4023 l -8.2617,12.4023 l -4.2578,0 l 10.4102,-15.5664 l -9.0821,-13.5937 z"
|
||||
style="font-size:40px;text-align:center;text-anchor:middle;fill:#ffffff"
|
||||
id="path21774-4"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
d="m 1400.3848,1483.9004 l 3.9453,0 l 0,25.8398 l 14.1992,0 l 0,3.3203 l -18.1445,0 l 0,-29.1601 z"
|
||||
style="font-size:40px;text-align:center;text-anchor:middle;fill:#ffffff"
|
||||
id="path21776-8"
|
||||
inkscape:connector-curvature="0" />
|
||||
</g>
|
||||
<g
|
||||
style="font-style:normal;font-variant:normal;font-weight:bold;font-stretch:normal;font-size:37.7733078px;line-height:125%;font-family:Arial;-inkscape-font-specification:'Sans Bold';letter-spacing:0px;word-spacing:0px;display:inline;fill:#ffffff;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
id="text20525-8"
|
||||
transform="matrix(0,-1,1,0,-68.75,2824.5001)">
|
||||
<path
|
||||
d="m 1264.1993,1413.0389 l 0,-27.0389 l 8.1707,0 l 4.9061,18.444 l 4.8507,-18.444 l 8.1892,0 l 0,27.0389 l -5.0721,0 l 0,-21.2843 l -5.3672,21.2843 l -5.2566,0 l -5.3487,-21.2843 l 0,21.2843 l -5.0721,0 z"
|
||||
id="path21779-0"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
d="m 1295.7385,1386 l 5.4594,0 l 0,14.6446 q 0,3.4859 0.2029,4.5188 q 0.3505,1.6599 1.66,2.6743 q 1.328,0.996 3.615,0.996 q 2.324,0 3.5044,-0.9406 q 1.1804,-0.9591 1.4202,-2.3424 q 0.2397,-1.3833 0.2397,-4.5926 l 0,-14.9581 l 5.4595,0 l 0,14.2019 q 0,4.8692 -0.4427,6.8796 q -0.4427,2.0104 -1.6415,3.3937 q -1.1804,1.3833 -3.1724,2.2133 q -1.9919,0.8115 -5.2012,0.8115 q -3.8732,0 -5.8836,-0.8853 q -1.992,-0.9037 -3.154,-2.3239 q -1.1619,-1.4386 -1.5308,-3.0064 q -0.5349,-2.3239 -0.5349,-6.8612 l 0,-14.4232 z"
|
||||
id="path21781-9"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
d="m 1323.2201,1413.0389 l 0,-26.8175 l 5.4594,0 l 0,22.2619 l 13.5748,0 l 0,4.5556 l -19.0342,0 z"
|
||||
id="path21783-1"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
d="m 1349.4474,1413.0389 l 0,-22.4647 l -8.0231,0 l 0,-4.5742 l 21.4873,0 l 0,4.5742 l -8.0047,0 l 0,22.4647 l -5.4595,0 z"
|
||||
id="path21785-1"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
d="m 1366.213,1413.0389 l 0,-27.0389 l 5.4595,0 l 0,27.0389 l -5.4595,0 z"
|
||||
id="path21787-2"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
d="m 1376.8552,1413.0389 l 0,-27.0389 l 8.7609,0 q 4.9799,0 6.4923,0.4058 q 2.3239,0.6087 3.8917,2.6559 q 1.5677,2.0289 1.5677,5.2566 q 0,2.4899 -0.9037,4.1868 q -0.9038,1.6968 -2.3055,2.6743 q -1.3833,0.9591 -2.822,1.2727 q -1.955,0.3873 -5.6623,0.3873 l -3.5597,0 l 0,10.1995 l -5.4594,0 z m 5.4594,-22.4647 l 0,7.6727 l 2.988,0 q 3.2277,0 4.3159,-0.4243 q 1.0882,-0.4242 1.6968,-1.3279 q 0.6271,-0.9038 0.6271,-2.1026 q 0,-1.4756 -0.8669,-2.4346 q -0.8668,-0.9591 -2.1948,-1.1989 q -0.9775,-0.1844 -3.9286,-0.1844 l -2.6375,0 z"
|
||||
id="path21789-4"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
d="m 1402.2342,1413.0389 l 0,-26.8175 l 5.4594,0 l 0,22.2619 l 13.5748,0 l 0,4.5556 l -19.0342,0 z"
|
||||
id="path21791-4"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
d="m 1425.1785,1413.0389 l 0,-27.0389 l 20.0486,0 l 0,4.5742 l -14.5892,0 l 0,5.9943 l 13.5748,0 l 0,4.5556 l -13.5748,0 l 0,7.3592 l 15.1057,0 l 0,4.5556 l -20.5651,0 z"
|
||||
id="path21793-5"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
d="m 1447.6617,1413.0389 l 9.2405,-14.1096 L 1448.5286,1386 l 6.3816,0 l 5.4226,8.6872 l 5.3118,-8.6872 l 6.3263,0 l -8.4104,13.1322 l 9.2404,13.9067 l -6.5845,0 l -5.9943,-9.3511 l -6.0128,9.3511 l -6.5476,0 z"
|
||||
id="path21795-4"
|
||||
inkscape:connector-curvature="0" />
|
||||
</g>
|
||||
</g>
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="layer21"
|
||||
@ -18364,7 +19243,8 @@
|
||||
style="display:none"
|
||||
inkscape:label="revo-satellite"
|
||||
id="g11310"
|
||||
inkscape:groupmode="layer">
|
||||
inkscape:groupmode="layer"
|
||||
sodipodi:insensitive="true">
|
||||
<g
|
||||
transform="matrix(0.4,0,0,0.4,-131.04473,-97.93132)"
|
||||
id="revo-satellite">
|
||||
@ -18372,35 +19252,35 @@
|
||||
style="fill:none;stroke:#777777;stroke-width:14.5;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
stroke-miterlimit="4"
|
||||
d="M 1250,1530 C 1185.1,1524.03 1129,1544.3 1079,1570.7"
|
||||
d="m 1250,1530 c -64.9,-5.97 -121,14.3 -171,40.7"
|
||||
id="path11315" />
|
||||
<path
|
||||
style="fill:none;stroke:#777777;stroke-width:14.5;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
stroke-miterlimit="4"
|
||||
d="M 1490,1530 C 1540.3,1528.91 1605,1535.3 1645,1566.6"
|
||||
d="m 1490,1530 c 50.3,-1.09 115,5.3 155,36.6"
|
||||
id="path11317" />
|
||||
<path
|
||||
id="path11319"
|
||||
d="M 1371.2889,1318.8556 L 1371.2889,1194.0962 L 1596.2889,1194.0962 L 1596.2889,1052.7282"
|
||||
d="m 1371.2889,1318.8556 l 0,-124.7594 l 225,0 l 0,-141.368"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#1f4697;stroke-width:15.29999924;stroke-linecap:butt;stroke-linejoin:round;stroke-miterlimit:4;stroke-dasharray:none"
|
||||
sodipodi:nodetypes="cccc" />
|
||||
<path
|
||||
id="path11321"
|
||||
d="M 1356.2889,1318.8556 L 1356.2889,1179.0962 L 1581.2889,1179.0962 L 1581.2889,1052.7282"
|
||||
d="m 1356.2889,1318.8556 l 0,-139.7594 l 225,0 l 0,-126.368"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#d81900;stroke-width:15.29999924;stroke-linecap:butt;stroke-linejoin:round;stroke-miterlimit:4;stroke-dasharray:none"
|
||||
sodipodi:nodetypes="cccc" />
|
||||
<path
|
||||
id="path11323"
|
||||
d="M 1386.2889,1318.8556 L 1386.2889,1209.0962 L 1611.7889,1209.0963 L 1611.7889,1052.7282"
|
||||
d="m 1386.2889,1318.8556 l 0,-109.7594 l 225.5,10e-5 l 0,-156.3681"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#ec6004;stroke-width:15.29999924;stroke-linecap:butt;stroke-linejoin:round;stroke-miterlimit:4;stroke-dasharray:none"
|
||||
sodipodi:nodetypes="cccc" />
|
||||
<path
|
||||
id="path11325"
|
||||
d="M 1342.571,1318.8556 L 1342.571,1164.0962 L 1566.2889,1164.0962 L 1566.2889,1052.7282"
|
||||
d="m 1342.571,1318.8556 l 0,-154.7594 l 223.7179,0 l 0,-111.368"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#000000;stroke-width:15.30000019;stroke-linecap:butt;stroke-linejoin:round;stroke-miterlimit:4;stroke-dasharray:none"
|
||||
sodipodi:nodetypes="cccc" />
|
||||
@ -18423,7 +19303,7 @@
|
||||
line-height="125%"
|
||||
font-size="40px"
|
||||
font-weight="normal"
|
||||
style="font-size:40px;font-style:normal;font-weight:normal;text-align:center;line-height:125%;letter-spacing:0px;word-spacing:0px;text-anchor:middle;fill:#ffffff;font-family:Sans"
|
||||
style="font-style:normal;font-weight:normal;font-size:40px;line-height:125%;font-family:Sans;text-align:center;letter-spacing:0px;word-spacing:0px;text-anchor:middle;fill:#ffffff"
|
||||
id="text11329"><tspan
|
||||
x="1368.6637"
|
||||
y="1415.5746"
|
||||
@ -18437,7 +19317,7 @@
|
||||
font-size="100px"
|
||||
xml:space="preserve"
|
||||
font-weight="normal"
|
||||
style="font-size:100px;font-style:normal;font-weight:normal;line-height:125%;letter-spacing:0px;word-spacing:0px;fill:#000000;font-family:Sans"
|
||||
style="font-style:normal;font-weight:normal;font-size:100px;line-height:125%;font-family:Sans;letter-spacing:0px;word-spacing:0px;fill:#000000"
|
||||
id="text11333"><tspan
|
||||
style="font-size:40px;fill:#ffffff"
|
||||
x="1291.984"
|
||||
@ -18446,126 +19326,6 @@
|
||||
id="tspan11335">Satellite</tspan></text>
|
||||
</g>
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="layer19"
|
||||
inkscape:label="nano-srxl"
|
||||
style="display:none"
|
||||
sodipodi:insensitive="true">
|
||||
<g
|
||||
style="display:inline"
|
||||
id="nano-srxl"
|
||||
transform="matrix(-0.4,0,0,-0.4,1078.3424,590.20822)">
|
||||
<path
|
||||
id="path9857-8-8-1-1"
|
||||
d="m 1430.6302,1592 c -5.97,64.9 57.0596,195.8293 232.2275,97.9523"
|
||||
stroke-miterlimit="4"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#777777;stroke-width:14.5;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none"
|
||||
sodipodi:nodetypes="cc" />
|
||||
<path
|
||||
sodipodi:nodetypes="cc"
|
||||
style="fill:#cccccc;stroke:#ec6004;stroke-width:15.29999924;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 1392.571,1323.8556 l 0,-171.0219"
|
||||
id="path8856-5-1-7-1-9-5-4-3" />
|
||||
<path
|
||||
sodipodi:nodetypes="cc"
|
||||
style="fill:none;stroke:#d81900;stroke-width:15.29999924;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 1362.571,1323.8556 l 0,-171.0209"
|
||||
id="path8856-1-2-1-9-0" />
|
||||
<path
|
||||
sodipodi:nodetypes="cc"
|
||||
style="fill:#cccccc;stroke:#000000;stroke-width:15.29999924;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 1347.571,1323.8556 l 0,-171.0209"
|
||||
id="path8856-1-5-7-7-2-9" />
|
||||
<path
|
||||
sodipodi:nodetypes="cc"
|
||||
style="fill:none;stroke:#777777;stroke-width:14.5;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
stroke-miterlimit="4"
|
||||
d="m 1308.744,1592 c 5.97,64.9 -57.0596,195.8293 -232.2275,97.9523"
|
||||
id="path21749" />
|
||||
<rect
|
||||
rx="11.5"
|
||||
id="rect8853-6-8-6-6"
|
||||
style="color:#000000;fill:url(#linearGradient27052);fill-rule:nonzero;stroke:#000000;stroke-width:5.76999998;stroke-miterlimit:4;stroke-dasharray:none;enable-background:accumulate"
|
||||
ry="11.5"
|
||||
height="272"
|
||||
width="237"
|
||||
stroke-miterlimit="4"
|
||||
y="1320"
|
||||
x="1250" />
|
||||
<g
|
||||
style="font-style:normal;font-weight:normal;font-size:100px;line-height:125%;font-family:Sans;text-align:center;letter-spacing:0px;word-spacing:0px;text-anchor:middle;fill:#000000"
|
||||
id="text4849-5-9-2"
|
||||
transform="matrix(-1,0,0,-1,2737,2914.5)">
|
||||
<path
|
||||
d="m 1337.2402,1484.8574 l 0,3.8477 q -2.2461,-1.0742 -4.2382,-1.6016 q -1.9922,-0.5273 -3.8477,-0.5273 q -3.2227,0 -4.9805,1.25 q -1.7383,1.25 -1.7383,3.5547 q 0,1.9336 1.1524,2.9296 q 1.1719,0.9766 4.4141,1.5821 l 2.3828,0.4883 q 4.414,0.8398 6.5039,2.9687 q 2.1093,2.1094 2.1093,5.6641 q 0,4.2383 -2.8515,6.4258 q -2.832,2.1875 -8.3203,2.1875 q -2.0703,0 -4.4141,-0.4688 q -2.3242,-0.4687 -4.8242,-1.3867 l 0,-4.0625 q 2.4023,1.3476 4.707,2.0312 q 2.3047,0.6836 4.5313,0.6836 q 3.3789,0 5.2148,-1.3281 q 1.836,-1.3281 1.836,-3.7891 q 0,-2.1484 -1.3282,-3.3593 q -1.3086,-1.211 -4.3164,-1.8164 l -2.4023,-0.4688 q -4.4141,-0.8789 -6.3867,-2.7539 q -1.9727,-1.875 -1.9727,-5.2148 q 0,-3.8672 2.7148,-6.0938 q 2.7344,-2.2266 7.5196,-2.2266 q 2.0508,0 4.1797,0.3711 q 2.1289,0.3711 4.3554,1.1133 z"
|
||||
style="font-size:40px;text-align:center;text-anchor:middle;fill:#ffffff"
|
||||
id="path21770"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
d="m 1358.9785,1499.3887 q 1.2695,0.4297 2.461,1.8359 q 1.2109,1.4063 2.4218,3.8672 l 4.0039,7.9687 l -4.2382,0 l -3.7305,-7.4804 q -1.4453,-2.9297 -2.8125,-3.8867 q -1.3477,-0.9571 -3.6914,-0.9571 l -4.2969,0 l 0,12.3242 l -3.9453,0 l 0,-29.1601 l 8.9062,0 q 5,0 7.461,2.0898 q 2.4609,2.0899 2.4609,6.3086 q 0,2.7539 -1.289,4.5703 q -1.2696,1.8164 -3.711,2.5196 z m -9.8828,-12.2461 l 0,10.3515 l 4.9609,0 q 2.8516,0 4.2969,-1.3086 q 1.4649,-1.3281 1.4649,-3.8867 q 0,-2.5586 -1.4649,-3.8476 q -1.4453,-1.3086 -4.2969,-1.3086 l -4.9609,0 z"
|
||||
style="font-size:40px;text-align:center;text-anchor:middle;fill:#ffffff"
|
||||
id="path21772"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
d="m 1371.5566,1483.9004 l 4.2383,0 l 7.2461,10.8398 l 7.2852,-10.8398 l 4.2383,0 l -9.375,14.0039 l 10,15.1562 l -4.2383,0 l -8.2032,-12.4023 l -8.2617,12.4023 l -4.2578,0 l 10.4102,-15.5664 l -9.0821,-13.5937 z"
|
||||
style="font-size:40px;text-align:center;text-anchor:middle;fill:#ffffff"
|
||||
id="path21774"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
d="m 1400.3848,1483.9004 l 3.9453,0 l 0,25.8398 l 14.1992,0 l 0,3.3203 l -18.1445,0 l 0,-29.1601 z"
|
||||
style="font-size:40px;text-align:center;text-anchor:middle;fill:#ffffff"
|
||||
id="path21776"
|
||||
inkscape:connector-curvature="0" />
|
||||
</g>
|
||||
<g
|
||||
style="font-style:normal;font-variant:normal;font-weight:bold;font-stretch:normal;font-size:37.7733078px;line-height:125%;font-family:Arial;-inkscape-font-specification:'Sans Bold';letter-spacing:0px;word-spacing:0px;display:inline;fill:#ffffff;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
id="text20525"
|
||||
transform="matrix(-1,0,0,-1,2737.0002,2904.5)">
|
||||
<path
|
||||
d="m 1264.1993,1413.0389 l 0,-27.0389 l 8.1707,0 l 4.9061,18.444 l 4.8507,-18.444 l 8.1892,0 l 0,27.0389 l -5.0721,0 l 0,-21.2843 l -5.3672,21.2843 l -5.2566,0 l -5.3487,-21.2843 l 0,21.2843 l -5.0721,0 z"
|
||||
id="path21779"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
d="m 1295.7385,1386 l 5.4594,0 l 0,14.6446 q 0,3.4859 0.2029,4.5188 q 0.3505,1.6599 1.66,2.6743 q 1.328,0.996 3.615,0.996 q 2.324,0 3.5044,-0.9406 q 1.1804,-0.9591 1.4202,-2.3424 q 0.2397,-1.3833 0.2397,-4.5926 l 0,-14.9581 l 5.4595,0 l 0,14.2019 q 0,4.8692 -0.4427,6.8796 q -0.4427,2.0104 -1.6415,3.3937 q -1.1804,1.3833 -3.1724,2.2133 q -1.9919,0.8115 -5.2012,0.8115 q -3.8732,0 -5.8836,-0.8853 q -1.992,-0.9037 -3.154,-2.3239 q -1.1619,-1.4386 -1.5308,-3.0064 q -0.5349,-2.3239 -0.5349,-6.8612 l 0,-14.4232 z"
|
||||
id="path21781"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
d="m 1323.2201,1413.0389 l 0,-26.8175 l 5.4594,0 l 0,22.2619 l 13.5748,0 l 0,4.5556 l -19.0342,0 z"
|
||||
id="path21783"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
d="m 1349.4474,1413.0389 l 0,-22.4647 l -8.0231,0 l 0,-4.5742 l 21.4873,0 l 0,4.5742 l -8.0047,0 l 0,22.4647 l -5.4595,0 z"
|
||||
id="path21785"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
d="m 1366.213,1413.0389 l 0,-27.0389 l 5.4595,0 l 0,27.0389 l -5.4595,0 z"
|
||||
id="path21787"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
d="m 1376.8552,1413.0389 l 0,-27.0389 l 8.7609,0 q 4.9799,0 6.4923,0.4058 q 2.3239,0.6087 3.8917,2.6559 q 1.5677,2.0289 1.5677,5.2566 q 0,2.4899 -0.9037,4.1868 q -0.9038,1.6968 -2.3055,2.6743 q -1.3833,0.9591 -2.822,1.2727 q -1.955,0.3873 -5.6623,0.3873 l -3.5597,0 l 0,10.1995 l -5.4594,0 z m 5.4594,-22.4647 l 0,7.6727 l 2.988,0 q 3.2277,0 4.3159,-0.4243 q 1.0882,-0.4242 1.6968,-1.3279 q 0.6271,-0.9038 0.6271,-2.1026 q 0,-1.4756 -0.8669,-2.4346 q -0.8668,-0.9591 -2.1948,-1.1989 q -0.9775,-0.1844 -3.9286,-0.1844 l -2.6375,0 z"
|
||||
id="path21789"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
d="m 1402.2342,1413.0389 l 0,-26.8175 l 5.4594,0 l 0,22.2619 l 13.5748,0 l 0,4.5556 l -19.0342,0 z"
|
||||
id="path21791"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
d="m 1425.1785,1413.0389 l 0,-27.0389 l 20.0486,0 l 0,4.5742 l -14.5892,0 l 0,5.9943 l 13.5748,0 l 0,4.5556 l -13.5748,0 l 0,7.3592 l 15.1057,0 l 0,4.5556 l -20.5651,0 z"
|
||||
id="path21793"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
d="m 1447.6617,1413.0389 l 9.2405,-14.1096 L 1448.5286,1386 l 6.3816,0 l 5.4226,8.6872 l 5.3118,-8.6872 l 6.3263,0 l -8.4104,13.1322 l 9.2404,13.9067 l -6.5845,0 l -5.9943,-9.3511 l -6.0128,9.3511 l -6.5476,0 z"
|
||||
id="path21795"
|
||||
inkscape:connector-curvature="0" />
|
||||
</g>
|
||||
</g>
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="layer4"
|
||||
@ -18786,7 +19546,8 @@
|
||||
inkscape:groupmode="layer"
|
||||
id="layer3"
|
||||
inkscape:label="nano-ppm"
|
||||
style="display:none">
|
||||
style="display:none"
|
||||
sodipodi:insensitive="true">
|
||||
<g
|
||||
id="nano-ppm"
|
||||
transform="translate(-4,0)">
|
||||
@ -18941,6 +19702,126 @@
|
||||
</g>
|
||||
</g>
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="layer19"
|
||||
inkscape:label="nano-srxl"
|
||||
style="display:none"
|
||||
sodipodi:insensitive="true">
|
||||
<g
|
||||
style="display:inline"
|
||||
id="nano-srxl"
|
||||
transform="matrix(-0.4,0,0,-0.4,1078.3424,590.20822)">
|
||||
<path
|
||||
id="path9857-8-8-1-1"
|
||||
d="m 1430.6302,1592 c -5.97,64.9 57.0596,195.8293 232.2275,97.9523"
|
||||
stroke-miterlimit="4"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#777777;stroke-width:14.5;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none"
|
||||
sodipodi:nodetypes="cc" />
|
||||
<path
|
||||
sodipodi:nodetypes="cc"
|
||||
style="fill:#cccccc;stroke:#ec6004;stroke-width:15.29999924;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 1392.571,1323.8556 l 0,-171.0219"
|
||||
id="path8856-5-1-7-1-9-5-4-3" />
|
||||
<path
|
||||
sodipodi:nodetypes="cc"
|
||||
style="fill:none;stroke:#d81900;stroke-width:15.29999924;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 1362.571,1323.8556 l 0,-171.0209"
|
||||
id="path8856-1-2-1-9-0" />
|
||||
<path
|
||||
sodipodi:nodetypes="cc"
|
||||
style="fill:#cccccc;stroke:#000000;stroke-width:15.29999924;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 1347.571,1323.8556 l 0,-171.0209"
|
||||
id="path8856-1-5-7-7-2-9" />
|
||||
<path
|
||||
sodipodi:nodetypes="cc"
|
||||
style="fill:none;stroke:#777777;stroke-width:14.5;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
stroke-miterlimit="4"
|
||||
d="m 1308.744,1592 c 5.97,64.9 -57.0596,195.8293 -232.2275,97.9523"
|
||||
id="path21749" />
|
||||
<rect
|
||||
rx="11.5"
|
||||
id="rect8853-6-8-6-6"
|
||||
style="color:#000000;fill:url(#linearGradient27052);fill-rule:nonzero;stroke:#000000;stroke-width:5.76999998;stroke-miterlimit:4;stroke-dasharray:none;enable-background:accumulate"
|
||||
ry="11.5"
|
||||
height="272"
|
||||
width="237"
|
||||
stroke-miterlimit="4"
|
||||
y="1320"
|
||||
x="1250" />
|
||||
<g
|
||||
style="font-style:normal;font-weight:normal;font-size:100px;line-height:125%;font-family:Sans;text-align:center;letter-spacing:0px;word-spacing:0px;text-anchor:middle;fill:#000000"
|
||||
id="text4849-5-9-2"
|
||||
transform="matrix(-1,0,0,-1,2737,2914.5)">
|
||||
<path
|
||||
d="m 1337.2402,1484.8574 l 0,3.8477 q -2.2461,-1.0742 -4.2382,-1.6016 q -1.9922,-0.5273 -3.8477,-0.5273 q -3.2227,0 -4.9805,1.25 q -1.7383,1.25 -1.7383,3.5547 q 0,1.9336 1.1524,2.9296 q 1.1719,0.9766 4.4141,1.5821 l 2.3828,0.4883 q 4.414,0.8398 6.5039,2.9687 q 2.1093,2.1094 2.1093,5.6641 q 0,4.2383 -2.8515,6.4258 q -2.832,2.1875 -8.3203,2.1875 q -2.0703,0 -4.4141,-0.4688 q -2.3242,-0.4687 -4.8242,-1.3867 l 0,-4.0625 q 2.4023,1.3476 4.707,2.0312 q 2.3047,0.6836 4.5313,0.6836 q 3.3789,0 5.2148,-1.3281 q 1.836,-1.3281 1.836,-3.7891 q 0,-2.1484 -1.3282,-3.3593 q -1.3086,-1.211 -4.3164,-1.8164 l -2.4023,-0.4688 q -4.4141,-0.8789 -6.3867,-2.7539 q -1.9727,-1.875 -1.9727,-5.2148 q 0,-3.8672 2.7148,-6.0938 q 2.7344,-2.2266 7.5196,-2.2266 q 2.0508,0 4.1797,0.3711 q 2.1289,0.3711 4.3554,1.1133 z"
|
||||
style="font-size:40px;text-align:center;text-anchor:middle;fill:#ffffff"
|
||||
id="path21770"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
d="m 1358.9785,1499.3887 q 1.2695,0.4297 2.461,1.8359 q 1.2109,1.4063 2.4218,3.8672 l 4.0039,7.9687 l -4.2382,0 l -3.7305,-7.4804 q -1.4453,-2.9297 -2.8125,-3.8867 q -1.3477,-0.9571 -3.6914,-0.9571 l -4.2969,0 l 0,12.3242 l -3.9453,0 l 0,-29.1601 l 8.9062,0 q 5,0 7.461,2.0898 q 2.4609,2.0899 2.4609,6.3086 q 0,2.7539 -1.289,4.5703 q -1.2696,1.8164 -3.711,2.5196 z m -9.8828,-12.2461 l 0,10.3515 l 4.9609,0 q 2.8516,0 4.2969,-1.3086 q 1.4649,-1.3281 1.4649,-3.8867 q 0,-2.5586 -1.4649,-3.8476 q -1.4453,-1.3086 -4.2969,-1.3086 l -4.9609,0 z"
|
||||
style="font-size:40px;text-align:center;text-anchor:middle;fill:#ffffff"
|
||||
id="path21772"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
d="m 1371.5566,1483.9004 l 4.2383,0 l 7.2461,10.8398 l 7.2852,-10.8398 l 4.2383,0 l -9.375,14.0039 l 10,15.1562 l -4.2383,0 l -8.2032,-12.4023 l -8.2617,12.4023 l -4.2578,0 l 10.4102,-15.5664 l -9.0821,-13.5937 z"
|
||||
style="font-size:40px;text-align:center;text-anchor:middle;fill:#ffffff"
|
||||
id="path21774"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
d="m 1400.3848,1483.9004 l 3.9453,0 l 0,25.8398 l 14.1992,0 l 0,3.3203 l -18.1445,0 l 0,-29.1601 z"
|
||||
style="font-size:40px;text-align:center;text-anchor:middle;fill:#ffffff"
|
||||
id="path21776"
|
||||
inkscape:connector-curvature="0" />
|
||||
</g>
|
||||
<g
|
||||
style="font-style:normal;font-variant:normal;font-weight:bold;font-stretch:normal;font-size:37.7733078px;line-height:125%;font-family:Arial;-inkscape-font-specification:'Sans Bold';letter-spacing:0px;word-spacing:0px;display:inline;fill:#ffffff;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
id="text20525"
|
||||
transform="matrix(-1,0,0,-1,2737.0002,2904.5)">
|
||||
<path
|
||||
d="m 1264.1993,1413.0389 l 0,-27.0389 l 8.1707,0 l 4.9061,18.444 l 4.8507,-18.444 l 8.1892,0 l 0,27.0389 l -5.0721,0 l 0,-21.2843 l -5.3672,21.2843 l -5.2566,0 l -5.3487,-21.2843 l 0,21.2843 l -5.0721,0 z"
|
||||
id="path21779"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
d="m 1295.7385,1386 l 5.4594,0 l 0,14.6446 q 0,3.4859 0.2029,4.5188 q 0.3505,1.6599 1.66,2.6743 q 1.328,0.996 3.615,0.996 q 2.324,0 3.5044,-0.9406 q 1.1804,-0.9591 1.4202,-2.3424 q 0.2397,-1.3833 0.2397,-4.5926 l 0,-14.9581 l 5.4595,0 l 0,14.2019 q 0,4.8692 -0.4427,6.8796 q -0.4427,2.0104 -1.6415,3.3937 q -1.1804,1.3833 -3.1724,2.2133 q -1.9919,0.8115 -5.2012,0.8115 q -3.8732,0 -5.8836,-0.8853 q -1.992,-0.9037 -3.154,-2.3239 q -1.1619,-1.4386 -1.5308,-3.0064 q -0.5349,-2.3239 -0.5349,-6.8612 l 0,-14.4232 z"
|
||||
id="path21781"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
d="m 1323.2201,1413.0389 l 0,-26.8175 l 5.4594,0 l 0,22.2619 l 13.5748,0 l 0,4.5556 l -19.0342,0 z"
|
||||
id="path21783"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
d="m 1349.4474,1413.0389 l 0,-22.4647 l -8.0231,0 l 0,-4.5742 l 21.4873,0 l 0,4.5742 l -8.0047,0 l 0,22.4647 l -5.4595,0 z"
|
||||
id="path21785"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
d="m 1366.213,1413.0389 l 0,-27.0389 l 5.4595,0 l 0,27.0389 l -5.4595,0 z"
|
||||
id="path21787"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
d="m 1376.8552,1413.0389 l 0,-27.0389 l 8.7609,0 q 4.9799,0 6.4923,0.4058 q 2.3239,0.6087 3.8917,2.6559 q 1.5677,2.0289 1.5677,5.2566 q 0,2.4899 -0.9037,4.1868 q -0.9038,1.6968 -2.3055,2.6743 q -1.3833,0.9591 -2.822,1.2727 q -1.955,0.3873 -5.6623,0.3873 l -3.5597,0 l 0,10.1995 l -5.4594,0 z m 5.4594,-22.4647 l 0,7.6727 l 2.988,0 q 3.2277,0 4.3159,-0.4243 q 1.0882,-0.4242 1.6968,-1.3279 q 0.6271,-0.9038 0.6271,-2.1026 q 0,-1.4756 -0.8669,-2.4346 q -0.8668,-0.9591 -2.1948,-1.1989 q -0.9775,-0.1844 -3.9286,-0.1844 l -2.6375,0 z"
|
||||
id="path21789"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
d="m 1402.2342,1413.0389 l 0,-26.8175 l 5.4594,0 l 0,22.2619 l 13.5748,0 l 0,4.5556 l -19.0342,0 z"
|
||||
id="path21791"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
d="m 1425.1785,1413.0389 l 0,-27.0389 l 20.0486,0 l 0,4.5742 l -14.5892,0 l 0,5.9943 l 13.5748,0 l 0,4.5556 l -13.5748,0 l 0,7.3592 l 15.1057,0 l 0,4.5556 l -20.5651,0 z"
|
||||
id="path21793"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
d="m 1447.6617,1413.0389 l 9.2405,-14.1096 L 1448.5286,1386 l 6.3816,0 l 5.4226,8.6872 l 5.3118,-8.6872 l 6.3263,0 l -8.4104,13.1322 l 9.2404,13.9067 l -6.5845,0 l -5.9943,-9.3511 l -6.0128,9.3511 l -6.5476,0 z"
|
||||
id="path21795"
|
||||
inkscape:connector-curvature="0" />
|
||||
</g>
|
||||
</g>
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="layer2"
|
||||
@ -20320,7 +21201,7 @@
|
||||
inkscape:groupmode="layer"
|
||||
id="layer36"
|
||||
inkscape:label="revo-OPGPS-v9"
|
||||
style="display:inline"
|
||||
style="display:none"
|
||||
sodipodi:insensitive="true">
|
||||
<g
|
||||
id="revo-OPGPS-v9">
|
||||
@ -20666,9 +21547,9 @@
|
||||
<polygon
|
||||
transform="matrix(1.5711089,0,0,1.5372108,235.33403,522.2062)"
|
||||
id="polygon8706-1"
|
||||
points="186.194,11.031 181.129,13.319 186.083,4.74 191.036,13.319 " />
|
||||
points="186.083,4.74 191.036,13.319 186.194,11.031 181.129,13.319 " />
|
||||
<polygon
|
||||
points="191.036,13.319 186.194,11.031 181.129,13.319 186.083,4.74 "
|
||||
points="181.129,13.319 186.083,4.74 191.036,13.319 186.194,11.031 "
|
||||
id="polygon10148"
|
||||
transform="matrix(1.5711089,0,0,1.5372108,357.19879,522.2062)" />
|
||||
<g
|
||||
@ -22380,88 +23261,88 @@
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path6565-9-8"
|
||||
d="M 166.08622,950.31232 L 109.55369,950.31232"
|
||||
style="fill:none;stroke:#545253;stroke-width:9.10000038;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
d="m 166.08622,950.31232 l -56.53253,0"
|
||||
style="fill:none;stroke:#545253;stroke-width:9.10000038;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
|
||||
<g
|
||||
transform="translate(-69.961847,449.88605)"
|
||||
id="g6567-4-5">
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path6569-5-87"
|
||||
d="M 236.04807,504.14551 L 179.51554,504.14551"
|
||||
style="fill:none;stroke:#6c6b6f;stroke-width:1.5;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
d="m 236.04807,504.14551 l -56.53253,0"
|
||||
style="fill:none;stroke:#6c6b6f;stroke-width:1.5;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
|
||||
<path
|
||||
style="fill:none;stroke:#6c6b6f;stroke-width:1.5;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
d="M 236.04807,496.88936 L 179.51554,496.88936"
|
||||
style="fill:none;stroke:#6c6b6f;stroke-width:1.5;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||
d="m 236.04807,496.88936 l -56.53253,0"
|
||||
id="path6571-27-4"
|
||||
inkscape:connector-curvature="0" />
|
||||
</g>
|
||||
<path
|
||||
style="fill:none;stroke:#545253;stroke-width:9.10000038;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
d="M 166.08622,976.31232 L 109.55369,976.31232"
|
||||
style="fill:none;stroke:#545253;stroke-width:9.10000038;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||
d="m 166.08622,976.31232 l -56.53253,0"
|
||||
id="path6555-3-3"
|
||||
inkscape:connector-curvature="0" />
|
||||
<g
|
||||
transform="translate(-69.961847,475.88605)"
|
||||
id="g6557-0-4">
|
||||
<path
|
||||
style="fill:none;stroke:#6c6b6f;stroke-width:1.5;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
d="M 236.04807,504.14551 L 179.51554,504.14551"
|
||||
style="fill:none;stroke:#6c6b6f;stroke-width:1.5;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||
d="m 236.04807,504.14551 l -56.53253,0"
|
||||
id="path6559-1-4"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path6561-82-5"
|
||||
d="M 236.04807,496.88936 L 179.51554,496.88936"
|
||||
style="fill:none;stroke:#6c6b6f;stroke-width:1.5;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
d="m 236.04807,496.88936 l -56.53253,0"
|
||||
style="fill:none;stroke:#6c6b6f;stroke-width:1.5;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
|
||||
</g>
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path6545-9-4"
|
||||
d="M 166.08622,1000.3123 L 109.55369,1000.3123"
|
||||
style="fill:none;stroke:#545253;stroke-width:9.10000038;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
d="m 166.08622,1000.3123 l -56.53253,0"
|
||||
style="fill:none;stroke:#545253;stroke-width:9.10000038;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
|
||||
<g
|
||||
transform="translate(-69.961847,499.88605)"
|
||||
id="g6547-1-3">
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path6549-1-6"
|
||||
d="M 236.04807,504.14551 L 179.51554,504.14551"
|
||||
style="fill:none;stroke:#6c6b6f;stroke-width:1.5;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
d="m 236.04807,504.14551 l -56.53253,0"
|
||||
style="fill:none;stroke:#6c6b6f;stroke-width:1.5;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
|
||||
<path
|
||||
style="fill:none;stroke:#6c6b6f;stroke-width:1.5;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
d="M 236.04807,496.88936 L 179.51554,496.88936"
|
||||
style="fill:none;stroke:#6c6b6f;stroke-width:1.5;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||
d="m 236.04807,496.88936 l -56.53253,0"
|
||||
id="path6551-4-25"
|
||||
inkscape:connector-curvature="0" />
|
||||
</g>
|
||||
<path
|
||||
style="fill:none;stroke:#545253;stroke-width:9.10000038;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
d="M 166.08622,1026.3123 L 109.55369,1026.3123"
|
||||
style="fill:none;stroke:#545253;stroke-width:9.10000038;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||
d="m 166.08622,1026.3123 l -56.53253,0"
|
||||
id="path6527-1-9"
|
||||
inkscape:connector-curvature="0" />
|
||||
<g
|
||||
transform="translate(-69.961847,525.88605)"
|
||||
id="g6533-32-8">
|
||||
<path
|
||||
style="fill:none;stroke:#6c6b6f;stroke-width:1.5;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
d="M 236.04807,504.14551 L 179.51554,504.14551"
|
||||
style="fill:none;stroke:#6c6b6f;stroke-width:1.5;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||
d="m 236.04807,504.14551 l -56.53253,0"
|
||||
id="path6529-8-2"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path6531-7-0"
|
||||
d="M 236.04807,496.88936 L 179.51554,496.88936"
|
||||
style="fill:none;stroke:#6c6b6f;stroke-width:1.5;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
d="m 236.04807,496.88936 l -56.53253,0"
|
||||
style="fill:none;stroke:#6c6b6f;stroke-width:1.5;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
|
||||
</g>
|
||||
<rect
|
||||
style="fill:#2e2f2e;fill-opacity:1;fill-rule:evenodd;stroke:none;display:inline"
|
||||
style="display:inline;fill:#2e2f2e;fill-opacity:1;fill-rule:evenodd;stroke:none"
|
||||
id="rect6519-2-3"
|
||||
width="24.794964"
|
||||
height="9.1741314"
|
||||
x="166.08623"
|
||||
y="960.12616" />
|
||||
<rect
|
||||
style="opacity:0.87969923;fill:#2f3430;fill-opacity:1;fill-rule:evenodd;stroke:#171600;stroke-width:1.11581445;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;stroke-dashoffset:0;display:inline"
|
||||
style="display:inline;opacity:0.87969923;fill:#2f3430;fill-opacity:1;fill-rule:evenodd;stroke:#171600;stroke-width:1.11581445;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1"
|
||||
id="rect6517-1-4"
|
||||
width="24.67915"
|
||||
height="119.41021"
|
||||
@ -22473,9 +23354,9 @@
|
||||
height="9.1741314"
|
||||
width="24.794964"
|
||||
id="rect6521-8-2"
|
||||
style="fill:#2e2f2e;fill-opacity:1;fill-rule:evenodd;stroke:none;display:inline" />
|
||||
style="display:inline;fill:#2e2f2e;fill-opacity:1;fill-rule:evenodd;stroke:none" />
|
||||
<rect
|
||||
style="fill:#2e2f2e;fill-opacity:1;fill-rule:evenodd;stroke:none;display:inline"
|
||||
style="display:inline;fill:#2e2f2e;fill-opacity:1;fill-rule:evenodd;stroke:none"
|
||||
id="rect6523-4-2"
|
||||
width="24.794964"
|
||||
height="9.1741314"
|
||||
@ -22484,19 +23365,19 @@
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path14347-9"
|
||||
d="M 166.08622,1049.6497 L 109.55369,1049.6497"
|
||||
style="fill:none;stroke:#545253;stroke-width:9.10000038;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
d="m 166.08622,1049.6497 l -56.53253,0"
|
||||
style="fill:none;stroke:#545253;stroke-width:9.10000038;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
|
||||
<g
|
||||
transform="translate(-69.961847,549.22341)"
|
||||
id="g14349-1">
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path14351-4"
|
||||
d="M 236.04807,504.14551 L 179.51554,504.14551"
|
||||
style="fill:none;stroke:#6c6b6f;stroke-width:1.5;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
d="m 236.04807,504.14551 l -56.53253,0"
|
||||
style="fill:none;stroke:#6c6b6f;stroke-width:1.5;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
|
||||
<path
|
||||
style="fill:none;stroke:#6c6b6f;stroke-width:1.5;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
d="M 236.04807,496.88936 L 179.51554,496.88936"
|
||||
style="fill:none;stroke:#6c6b6f;stroke-width:1.5;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||
d="m 236.04807,496.88936 l -56.53253,0"
|
||||
id="path14353-2"
|
||||
inkscape:connector-curvature="0" />
|
||||
</g>
|
||||
@ -22506,7 +23387,7 @@
|
||||
height="9.1741314"
|
||||
width="24.794964"
|
||||
id="rect14355-9"
|
||||
style="fill:#2e2f2e;fill-opacity:1;fill-rule:evenodd;stroke:none;display:inline" />
|
||||
style="display:inline;fill:#2e2f2e;fill-opacity:1;fill-rule:evenodd;stroke:none" />
|
||||
</g>
|
||||
<rect
|
||||
transform="matrix(0,1,-1,0,0,0)"
|
||||
@ -22521,7 +23402,7 @@
|
||||
<rect
|
||||
inkscape:transform-center-y="28.155766"
|
||||
inkscape:transform-center-x="-50.291428"
|
||||
style="fill:#e9dcdc;display:inline"
|
||||
style="display:inline;fill:#e9dcdc"
|
||||
x="554.66888"
|
||||
y="650.36731"
|
||||
width="11.251238"
|
||||
@ -22531,7 +23412,7 @@
|
||||
<rect
|
||||
inkscape:transform-center-y="28.155766"
|
||||
inkscape:transform-center-x="-49.979767"
|
||||
style="fill:#8c8989;display:inline"
|
||||
style="display:inline;fill:#8c8989"
|
||||
x="558.76025"
|
||||
y="650.36731"
|
||||
width="2.587785"
|
||||
@ -22545,7 +23426,7 @@
|
||||
width="11.251238"
|
||||
y="642.44122"
|
||||
x="554.66888"
|
||||
style="fill:#e9dcdc;display:inline"
|
||||
style="display:inline;fill:#e9dcdc"
|
||||
inkscape:transform-center-x="-50.291428"
|
||||
inkscape:transform-center-y="28.155811" />
|
||||
<rect
|
||||
@ -22555,13 +23436,13 @@
|
||||
width="2.587785"
|
||||
y="642.44122"
|
||||
x="558.76025"
|
||||
style="fill:#8c8989;display:inline"
|
||||
style="display:inline;fill:#8c8989"
|
||||
inkscape:transform-center-x="-49.979767"
|
||||
inkscape:transform-center-y="28.155811" />
|
||||
<rect
|
||||
inkscape:transform-center-y="28.155826"
|
||||
inkscape:transform-center-x="-50.291428"
|
||||
style="fill:#e9dcdc;display:inline"
|
||||
style="display:inline;fill:#e9dcdc"
|
||||
x="554.66888"
|
||||
y="634.51526"
|
||||
width="11.251238"
|
||||
@ -22571,7 +23452,7 @@
|
||||
<rect
|
||||
inkscape:transform-center-y="28.155826"
|
||||
inkscape:transform-center-x="-49.979767"
|
||||
style="fill:#8c8989;display:inline"
|
||||
style="display:inline;fill:#8c8989"
|
||||
x="558.76025"
|
||||
y="634.51526"
|
||||
width="2.587785"
|
||||
@ -22585,7 +23466,7 @@
|
||||
width="11.251238"
|
||||
y="626.58936"
|
||||
x="554.66888"
|
||||
style="fill:#e9dcdc;display:inline"
|
||||
style="display:inline;fill:#e9dcdc"
|
||||
inkscape:transform-center-x="-50.291428"
|
||||
inkscape:transform-center-y="28.155795" />
|
||||
<rect
|
||||
@ -22595,13 +23476,13 @@
|
||||
width="2.587785"
|
||||
y="626.58936"
|
||||
x="558.76025"
|
||||
style="fill:#8c8989;display:inline"
|
||||
style="display:inline;fill:#8c8989"
|
||||
inkscape:transform-center-x="-49.979767"
|
||||
inkscape:transform-center-y="28.155795" />
|
||||
<rect
|
||||
inkscape:transform-center-y="28.155764"
|
||||
inkscape:transform-center-x="-50.291428"
|
||||
style="fill:#e9dcdc;display:inline"
|
||||
style="display:inline;fill:#e9dcdc"
|
||||
x="554.66888"
|
||||
y="618.66339"
|
||||
width="11.251238"
|
||||
@ -22611,7 +23492,7 @@
|
||||
<rect
|
||||
inkscape:transform-center-y="28.155764"
|
||||
inkscape:transform-center-x="-49.979767"
|
||||
style="fill:#8c8989;display:inline"
|
||||
style="display:inline;fill:#8c8989"
|
||||
x="558.76025"
|
||||
y="618.66339"
|
||||
width="2.587785"
|
||||
@ -22625,7 +23506,7 @@
|
||||
width="11.251238"
|
||||
y="610.73755"
|
||||
x="554.66888"
|
||||
style="fill:#e9dcdc;display:inline"
|
||||
style="display:inline;fill:#e9dcdc"
|
||||
inkscape:transform-center-x="-50.291428"
|
||||
inkscape:transform-center-y="28.155795" />
|
||||
<rect
|
||||
@ -22635,7 +23516,7 @@
|
||||
width="2.587785"
|
||||
y="610.73755"
|
||||
x="558.76025"
|
||||
style="fill:#8c8989;display:inline"
|
||||
style="display:inline;fill:#8c8989"
|
||||
inkscape:transform-center-x="-49.979767"
|
||||
inkscape:transform-center-y="28.155795" />
|
||||
<rect
|
||||
@ -22647,7 +23528,7 @@
|
||||
height="63.408699"
|
||||
width="35.010941"
|
||||
id="rect10533-9"
|
||||
style="fill:#dbddde;fill-opacity:1;fill-rule:evenodd;stroke:#393a3e;stroke-width:0.66049641;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;stroke-dashoffset:0" />
|
||||
style="fill:#dbddde;fill-opacity:1;fill-rule:evenodd;stroke:#393a3e;stroke-width:0.66049641;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1" />
|
||||
<g
|
||||
transform="matrix(0,0.94133169,-0.79502748,0,1498.3162,522.28997)"
|
||||
id="g13003-8">
|
||||
@ -22774,7 +23655,7 @@
|
||||
<path
|
||||
style="fill:#6a6a6a;stroke:#000000;stroke-width:1.54616272;stroke-miterlimit:4;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="M 71.172675,1136.1032 H 64.097833 C 63.725473,1136.1032 63.421705,1135.8081 63.421705,1135.4417 V 1122.7265 C 63.421705,1122.36 63.725473,1122.0628 64.097833,1122.0628 H 71.172675 C 71.547213,1122.0628 71.848803,1122.36 71.848803,1122.7265 V 1135.4417 C 71.848803,1135.8081 71.546124,1136.1032 71.172675,1136.1032 z"
|
||||
d="m 71.172675,1136.1032 l -7.074842,0 c -0.37236,0 -0.676128,-0.2951 -0.676128,-0.6615 l 0,-12.7152 c 0,-0.3665 0.303768,-0.6637 0.676128,-0.6637 l 7.074842,0 c 0.374538,0 0.676128,0.2972 0.676128,0.6637 l 0,12.7152 c 0,0.3664 -0.302679,0.6615 -0.676128,0.6615 z"
|
||||
id="rect4841_3_-0-6" />
|
||||
</g>
|
||||
<rect
|
||||
@ -22975,7 +23856,7 @@
|
||||
transform="matrix(0,0.66049637,-0.66049637,0,1338.5232,386.46429)"
|
||||
id="g13185-6">
|
||||
<rect
|
||||
style="fill:url(#radialGradient13226-6-7);fill-opacity:1;fill-rule:evenodd;stroke:#393a3e;stroke-width:0.58099997;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;stroke-dashoffset:0"
|
||||
style="fill:url(#radialGradient13226-6-7);fill-opacity:1;fill-rule:evenodd;stroke:#393a3e;stroke-width:0.58099997;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1"
|
||||
id="rect13141-0"
|
||||
width="21"
|
||||
height="12.5"
|
||||
@ -22984,7 +23865,7 @@
|
||||
rx="2"
|
||||
ry="2" />
|
||||
<rect
|
||||
style="fill:url(#radialGradient13228-7-2);fill-opacity:1;fill-rule:evenodd;stroke:#393a3e;stroke-width:0.58099997;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;stroke-dashoffset:0"
|
||||
style="fill:url(#radialGradient13228-7-2);fill-opacity:1;fill-rule:evenodd;stroke:#393a3e;stroke-width:0.58099997;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1"
|
||||
id="rect13117-2"
|
||||
width="21"
|
||||
height="12.5"
|
||||
@ -23000,9 +23881,9 @@
|
||||
height="12.5"
|
||||
width="21"
|
||||
id="rect13129-7"
|
||||
style="fill:url(#radialGradient13230-7-4);fill-opacity:1;fill-rule:evenodd;stroke:#393a3e;stroke-width:0.58099997;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;stroke-dashoffset:0" />
|
||||
style="fill:url(#radialGradient13230-7-4);fill-opacity:1;fill-rule:evenodd;stroke:#393a3e;stroke-width:0.58099997;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1" />
|
||||
<rect
|
||||
style="fill:url(#radialGradient13232-1-5);fill-opacity:1;fill-rule:evenodd;stroke:#393a3e;stroke-width:0.58099997;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;stroke-dashoffset:0"
|
||||
style="fill:url(#radialGradient13232-1-5);fill-opacity:1;fill-rule:evenodd;stroke:#393a3e;stroke-width:0.58099997;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1"
|
||||
id="rect13133-5"
|
||||
width="21"
|
||||
height="12.5"
|
||||
@ -23018,7 +23899,7 @@
|
||||
height="12.5"
|
||||
width="21"
|
||||
id="rect13137-0"
|
||||
style="fill:url(#radialGradient13234-2-9);fill-opacity:1;fill-rule:evenodd;stroke:#393a3e;stroke-width:0.58099997;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;stroke-dashoffset:0" />
|
||||
style="fill:url(#radialGradient13234-2-9);fill-opacity:1;fill-rule:evenodd;stroke:#393a3e;stroke-width:0.58099997;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1" />
|
||||
<rect
|
||||
ry="2"
|
||||
rx="2"
|
||||
@ -23027,9 +23908,9 @@
|
||||
height="12.5"
|
||||
width="21"
|
||||
id="rect13145-2"
|
||||
style="fill:url(#radialGradient13236-2-5);fill-opacity:1;fill-rule:evenodd;stroke:#393a3e;stroke-width:0.58099997;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;stroke-dashoffset:0" />
|
||||
style="fill:url(#radialGradient13236-2-5);fill-opacity:1;fill-rule:evenodd;stroke:#393a3e;stroke-width:0.58099997;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1" />
|
||||
<rect
|
||||
style="fill:url(#radialGradient13238-1-0);fill-opacity:1;fill-rule:evenodd;stroke:#393a3e;stroke-width:0.58099997;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;stroke-dashoffset:0"
|
||||
style="fill:url(#radialGradient13238-1-0);fill-opacity:1;fill-rule:evenodd;stroke:#393a3e;stroke-width:0.58099997;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1"
|
||||
id="rect13149-7"
|
||||
width="21"
|
||||
height="12.5"
|
||||
@ -23045,9 +23926,9 @@
|
||||
height="12.5"
|
||||
width="21"
|
||||
id="rect13153-8"
|
||||
style="fill:url(#radialGradient13240-6-1);fill-opacity:1;fill-rule:evenodd;stroke:#393a3e;stroke-width:0.58099997;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;stroke-dashoffset:0" />
|
||||
style="fill:url(#radialGradient13240-6-1);fill-opacity:1;fill-rule:evenodd;stroke:#393a3e;stroke-width:0.58099997;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1" />
|
||||
<rect
|
||||
style="fill:url(#radialGradient13242-9-9);fill-opacity:1;fill-rule:evenodd;stroke:#393a3e;stroke-width:0.58099997;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;stroke-dashoffset:0"
|
||||
style="fill:url(#radialGradient13242-9-9);fill-opacity:1;fill-rule:evenodd;stroke:#393a3e;stroke-width:0.58099997;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1"
|
||||
id="rect13157-21"
|
||||
width="21"
|
||||
height="12.5"
|
||||
@ -23063,68 +23944,68 @@
|
||||
height="12.5"
|
||||
width="21"
|
||||
id="rect13161-4"
|
||||
style="fill:url(#radialGradient13244-6-2);fill-opacity:1;fill-rule:evenodd;stroke:#393a3e;stroke-width:0.58099997;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;stroke-dashoffset:0" />
|
||||
style="fill:url(#radialGradient13244-6-2);fill-opacity:1;fill-rule:evenodd;stroke:#393a3e;stroke-width:0.58099997;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1" />
|
||||
<path
|
||||
style="fill:#b49053;fill-opacity:1;fill-rule:evenodd;stroke:#393a3e;stroke-width:2.08898377;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dashoffset:0"
|
||||
d="M 375.70013,981.69122 L 512.51276,981.69122 C 523.89701,981.69122 533.06195,990.43957 533.06195,1001.3064 L 533.06195,1139.9871 L 512.51276,1159.6022 L 375.70013,1159.6022 C 364.31588,1159.6022 355.15094,1150.8539 355.15094,1139.9871 L 355.15094,1001.3064 C 355.15094,990.43957 364.31588,981.69122 375.70013,981.69122 z"
|
||||
style="fill:#b49053;fill-opacity:1;fill-rule:evenodd;stroke:#393a3e;stroke-width:2.08898377;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-dashoffset:0;stroke-opacity:1"
|
||||
d="m 375.70013,981.69122 l 136.81263,0 c 11.38425,0 20.54919,8.74835 20.54919,19.61518 l 0,138.6807 l -20.54919,19.6151 l -136.81263,0 c -11.38425,0 -20.54919,-8.7483 -20.54919,-19.6151 l 0,-138.6807 c 0,-10.86683 9.16494,-19.61518 20.54919,-19.61518 z"
|
||||
id="rect13070-0"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="sssccssss" />
|
||||
<path
|
||||
style="fill:#cccdce;fill-opacity:1;fill-rule:evenodd;stroke:#393a3e;stroke-width:0.58099997;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;stroke-dashoffset:0"
|
||||
d="M 379.5,1006.8027 L 495.5,1006.8027 L 505.5,1016.5527 L 505.5,1134.3027 L 387.5,1134.3027 L 379.5,1126.5527 z"
|
||||
style="fill:#cccdce;fill-opacity:1;fill-rule:evenodd;stroke:#393a3e;stroke-width:0.58099997;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1"
|
||||
d="m 379.5,1006.8027 l 116,0 l 10,9.75 l 0,117.75 l -118,0 l -8,-7.75 z"
|
||||
id="rect13073-5"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="ccccccc" />
|
||||
<g
|
||||
id="text13076-9"
|
||||
style="font-size:21.66483116px;font-style:normal;font-variant:normal;font-weight:bold;font-stretch:condensed;line-height:125%;letter-spacing:0px;word-spacing:0px;fill:#000000;fill-opacity:1;stroke:none;font-family:Arial Narrow;-inkscape-font-specification:Arial Narrow Bold Condensed"
|
||||
style="font-style:normal;font-variant:normal;font-weight:bold;font-stretch:condensed;font-size:21.66483116px;line-height:125%;font-family:'Arial Narrow';-inkscape-font-specification:'Arial Narrow Bold Condensed';letter-spacing:0px;word-spacing:0px;fill:#000000;fill-opacity:1;stroke:none"
|
||||
transform="scale(1.0832416,0.92315509)">
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path13212-9"
|
||||
style="font-weight:normal;-inkscape-font-specification:Arial Narrow Condensed"
|
||||
d="M 379.71034,1197.185 L 379.71034,1195.3655 L 385.09482,1195.3545 L 385.09482,1201.1092 C 384.26968,1201.9131 383.41635,1202.5197 382.53481,1202.9287 C 381.65326,1203.3307 380.74703,1203.5317 379.81613,1203.5317 C 378.57491,1203.5317 377.46769,1203.2214 376.49447,1202.6008 C 375.52124,1201.9801 374.74901,1201.0739 374.17777,1199.8821 C 373.61358,1198.6902 373.33149,1197.2586 373.33149,1195.5872 C 373.33149,1193.8946 373.61711,1192.4207 374.18835,1191.1654 C 374.75959,1189.9101 375.50714,1188.9862 376.431,1188.3938 C 377.35485,1187.7944 378.44797,1187.4946 379.71034,1187.4946 C 380.64125,1187.4946 381.45579,1187.6674 382.15398,1188.013 C 382.85216,1188.3585 383.42692,1188.8487 383.87829,1189.4834 C 384.32962,1190.1181 384.66814,1190.9891 384.89382,1192.0963 L 383.38109,1192.604 C 383.17657,1191.7296 382.91915,1191.0772 382.60886,1190.647 C 382.29855,1190.2098 381.88951,1189.8677 381.38175,1189.6209 C 380.87397,1189.3741 380.30273,1189.2507 379.66803,1189.2506 C 378.74417,1189.2507 377.94725,1189.4763 377.27728,1189.9277 C 376.61436,1190.372 376.07838,1191.0666 375.66935,1192.0116 C 375.26736,1192.9567 375.06637,1194.1097 375.06637,1195.4708 C 375.06637,1197.5442 375.50009,1199.0993 376.36753,1200.136 C 377.23496,1201.1656 378.36334,1201.6804 379.75266,1201.6804 C 380.41557,1201.6804 381.0926,1201.5217 381.78374,1201.2044 C 382.48191,1200.887 383.03552,1200.5097 383.44457,1200.0725 L 383.44457,1197.1845 L 379.71034,1197.1845" />
|
||||
style="font-weight:normal;-inkscape-font-specification:'Arial Narrow Condensed'"
|
||||
d="m 379.71034,1197.185 l 0,-1.8195 l 5.38448,-0.011 l 0,5.7547 c -0.82514,0.8039 -1.67847,1.4105 -2.56001,1.8195 c -0.88155,0.402 -1.78778,0.603 -2.71868,0.603 c -1.24122,0 -2.34844,-0.3103 -3.32166,-0.9309 c -0.97323,-0.6207 -1.74546,-1.5269 -2.3167,-2.7187 c -0.56419,-1.1919 -0.84628,-2.6235 -0.84628,-4.2949 c 0,-1.6926 0.28562,-3.1665 0.85686,-4.4218 c 0.57124,-1.2553 1.31879,-2.1792 2.24265,-2.7716 c 0.92385,-0.5994 2.01697,-0.8992 3.27934,-0.8992 c 0.93091,0 1.74545,0.1728 2.44364,0.5184 c 0.69818,0.3455 1.27294,0.8357 1.72431,1.4704 c 0.45133,0.6347 0.78985,1.5057 1.01553,2.6129 l -1.51273,0.5077 c -0.20452,-0.8744 -0.46194,-1.5268 -0.77223,-1.957 c -0.31031,-0.4372 -0.71935,-0.7793 -1.22711,-1.0261 c -0.50778,-0.2468 -1.07902,-0.3702 -1.71372,-0.3703 c -0.92386,10e-5 -1.72078,0.2257 -2.39075,0.6771 c -0.66292,0.4443 -1.1989,1.1389 -1.60793,2.0839 c -0.40199,0.9451 -0.60298,2.0981 -0.60298,3.4592 c 0,2.0734 0.43372,3.6285 1.30116,4.6652 c 0.86743,1.0296 1.99581,1.5444 3.38513,1.5444 c 0.66291,0 1.33994,-0.1587 2.03108,-0.476 c 0.69817,-0.3174 1.25178,-0.6947 1.66083,-1.1319 l 0,-2.888 l -3.73423,0" />
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path13214-5"
|
||||
style="font-weight:normal;-inkscape-font-specification:Arial Narrow Condensed"
|
||||
d="M 390.8178,1203.2677 L 390.8178,1189.5897 L 386.6287,1189.5897 L 386.6287,1187.7596 L 396.71004,1187.7596 L 396.71004,1189.5897 L 392.49979,1189.5897 L 392.49979,1203.2677 L 390.8178,1203.2677" />
|
||||
style="font-weight:normal;-inkscape-font-specification:'Arial Narrow Condensed'"
|
||||
d="m 390.8178,1203.2677 l 0,-13.678 l -4.1891,0 l 0,-1.8301 l 10.08134,0 l 0,1.8301 l -4.21025,0 l 0,13.678 l -1.68199,0" />
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path13216-4"
|
||||
style="font-weight:normal;-inkscape-font-specification:Arial Narrow Condensed"
|
||||
d="M 398.43434,1203.2677 L 398.43434,1187.7596 L 403.22642,1187.7596 C 404.35479,1187.7596 405.18697,1187.8586 405.72295,1188.0558 C 406.45639,1188.3238 407.04173,1188.821 407.47899,1189.5473 C 407.91622,1190.2738 408.13485,1191.1659 408.13486,1192.2237 C 408.13485,1193.6201 407.7787,1194.759 407.06643,1195.6406 C 406.35413,1196.5221 405.12349,1196.9629 403.37452,1196.9629 L 400.11633,1196.9629 L 400.11633,1203.2677 L 398.43434,1203.2677 M 400.11633,1195.1328 L 403.40625,1195.1328 C 404.44294,1195.1328 405.20107,1194.9001 405.68064,1194.4346 C 406.16019,1193.9621 406.39997,1193.2534 406.39998,1192.3083 C 406.39997,1191.6948 406.28008,1191.1694 406.04031,1190.7321 C 405.80757,1190.2949 405.52195,1189.9952 405.18345,1189.833 C 404.85198,1189.6708 404.249,1189.5897 403.37452,1189.5897 L 400.11633,1189.5897 L 400.11633,1195.1328" />
|
||||
style="font-weight:normal;-inkscape-font-specification:'Arial Narrow Condensed'"
|
||||
d="m 398.43434,1203.2677 l 0,-15.5081 l 4.79208,0 c 1.12837,0 1.96055,0.099 2.49653,0.2962 c 0.73344,0.268 1.31878,0.7652 1.75604,1.4915 c 0.43723,0.7265 0.65586,1.6186 0.65587,2.6764 c -1e-5,1.3964 -0.35616,2.5353 -1.06843,3.4169 c -0.7123,0.8815 -1.94294,1.3223 -3.69191,1.3223 l -3.25819,0 l 0,6.3048 l -1.68199,0 m 1.68199,-8.1349 l 3.28992,0 c 1.03669,0 1.79482,-0.2327 2.27439,-0.6982 c 0.47955,-0.4725 0.71933,-1.1812 0.71934,-2.1263 c -1e-5,-0.6135 -0.1199,-1.1389 -0.35967,-1.5762 c -0.23274,-0.4372 -0.51836,-0.7369 -0.85686,-0.8991 c -0.33147,-0.1622 -0.93445,-0.2433 -1.80893,-0.2433 l -3.25819,0 l 0,5.5431" />
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path13218-1"
|
||||
style="font-weight:normal;-inkscape-font-specification:Arial Narrow Condensed"
|
||||
d="M 407.59535,1203.2677 L 412.48263,1187.7596 L 414.29156,1187.7596 L 419.4962,1203.2677 L 417.57091,1203.2677 L 416.08991,1198.5708 L 410.77949,1198.5708 L 409.38312,1203.2677 L 407.59535,1203.2677 M 411.2661,1196.8994 L 415.57156,1196.8994 L 414.24925,1192.6045 C 413.8402,1191.2858 413.54048,1190.2138 413.35007,1189.3887 C 413.18786,1190.3831 412.95866,1191.3704 412.66247,1192.3507 L 411.2661,1196.8994" />
|
||||
style="font-weight:normal;-inkscape-font-specification:'Arial Narrow Condensed'"
|
||||
d="m 407.59535,1203.2677 l 4.88728,-15.5081 l 1.80893,0 l 5.20464,15.5081 l -1.92529,0 l -1.481,-4.6969 l -5.31042,0 l -1.39637,4.6969 l -1.78777,0 m 3.67075,-6.3683 l 4.30546,0 l -1.32231,-4.2949 c -0.40905,-1.3187 -0.70877,-2.3907 -0.89918,-3.2158 c -0.16221,0.9944 -0.39141,1.9817 -0.6876,2.962 l -1.39637,4.5487" />
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path13220-5"
|
||||
style="font-weight:normal;-inkscape-font-specification:Arial Narrow Condensed"
|
||||
d="M 420.19438,1195.6194 C 420.19438,1193.0171 420.54347,1191.046 421.24165,1189.706 C 421.94689,1188.3661 422.98358,1187.6961 424.35174,1187.6961 C 425.56474,1187.6961 426.52033,1188.2391 427.21852,1189.3252 C 428.0648,1190.6369 428.48794,1192.735 428.48795,1195.6194 C 428.48794,1198.2076 428.13885,1200.1752 427.44067,1201.5222 C 426.74248,1202.8622 425.70579,1203.5322 424.33059,1203.5322 C 423.11758,1203.5322 422.1232,1202.9398 421.34744,1201.755 C 420.57873,1200.5702 420.19438,1198.525 420.19438,1195.6194 M 421.79174,1195.6194 C 421.79174,1198.1371 422.03152,1199.8262 422.51108,1200.6865 C 422.99769,1201.5399 423.61829,1201.9665 424.3729,1201.9665 C 425.08518,1201.9665 425.68111,1201.5328 426.16067,1200.6654 C 426.64022,1199.7979 426.88,1198.116 426.88001,1195.6194 C 426.88,1193.0947 426.6367,1191.4057 426.15009,1190.5523 C 425.67053,1189.699 425.04639,1189.2723 424.27769,1189.2723 C 423.57245,1189.2723 422.98006,1189.706 422.5005,1190.5735 C 422.02799,1191.4409 421.79174,1193.1229 421.79174,1195.6194" />
|
||||
style="font-weight:normal;-inkscape-font-specification:'Arial Narrow Condensed'"
|
||||
d="m 420.19438,1195.6194 c 0,-2.6023 0.34909,-4.5734 1.04727,-5.9134 c 0.70524,-1.3399 1.74193,-2.0099 3.11009,-2.0099 c 1.213,0 2.16859,0.543 2.86678,1.6291 c 0.84628,1.3117 1.26942,3.4098 1.26943,6.2942 c -1e-5,2.5882 -0.3491,4.5558 -1.04728,5.9028 c -0.69819,1.34 -1.73488,2.01 -3.11008,2.01 c -1.21301,0 -2.20739,-0.5924 -2.98315,-1.7772 c -0.76871,-1.1848 -1.15306,-3.23 -1.15306,-6.1356 m 1.59736,0 c 0,2.5177 0.23978,4.2068 0.71934,5.0671 c 0.48661,0.8534 1.10721,1.28 1.86182,1.28 c 0.71228,0 1.30821,-0.4337 1.78777,-1.3011 c 0.47955,-0.8675 0.71933,-2.5494 0.71934,-5.046 c -1e-5,-2.5247 -0.24331,-4.2137 -0.72992,-5.0671 c -0.47956,-0.8533 -1.1037,-1.28 -1.8724,-1.28 c -0.70524,0 -1.29763,0.4337 -1.77719,1.3012 c -0.47251,0.8674 -0.70876,2.5494 -0.70876,5.0459" />
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path13222-3"
|
||||
style="font-weight:normal;-inkscape-font-specification:Arial Narrow Condensed"
|
||||
d="M 435.97755,1203.2677 L 434.41193,1203.2677 L 434.41193,1191.1341 C 434.05225,1191.5573 433.56916,1191.991 432.96267,1192.4353 C 432.35616,1192.8725 431.79903,1193.204 431.29126,1193.4297 L 431.29126,1191.589 C 432.15164,1191.0953 432.90977,1190.4924 433.56564,1189.7801 C 434.22856,1189.0678 434.69401,1188.3731 434.96201,1187.6961 L 435.97755,1187.6961 L 435.97755,1203.2677" />
|
||||
style="font-weight:normal;-inkscape-font-specification:'Arial Narrow Condensed'"
|
||||
d="m 435.97755,1203.2677 l -1.56562,0 l 0,-12.1336 c -0.35968,0.4232 -0.84277,0.8569 -1.44926,1.3012 c -0.60651,0.4372 -1.16364,0.7687 -1.67141,0.9944 l 0,-1.8407 c 0.86038,-0.4937 1.61851,-1.0966 2.27438,-1.8089 c 0.66292,-0.7123 1.12837,-1.407 1.39637,-2.084 l 1.01554,0 l 0,15.5716" />
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path13224-5"
|
||||
style="font-weight:normal;-inkscape-font-specification:Arial Narrow Condensed"
|
||||
d="M 439.99739,1195.6194 C 439.99739,1193.0171 440.34648,1191.046 441.04466,1189.706 C 441.7499,1188.3661 442.78659,1187.6961 444.15475,1187.6961 C 445.36775,1187.6961 446.32334,1188.2391 447.02153,1189.3252 C 447.86781,1190.6369 448.29095,1192.735 448.29096,1195.6194 C 448.29095,1198.2076 447.94186,1200.1752 447.24368,1201.5222 C 446.54549,1202.8622 445.5088,1203.5322 444.13359,1203.5322 C 442.92059,1203.5322 441.92621,1202.9398 441.15045,1201.755 C 440.38174,1200.5702 439.99739,1198.525 439.99739,1195.6194 M 441.59475,1195.6194 C 441.59475,1198.1371 441.83452,1199.8262 442.31409,1200.6865 C 442.8007,1201.5399 443.4213,1201.9665 444.17591,1201.9665 C 444.88819,1201.9665 445.48411,1201.5328 445.96368,1200.6654 C 446.44323,1199.7979 446.68301,1198.116 446.68302,1195.6194 C 446.68301,1193.0947 446.43971,1191.4057 445.9531,1190.5523 C 445.47354,1189.699 444.8494,1189.2723 444.0807,1189.2723 C 443.37546,1189.2723 442.78307,1189.706 442.30351,1190.5735 C 441.831,1191.4409 441.59475,1193.1229 441.59475,1195.6194" />
|
||||
style="font-weight:normal;-inkscape-font-specification:'Arial Narrow Condensed'"
|
||||
d="m 439.99739,1195.6194 c 0,-2.6023 0.34909,-4.5734 1.04727,-5.9134 c 0.70524,-1.3399 1.74193,-2.0099 3.11009,-2.0099 c 1.213,0 2.16859,0.543 2.86678,1.6291 c 0.84628,1.3117 1.26942,3.4098 1.26943,6.2942 c -10e-6,2.5882 -0.3491,4.5558 -1.04728,5.9028 c -0.69819,1.34 -1.73488,2.01 -3.11009,2.01 c -1.213,0 -2.20738,-0.5924 -2.98314,-1.7772 c -0.76871,-1.1848 -1.15306,-3.23 -1.15306,-6.1356 m 1.59736,0 c 0,2.5177 0.23977,4.2068 0.71934,5.0671 c 0.48661,0.8534 1.10721,1.28 1.86182,1.28 c 0.71228,0 1.3082,-0.4337 1.78777,-1.3011 c 0.47955,-0.8675 0.71933,-2.5494 0.71934,-5.046 c -10e-6,-2.5247 -0.24331,-4.2137 -0.72992,-5.0671 c -0.47956,-0.8533 -1.1037,-1.28 -1.8724,-1.28 c -0.70524,0 -1.29763,0.4337 -1.77719,1.3012 c -0.47251,0.8674 -0.70876,2.5494 -0.70876,5.0459" />
|
||||
</g>
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path7384-0-2"
|
||||
d="M 444.40744,1038.0272 C 452.57603,1038.0272 459.19798,1044.6491 459.19798,1052.8177 C 459.19798,1060.9863 452.57603,1067.6082 444.40744,1067.6082 C 436.23885,1067.6082 429.6169,1060.9863 429.6169,1052.8177 C 429.6169,1044.6491 436.23885,1038.0272 444.40744,1038.0272 z"
|
||||
style="fill:url(#radialGradient13246-3-7);fill-opacity:1;fill-rule:evenodd;stroke:#87878d;stroke-width:5.08913088;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
d="m 444.40744,1038.0272 c 8.16859,0 14.79054,6.6219 14.79054,14.7905 c 0,8.1686 -6.62195,14.7905 -14.79054,14.7905 c -8.16859,0 -14.79054,-6.6219 -14.79054,-14.7905 c 0,-8.1686 6.62195,-14.7905 14.79054,-14.7905 z"
|
||||
style="fill:url(#radialGradient13246-3-7);fill-opacity:1;fill-rule:evenodd;stroke:#87878d;stroke-width:5.08913088;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:#cccdce;fill-opacity:1;fill-rule:evenodd;stroke:#393a3e;stroke-width:0.58099997;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;stroke-dashoffset:0"
|
||||
d="M 520,1000.0527 C 520,1003.2283 517.42564,1005.8027 514.25,1005.8027 C 511.07436,1005.8027 508.5,1003.2283 508.5,1000.0527 C 508.5,996.87704 511.07436,994.30267 514.25,994.30267 C 517.42564,994.30267 520,996.87704 520,1000.0527 z"
|
||||
style="fill:#cccdce;fill-opacity:1;fill-rule:evenodd;stroke:#393a3e;stroke-width:0.58099997;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1"
|
||||
d="m 520,1000.0527 c 0,3.1756 -2.57436,5.75 -5.75,5.75 c -3.17564,0 -5.75,-2.5744 -5.75,-5.75 c 0,-3.17566 2.57436,-5.75003 5.75,-5.75003 c 3.17564,0 5.75,2.57437 5.75,5.75003 z"
|
||||
id="path13114-9" />
|
||||
</g>
|
||||
<g
|
||||
@ -23132,98 +24013,98 @@
|
||||
transform="matrix(0,0.77129601,-0.77129601,0,1428.0498,353.39548)">
|
||||
<g
|
||||
id="text13504-7"
|
||||
style="font-size:40px;font-style:normal;font-variant:normal;font-weight:bold;font-stretch:condensed;line-height:125%;letter-spacing:0px;word-spacing:0px;fill:#545352;fill-opacity:1;stroke:none;font-family:Arial Narrow;-inkscape-font-specification:Arial Narrow Bold Condensed">
|
||||
style="font-style:normal;font-variant:normal;font-weight:bold;font-stretch:condensed;font-size:40px;line-height:125%;font-family:'Arial Narrow';-inkscape-font-specification:'Arial Narrow Bold Condensed';letter-spacing:0px;word-spacing:0px;fill:#545352;fill-opacity:1;stroke:none">
|
||||
<path
|
||||
id="path13532-9"
|
||||
d="M 265.02742,1153.6896 L 265.02742,1148.8654 L 275.24226,1148.8654 L 275.24226,1160.2716 C 274.2136,1161.4825 272.75526,1162.5242 270.86726,1163.3966 C 268.97923,1164.269 267.0847,1164.7052 265.18367,1164.7052 C 262.86595,1164.7052 260.82168,1164.1388 259.05086,1163.006 C 257.28002,1161.8602 255.87377,1160.1544 254.83211,1157.8888 C 253.80346,1155.6102 253.28914,1152.9344 253.28914,1149.8615 C 253.28914,1146.7104 253.80997,1144.0151 254.85164,1141.7755 C 255.90632,1139.536 257.267,1137.8628 258.93367,1136.756 C 260.61335,1135.6492 262.61855,1135.0959 264.9493,1135.0958 C 267.74876,1135.0959 269.98834,1135.812 271.66805,1137.2443 C 273.36073,1138.6636 274.44797,1140.7534 274.92976,1143.5138 L 270.24226,1144.588 C 269.89068,1143.1167 269.24615,1141.9904 268.30867,1141.2091 C 267.37115,1140.4279 266.25136,1140.0373 264.9493,1140.0372 C 262.93105,1140.0373 261.29694,1140.825 260.04695,1142.4005 C 258.79694,1143.963 258.17194,1146.3524 258.17195,1149.5685 C 258.17194,1153.019 258.84903,1155.6427 260.2032,1157.4396 C 261.36205,1158.9891 262.93105,1159.7638 264.91023,1159.7638 C 265.8347,1159.7638 266.79173,1159.549 267.78133,1159.1193 C 268.78391,1158.6766 269.67584,1158.0776 270.45711,1157.3224 L 270.45711,1153.6896 L 265.02742,1153.6896"
|
||||
d="m 265.02742,1153.6896 l 0,-4.8242 l 10.21484,0 l 0,11.4062 c -1.02866,1.2109 -2.487,2.2526 -4.375,3.125 c -1.88803,0.8724 -3.78256,1.3086 -5.68359,1.3086 c -2.31772,0 -4.36199,-0.5664 -6.13281,-1.6992 c -1.77084,-1.1458 -3.17709,-2.8516 -4.21875,-5.1172 c -1.02865,-2.2786 -1.54297,-4.9544 -1.54297,-8.0273 c 0,-3.1511 0.52083,-5.8464 1.5625,-8.086 c 1.05468,-2.2395 2.41536,-3.9127 4.08203,-5.0195 c 1.67968,-1.1068 3.68488,-1.6601 6.01563,-1.6602 c 2.79946,10e-5 5.03904,0.7162 6.71875,2.1485 c 1.69268,1.4193 2.77992,3.5091 3.26171,6.2695 l -4.6875,1.0742 c -0.35158,-1.4713 -0.99611,-2.5976 -1.93359,-3.3789 c -0.93752,-0.7812 -2.05731,-1.1718 -3.35937,-1.1719 c -2.01825,10e-5 -3.65236,0.7878 -4.90235,2.3633 c -1.25001,1.5625 -1.87501,3.9519 -1.875,7.168 c -10e-6,3.4505 0.67708,6.0742 2.03125,7.8711 c 1.15885,1.5495 2.72785,2.3242 4.70703,2.3242 c 0.92447,0 1.8815,-0.2148 2.8711,-0.6445 c 1.00258,-0.4427 1.89451,-1.0417 2.67578,-1.7969 l 0,-3.6328 l -5.42969,0"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
id="path13534-4"
|
||||
d="M 289.48055,1157.6154 L 293.9532,1158.5333 C 293.35423,1160.6167 292.42324,1162.1661 291.16023,1163.1818 C 289.8972,1164.1844 288.36074,1164.6857 286.55086,1164.6857 C 284.03783,1164.6857 282.09773,1163.8458 280.73055,1162.1661 C 279.11596,1160.213 278.30867,1157.4786 278.30867,1153.963 C 278.30867,1150.4995 279.12247,1147.7261 280.75008,1145.6427 C 282.13028,1143.8849 283.91413,1143.006 286.10164,1143.006 C 288.53652,1143.006 290.44407,1143.9044 291.8243,1145.7013 C 293.41282,1147.7586 294.20709,1150.7925 294.20711,1154.8029 L 294.18761,1155.4279 L 282.91808,1155.4279 C 282.94408,1157.0685 283.30869,1158.338 284.01183,1159.2365 C 284.72796,1160.1349 285.58734,1160.5841 286.58995,1160.5841 C 288.03525,1160.5841 288.99879,1159.5945 289.48058,1157.6154 M 289.73448,1152.0685 C 289.69538,1150.4539 289.35035,1149.243 288.69933,1148.4357 C 288.04827,1147.6154 287.27353,1147.2052 286.37511,1147.2052 C 285.42458,1147.2052 284.6238,1147.6284 283.97276,1148.4747 C 283.30869,1149.3341 282.98317,1150.532 282.9962,1152.0685 L 289.73448,1152.0685"
|
||||
d="m 289.48055,1157.6154 l 4.47265,0.9179 c -0.59897,2.0834 -1.52996,3.6328 -2.79297,4.6485 c -1.26303,1.0026 -2.79949,1.5039 -4.60937,1.5039 c -2.51303,0 -4.45313,-0.8399 -5.82031,-2.5196 c -1.61459,-1.9531 -2.42188,-4.6875 -2.42188,-8.2031 c 0,-3.4635 0.8138,-6.2369 2.44141,-8.3203 c 1.3802,-1.7578 3.16405,-2.6367 5.35156,-2.6367 c 2.43488,0 4.34243,0.8984 5.72266,2.6953 c 1.58852,2.0573 2.38279,5.0912 2.38281,9.1016 l -0.0195,0.625 l -11.26953,0 c 0.026,1.6406 0.39061,2.9101 1.09375,3.8086 c 0.71613,0.8984 1.57551,1.3476 2.57812,1.3476 c 1.4453,0 2.40884,-0.9896 2.89063,-2.9687 m 0.2539,-5.5469 c -0.0391,-1.6146 -0.38413,-2.8255 -1.03515,-3.6328 c -0.65106,-0.8203 -1.4258,-1.2305 -2.32422,-1.2305 c -0.95053,0 -1.75131,0.4232 -2.40235,1.2695 c -0.66407,0.8594 -0.98959,2.0573 -0.97656,3.5938 l 6.73828,0"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
id="path13536-1-0"
|
||||
d="M 313.36726,1164.2169 L 308.85555,1164.2169 L 308.85555,1153.631 C 308.85553,1151.5086 308.77085,1150.0958 308.60164,1149.3927 C 308.43236,1148.6896 308.11334,1148.1492 307.64461,1147.7716 C 307.18887,1147.394 306.66803,1147.2052 306.08211,1147.2052 C 305.32689,1147.2052 304.6433,1147.4526 304.03133,1147.9474 C 303.41934,1148.4292 302.98965,1149.0997 302.74226,1149.9591 C 302.49486,1150.8185 302.37116,1152.4396 302.37117,1154.8224 L 302.37117,1164.2169 L 297.85945,1164.2169 L 297.85945,1143.4747 L 302.03914,1143.4747 L 302.03914,1146.5216 C 302.78132,1145.3498 303.61465,1144.4708 304.53914,1143.8849 C 305.47663,1143.299 306.51178,1143.006 307.64461,1143.006 C 308.9597,1143.006 310.06647,1143.3511 310.96492,1144.0411 C 311.87636,1144.7182 312.50136,1145.5971 312.83992,1146.6779 C 313.19146,1147.7456 313.36725,1149.2951 313.36726,1151.3263 L 313.36726,1164.2169"
|
||||
d="m 313.36726,1164.2169 l -4.51171,0 l 0,-10.5859 c -2e-5,-2.1224 -0.0847,-3.5352 -0.25391,-4.2383 c -0.16928,-0.7031 -0.4883,-1.2435 -0.95703,-1.6211 c -0.45574,-0.3776 -0.97658,-0.5664 -1.5625,-0.5664 c -0.75522,0 -1.43881,0.2474 -2.05078,0.7422 c -0.61199,0.4818 -1.04168,1.1523 -1.28907,2.0117 c -0.2474,0.8594 -0.3711,2.4805 -0.37109,4.8633 l 0,9.3945 l -4.51172,0 l 0,-20.7422 l 4.17969,0 l 0,3.0469 c 0.74218,-1.1718 1.57551,-2.0508 2.5,-2.6367 c 0.93749,-0.5859 1.97264,-0.8789 3.10547,-0.8789 c 1.31509,0 2.42186,0.3451 3.32031,1.0351 c 0.91144,0.6771 1.53644,1.556 1.875,2.6368 c 0.35154,1.0677 0.52733,2.6172 0.52734,4.6484 l 0,12.8906"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
id="path13538-5-5"
|
||||
d="M 327.83992,1157.6154 L 332.31258,1158.5333 C 331.7136,1160.6167 330.78261,1162.1661 329.51961,1163.1818 C 328.25657,1164.1844 326.72012,1164.6857 324.91023,1164.6857 C 322.3972,1164.6857 320.4571,1163.8458 319.08992,1162.1661 C 317.47533,1160.213 316.66804,1157.4786 316.66805,1153.963 C 316.66804,1150.4995 317.48185,1147.7261 319.10945,1145.6427 C 320.48965,1143.8849 322.27351,1143.006 324.46101,1143.006 C 326.8959,1143.006 328.80345,1143.9044 330.18367,1145.7013 C 331.7722,1147.7586 332.56647,1150.7925 332.56648,1154.8029 L 332.54698,1155.4279 L 321.27745,1155.4279 C 321.30345,1157.0685 321.66807,1158.338 322.3712,1159.2365 C 323.08734,1160.1349 323.94671,1160.5841 324.94933,1160.5841 C 326.39463,1160.5841 327.35817,1159.5945 327.83995,1157.6154 M 328.09386,1152.0685 C 328.05476,1150.4539 327.70973,1149.243 327.0587,1148.4357 C 326.40765,1147.6154 325.63291,1147.2052 324.73448,1147.2052 C 323.78395,1147.2052 322.98317,1147.6284 322.33214,1148.4747 C 321.66807,1149.3341 321.34255,1150.532 321.35558,1152.0685 L 328.09386,1152.0685"
|
||||
d="m 327.83992,1157.6154 l 4.47266,0.9179 c -0.59898,2.0834 -1.52997,3.6328 -2.79297,4.6485 c -1.26304,1.0026 -2.79949,1.5039 -4.60938,1.5039 c -2.51303,0 -4.45313,-0.8399 -5.82031,-2.5196 c -1.61459,-1.9531 -2.42188,-4.6875 -2.42187,-8.2031 c -10e-6,-3.4635 0.8138,-6.2369 2.4414,-8.3203 c 1.3802,-1.7578 3.16406,-2.6367 5.35156,-2.6367 c 2.43489,0 4.34244,0.8984 5.72266,2.6953 c 1.58853,2.0573 2.3828,5.0912 2.38281,9.1016 l -0.0195,0.625 l -11.26953,0 c 0.026,1.6406 0.39062,2.9101 1.09375,3.8086 c 0.71614,0.8984 1.57551,1.3476 2.57813,1.3476 c 1.4453,0 2.40884,-0.9896 2.89062,-2.9687 m 0.25391,-5.5469 c -0.0391,-1.6146 -0.38413,-2.8255 -1.03516,-3.6328 c -0.65105,-0.8203 -1.42579,-1.2305 -2.32422,-1.2305 c -0.95053,0 -1.75131,0.4232 -2.40234,1.2695 c -0.66407,0.8594 -0.98959,2.0573 -0.97656,3.5938 l 6.73828,0"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
id="path13540-4-0"
|
||||
d="M 340.5743,1164.2169 L 336.06258,1164.2169 L 336.06258,1143.4747 L 340.24226,1143.4747 L 340.24226,1146.424 C 340.9584,1145.0438 341.59642,1144.1323 342.15633,1143.6896 C 342.72923,1143.2339 343.38679,1143.006 344.12898,1143.006 C 345.15762,1143.006 346.14069,1143.3511 347.0782,1144.0411 L 345.67195,1148.8263 C 344.92975,1148.2274 344.22663,1147.9279 343.56258,1147.9279 C 342.93757,1147.9279 342.38418,1148.1622 341.90242,1148.631 C 341.43366,1149.0867 341.09512,1149.9201 340.8868,1151.131 C 340.67845,1152.3419 340.57429,1154.5685 340.5743,1157.8107 L 340.5743,1164.2169"
|
||||
d="m 340.5743,1164.2169 l -4.51172,0 l 0,-20.7422 l 4.17968,0 l 0,2.9493 c 0.71614,-1.3802 1.35416,-2.2917 1.91407,-2.7344 c 0.5729,-0.4557 1.23046,-0.6836 1.97265,-0.6836 c 1.02864,0 2.01171,0.3451 2.94922,1.0351 l -1.40625,4.7852 c -0.7422,-0.5989 -1.44532,-0.8984 -2.10937,-0.8984 c -0.62501,0 -1.1784,0.2343 -1.66016,0.7031 c -0.46876,0.4557 -0.8073,1.2891 -1.01562,2.5 c -0.20835,1.2109 -0.31251,3.4375 -0.3125,6.6797 l 0,6.4062"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
id="path13542-9-7"
|
||||
d="M 348.99226,1140.6622 L 348.99226,1135.5841 L 353.50398,1135.5841 L 353.50398,1140.6622 L 348.99226,1140.6622 M 348.99226,1164.2169 L 348.99226,1143.4747 L 353.50398,1143.4747 L 353.50398,1164.2169 L 348.99226,1164.2169"
|
||||
d="m 348.99226,1140.6622 l 0,-5.0781 l 4.51172,0 l 0,5.0781 l -4.51172,0 m 0,23.5547 l 0,-20.7422 l 4.51172,0 l 0,20.7422 l -4.51172,0"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
id="path13544-4-8"
|
||||
d="M 372.95711,1149.6075 L 368.52351,1150.5841 C 368.19798,1148.4096 367.17585,1147.3224 365.45711,1147.3224 C 364.35033,1147.3224 363.4584,1147.7912 362.78133,1148.7286 C 362.10424,1149.6662 361.7657,1151.2482 361.7657,1153.4747 C 361.7657,1155.9357 362.10424,1157.674 362.78133,1158.6896 C 363.4584,1159.7052 364.36335,1160.213 365.49617,1160.213 C 366.34251,1160.213 367.03913,1159.9266 367.58601,1159.3536 C 368.13288,1158.7677 368.5235,1157.7391 368.75789,1156.2677 L 373.19148,1157.1857 C 372.28001,1162.1857 369.65631,1164.6857 365.32039,1164.6857 C 362.54694,1164.6857 360.48965,1163.631 359.14851,1161.5216 C 357.80737,1159.4122 357.13679,1156.8732 357.1368,1153.9044 C 357.13679,1150.3497 357.892,1147.6479 359.40242,1145.799 C 360.92585,1143.937 362.91804,1143.006 365.37898,1143.006 C 367.37116,1143.006 368.99225,1143.5333 370.24226,1144.588 C 371.50527,1145.6427 372.41022,1147.3159 372.95711,1149.6075"
|
||||
d="m 372.95711,1149.6075 l -4.4336,0.9766 c -0.32553,-2.1745 -1.34766,-3.2617 -3.0664,-3.2617 c -1.10678,0 -1.99871,0.4688 -2.67578,1.4062 c -0.67709,0.9376 -1.01563,2.5196 -1.01563,4.7461 c 0,2.461 0.33854,4.1993 1.01563,5.2149 c 0.67707,1.0156 1.58202,1.5234 2.71484,1.5234 c 0.84634,0 1.54296,-0.2864 2.08984,-0.8594 c 0.54687,-0.5859 0.93749,-1.6145 1.17188,-3.0859 l 4.43359,0.918 c -0.91147,5 -3.53517,7.5 -7.87109,7.5 c -2.77345,0 -4.83074,-1.0547 -6.17188,-3.1641 c -1.34114,-2.1094 -2.01172,-4.6484 -2.01171,-7.6172 c -10e-6,-3.5547 0.7552,-6.2565 2.26562,-8.1054 c 1.52343,-1.862 3.51562,-2.793 5.97656,-2.793 c 1.99218,0 3.61327,0.5273 4.86328,1.582 c 1.26301,1.0547 2.16796,2.7279 2.71485,5.0195"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
id="path13546-8-4"
|
||||
d="M 385.63289,1164.2169 L 385.63289,1135.5841 L 390.24226,1135.5841 L 399.85164,1154.7052 L 399.85164,1135.5841 L 404.2657,1135.5841 L 404.2657,1164.2169 L 399.50008,1164.2169 L 390.04695,1145.545 L 390.04695,1164.2169 L 385.63289,1164.2169"
|
||||
d="m 385.63289,1164.2169 l 0,-28.6328 l 4.60937,0 l 9.60938,19.1211 l 0,-19.1211 l 4.41406,0 l 0,28.6328 l -4.76562,0 l -9.45313,-18.6719 l 0,18.6719 l -4.41406,0"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
id="path13548-8-4"
|
||||
d="M 409.18758,1164.2169 L 409.18758,1135.5841 L 416.27742,1135.5841 L 420.53523,1155.1154 L 424.75398,1135.5841 L 431.86336,1135.5841 L 431.86336,1164.2169 L 427.46883,1164.2169 L 427.46883,1141.6779 L 422.80086,1164.2169 L 418.23055,1164.2169 L 413.60164,1141.6779 L 413.60164,1164.2169 L 409.18758,1164.2169"
|
||||
d="m 409.18758,1164.2169 l 0,-28.6328 l 7.08984,0 l 4.25781,19.5313 l 4.21875,-19.5313 l 7.10938,0 l 0,28.6328 l -4.39453,0 l 0,-22.539 l -4.66797,22.539 l -4.57031,0 l -4.62891,-22.539 l 0,22.539 l -4.41406,0"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
id="path13550-1-3"
|
||||
d="M 436.60945,1164.2169 L 436.60945,1135.5841 L 454.03133,1135.5841 L 454.03133,1140.4279 L 441.33601,1140.4279 L 441.33601,1146.7755 L 453.13289,1146.7755 L 453.13289,1151.5997 L 441.33601,1151.5997 L 441.33601,1159.3927 L 454.46101,1159.3927 L 454.46101,1164.2169 L 436.60945,1164.2169"
|
||||
d="m 436.60945,1164.2169 l 0,-28.6328 l 17.42188,0 l 0,4.8438 l -12.69532,0 l 0,6.3476 l 11.79688,0 l 0,4.8242 l -11.79688,0 l 0,7.793 l 13.125,0 l 0,4.8242 l -17.85156,0"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
id="path13552-7-4"
|
||||
d="M 479.6368,1164.2169 L 474.48055,1164.2169 L 472.42976,1157.713 L 463.05476,1157.713 L 461.12117,1164.2169 L 456.08211,1164.2169 L 465.22273,1135.5841 L 470.24226,1135.5841 L 479.6368,1164.2169 M 470.90633,1152.8888 L 467.68367,1142.2638 L 464.50008,1152.8888 L 470.90633,1152.8888"
|
||||
d="m 479.6368,1164.2169 l -5.15625,0 l -2.05079,-6.5039 l -9.375,0 l -1.93359,6.5039 l -5.03906,0 l 9.14062,-28.6328 l 5.01953,0 l 9.39454,28.6328 m -8.73047,-11.3281 l -3.22266,-10.625 l -3.18359,10.625 l 6.40625,0"
|
||||
inkscape:connector-curvature="0" />
|
||||
</g>
|
||||
<g
|
||||
id="text13500-73"
|
||||
style="font-size:40px;font-style:normal;font-variant:normal;font-weight:bold;font-stretch:condensed;line-height:125%;letter-spacing:0px;word-spacing:0px;fill:#000000;fill-opacity:1;stroke:none;font-family:Arial Narrow;-inkscape-font-specification:Arial Narrow Bold Condensed">
|
||||
style="font-style:normal;font-variant:normal;font-weight:bold;font-stretch:condensed;font-size:40px;line-height:125%;font-family:'Arial Narrow';-inkscape-font-specification:'Arial Narrow Bold Condensed';letter-spacing:0px;word-spacing:0px;fill:#000000;fill-opacity:1;stroke:none">
|
||||
<path
|
||||
id="path13509-4"
|
||||
d="M 264.32031,1152.2754 L 264.32031,1147.4512 L 274.53516,1147.4512 L 274.53516,1158.8574 C 273.50649,1160.0684 272.04816,1161.11 270.16016,1161.9824 C 268.27212,1162.8548 266.37759,1163.291 264.47656,1163.291 C 262.15884,1163.291 260.11457,1162.7246 258.34375,1161.5918 C 256.57291,1160.446 255.16666,1158.7402 254.125,1156.4746 C 253.09635,1154.196 252.58203,1151.5202 252.58203,1148.4473 C 252.58203,1145.2962 253.10286,1142.6009 254.14453,1140.3613 C 255.19921,1138.1218 256.55989,1136.4486 258.22656,1135.3418 C 259.90624,1134.2351 261.91145,1133.6817 264.24219,1133.6816 C 267.04165,1133.6817 269.28123,1134.3978 270.96094,1135.8301 C 272.65362,1137.2494 273.74086,1139.3392 274.22266,1142.0996 L 269.53516,1143.1738 C 269.18358,1141.7025 268.53904,1140.5762 267.60156,1139.7949 C 266.66405,1139.0137 265.54426,1138.6231 264.24219,1138.623 C 262.22395,1138.6231 260.58983,1139.4108 259.33984,1140.9863 C 258.08984,1142.5488 257.46484,1144.9382 257.46484,1148.1543 C 257.46484,1151.6048 258.14192,1154.2285 259.49609,1156.0254 C 260.65494,1157.5749 262.22395,1158.3496 264.20312,1158.3496 C 265.12759,1158.3496 266.08462,1158.1348 267.07422,1157.7051 C 268.07681,1157.2624 268.96873,1156.6634 269.75,1155.9082 L 269.75,1152.2754 L 264.32031,1152.2754"
|
||||
d="m 264.32031,1152.2754 l 0,-4.8242 l 10.21485,0 l 0,11.4062 c -1.02867,1.211 -2.487,2.2526 -4.375,3.125 c -1.88804,0.8724 -3.78257,1.3086 -5.6836,1.3086 c -2.31772,0 -4.36199,-0.5664 -6.13281,-1.6992 c -1.77084,-1.1458 -3.17709,-2.8516 -4.21875,-5.1172 c -1.02865,-2.2786 -1.54297,-4.9544 -1.54297,-8.0273 c 0,-3.1511 0.52083,-5.8464 1.5625,-8.086 c 1.05468,-2.2395 2.41536,-3.9127 4.08203,-5.0195 c 1.67968,-1.1067 3.68489,-1.6601 6.01563,-1.6602 c 2.79946,1e-4 5.03904,0.7162 6.71875,2.1485 c 1.69268,1.4193 2.77992,3.5091 3.26172,6.2695 l -4.6875,1.0742 c -0.35158,-1.4713 -0.99612,-2.5976 -1.9336,-3.3789 c -0.93751,-0.7812 -2.0573,-1.1718 -3.35937,-1.1719 c -2.01824,10e-5 -3.65236,0.7878 -4.90235,2.3633 c -1.25,1.5625 -1.875,3.9519 -1.875,7.168 c 0,3.4505 0.67708,6.0742 2.03125,7.8711 c 1.15885,1.5495 2.72786,2.3242 4.70703,2.3242 c 0.92447,0 1.8815,-0.2148 2.8711,-0.6445 c 1.00259,-0.4427 1.89451,-1.0417 2.67578,-1.7969 l 0,-3.6328 l -5.42969,0"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
id="path13511-1"
|
||||
d="M 288.77344,1156.2012 L 293.24609,1157.1191 C 292.64712,1159.2025 291.71613,1160.752 290.45312,1161.7676 C 289.19009,1162.7702 287.65363,1163.2715 285.84375,1163.2715 C 283.33072,1163.2715 281.39062,1162.4316 280.02344,1160.752 C 278.40885,1158.7988 277.60156,1156.0645 277.60156,1152.5488 C 277.60156,1149.0853 278.41536,1146.3119 280.04297,1144.2285 C 281.42317,1142.4707 283.20702,1141.5918 285.39453,1141.5918 C 287.82942,1141.5918 289.73697,1142.4903 291.11719,1144.2871 C 292.70571,1146.3444 293.49998,1149.3783 293.5,1153.3887 L 293.4805,1154.0137 L 282.21097,1154.0137 C 282.23697,1155.6543 282.60159,1156.9238 283.30472,1157.8223 C 284.02086,1158.7207 284.88023,1159.1699 285.88284,1159.1699 C 287.32814,1159.1699 288.29168,1158.1803 288.77347,1156.2012 M 289.02737,1150.6543 C 288.98827,1149.0397 288.64325,1147.8288 287.99222,1147.0215 C 287.34117,1146.2012 286.56643,1145.791 285.668,1145.791 C 284.71747,1145.791 283.91669,1146.2142 283.26565,1147.0605 C 282.60159,1147.9199 282.27607,1149.1179 282.28909,1150.6543 L 289.02737,1150.6543"
|
||||
d="m 288.77344,1156.2012 l 4.47265,0.9179 c -0.59897,2.0834 -1.52996,3.6329 -2.79297,4.6485 c -1.26303,1.0026 -2.79949,1.5039 -4.60937,1.5039 c -2.51303,0 -4.45313,-0.8399 -5.82031,-2.5195 c -1.61459,-1.9532 -2.42188,-4.6875 -2.42188,-8.2032 c 0,-3.4635 0.8138,-6.2369 2.44141,-8.3203 c 1.3802,-1.7578 3.16405,-2.6367 5.35156,-2.6367 c 2.43489,0 4.34244,0.8985 5.72266,2.6953 c 1.58852,2.0573 2.38279,5.0912 2.38281,9.1016 l -0.0195,0.625 l -11.26953,0 c 0.026,1.6406 0.39062,2.9101 1.09375,3.8086 c 0.71614,0.8984 1.57551,1.3476 2.57812,1.3476 c 1.4453,0 2.40884,-0.9896 2.89063,-2.9687 m 0.2539,-5.5469 c -0.0391,-1.6146 -0.38412,-2.8255 -1.03515,-3.6328 c -0.65105,-0.8203 -1.42579,-1.2305 -2.32422,-1.2305 c -0.95053,0 -1.75131,0.4232 -2.40235,1.2695 c -0.66406,0.8594 -0.98958,2.0574 -0.97656,3.5938 l 6.73828,0"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
id="path13513-4"
|
||||
d="M 312.66016,1162.8027 L 308.14844,1162.8027 L 308.14844,1152.2168 C 308.14842,1150.0944 308.06374,1148.6817 307.89453,1147.9785 C 307.72525,1147.2754 307.40624,1146.735 306.9375,1146.3574 C 306.48176,1145.9798 305.96093,1145.791 305.375,1145.791 C 304.61978,1145.791 303.93619,1146.0384 303.32422,1146.5332 C 302.71223,1147.015 302.28254,1147.6856 302.03516,1148.5449 C 301.78775,1149.4043 301.66406,1151.0254 301.66406,1153.4082 L 301.66406,1162.8027 L 297.15234,1162.8027 L 297.15234,1142.0605 L 301.33203,1142.0605 L 301.33203,1145.1074 C 302.07421,1143.9356 302.90754,1143.0567 303.83203,1142.4707 C 304.76952,1141.8848 305.80468,1141.5918 306.9375,1141.5918 C 308.25259,1141.5918 309.35936,1141.9369 310.25781,1142.627 C 311.16925,1143.3041 311.79425,1144.183 312.13281,1145.2637 C 312.48436,1146.3314 312.66014,1147.8809 312.66016,1149.9121 L 312.66016,1162.8027"
|
||||
d="m 312.66016,1162.8027 l -4.51172,0 l 0,-10.5859 c -2e-5,-2.1224 -0.0847,-3.5351 -0.25391,-4.2383 c -0.16928,-0.7031 -0.48829,-1.2435 -0.95703,-1.6211 c -0.45574,-0.3776 -0.97657,-0.5664 -1.5625,-0.5664 c -0.75522,0 -1.43881,0.2474 -2.05078,0.7422 c -0.61199,0.4818 -1.04168,1.1524 -1.28906,2.0117 c -0.24741,0.8594 -0.3711,2.4805 -0.3711,4.8633 l 0,9.3945 l -4.51172,0 l 0,-20.7422 l 4.17969,0 l 0,3.0469 c 0.74218,-1.1718 1.57551,-2.0507 2.5,-2.6367 c 0.93749,-0.5859 1.97265,-0.8789 3.10547,-0.8789 c 1.31509,0 2.42186,0.3451 3.32031,1.0352 c 0.91144,0.6771 1.53644,1.556 1.875,2.6367 c 0.35155,1.0677 0.52733,2.6172 0.52735,4.6484 l 0,12.8906"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
id="path13515-8-8"
|
||||
d="M 327.13281,1156.2012 L 331.60547,1157.1191 C 331.00649,1159.2025 330.07551,1160.752 328.8125,1161.7676 C 327.54947,1162.7702 326.01301,1163.2715 324.20312,1163.2715 C 321.6901,1163.2715 319.75,1162.4316 318.38281,1160.752 C 316.76823,1158.7988 315.96094,1156.0645 315.96094,1152.5488 C 315.96094,1149.0853 316.77474,1146.3119 318.40234,1144.2285 C 319.78255,1142.4707 321.5664,1141.5918 323.75391,1141.5918 C 326.18879,1141.5918 328.09634,1142.4903 329.47656,1144.2871 C 331.06509,1146.3444 331.85936,1149.3783 331.85937,1153.3887 L 331.83987,1154.0137 L 320.57034,1154.0137 C 320.59634,1155.6543 320.96096,1156.9238 321.66409,1157.8223 C 322.38023,1158.7207 323.2396,1159.1699 324.24222,1159.1699 C 325.68752,1159.1699 326.65106,1158.1803 327.13284,1156.2012 M 327.38675,1150.6543 C 327.34765,1149.0397 327.00262,1147.8288 326.35159,1147.0215 C 325.70054,1146.2012 324.9258,1145.791 324.02737,1145.791 C 323.07684,1145.791 322.27606,1146.2142 321.62503,1147.0605 C 320.96096,1147.9199 320.63544,1149.1179 320.64847,1150.6543 L 327.38675,1150.6543"
|
||||
d="m 327.13281,1156.2012 l 4.47266,0.9179 c -0.59898,2.0834 -1.52996,3.6329 -2.79297,4.6485 c -1.26303,1.0026 -2.79949,1.5039 -4.60938,1.5039 c -2.51302,0 -4.45312,-0.8399 -5.82031,-2.5195 c -1.61458,-1.9532 -2.42187,-4.6875 -2.42187,-8.2032 c 0,-3.4635 0.8138,-6.2369 2.4414,-8.3203 c 1.38021,-1.7578 3.16406,-2.6367 5.35157,-2.6367 c 2.43488,0 4.34243,0.8985 5.72265,2.6953 c 1.58853,2.0573 2.3828,5.0912 2.38281,9.1016 l -0.0195,0.625 l -11.26953,0 c 0.026,1.6406 0.39062,2.9101 1.09375,3.8086 c 0.71614,0.8984 1.57551,1.3476 2.57813,1.3476 c 1.4453,0 2.40884,-0.9896 2.89062,-2.9687 m 0.25391,-5.5469 c -0.0391,-1.6146 -0.38413,-2.8255 -1.03516,-3.6328 c -0.65105,-0.8203 -1.42579,-1.2305 -2.32422,-1.2305 c -0.95053,0 -1.75131,0.4232 -2.40234,1.2695 c -0.66407,0.8594 -0.98959,2.0574 -0.97656,3.5938 l 6.73828,0"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
id="path13517-3"
|
||||
d="M 339.86719,1162.8027 L 335.35547,1162.8027 L 335.35547,1142.0605 L 339.53516,1142.0605 L 339.53516,1145.0098 C 340.2513,1143.6296 340.88932,1142.7181 341.44922,1142.2754 C 342.02213,1141.8197 342.67968,1141.5918 343.42187,1141.5918 C 344.45051,1141.5918 345.43358,1141.9369 346.37109,1142.627 L 344.96484,1147.4121 C 344.22265,1146.8132 343.51952,1146.5137 342.85547,1146.5137 C 342.23046,1146.5137 341.67707,1146.7481 341.19531,1147.2168 C 340.72655,1147.6725 340.38801,1148.5059 340.17969,1149.7168 C 339.97135,1150.9277 339.86718,1153.1543 339.86719,1156.3965 L 339.86719,1162.8027"
|
||||
d="m 339.86719,1162.8027 l -4.51172,0 l 0,-20.7422 l 4.17969,0 l 0,2.9493 c 0.71614,-1.3802 1.35416,-2.2917 1.91406,-2.7344 c 0.57291,-0.4557 1.23046,-0.6836 1.97265,-0.6836 c 1.02864,0 2.01171,0.3451 2.94922,1.0352 l -1.40625,4.7851 c -0.74219,-0.5989 -1.44532,-0.8984 -2.10937,-0.8984 c -0.62501,0 -1.1784,0.2344 -1.66016,0.7031 c -0.46876,0.4557 -0.8073,1.2891 -1.01562,2.5 c -0.20834,1.2109 -0.31251,3.4375 -0.3125,6.6797 l 0,6.4062"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
id="path13519-9"
|
||||
d="M 348.28516,1139.248 L 348.28516,1134.1699 L 352.79687,1134.1699 L 352.79687,1139.248 L 348.28516,1139.248 M 348.28516,1162.8027 L 348.28516,1142.0605 L 352.79687,1142.0605 L 352.79687,1162.8027 L 348.28516,1162.8027"
|
||||
d="m 348.28516,1139.248 l 0,-5.0781 l 4.51171,0 l 0,5.0781 l -4.51171,0 m 0,23.5547 l 0,-20.7422 l 4.51171,0 l 0,20.7422 l -4.51171,0"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
id="path13521-9"
|
||||
d="M 372.25,1148.1934 L 367.81641,1149.1699 C 367.49087,1146.9955 366.46874,1145.9082 364.75,1145.9082 C 363.64322,1145.9082 362.75129,1146.377 362.07422,1147.3145 C 361.39713,1148.252 361.05859,1149.834 361.05859,1152.0605 C 361.05859,1154.5215 361.39713,1156.2598 362.07422,1157.2754 C 362.75129,1158.291 363.65624,1158.7988 364.78906,1158.7988 C 365.63541,1158.7988 366.33202,1158.5124 366.87891,1157.9395 C 367.42577,1157.3535 367.81639,1156.3249 368.05078,1154.8535 L 372.48437,1155.7715 C 371.5729,1160.7715 368.9492,1163.2715 364.61328,1163.2715 C 361.83984,1163.2715 359.78255,1162.2168 358.44141,1160.1074 C 357.10026,1157.9981 356.42969,1155.459 356.42969,1152.4902 C 356.42969,1148.9356 357.18489,1146.2337 358.69531,1144.3848 C 360.21874,1142.5228 362.21093,1141.5918 364.67187,1141.5918 C 366.66405,1141.5918 368.28514,1142.1192 369.53516,1143.1738 C 370.79816,1144.2285 371.70311,1145.9017 372.25,1148.1934"
|
||||
d="m 372.25,1148.1934 l -4.43359,0.9765 c -0.32554,-2.1744 -1.34767,-3.2617 -3.06641,-3.2617 c -1.10678,0 -1.99871,0.4688 -2.67578,1.4063 c -0.67709,0.9375 -1.01563,2.5195 -1.01563,4.746 c 0,2.461 0.33854,4.1993 1.01563,5.2149 c 0.67707,1.0156 1.58202,1.5234 2.71484,1.5234 c 0.84635,0 1.54296,-0.2864 2.08985,-0.8593 c 0.54686,-0.586 0.93748,-1.6146 1.17187,-3.086 l 4.43359,0.918 c -0.91147,5 -3.53517,7.5 -7.87109,7.5 c -2.77344,0 -4.83073,-1.0547 -6.17187,-3.1641 c -1.34115,-2.1093 -2.01172,-4.6484 -2.01172,-7.6172 c 0,-3.5546 0.7552,-6.2565 2.26562,-8.1054 c 1.52343,-1.862 3.51562,-2.793 5.97656,-2.793 c 1.99218,0 3.61327,0.5274 4.86329,1.582 c 1.263,1.0547 2.16795,2.7279 2.71484,5.0196"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
id="path13523-27"
|
||||
d="M 384.92578,1162.8027 L 384.92578,1134.1699 L 389.53516,1134.1699 L 399.14453,1153.291 L 399.14453,1134.1699 L 403.55859,1134.1699 L 403.55859,1162.8027 L 398.79297,1162.8027 L 389.33984,1144.1309 L 389.33984,1162.8027 L 384.92578,1162.8027"
|
||||
d="m 384.92578,1162.8027 l 0,-28.6328 l 4.60938,0 l 9.60937,19.1211 l 0,-19.1211 l 4.41406,0 l 0,28.6328 l -4.76562,0 l -9.45313,-18.6718 l 0,18.6718 l -4.41406,0"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
id="path13525-4"
|
||||
d="M 408.48047,1162.8027 L 408.48047,1134.1699 L 415.57031,1134.1699 L 419.82812,1153.7012 L 424.04687,1134.1699 L 431.15625,1134.1699 L 431.15625,1162.8027 L 426.76172,1162.8027 L 426.76172,1140.2637 L 422.09375,1162.8027 L 417.52344,1162.8027 L 412.89453,1140.2637 L 412.89453,1162.8027 L 408.48047,1162.8027"
|
||||
d="m 408.48047,1162.8027 l 0,-28.6328 l 7.08984,0 l 4.25781,19.5313 l 4.21875,-19.5313 l 7.10938,0 l 0,28.6328 l -4.39453,0 l 0,-22.539 l -4.66797,22.539 l -4.57031,0 l -4.62891,-22.539 l 0,22.539 l -4.41406,0"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
id="path13527-3"
|
||||
d="M 435.90234,1162.8027 L 435.90234,1134.1699 L 453.32422,1134.1699 L 453.32422,1139.0137 L 440.62891,1139.0137 L 440.62891,1145.3613 L 452.42578,1145.3613 L 452.42578,1150.1855 L 440.62891,1150.1855 L 440.62891,1157.9785 L 453.75391,1157.9785 L 453.75391,1162.8027 L 435.90234,1162.8027"
|
||||
d="m 435.90234,1162.8027 l 0,-28.6328 l 17.42188,0 l 0,4.8438 l -12.69531,0 l 0,6.3476 l 11.79687,0 l 0,4.8242 l -11.79687,0 l 0,7.793 l 13.125,0 l 0,4.8242 l -17.85157,0"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
id="path13529-49"
|
||||
d="M 478.92969,1162.8027 L 473.77344,1162.8027 L 471.72266,1156.2988 L 462.34766,1156.2988 L 460.41406,1162.8027 L 455.375,1162.8027 L 464.51562,1134.1699 L 469.53516,1134.1699 L 478.92969,1162.8027 M 470.19922,1151.4746 L 466.97656,1140.8496 L 463.79297,1151.4746 L 470.19922,1151.4746"
|
||||
d="m 478.92969,1162.8027 l -5.15625,0 l -2.05078,-6.5039 l -9.375,0 l -1.9336,6.5039 l -5.03906,0 l 9.14062,-28.6328 l 5.01954,0 l 9.39453,28.6328 m -8.73047,-11.3281 l -3.22266,-10.625 l -3.18359,10.625 l 6.40625,0"
|
||||
inkscape:connector-curvature="0" />
|
||||
</g>
|
||||
</g>
|
||||
@ -23231,25 +24112,25 @@
|
||||
sodipodi:nodetypes="cccc"
|
||||
style="fill:none;stroke:#000000;stroke-width:6.11999989;stroke-linecap:butt;stroke-linejoin:round;stroke-miterlimit:4;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="M 593.04083,505.15991 L 593.04081,423.70716 L 743.04079,423.70716 L 743.04076,323.15998"
|
||||
d="m 593.04083,505.15991 l -2e-5,-81.45275 l 149.99998,0 l -3e-5,-100.54718"
|
||||
id="path8856-1-5-7-7-6-6" />
|
||||
<path
|
||||
sodipodi:nodetypes="cccc"
|
||||
style="fill:none;stroke:#d81900;stroke-width:6.11999989;stroke-linecap:butt;stroke-linejoin:round;stroke-miterlimit:4;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="M 612.45552,504.56836 L 612.60184,429.51435 L 749.39767,429.51435 L 749.54399,323.15998"
|
||||
d="m 612.45552,504.56836 l 0.14632,-75.05401 l 136.79583,0 l 0.14632,-106.35437"
|
||||
id="path8856-1-2-1-90-4" />
|
||||
<path
|
||||
sodipodi:nodetypes="cccc"
|
||||
style="fill:none;stroke:#1f4697;stroke-width:6.11999989;stroke-linecap:butt;stroke-linejoin:round;stroke-miterlimit:4;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="M 651.02032,503.56837 L 651.02032,389.51434 L 756.47083,389.51434 L 756.47083,323.15998"
|
||||
d="m 651.02032,503.56837 l 0,-114.05403 l 105.45051,0 l 0,-66.35436"
|
||||
id="path8856-5-6-5-6-0" />
|
||||
<path
|
||||
sodipodi:nodetypes="cccc"
|
||||
style="fill:none;stroke:#ec6004;stroke-width:6.11999989;stroke-linecap:butt;stroke-linejoin:round;stroke-miterlimit:4;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="M 632.50924,503.56837 L 632.50924,395.51434 L 763.04076,395.51434 L 763.04076,323.15957"
|
||||
d="m 632.50924,503.56837 l 0,-108.05403 l 130.53152,0 l 0,-72.35477"
|
||||
id="path8856-5-1-7-1-9-5-3-68" />
|
||||
</g>
|
||||
</g>
|
||||
@ -29013,13 +29894,13 @@
|
||||
id="layer11"
|
||||
inkscape:label="boards"
|
||||
style="display:inline"
|
||||
transform="translate(-32.46875,315.85439)"
|
||||
sodipodi:insensitive="true">
|
||||
transform="translate(-32.46875,315.85439)">
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="layer15"
|
||||
inkscape:label="revo"
|
||||
style="display:inline">
|
||||
style="display:none"
|
||||
sodipodi:insensitive="true">
|
||||
<g
|
||||
style="display:inline"
|
||||
transform="translate(-1.4348189,-1.0188297)"
|
||||
@ -32305,10 +33186,10 @@
|
||||
cx="151.73199" />
|
||||
<polygon
|
||||
id="polygon8706"
|
||||
points="186.194,11.031 181.129,13.319 186.083,4.74 191.036,13.319 " />
|
||||
points="186.083,4.74 191.036,13.319 186.194,11.031 181.129,13.319 " />
|
||||
<polygon
|
||||
id="polygon8708"
|
||||
points="36.194,11.031 31.129,13.319 36.083,4.74 41.036,13.319 " />
|
||||
points="36.083,4.74 41.036,13.319 36.194,11.031 31.129,13.319 " />
|
||||
<g
|
||||
id="g8710">
|
||||
<circle
|
||||
@ -32499,7 +33380,8 @@
|
||||
inkscape:groupmode="layer"
|
||||
id="layer18"
|
||||
inkscape:label="nano"
|
||||
style="display:none">
|
||||
style="display:none"
|
||||
sodipodi:insensitive="true">
|
||||
<g
|
||||
id="controller-nano"
|
||||
transform="translate(-726.76021,-465.53821)">
|
||||
@ -33852,6 +34734,2597 @@
|
||||
</g>
|
||||
</g>
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="layer20"
|
||||
inkscape:label="cc">
|
||||
<g
|
||||
style="display:inline"
|
||||
inkscape:label="#controller"
|
||||
id="controller-cc"
|
||||
transform="translate(-1.2734354,-1.2734429)">
|
||||
<path
|
||||
id="path10151-2"
|
||||
d="m 530.25061,73.31614 l 9.00763,0 l 0,25.796734 l 22.41432,0 l 0,-25.796734 l 9.55228,0 L 550.75867,53.411253 Z"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:url(#linearGradient20337-1)" />
|
||||
<rect
|
||||
style="fill:#171717;stroke:#000000;stroke-width:2.16707063;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-dasharray:none"
|
||||
x="438.74414"
|
||||
y="99.148933"
|
||||
stroke-miterlimit="4"
|
||||
width="227.54243"
|
||||
height="227.54242"
|
||||
ry="14"
|
||||
rx="14.194314"
|
||||
id="rect9798" />
|
||||
<rect
|
||||
id="rect4320"
|
||||
height="5.5151949"
|
||||
width="7.064651"
|
||||
y="244.72189"
|
||||
x="507.61179"
|
||||
style="fill:#312d29;stroke-width:0;stroke-miterlimit:4" />
|
||||
<rect
|
||||
id="rect4322"
|
||||
height="5.5151949"
|
||||
width="3.8682213"
|
||||
y="244.72189"
|
||||
x="515.19653"
|
||||
style="fill:#d3d0ce;stroke-width:0;stroke-miterlimit:4" />
|
||||
<rect
|
||||
id="rect4324"
|
||||
height="5.5151949"
|
||||
width="3.8682213"
|
||||
y="244.72189"
|
||||
x="504.36118"
|
||||
style="fill:#d3d0ce;stroke-width:0;stroke-miterlimit:4" />
|
||||
<rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
id="rect4408"
|
||||
height="5.5151954"
|
||||
width="7.0646501"
|
||||
y="612.47388"
|
||||
x="-279.05756"
|
||||
style="fill:#312d29;stroke-width:0;stroke-miterlimit:4" />
|
||||
<rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
id="rect4410"
|
||||
height="5.5151954"
|
||||
width="3.868221"
|
||||
y="612.47388"
|
||||
x="-271.47281"
|
||||
style="fill:#d3d0ce;stroke-width:0;stroke-miterlimit:4" />
|
||||
<rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
id="rect4412"
|
||||
height="5.5151954"
|
||||
width="3.868221"
|
||||
y="612.47388"
|
||||
x="-282.30814"
|
||||
style="fill:#d3d0ce;stroke-width:0;stroke-miterlimit:4" />
|
||||
<rect
|
||||
id="rect10507"
|
||||
height="5.5151949"
|
||||
width="7.064651"
|
||||
y="149.71573"
|
||||
x="587.396"
|
||||
style="fill:#312d29;stroke-width:0;stroke-miterlimit:4" />
|
||||
<rect
|
||||
id="rect10509"
|
||||
height="5.5151949"
|
||||
width="3.8682213"
|
||||
y="149.71573"
|
||||
x="594.98071"
|
||||
style="fill:#d3d0ce;stroke-width:0;stroke-miterlimit:4" />
|
||||
<rect
|
||||
id="rect10511"
|
||||
height="5.5151949"
|
||||
width="3.8682213"
|
||||
y="149.71573"
|
||||
x="584.14539"
|
||||
style="fill:#d3d0ce;stroke-width:0;stroke-miterlimit:4" />
|
||||
<rect
|
||||
id="rect10515"
|
||||
height="5.5151949"
|
||||
width="7.064651"
|
||||
y="259.94388"
|
||||
x="523.35864"
|
||||
style="fill:#312d29;stroke-width:0;stroke-miterlimit:4" />
|
||||
<rect
|
||||
id="rect10517"
|
||||
height="5.5151949"
|
||||
width="3.8682213"
|
||||
y="259.94388"
|
||||
x="530.94342"
|
||||
style="fill:#d3d0ce;stroke-width:0;stroke-miterlimit:4" />
|
||||
<rect
|
||||
id="rect10519"
|
||||
height="5.5151949"
|
||||
width="3.8682213"
|
||||
y="259.94388"
|
||||
x="520.10803"
|
||||
style="fill:#d3d0ce;stroke-width:0;stroke-miterlimit:4" />
|
||||
<rect
|
||||
id="rect4219"
|
||||
height="5.5151949"
|
||||
width="7.064651"
|
||||
y="256.50372"
|
||||
x="494.18936"
|
||||
style="fill:#bc781e;stroke-width:0;stroke-miterlimit:4" />
|
||||
<rect
|
||||
id="rect4221"
|
||||
height="5.5151949"
|
||||
width="3.8682213"
|
||||
y="256.50372"
|
||||
x="501.77411"
|
||||
style="fill:#d3d0ce;stroke-width:0;stroke-miterlimit:4" />
|
||||
<rect
|
||||
id="rect4223"
|
||||
height="5.5151949"
|
||||
width="3.8682213"
|
||||
y="256.50372"
|
||||
x="490.93878"
|
||||
style="fill:#d3d0ce;stroke-width:0;stroke-miterlimit:4" />
|
||||
<rect
|
||||
id="rect10550"
|
||||
height="5.5151949"
|
||||
width="7.064651"
|
||||
y="266.47675"
|
||||
x="596.80658"
|
||||
style="fill:#bc781e;stroke-width:0;stroke-miterlimit:4" />
|
||||
<rect
|
||||
id="rect10552"
|
||||
height="5.5151949"
|
||||
width="3.8682213"
|
||||
y="266.47675"
|
||||
x="604.3913"
|
||||
style="fill:#d3d0ce;stroke-width:0;stroke-miterlimit:4" />
|
||||
<rect
|
||||
id="rect10554"
|
||||
height="5.5151949"
|
||||
width="3.8682213"
|
||||
y="266.47675"
|
||||
x="593.55597"
|
||||
style="fill:#d3d0ce;stroke-width:0;stroke-miterlimit:4" />
|
||||
<rect
|
||||
id="rect10558"
|
||||
height="5.5151949"
|
||||
width="7.064651"
|
||||
y="279.3367"
|
||||
x="596.01923"
|
||||
style="fill:#bc781e;stroke-width:0;stroke-miterlimit:4" />
|
||||
<rect
|
||||
id="rect10560"
|
||||
height="5.5151949"
|
||||
width="3.8682213"
|
||||
y="279.3367"
|
||||
x="603.60394"
|
||||
style="fill:#d3d0ce;stroke-width:0;stroke-miterlimit:4" />
|
||||
<rect
|
||||
id="rect10562"
|
||||
height="5.5151949"
|
||||
width="3.8682213"
|
||||
y="279.3367"
|
||||
x="592.76862"
|
||||
style="fill:#d3d0ce;stroke-width:0;stroke-miterlimit:4" />
|
||||
<rect
|
||||
id="rect10566"
|
||||
height="5.5151949"
|
||||
width="7.064651"
|
||||
y="185.90521"
|
||||
x="590.50781"
|
||||
style="fill:#bc781e;stroke-width:0;stroke-miterlimit:4" />
|
||||
<rect
|
||||
id="rect10568"
|
||||
height="5.5151949"
|
||||
width="3.8682213"
|
||||
y="185.90521"
|
||||
x="598.09253"
|
||||
style="fill:#d3d0ce;stroke-width:0;stroke-miterlimit:4" />
|
||||
<rect
|
||||
id="rect10570"
|
||||
height="5.5151949"
|
||||
width="3.8682213"
|
||||
y="185.90521"
|
||||
x="587.2572"
|
||||
style="fill:#d3d0ce;stroke-width:0;stroke-miterlimit:4" />
|
||||
<rect
|
||||
id="rect10574"
|
||||
height="5.5151949"
|
||||
width="7.064651"
|
||||
y="105.85859"
|
||||
x="613.34076"
|
||||
style="fill:#bc781e;stroke-width:0;stroke-miterlimit:4" />
|
||||
<rect
|
||||
id="rect10576"
|
||||
height="5.5151949"
|
||||
width="3.8682213"
|
||||
y="105.85859"
|
||||
x="620.92554"
|
||||
style="fill:#d3d0ce;stroke-width:0;stroke-miterlimit:4" />
|
||||
<rect
|
||||
id="rect10578"
|
||||
height="5.5151949"
|
||||
width="3.8682213"
|
||||
y="105.85859"
|
||||
x="610.09015"
|
||||
style="fill:#d3d0ce;stroke-width:0;stroke-miterlimit:4" />
|
||||
<rect
|
||||
id="rect4416"
|
||||
height="5.5151949"
|
||||
width="7.064651"
|
||||
y="148.40121"
|
||||
x="449.0675"
|
||||
style="fill:#0052ff;stroke-width:0;stroke-miterlimit:4" />
|
||||
<rect
|
||||
id="rect4418"
|
||||
height="5.5151949"
|
||||
width="3.8682213"
|
||||
y="148.40121"
|
||||
x="456.65225"
|
||||
style="fill:#d3d0ce;stroke-width:0;stroke-miterlimit:4" />
|
||||
<rect
|
||||
id="rect4420"
|
||||
height="5.5151949"
|
||||
width="3.8682213"
|
||||
y="148.40121"
|
||||
x="445.81689"
|
||||
style="fill:#d3d0ce;stroke-width:0;stroke-miterlimit:4" />
|
||||
<rect
|
||||
id="rect4432"
|
||||
height="5.5151949"
|
||||
width="7.064651"
|
||||
y="161.59825"
|
||||
x="448.71127"
|
||||
style="fill:#ff7900;stroke-width:0;stroke-miterlimit:4" />
|
||||
<rect
|
||||
id="rect4434"
|
||||
height="5.5151949"
|
||||
width="3.8682213"
|
||||
y="161.59825"
|
||||
x="456.29602"
|
||||
style="fill:#d3d0ce;stroke-width:0;stroke-miterlimit:4" />
|
||||
<rect
|
||||
id="rect4436"
|
||||
height="5.5151949"
|
||||
width="3.8682213"
|
||||
y="161.59825"
|
||||
x="445.46066"
|
||||
style="fill:#d3d0ce;stroke-width:0;stroke-miterlimit:4" />
|
||||
<rect
|
||||
transform="matrix(0,1,-1,0,0,0)"
|
||||
id="rect4280"
|
||||
height="5.5151954"
|
||||
width="7.0646501"
|
||||
y="-508.21155"
|
||||
x="117.81582"
|
||||
style="fill:#bc781e;stroke-width:0;stroke-miterlimit:4" />
|
||||
<rect
|
||||
transform="matrix(0,1,-1,0,0,0)"
|
||||
id="rect4282"
|
||||
height="5.5151954"
|
||||
width="3.868221"
|
||||
y="-508.21155"
|
||||
x="125.40057"
|
||||
style="fill:#d3d0ce;stroke-width:0;stroke-miterlimit:4" />
|
||||
<rect
|
||||
transform="matrix(0,1,-1,0,0,0)"
|
||||
id="rect4284"
|
||||
height="5.5151954"
|
||||
width="3.868221"
|
||||
y="-508.21155"
|
||||
x="114.56521"
|
||||
style="fill:#d3d0ce;stroke-width:0;stroke-miterlimit:4" />
|
||||
<rect
|
||||
id="rect10763"
|
||||
height="5.5151954"
|
||||
width="7.0646501"
|
||||
y="-508.21155"
|
||||
x="152.48895"
|
||||
style="fill:#bc781e;stroke-width:0;stroke-miterlimit:4"
|
||||
transform="matrix(0,1,-1,0,0,0)" />
|
||||
<rect
|
||||
id="rect10765"
|
||||
height="5.5151954"
|
||||
width="3.868221"
|
||||
y="-508.21155"
|
||||
x="160.0737"
|
||||
style="fill:#d3d0ce;stroke-width:0;stroke-miterlimit:4"
|
||||
transform="matrix(0,1,-1,0,0,0)" />
|
||||
<rect
|
||||
id="rect10767"
|
||||
height="5.5151954"
|
||||
width="3.868221"
|
||||
y="-508.21155"
|
||||
x="149.23834"
|
||||
style="fill:#d3d0ce;stroke-width:0;stroke-miterlimit:4"
|
||||
transform="matrix(0,1,-1,0,0,0)" />
|
||||
<rect
|
||||
id="rect10771"
|
||||
height="5.5151954"
|
||||
width="7.0646501"
|
||||
y="-567.24731"
|
||||
x="161.61464"
|
||||
style="fill:#bc781e;stroke-width:0;stroke-miterlimit:4"
|
||||
transform="matrix(0,1,-1,0,0,0)" />
|
||||
<rect
|
||||
id="rect10773"
|
||||
height="5.5151954"
|
||||
width="3.868221"
|
||||
y="-567.24731"
|
||||
x="169.19939"
|
||||
style="fill:#d3d0ce;stroke-width:0;stroke-miterlimit:4"
|
||||
transform="matrix(0,1,-1,0,0,0)" />
|
||||
<rect
|
||||
id="rect10775"
|
||||
height="5.5151954"
|
||||
width="3.868221"
|
||||
y="-567.24731"
|
||||
x="158.36404"
|
||||
style="fill:#d3d0ce;stroke-width:0;stroke-miterlimit:4"
|
||||
transform="matrix(0,1,-1,0,0,0)" />
|
||||
<rect
|
||||
id="rect10779"
|
||||
height="5.5151954"
|
||||
width="7.0646501"
|
||||
y="-482.47665"
|
||||
x="266.85629"
|
||||
style="fill:#bc781e;stroke-width:0;stroke-miterlimit:4"
|
||||
transform="matrix(0,1,-1,0,0,0)" />
|
||||
<rect
|
||||
id="rect10781"
|
||||
height="5.5151954"
|
||||
width="3.868221"
|
||||
y="-482.47665"
|
||||
x="274.44104"
|
||||
style="fill:#d3d0ce;stroke-width:0;stroke-miterlimit:4"
|
||||
transform="matrix(0,1,-1,0,0,0)" />
|
||||
<rect
|
||||
id="rect10783"
|
||||
height="5.5151954"
|
||||
width="3.868221"
|
||||
y="-482.47665"
|
||||
x="263.60568"
|
||||
style="fill:#d3d0ce;stroke-width:0;stroke-miterlimit:4"
|
||||
transform="matrix(0,1,-1,0,0,0)" />
|
||||
<rect
|
||||
id="rect10787"
|
||||
height="5.5151954"
|
||||
width="7.0646501"
|
||||
y="-482.47665"
|
||||
x="289.68927"
|
||||
style="fill:#bc781e;stroke-width:0;stroke-miterlimit:4"
|
||||
transform="matrix(0,1,-1,0,0,0)" />
|
||||
<rect
|
||||
id="rect10789"
|
||||
height="5.5151954"
|
||||
width="3.868221"
|
||||
y="-482.47665"
|
||||
x="297.27402"
|
||||
style="fill:#d3d0ce;stroke-width:0;stroke-miterlimit:4"
|
||||
transform="matrix(0,1,-1,0,0,0)" />
|
||||
<rect
|
||||
id="rect10791"
|
||||
height="5.5151954"
|
||||
width="3.868221"
|
||||
y="-482.47665"
|
||||
x="286.43866"
|
||||
style="fill:#d3d0ce;stroke-width:0;stroke-miterlimit:4"
|
||||
transform="matrix(0,1,-1,0,0,0)" />
|
||||
<rect
|
||||
id="rect10795"
|
||||
height="5.5151954"
|
||||
width="7.0646501"
|
||||
y="-530.76709"
|
||||
x="280.24115"
|
||||
style="fill:#bc781e;stroke-width:0;stroke-miterlimit:4"
|
||||
transform="matrix(0,1,-1,0,0,0)" />
|
||||
<rect
|
||||
id="rect10797"
|
||||
height="5.5151954"
|
||||
width="3.868221"
|
||||
y="-530.76709"
|
||||
x="287.8259"
|
||||
style="fill:#d3d0ce;stroke-width:0;stroke-miterlimit:4"
|
||||
transform="matrix(0,1,-1,0,0,0)" />
|
||||
<rect
|
||||
id="rect10799"
|
||||
height="5.5151954"
|
||||
width="3.868221"
|
||||
y="-530.76709"
|
||||
x="276.99054"
|
||||
style="fill:#d3d0ce;stroke-width:0;stroke-miterlimit:4"
|
||||
transform="matrix(0,1,-1,0,0,0)" />
|
||||
<rect
|
||||
id="rect10803"
|
||||
height="5.5151954"
|
||||
width="7.0646501"
|
||||
y="511.16895"
|
||||
x="-234.70383"
|
||||
style="fill:#312d29;stroke-width:0;stroke-miterlimit:4"
|
||||
transform="matrix(0,-1,1,0,0,0)" />
|
||||
<rect
|
||||
id="rect10805"
|
||||
height="5.5151954"
|
||||
width="3.868221"
|
||||
y="511.16895"
|
||||
x="-227.11908"
|
||||
style="fill:#d3d0ce;stroke-width:0;stroke-miterlimit:4"
|
||||
transform="matrix(0,-1,1,0,0,0)" />
|
||||
<rect
|
||||
id="rect10807"
|
||||
height="5.5151954"
|
||||
width="3.868221"
|
||||
y="511.16895"
|
||||
x="-237.95442"
|
||||
style="fill:#d3d0ce;stroke-width:0;stroke-miterlimit:4"
|
||||
transform="matrix(0,-1,1,0,0,0)" />
|
||||
<rect
|
||||
id="rect10811"
|
||||
height="5.5151954"
|
||||
width="7.0646501"
|
||||
y="499.62125"
|
||||
x="-234.96628"
|
||||
style="fill:#312d29;stroke-width:0;stroke-miterlimit:4"
|
||||
transform="matrix(0,-1,1,0,0,0)" />
|
||||
<rect
|
||||
id="rect10813"
|
||||
height="5.5151954"
|
||||
width="3.868221"
|
||||
y="499.62125"
|
||||
x="-227.38153"
|
||||
style="fill:#d3d0ce;stroke-width:0;stroke-miterlimit:4"
|
||||
transform="matrix(0,-1,1,0,0,0)" />
|
||||
<rect
|
||||
id="rect10815"
|
||||
height="5.5151954"
|
||||
width="3.868221"
|
||||
y="499.62125"
|
||||
x="-238.21687"
|
||||
style="fill:#d3d0ce;stroke-width:0;stroke-miterlimit:4"
|
||||
transform="matrix(0,-1,1,0,0,0)" />
|
||||
<rect
|
||||
id="rect10819"
|
||||
height="5.5151954"
|
||||
width="7.0646501"
|
||||
y="488.336"
|
||||
x="-235.75362"
|
||||
style="fill:#312d29;stroke-width:0;stroke-miterlimit:4"
|
||||
transform="matrix(0,-1,1,0,0,0)" />
|
||||
<rect
|
||||
id="rect10821"
|
||||
height="5.5151954"
|
||||
width="3.868221"
|
||||
y="488.336"
|
||||
x="-228.16887"
|
||||
style="fill:#d3d0ce;stroke-width:0;stroke-miterlimit:4"
|
||||
transform="matrix(0,-1,1,0,0,0)" />
|
||||
<rect
|
||||
id="rect10823"
|
||||
height="5.5151954"
|
||||
width="3.868221"
|
||||
y="488.336"
|
||||
x="-239.00423"
|
||||
style="fill:#d3d0ce;stroke-width:0;stroke-miterlimit:4"
|
||||
transform="matrix(0,-1,1,0,0,0)" />
|
||||
<rect
|
||||
id="rect10827"
|
||||
height="5.5151954"
|
||||
width="7.0646501"
|
||||
y="489.38577"
|
||||
x="-198.74844"
|
||||
style="fill:#312d29;stroke-width:0;stroke-miterlimit:4"
|
||||
transform="matrix(0,-1,1,0,0,0)" />
|
||||
<rect
|
||||
id="rect10829"
|
||||
height="5.5151954"
|
||||
width="3.868221"
|
||||
y="489.38577"
|
||||
x="-191.1637"
|
||||
style="fill:#d3d0ce;stroke-width:0;stroke-miterlimit:4"
|
||||
transform="matrix(0,-1,1,0,0,0)" />
|
||||
<rect
|
||||
id="rect10831"
|
||||
height="5.5151954"
|
||||
width="3.868221"
|
||||
y="489.38577"
|
||||
x="-201.99905"
|
||||
style="fill:#d3d0ce;stroke-width:0;stroke-miterlimit:4"
|
||||
transform="matrix(0,-1,1,0,0,0)" />
|
||||
<rect
|
||||
id="rect10835"
|
||||
height="5.5151954"
|
||||
width="7.0646501"
|
||||
y="506.18246"
|
||||
x="-199.01088"
|
||||
style="fill:#312d29;stroke-width:0;stroke-miterlimit:4"
|
||||
transform="matrix(0,-1,1,0,0,0)" />
|
||||
<rect
|
||||
id="rect10837"
|
||||
height="5.5151954"
|
||||
width="3.868221"
|
||||
y="506.18246"
|
||||
x="-191.42613"
|
||||
style="fill:#d3d0ce;stroke-width:0;stroke-miterlimit:4"
|
||||
transform="matrix(0,-1,1,0,0,0)" />
|
||||
<rect
|
||||
id="rect10839"
|
||||
height="5.5151954"
|
||||
width="3.868221"
|
||||
y="506.18246"
|
||||
x="-202.26149"
|
||||
style="fill:#d3d0ce;stroke-width:0;stroke-miterlimit:4"
|
||||
transform="matrix(0,-1,1,0,0,0)" />
|
||||
<path
|
||||
style="fill:none;stroke:#f2edda;stroke-width:1.62530303;stroke-linecap:square;stroke-miterlimit:4;stroke-dasharray:none"
|
||||
id="path4550"
|
||||
d="m 660.83109,147.16536 c 0,3.09891 -2.5138,5.61271 -5.61272,5.61271 c -3.09891,0 -5.61271,-2.5138 -5.61271,-5.61271 c 0,-3.09891 2.5138,-5.61271 5.61271,-5.61271 c 3.09892,0 5.61272,2.5138 5.61272,5.61271 z"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
style="fill:none;stroke:#f2edda;stroke-width:1.62530303;stroke-linecap:square;stroke-miterlimit:4;stroke-dasharray:none"
|
||||
id="path4554"
|
||||
d="m 643.49452,147.16536 c 0,3.09891 -2.5138,5.61271 -5.61272,5.61271 c -3.09891,0 -5.61271,-2.5138 -5.61271,-5.61271 c 0,-3.09891 2.5138,-5.61271 5.61271,-5.61271 c 3.09892,0 5.61272,2.5138 5.61272,5.61271 z"
|
||||
inkscape:connector-curvature="0" />
|
||||
<rect
|
||||
style="fill:none;stroke:#f2edda;stroke-width:1.62530303;stroke-linecap:square;stroke-miterlimit:4;stroke-dasharray:none"
|
||||
id="rect4556"
|
||||
height="9.2858973"
|
||||
width="10.445282"
|
||||
y="141.73187"
|
||||
x="616.76898" />
|
||||
<path
|
||||
style="fill:none;stroke:#f2edda;stroke-width:1.62530303;stroke-linecap:square;stroke-miterlimit:4;stroke-dasharray:none"
|
||||
id="path10894"
|
||||
d="m 660.83109,162.33485 c 0,3.09891 -2.5138,5.61271 -5.61272,5.61271 c -3.09891,0 -5.61271,-2.5138 -5.61271,-5.61271 c 0,-3.09891 2.5138,-5.61271 5.61271,-5.61271 c 3.09892,0 5.61272,2.5138 5.61272,5.61271 z"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
style="fill:none;stroke:#f2edda;stroke-width:1.62530303;stroke-linecap:square;stroke-miterlimit:4;stroke-dasharray:none"
|
||||
id="path10896"
|
||||
d="m 643.49452,162.33485 c 0,3.09891 -2.5138,5.61271 -5.61272,5.61271 c -3.09891,0 -5.61271,-2.5138 -5.61271,-5.61271 c 0,-3.09891 2.5138,-5.61271 5.61271,-5.61271 c 3.09892,0 5.61272,2.5138 5.61272,5.61271 z"
|
||||
inkscape:connector-curvature="0" />
|
||||
<rect
|
||||
style="fill:none;stroke:#f2edda;stroke-width:1.62530303;stroke-linecap:square;stroke-miterlimit:4;stroke-dasharray:none"
|
||||
id="rect10898"
|
||||
height="9.2858973"
|
||||
width="10.445282"
|
||||
y="156.90137"
|
||||
x="616.76898" />
|
||||
<path
|
||||
style="fill:none;stroke:#f2edda;stroke-width:1.62530303;stroke-linecap:square;stroke-miterlimit:4;stroke-dasharray:none"
|
||||
id="path10902"
|
||||
d="m 660.83109,179.67142 c 0,3.09891 -2.5138,5.61271 -5.61272,5.61271 c -3.09891,0 -5.61271,-2.5138 -5.61271,-5.61271 c 0,-3.09891 2.5138,-5.61271 5.61271,-5.61271 c 3.09892,0 5.61272,2.5138 5.61272,5.61271 z"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
style="fill:none;stroke:#f2edda;stroke-width:1.62530303;stroke-linecap:square;stroke-miterlimit:4;stroke-dasharray:none"
|
||||
id="path10904"
|
||||
d="m 643.49452,179.67142 c 0,3.09891 -2.5138,5.61271 -5.61272,5.61271 c -3.09891,0 -5.61271,-2.5138 -5.61271,-5.61271 c 0,-3.09891 2.5138,-5.61271 5.61271,-5.61271 c 3.09892,0 5.61272,2.5138 5.61272,5.61271 z"
|
||||
inkscape:connector-curvature="0" />
|
||||
<rect
|
||||
style="fill:none;stroke:#f2edda;stroke-width:1.62530303;stroke-linecap:square;stroke-miterlimit:4;stroke-dasharray:none"
|
||||
id="rect10906"
|
||||
height="9.2858973"
|
||||
width="10.445282"
|
||||
y="174.23793"
|
||||
x="616.76898" />
|
||||
<path
|
||||
style="fill:none;stroke:#f2edda;stroke-width:1.62530303;stroke-linecap:square;stroke-miterlimit:4;stroke-dasharray:none"
|
||||
id="path10910"
|
||||
d="m 660.83109,197.00798 c 0,3.09891 -2.5138,5.61271 -5.61272,5.61271 c -3.09891,0 -5.61271,-2.5138 -5.61271,-5.61271 c 0,-3.09891 2.5138,-5.61271 5.61271,-5.61271 c 3.09892,0 5.61272,2.5138 5.61272,5.61271 z"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
style="fill:none;stroke:#f2edda;stroke-width:1.62530303;stroke-linecap:square;stroke-miterlimit:4;stroke-dasharray:none"
|
||||
id="path10912"
|
||||
d="m 643.49452,197.00798 c 0,3.09891 -2.5138,5.61271 -5.61272,5.61271 c -3.09891,0 -5.61271,-2.5138 -5.61271,-5.61271 c 0,-3.09891 2.5138,-5.61271 5.61271,-5.61271 c 3.09892,0 5.61272,2.5138 5.61272,5.61271 z"
|
||||
inkscape:connector-curvature="0" />
|
||||
<rect
|
||||
style="fill:none;stroke:#f2edda;stroke-width:1.62530303;stroke-linecap:square;stroke-miterlimit:4;stroke-dasharray:none"
|
||||
id="rect10914"
|
||||
height="9.2858973"
|
||||
width="10.445282"
|
||||
y="191.57449"
|
||||
x="616.76898" />
|
||||
<path
|
||||
style="fill:none;stroke:#f2edda;stroke-width:1.62530303;stroke-linecap:square;stroke-miterlimit:4;stroke-dasharray:none"
|
||||
id="path10918"
|
||||
d="m 660.83109,214.34455 c 0,3.09891 -2.5138,5.61271 -5.61272,5.61271 c -3.09891,0 -5.61271,-2.5138 -5.61271,-5.61271 c 0,-3.09891 2.5138,-5.61271 5.61271,-5.61271 c 3.09892,0 5.61272,2.5138 5.61272,5.61271 z"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
style="fill:none;stroke:#f2edda;stroke-width:1.62530303;stroke-linecap:square;stroke-miterlimit:4;stroke-dasharray:none"
|
||||
id="path10920"
|
||||
d="m 643.49452,214.34455 c 0,3.09891 -2.5138,5.61271 -5.61272,5.61271 c -3.09891,0 -5.61271,-2.5138 -5.61271,-5.61271 c 0,-3.09891 2.5138,-5.61271 5.61271,-5.61271 c 3.09892,0 5.61272,2.5138 5.61272,5.61271 z"
|
||||
inkscape:connector-curvature="0" />
|
||||
<rect
|
||||
style="fill:none;stroke:#f2edda;stroke-width:1.62530303;stroke-linecap:square;stroke-miterlimit:4;stroke-dasharray:none"
|
||||
id="rect10922"
|
||||
height="9.2858973"
|
||||
width="10.445282"
|
||||
y="208.91106"
|
||||
x="616.76898" />
|
||||
<path
|
||||
style="fill:none;stroke:#f2edda;stroke-width:1.62530303;stroke-linecap:square;stroke-miterlimit:4;stroke-dasharray:none"
|
||||
id="path10926"
|
||||
d="m 660.83109,229.51404 c 0,3.09891 -2.5138,5.61271 -5.61272,5.61271 c -3.09891,0 -5.61271,-2.5138 -5.61271,-5.61271 c 0,-3.09891 2.5138,-5.61271 5.61271,-5.61271 c 3.09892,0 5.61272,2.5138 5.61272,5.61271 z"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
style="fill:none;stroke:#f2edda;stroke-width:1.62530303;stroke-linecap:square;stroke-miterlimit:4;stroke-dasharray:none"
|
||||
id="path10928"
|
||||
d="m 643.49452,229.51404 c 0,3.09891 -2.5138,5.61271 -5.61272,5.61271 c -3.09891,0 -5.61271,-2.5138 -5.61271,-5.61271 c 0,-3.09891 2.5138,-5.61271 5.61271,-5.61271 c 3.09892,0 5.61272,2.5138 5.61272,5.61271 z"
|
||||
inkscape:connector-curvature="0" />
|
||||
<rect
|
||||
style="fill:none;stroke:#f2edda;stroke-width:1.62530303;stroke-linecap:square;stroke-miterlimit:4;stroke-dasharray:none"
|
||||
id="rect10930"
|
||||
height="9.2858973"
|
||||
width="10.445282"
|
||||
y="224.08055"
|
||||
x="616.76898" />
|
||||
<rect
|
||||
id="rect4790"
|
||||
height="9.8560762"
|
||||
width="8.7648525"
|
||||
y="-495.40668"
|
||||
x="151.32674"
|
||||
style="fill:#a9814d;stroke-width:0;stroke-miterlimit:4"
|
||||
transform="matrix(0,1,-1,0,0,0)" />
|
||||
<rect
|
||||
id="rect4792"
|
||||
height="9.8560762"
|
||||
width="4.79916"
|
||||
y="-495.40668"
|
||||
x="160.73685"
|
||||
style="fill:#d3d0ce;stroke-width:0;stroke-miterlimit:4"
|
||||
transform="matrix(0,1,-1,0,0,0)" />
|
||||
<rect
|
||||
id="rect4794"
|
||||
height="9.8560762"
|
||||
width="4.79916"
|
||||
y="-495.40668"
|
||||
x="147.29382"
|
||||
style="fill:#d3d0ce;stroke-width:0;stroke-miterlimit:4"
|
||||
transform="matrix(0,1,-1,0,0,0)" />
|
||||
<rect
|
||||
id="rect12056"
|
||||
height="9.8560762"
|
||||
width="8.7648525"
|
||||
y="-495.40668"
|
||||
x="116.6536"
|
||||
style="fill:#a9814d;stroke-width:0;stroke-miterlimit:4"
|
||||
transform="matrix(0,1,-1,0,0,0)" />
|
||||
<rect
|
||||
id="rect12058"
|
||||
height="9.8560762"
|
||||
width="4.79916"
|
||||
y="-495.40668"
|
||||
x="126.06372"
|
||||
style="fill:#d3d0ce;stroke-width:0;stroke-miterlimit:4"
|
||||
transform="matrix(0,1,-1,0,0,0)" />
|
||||
<rect
|
||||
id="rect12060"
|
||||
height="9.8560762"
|
||||
width="4.79916"
|
||||
y="-495.40668"
|
||||
x="112.6207"
|
||||
style="fill:#d3d0ce;stroke-width:0;stroke-miterlimit:4"
|
||||
transform="matrix(0,1,-1,0,0,0)" />
|
||||
<rect
|
||||
id="rect12064"
|
||||
height="9.8560753"
|
||||
width="8.7648525"
|
||||
y="277.10086"
|
||||
x="456.07767"
|
||||
style="fill:#a9814d;stroke-width:0;stroke-miterlimit:4" />
|
||||
<rect
|
||||
id="rect12066"
|
||||
height="9.8560753"
|
||||
width="4.79916"
|
||||
y="277.10086"
|
||||
x="465.48776"
|
||||
style="fill:#d3d0ce;stroke-width:0;stroke-miterlimit:4" />
|
||||
<rect
|
||||
id="rect12068"
|
||||
height="9.8560753"
|
||||
width="4.79916"
|
||||
y="277.10086"
|
||||
x="452.04474"
|
||||
style="fill:#d3d0ce;stroke-width:0;stroke-miterlimit:4" />
|
||||
<rect
|
||||
id="rect12072"
|
||||
height="9.8560753"
|
||||
width="8.7648525"
|
||||
y="277.10086"
|
||||
x="492.91785"
|
||||
style="fill:#a9814d;stroke-width:0;stroke-miterlimit:4" />
|
||||
<rect
|
||||
id="rect12074"
|
||||
height="9.8560753"
|
||||
width="4.79916"
|
||||
y="277.10086"
|
||||
x="502.32797"
|
||||
style="fill:#d3d0ce;stroke-width:0;stroke-miterlimit:4" />
|
||||
<rect
|
||||
id="rect12076"
|
||||
height="9.8560753"
|
||||
width="4.79916"
|
||||
y="277.10086"
|
||||
x="488.88495"
|
||||
style="fill:#d3d0ce;stroke-width:0;stroke-miterlimit:4" />
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.61765516;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 532.94311,107.25258 l 0,-2.91471"
|
||||
id="path5376" />
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.61765516;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 529.69251,107.25258 l 0,-2.91471"
|
||||
id="path5378" />
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.61765516;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 545.94554,107.25258 l 0,-2.91471"
|
||||
id="path5386" />
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.61765516;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 542.69493,107.25258 l 0,-2.91471"
|
||||
id="path5388" />
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.61765516;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 539.44433,107.25258 l 0,-2.91471"
|
||||
id="path5390" />
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.61765516;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 529.69251,139.75864 l 0,-2.91471"
|
||||
id="path5454" />
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.61765516;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 532.94311,139.75864 l 0,-2.91471"
|
||||
id="path5456" />
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.61765516;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 539.44433,139.75864 l 0,-2.91471"
|
||||
id="path5466" />
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.61765516;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 542.69493,139.75864 l 0,-2.91471"
|
||||
id="path5468" />
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.61765516;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 545.94554,139.75864 l 0,-2.91471"
|
||||
id="path5470" />
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.61765516;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 523.19129,126.75621 l 2.91472,0"
|
||||
id="path5612" />
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.61765516;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 523.19129,129.79011 l 2.91472,0"
|
||||
id="path5614" />
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.61765516;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 523.19129,133.04072 l 2.91472,0"
|
||||
id="path5616" />
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.61765516;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 549.19614,133.04072 l 2.75218,0"
|
||||
id="path5618" />
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.61765516;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 549.19614,129.79011 l 2.75218,0"
|
||||
id="path5620" />
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.61765516;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 549.19614,126.75621 l 2.75218,0"
|
||||
id="path5622" />
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.61765516;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 523.19129,113.9705 l 2.91472,0"
|
||||
id="path5624" />
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.61765516;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 523.19129,117.2211 l 2.91472,0"
|
||||
id="path5626" />
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.61765516;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 523.19129,120.255 l 2.91472,0"
|
||||
id="path5628" />
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.61765516;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 549.19614,120.255 l 2.75218,0"
|
||||
id="path5630" />
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.61765516;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 549.19614,117.2211 l 2.75218,0"
|
||||
id="path5632" />
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.61765516;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 549.19614,113.9705 l 2.75218,0"
|
||||
id="path5634" />
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.61765516;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 536.19372,107.25258 l 0,-2.91471"
|
||||
id="path5636" />
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.61765516;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 523.19129,123.50561 l 2.91472,0"
|
||||
id="path5726" />
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.61765516;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 536.19372,139.75864 l 0,-2.91471"
|
||||
id="path5728" />
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.61765516;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 549.19614,123.50561 l 2.75218,0"
|
||||
id="path5730" />
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.61765516;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 523.19129,110.71989 l 2.91472,0"
|
||||
id="path5738" />
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.61765516;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 549.19614,110.71989 l 2.75218,0"
|
||||
id="path5740" />
|
||||
<rect
|
||||
id="rect4974"
|
||||
height="33.806301"
|
||||
width="26.32991"
|
||||
stroke-miterlimit="4"
|
||||
y="105.10838"
|
||||
x="524.66852"
|
||||
style="fill:#6a6a6a;stroke:#000000;stroke-width:0.75847471;stroke-miterlimit:4;stroke-dasharray:none" />
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.61765516;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 532.94311,107.25258 l 0,-2.91471"
|
||||
id="path12832" />
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.61765516;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 529.69251,107.25258 l 0,-2.91471"
|
||||
id="path12834" />
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.61765516;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 545.94554,107.25258 l 0,-2.91471"
|
||||
id="path12836" />
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.61765516;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 542.69493,107.25258 l 0,-2.91471"
|
||||
id="path12838" />
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.61765516;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 539.44433,107.25258 l 0,-2.91471"
|
||||
id="path12840" />
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.61765516;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 529.69251,139.75864 l 0,-2.91471"
|
||||
id="path12842" />
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.61765516;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 532.94311,139.75864 l 0,-2.91471"
|
||||
id="path13512" />
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.61765516;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 539.44433,139.75864 l 0,-2.91471"
|
||||
id="path12846" />
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.61765516;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 542.69493,139.75864 l 0,-2.91471"
|
||||
id="path13515" />
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.61765516;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 545.94554,139.75864 l 0,-2.91471"
|
||||
id="path12850" />
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.61765516;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 523.19129,126.75621 l 2.91472,0"
|
||||
id="path12852" />
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.61765516;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 523.19129,129.79011 l 2.91472,0"
|
||||
id="path12854" />
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.61765516;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 523.19129,133.04072 l 2.91472,0"
|
||||
id="path12856" />
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.61765516;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 549.19614,133.04072 l 2.75218,0"
|
||||
id="path12858" />
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.61765516;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 549.19614,129.79011 l 2.75218,0"
|
||||
id="path12860" />
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.61765516;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 549.19614,126.75621 l 2.75218,0"
|
||||
id="path12862" />
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.61765516;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 523.19129,113.9705 l 2.91472,0"
|
||||
id="path12864" />
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.61765516;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 523.19129,117.2211 l 2.91472,0"
|
||||
id="path12866" />
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.61765516;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 523.19129,120.255 l 2.91472,0"
|
||||
id="path12868" />
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.61765516;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 549.19614,120.255 l 2.75218,0"
|
||||
id="path12870" />
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.61765516;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 549.19614,117.2211 l 2.75218,0"
|
||||
id="path12872" />
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.61765516;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 549.19614,113.9705 l 2.75218,0"
|
||||
id="path12874" />
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.61765516;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 536.19372,107.25258 l 0,-2.91471"
|
||||
id="path12876" />
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.61765516;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 523.19129,123.50561 l 2.91472,0"
|
||||
id="path12878" />
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.61765516;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 536.19372,139.75864 l 0,-2.91471"
|
||||
id="path12880" />
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.61765516;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 549.19614,123.50561 l 2.75218,0"
|
||||
id="path12882" />
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.61765516;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 523.19129,110.71989 l 2.91472,0"
|
||||
id="path12884" />
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.61765516;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 549.19614,110.71989 l 2.75218,0"
|
||||
id="path12886" />
|
||||
<rect
|
||||
id="rect12888"
|
||||
height="33.806301"
|
||||
width="26.32991"
|
||||
stroke-miterlimit="4"
|
||||
y="105.10838"
|
||||
x="524.66852"
|
||||
style="fill:#6a6a6a;stroke:#000000;stroke-width:0.75847471;stroke-miterlimit:4;stroke-dasharray:none" />
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.61765516;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 533.68543,149.16923 l 0,-2.91471"
|
||||
id="path12894" />
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.61765516;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 530.43483,149.16923 l 0,-2.91471"
|
||||
id="path12896" />
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.61765516;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 546.68786,149.16923 l 0,-2.91471"
|
||||
id="path12898" />
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.61765516;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 543.43725,149.16923 l 0,-2.91471"
|
||||
id="path12900" />
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.61765516;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 540.18665,149.16923 l 0,-2.91471"
|
||||
id="path12902" />
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.61765516;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 530.43483,181.67529 l 0,-2.91471"
|
||||
id="path12904" />
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.61765516;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 533.68543,181.67529 l 0,-2.91471"
|
||||
id="path12906" />
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.61765516;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 540.18665,181.67529 l 0,-2.91471"
|
||||
id="path12908" />
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.61765516;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 543.43725,181.67529 l 0,-2.91471"
|
||||
id="path12910" />
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.61765516;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 546.68786,181.67529 l 0,-2.91471"
|
||||
id="path12912" />
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.61765516;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 523.93362,168.67287 l 2.91471,0"
|
||||
id="path12914" />
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.61765516;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 523.93362,171.70677 l 2.91471,0"
|
||||
id="path12916" />
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.61765516;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 523.93362,174.95738 l 2.91471,0"
|
||||
id="path12918" />
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.61765516;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 549.93846,174.95738 l 2.75218,0"
|
||||
id="path12920" />
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.61765516;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 549.93846,171.70677 l 2.75218,0"
|
||||
id="path12922" />
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.61765516;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 549.93846,168.67287 l 2.75218,0"
|
||||
id="path12924" />
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.61765516;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 523.93362,155.88715 l 2.91471,0"
|
||||
id="path12926" />
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.61765516;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 523.93362,159.13776 l 2.91471,0"
|
||||
id="path12928" />
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.61765516;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 523.93362,162.17166 l 2.91471,0"
|
||||
id="path12930" />
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.61765516;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 549.93846,162.17166 l 2.75218,0"
|
||||
id="path12932" />
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.61765516;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 549.93846,159.13776 l 2.75218,0"
|
||||
id="path12934" />
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.61765516;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 549.93846,155.88715 l 2.75218,0"
|
||||
id="path12936" />
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.61765516;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 536.93604,149.16923 l 0,-2.91471"
|
||||
id="path12938" />
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.61765516;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 523.93362,165.42226 l 2.91471,0"
|
||||
id="path12940" />
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.61765516;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 536.93604,181.67529 l 0,-2.91471"
|
||||
id="path12942" />
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.61765516;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 549.93846,165.42226 l 2.75218,0"
|
||||
id="path12944" />
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.61765516;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 523.93362,152.63655 l 2.91471,0"
|
||||
id="path12946" />
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.61765516;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0"
|
||||
d="m 549.93846,152.63655 l 2.75218,0"
|
||||
id="path12948" />
|
||||
<rect
|
||||
id="rect12950"
|
||||
height="33.806301"
|
||||
width="26.32991"
|
||||
stroke-miterlimit="4"
|
||||
y="147.02502"
|
||||
x="525.41083"
|
||||
style="fill:#6a6a6a;stroke:#000000;stroke-width:0.75847471;stroke-miterlimit:4;stroke-dasharray:none" />
|
||||
<rect
|
||||
rx="1.4983482"
|
||||
id="rect3773"
|
||||
ry="1.4983482"
|
||||
height="46.029259"
|
||||
width="45.789528"
|
||||
stroke-miterlimit="4"
|
||||
y="207.27293"
|
||||
x="544.84949"
|
||||
style="fill:#6a6a6a;stroke:#000000;stroke-width:2.16960835;stroke-miterlimit:4;stroke-dasharray:none" />
|
||||
<path
|
||||
id="path3777"
|
||||
d="m 549.32105,206.71507 l 0,-4.7108"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.32574069px;stroke-linecap:butt;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path3779"
|
||||
d="m 549.32105,205.51639 l 0.12203,0"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.1479758px;stroke-linecap:square;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path3787"
|
||||
d="m 551.7184,206.71507 l 0,-4.7108"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.32574069px;stroke-linecap:butt;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path3789"
|
||||
d="m 551.7184,205.51639 l 0.12203,0"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.1479758px;stroke-linecap:square;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path3793"
|
||||
d="m 554.11576,206.71507 l 0,-4.7108"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.32574069px;stroke-linecap:butt;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path3795"
|
||||
d="m 554.11576,205.51639 l 0.12203,0"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.1479758px;stroke-linecap:square;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path3799"
|
||||
d="m 556.51312,206.71507 l 0,-4.7108"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.32574069px;stroke-linecap:butt;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path3801"
|
||||
d="m 556.51312,205.51639 l 0.12203,0"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.1479758px;stroke-linecap:square;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path3805"
|
||||
d="m 558.91048,206.71507 l 0,-4.7108"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.32574069px;stroke-linecap:butt;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path3807"
|
||||
d="m 558.91048,205.51639 l 0.12203,0"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.1479758px;stroke-linecap:square;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path3811"
|
||||
d="m 561.30783,206.71507 l 0,-4.7108"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.32574069px;stroke-linecap:butt;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path3813"
|
||||
d="m 561.30783,205.51639 l 0.12203,0"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.1479758px;stroke-linecap:square;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path3817"
|
||||
d="m 563.70519,206.71507 l 0,-4.7108"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.32574069px;stroke-linecap:butt;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path3819"
|
||||
d="m 563.70519,205.51639 l 0.12203,0"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.1479758px;stroke-linecap:square;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path3823"
|
||||
d="m 566.10255,206.71507 l 0,-4.7108"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.32574069px;stroke-linecap:butt;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path3825"
|
||||
d="m 566.10255,205.51639 l 0.12203,0"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.1479758px;stroke-linecap:square;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path3829"
|
||||
d="m 568.49991,206.71507 l 0,-4.7108"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.32574069px;stroke-linecap:butt;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path3831"
|
||||
d="m 568.49991,205.51639 l 0.12203,0"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.1479758px;stroke-linecap:square;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path3835"
|
||||
d="m 570.89726,206.71507 l 0,-4.7108"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.32574069px;stroke-linecap:butt;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path3837"
|
||||
d="m 570.89726,205.51639 l 0.12203,0"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.1479758px;stroke-linecap:square;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path3841"
|
||||
d="m 573.29462,206.71507 l 0,-4.7108"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.32574069px;stroke-linecap:butt;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path3843"
|
||||
d="m 573.29462,205.51639 l 0.12203,0"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.1479758px;stroke-linecap:square;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path3847"
|
||||
d="m 575.69198,206.71507 l 0,-4.7108"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.32574069px;stroke-linecap:butt;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path3849"
|
||||
d="m 575.69198,205.51639 l 0.12203,0"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.1479758px;stroke-linecap:square;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path3853"
|
||||
d="m 578.08934,206.71507 l 0,-4.7108"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.32574069px;stroke-linecap:butt;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path3855"
|
||||
d="m 578.08934,205.51639 l 0.12203,0"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.1479758px;stroke-linecap:square;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path3859"
|
||||
d="m 580.48669,206.71507 l 0,-4.7108"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.32574069px;stroke-linecap:butt;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path3861"
|
||||
d="m 580.48669,205.51639 l 0.12203,0"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.1479758px;stroke-linecap:square;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path3865"
|
||||
d="m 582.88405,206.71507 l 0,-4.7108"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.32574069px;stroke-linecap:butt;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path3867"
|
||||
d="m 582.88405,205.51639 l 0.12203,0"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.1479758px;stroke-linecap:square;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path3871"
|
||||
d="m 585.28141,206.71507 l 0,-4.7108"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.32574069px;stroke-linecap:butt;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path3873"
|
||||
d="m 585.28141,205.51639 l 0.12203,0"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.1479758px;stroke-linecap:square;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path3929"
|
||||
d="m 591.43136,213.54644 l 4.71081,0"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.32574069px;stroke-linecap:butt;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path3931"
|
||||
d="m 592.63004,213.54644 l 0,0.12202"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.1479758px;stroke-linecap:square;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path3935"
|
||||
d="m 591.43136,215.9438 l 4.71081,0"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.32574069px;stroke-linecap:butt;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path3937"
|
||||
d="m 592.63004,215.9438 l 0,0.12202"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.1479758px;stroke-linecap:square;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path3941"
|
||||
d="m 591.43136,218.34116 l 4.71081,0"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.32574069px;stroke-linecap:butt;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path3943"
|
||||
d="m 592.63004,218.34116 l 0,0.12202"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.1479758px;stroke-linecap:square;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path3947"
|
||||
d="m 591.43136,220.73851 l 4.71081,0"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.32574069px;stroke-linecap:butt;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path3949"
|
||||
d="m 592.63004,220.73851 l 0,0.12202"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.1479758px;stroke-linecap:square;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path3953"
|
||||
d="m 591.43136,223.13587 l 4.71081,0"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.32574069px;stroke-linecap:butt;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path3955"
|
||||
d="m 592.63004,223.13587 l 0,0.12202"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.1479758px;stroke-linecap:square;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path3959"
|
||||
d="m 591.43136,225.53323 l 4.71081,0"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.32574069px;stroke-linecap:butt;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path3961"
|
||||
d="m 592.63004,225.53323 l 0,0.12202"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.1479758px;stroke-linecap:square;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path3965"
|
||||
d="m 591.43136,227.93058 l 4.71081,0"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.32574069px;stroke-linecap:butt;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path3967"
|
||||
d="m 592.63004,227.93058 l 0,0.12202"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.1479758px;stroke-linecap:square;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path3971"
|
||||
d="m 591.43136,230.32794 l 4.71081,0"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.32574069px;stroke-linecap:butt;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path3973"
|
||||
d="m 592.63004,230.32794 l 0,0.12202"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.1479758px;stroke-linecap:square;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path3977"
|
||||
d="m 591.43136,232.7253 l 4.71081,0"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.32574069px;stroke-linecap:butt;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path3979"
|
||||
d="m 592.63004,232.7253 l 0,0.12202"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.1479758px;stroke-linecap:square;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path3983"
|
||||
d="m 591.43136,235.12266 l 4.71081,0"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.32574069px;stroke-linecap:butt;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path3985"
|
||||
d="m 592.63004,235.12266 l 0,0.12202"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.1479758px;stroke-linecap:square;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path3989"
|
||||
d="m 591.43136,237.52001 l 4.71081,0"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.32574069px;stroke-linecap:butt;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path3991"
|
||||
d="m 592.63004,237.52001 l 0,0.12202"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.1479758px;stroke-linecap:square;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path3995"
|
||||
d="m 591.43136,239.91737 l 4.71081,0"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.32574069px;stroke-linecap:butt;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path3997"
|
||||
d="m 592.63004,239.91737 l 0,0.12202"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.1479758px;stroke-linecap:square;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path4001"
|
||||
d="m 591.43136,242.31473 l 4.71081,0"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.32574069px;stroke-linecap:butt;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path4003"
|
||||
d="m 592.63004,242.31473 l 0,0.12202"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.1479758px;stroke-linecap:square;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path4007"
|
||||
d="m 591.43136,244.71208 l 4.71081,0"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.32574069px;stroke-linecap:butt;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path4009"
|
||||
d="m 592.63004,244.71208 l 0,0.12202"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.1479758px;stroke-linecap:square;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path4013"
|
||||
d="m 591.43136,247.10944 l 4.71081,0"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.32574069px;stroke-linecap:butt;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path4015"
|
||||
d="m 592.63004,247.10944 l 0,0.12202"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.1479758px;stroke-linecap:square;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path4019"
|
||||
d="m 591.43136,249.5068 l 4.71081,0"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.32574069px;stroke-linecap:butt;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path4021"
|
||||
d="m 592.63004,249.5068 l 0,0.12202"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.1479758px;stroke-linecap:square;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path4027"
|
||||
d="m 543.76405,213.54644 l -4.71081,0"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.32574069px;stroke-linecap:butt;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path4029"
|
||||
d="m 542.56537,213.54644 l 0,0.12202"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.1479758px;stroke-linecap:square;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path4033"
|
||||
d="m 543.76405,215.9438 l -4.71081,0"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.32574069px;stroke-linecap:butt;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path4035"
|
||||
d="m 542.56537,215.9438 l 0,0.12202"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.1479758px;stroke-linecap:square;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path4039"
|
||||
d="m 543.76405,218.34116 l -4.71081,0"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.32574069px;stroke-linecap:butt;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path4041"
|
||||
d="m 542.56537,218.34116 l 0,0.12202"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.1479758px;stroke-linecap:square;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path4045"
|
||||
d="m 543.76405,220.73851 l -4.71081,0"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.32574069px;stroke-linecap:butt;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path4047"
|
||||
d="m 542.56537,220.73851 l 0,0.12202"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.1479758px;stroke-linecap:square;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path4051"
|
||||
d="m 543.76405,223.13587 l -4.71081,0"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.32574069px;stroke-linecap:butt;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path4053"
|
||||
d="m 542.56537,223.13587 l 0,0.12202"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.1479758px;stroke-linecap:square;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path4057"
|
||||
d="m 543.76405,225.53323 l -4.71081,0"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.32574069px;stroke-linecap:butt;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path4059"
|
||||
d="m 542.56537,225.53323 l 0,0.12202"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.1479758px;stroke-linecap:square;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path4063"
|
||||
d="m 543.76405,227.93058 l -4.71081,0"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.32574069px;stroke-linecap:butt;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path4065"
|
||||
d="m 542.56537,227.93058 l 0,0.12202"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.1479758px;stroke-linecap:square;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path4069"
|
||||
d="m 543.76405,230.32794 l -4.71081,0"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.32574069px;stroke-linecap:butt;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path4071"
|
||||
d="m 542.56537,230.32794 l 0,0.12202"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.1479758px;stroke-linecap:square;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path4075"
|
||||
d="m 543.76405,232.7253 l -4.71081,0"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.32574069px;stroke-linecap:butt;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path4077"
|
||||
d="m 542.56537,232.7253 l 0,0.12202"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.1479758px;stroke-linecap:square;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path4081"
|
||||
d="m 543.76405,235.12266 l -4.71081,0"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.32574069px;stroke-linecap:butt;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path4083"
|
||||
d="m 542.56537,235.12266 l 0,0.12202"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.1479758px;stroke-linecap:square;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path4087"
|
||||
d="m 543.76405,237.52001 l -4.71081,0"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.32574069px;stroke-linecap:butt;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path4089"
|
||||
d="m 542.56537,237.52001 l 0,0.12202"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.1479758px;stroke-linecap:square;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path4093"
|
||||
d="m 543.76405,239.91737 l -4.71081,0"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.32574069px;stroke-linecap:butt;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path4095"
|
||||
d="m 542.56537,239.91737 l 0,0.12202"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.1479758px;stroke-linecap:square;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path4099"
|
||||
d="m 543.76405,242.31473 l -4.71081,0"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.32574069px;stroke-linecap:butt;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path4101"
|
||||
d="m 542.56537,242.31473 l 0,0.12202"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.1479758px;stroke-linecap:square;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path4105"
|
||||
d="m 543.76405,244.71208 l -4.71081,0"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.32574069px;stroke-linecap:butt;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path4107"
|
||||
d="m 542.56537,244.71208 l 0,0.12202"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.1479758px;stroke-linecap:square;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path4111"
|
||||
d="m 543.76405,247.10944 l -4.71081,0"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.32574069px;stroke-linecap:butt;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path4113"
|
||||
d="m 542.56537,247.10944 l 0,0.12202"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.1479758px;stroke-linecap:square;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path4117"
|
||||
d="m 543.76405,249.5068 l -4.71081,0"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.32574069px;stroke-linecap:butt;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path4119"
|
||||
d="m 542.56537,249.5068 l 0,0.12202"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.1479758px;stroke-linecap:square;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path4125"
|
||||
d="m 549.32105,253.94049 l 0,4.7108"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.32574069px;stroke-linecap:butt;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path4127"
|
||||
d="m 549.32105,255.13916 l 0.12203,0"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.1479758px;stroke-linecap:square;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path4131"
|
||||
d="m 551.7184,253.94049 l 0,4.7108"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.32574069px;stroke-linecap:butt;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path4133"
|
||||
d="m 551.7184,255.13916 l 0.12203,0"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.1479758px;stroke-linecap:square;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path4137"
|
||||
d="m 554.11576,253.94049 l 0,4.7108"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.32574069px;stroke-linecap:butt;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path4139"
|
||||
d="m 554.11576,255.13916 l 0.12203,0"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.1479758px;stroke-linecap:square;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path4143"
|
||||
d="m 556.51312,253.94049 l 0,4.7108"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.32574069px;stroke-linecap:butt;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path4145"
|
||||
d="m 556.51312,255.13916 l 0.12203,0"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.1479758px;stroke-linecap:square;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path4149"
|
||||
d="m 558.91048,253.94049 l 0,4.7108"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.32574069px;stroke-linecap:butt;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path4151"
|
||||
d="m 558.91048,255.13916 l 0.12203,0"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.1479758px;stroke-linecap:square;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path4155"
|
||||
d="m 561.30783,253.94049 l 0,4.7108"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.32574069px;stroke-linecap:butt;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path4157"
|
||||
d="m 561.30783,255.13916 l 0.12203,0"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.1479758px;stroke-linecap:square;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path4161"
|
||||
d="m 563.70519,253.94049 l 0,4.7108"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.32574069px;stroke-linecap:butt;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path4163"
|
||||
d="m 563.70519,255.13916 l 0.12203,0"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.1479758px;stroke-linecap:square;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path4167"
|
||||
d="m 566.10255,253.94049 l 0,4.7108"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.32574069px;stroke-linecap:butt;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path4169"
|
||||
d="m 566.10255,255.13916 l 0.12203,0"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.1479758px;stroke-linecap:square;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path4173"
|
||||
d="m 568.49991,253.94049 l 0,4.7108"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.32574069px;stroke-linecap:butt;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path4175"
|
||||
d="m 568.49991,255.13916 l 0.12203,0"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.1479758px;stroke-linecap:square;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path4179"
|
||||
d="m 570.89726,253.94049 l 0,4.7108"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.32574069px;stroke-linecap:butt;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path4181"
|
||||
d="m 570.89726,255.13916 l 0.12203,0"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.1479758px;stroke-linecap:square;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path4185"
|
||||
d="m 573.29462,253.94049 l 0,4.7108"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.32574069px;stroke-linecap:butt;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path4187"
|
||||
d="m 573.29462,255.13916 l 0.12203,0"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.1479758px;stroke-linecap:square;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path4191"
|
||||
d="m 575.69198,253.94049 l 0,4.7108"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.32574069px;stroke-linecap:butt;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path4193"
|
||||
d="m 575.69198,255.13916 l 0.12203,0"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.1479758px;stroke-linecap:square;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path4197"
|
||||
d="m 578.08934,253.94049 l 0,4.7108"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.32574069px;stroke-linecap:butt;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path4199"
|
||||
d="m 578.08934,255.13916 l 0.12203,0"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.1479758px;stroke-linecap:square;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path4203-8"
|
||||
d="m 580.48669,253.94049 l 0,4.7108"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.32574069px;stroke-linecap:butt;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path4205"
|
||||
d="m 580.48669,255.13916 l 0.12203,0"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.1479758px;stroke-linecap:square;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path4209"
|
||||
d="m 582.88405,253.94049 l 0,4.7108"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.32574069px;stroke-linecap:butt;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path4211-8"
|
||||
d="m 582.88405,255.13916 l 0.12203,0"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.1479758px;stroke-linecap:square;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path4215-2"
|
||||
d="m 585.28141,253.94049 l 0,4.7108"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.32574069px;stroke-linecap:butt;stroke-linejoin:miter" />
|
||||
<path
|
||||
id="path4217"
|
||||
d="m 585.28141,255.13916 l 0.12203,0"
|
||||
inkscape:connector-curvature="0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.1479758px;stroke-linecap:square;stroke-linejoin:miter" />
|
||||
<rect
|
||||
style="fill:#e9dcdc"
|
||||
x="584.37372"
|
||||
y="274.48654"
|
||||
width="4.9367957"
|
||||
height="2.7210622"
|
||||
id="rect4867" />
|
||||
<rect
|
||||
style="fill:#8c8989"
|
||||
x="586.16888"
|
||||
y="274.48654"
|
||||
width="1.135463"
|
||||
height="2.7210622"
|
||||
id="rect4869" />
|
||||
<rect
|
||||
style="fill:#e9dcdc"
|
||||
x="584.37372"
|
||||
y="278.97452"
|
||||
width="4.9367957"
|
||||
height="2.7210622"
|
||||
id="rect4877" />
|
||||
<rect
|
||||
style="fill:#8c8989"
|
||||
x="586.16888"
|
||||
y="278.97452"
|
||||
width="1.135463"
|
||||
height="2.7210622"
|
||||
id="rect4879" />
|
||||
<rect
|
||||
style="fill:#e9dcdc"
|
||||
x="584.37372"
|
||||
y="283.46252"
|
||||
width="4.9367957"
|
||||
height="2.7210622"
|
||||
id="rect4883" />
|
||||
<rect
|
||||
style="fill:#8c8989"
|
||||
x="586.16888"
|
||||
y="283.46252"
|
||||
width="1.135463"
|
||||
height="2.7210622"
|
||||
id="rect4885" />
|
||||
<rect
|
||||
style="fill:#e9dcdc"
|
||||
x="-575.68927"
|
||||
y="283.46252"
|
||||
width="4.9367957"
|
||||
height="2.7210622"
|
||||
transform="scale(-1,1)"
|
||||
id="rect4889" />
|
||||
<rect
|
||||
style="fill:#8c8989"
|
||||
x="-573.89404"
|
||||
y="283.46252"
|
||||
width="1.135463"
|
||||
height="2.7210622"
|
||||
transform="scale(-1,1)"
|
||||
id="rect4891" />
|
||||
<rect
|
||||
style="fill:#e9dcdc"
|
||||
x="-575.68927"
|
||||
y="274.48654"
|
||||
width="4.9367957"
|
||||
height="2.7210622"
|
||||
transform="scale(-1,1)"
|
||||
id="rect4901" />
|
||||
<rect
|
||||
style="fill:#8c8989"
|
||||
x="-573.89404"
|
||||
y="274.48654"
|
||||
width="1.135463"
|
||||
height="2.7210622"
|
||||
transform="scale(-1,1)"
|
||||
id="rect4903" />
|
||||
<rect
|
||||
rx="0.6731993"
|
||||
id="rect4841"
|
||||
ry="0.6731993"
|
||||
height="14.271826"
|
||||
width="8.3925524"
|
||||
stroke-miterlimit="4"
|
||||
y="273.93018"
|
||||
x="575.72699"
|
||||
style="fill:#6a6a6a;stroke:#000000;stroke-width:1.08160698;stroke-miterlimit:4;stroke-dasharray:none" />
|
||||
<rect
|
||||
style="fill:#e9dcdc"
|
||||
x="127.2851"
|
||||
y="-623.52423"
|
||||
width="4.9367952"
|
||||
height="2.7210624"
|
||||
transform="matrix(0,1,-1,0,0,0)"
|
||||
id="rect13881" />
|
||||
<rect
|
||||
style="fill:#8c8989"
|
||||
x="129.08029"
|
||||
y="-623.52423"
|
||||
width="1.1354629"
|
||||
height="2.7210624"
|
||||
transform="matrix(0,1,-1,0,0,0)"
|
||||
id="rect13883" />
|
||||
<rect
|
||||
style="fill:#e9dcdc"
|
||||
x="127.2851"
|
||||
y="-619.03619"
|
||||
width="4.9367952"
|
||||
height="2.7210624"
|
||||
transform="matrix(0,1,-1,0,0,0)"
|
||||
id="rect13887" />
|
||||
<rect
|
||||
style="fill:#8c8989"
|
||||
x="129.08029"
|
||||
y="-619.03619"
|
||||
width="1.1354629"
|
||||
height="2.7210624"
|
||||
transform="matrix(0,1,-1,0,0,0)"
|
||||
id="rect13889" />
|
||||
<rect
|
||||
style="fill:#e9dcdc"
|
||||
x="127.2851"
|
||||
y="-614.54822"
|
||||
width="4.9367952"
|
||||
height="2.7210624"
|
||||
transform="matrix(0,1,-1,0,0,0)"
|
||||
id="rect13893" />
|
||||
<rect
|
||||
style="fill:#8c8989"
|
||||
x="129.08029"
|
||||
y="-614.54822"
|
||||
width="1.1354629"
|
||||
height="2.7210624"
|
||||
transform="matrix(0,1,-1,0,0,0)"
|
||||
id="rect13895" />
|
||||
<rect
|
||||
style="fill:#e9dcdc"
|
||||
x="-118.60066"
|
||||
y="-614.54822"
|
||||
width="4.9367952"
|
||||
height="2.7210624"
|
||||
transform="matrix(0,-1,-1,0,0,0)"
|
||||
id="rect13899" />
|
||||
<rect
|
||||
style="fill:#8c8989"
|
||||
x="-116.80547"
|
||||
y="-614.54822"
|
||||
width="1.1354629"
|
||||
height="2.7210624"
|
||||
transform="matrix(0,-1,-1,0,0,0)"
|
||||
id="rect13901" />
|
||||
<rect
|
||||
style="fill:#e9dcdc"
|
||||
x="-118.60066"
|
||||
y="-623.52423"
|
||||
width="4.9367952"
|
||||
height="2.7210624"
|
||||
transform="matrix(0,-1,-1,0,0,0)"
|
||||
id="rect13905" />
|
||||
<rect
|
||||
style="fill:#8c8989"
|
||||
x="-116.80547"
|
||||
y="-623.52423"
|
||||
width="1.1354629"
|
||||
height="2.7210624"
|
||||
transform="matrix(0,-1,-1,0,0,0)"
|
||||
id="rect13907" />
|
||||
<rect
|
||||
rx="0.67319936"
|
||||
id="rect13909"
|
||||
ry="0.67319936"
|
||||
height="14.271827"
|
||||
width="8.3925524"
|
||||
stroke-miterlimit="4"
|
||||
y="-624.08057"
|
||||
x="118.63837"
|
||||
style="fill:#6a6a6a;stroke:#000000;stroke-width:1.08160698;stroke-miterlimit:4;stroke-dasharray:none"
|
||||
transform="matrix(0,1,-1,0,0,0)" />
|
||||
<rect
|
||||
id="rect5020"
|
||||
transform="matrix(0,1,-1,0,0,0)"
|
||||
height="34.898285"
|
||||
width="59.816059"
|
||||
stroke-miterlimit="4"
|
||||
y="-467.97284"
|
||||
x="177.77756"
|
||||
style="fill:#fffcfc;stroke:#828282;stroke-width:2.17025805;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-dasharray:none" />
|
||||
<rect
|
||||
style="fill:#e9dcdc"
|
||||
x="468.33835"
|
||||
y="-189.53841"
|
||||
width="7.3681602"
|
||||
height="4.0611815"
|
||||
transform="scale(1,-1)"
|
||||
id="rect4966-2" />
|
||||
<rect
|
||||
style="fill:#8c8989"
|
||||
x="471.01767"
|
||||
y="-189.53841"
|
||||
width="1.6946768"
|
||||
height="4.0611815"
|
||||
transform="scale(1,-1)"
|
||||
id="rect4968-1" />
|
||||
<rect
|
||||
style="fill:#e9dcdc"
|
||||
x="468.33835"
|
||||
y="-196.23674"
|
||||
width="7.3681602"
|
||||
height="4.0611815"
|
||||
transform="scale(1,-1)"
|
||||
id="rect5048" />
|
||||
<rect
|
||||
style="fill:#8c8989"
|
||||
x="471.01767"
|
||||
y="-196.23674"
|
||||
width="1.6946768"
|
||||
height="4.0611815"
|
||||
transform="scale(1,-1)"
|
||||
id="rect5050" />
|
||||
<rect
|
||||
style="fill:#e9dcdc"
|
||||
x="468.33835"
|
||||
y="-202.93506"
|
||||
width="7.3681602"
|
||||
height="4.0611815"
|
||||
transform="scale(1,-1)"
|
||||
id="rect5054" />
|
||||
<rect
|
||||
style="fill:#8c8989"
|
||||
x="471.01767"
|
||||
y="-202.93506"
|
||||
width="1.6946768"
|
||||
height="4.0611815"
|
||||
transform="scale(1,-1)"
|
||||
id="rect5056" />
|
||||
<rect
|
||||
style="fill:#e9dcdc"
|
||||
x="468.33835"
|
||||
y="-209.63339"
|
||||
width="7.3681602"
|
||||
height="4.0611815"
|
||||
transform="scale(1,-1)"
|
||||
id="rect5060" />
|
||||
<rect
|
||||
style="fill:#8c8989"
|
||||
x="471.01767"
|
||||
y="-209.63339"
|
||||
width="1.6946768"
|
||||
height="4.0611815"
|
||||
transform="scale(1,-1)"
|
||||
id="rect5062" />
|
||||
<rect
|
||||
style="fill:#e9dcdc"
|
||||
x="468.33835"
|
||||
y="-216.33173"
|
||||
width="7.3681602"
|
||||
height="4.0611815"
|
||||
transform="scale(1,-1)"
|
||||
id="rect5066" />
|
||||
<rect
|
||||
style="fill:#8c8989"
|
||||
x="471.01767"
|
||||
y="-216.33173"
|
||||
width="1.6946768"
|
||||
height="4.0611815"
|
||||
transform="scale(1,-1)"
|
||||
id="rect5068" />
|
||||
<rect
|
||||
style="fill:#e9dcdc"
|
||||
x="468.33835"
|
||||
y="-223.03006"
|
||||
width="7.3681602"
|
||||
height="4.0611815"
|
||||
transform="scale(1,-1)"
|
||||
id="rect5072" />
|
||||
<rect
|
||||
style="fill:#8c8989"
|
||||
x="471.01767"
|
||||
y="-223.03006"
|
||||
width="1.6946768"
|
||||
height="4.0611815"
|
||||
transform="scale(1,-1)"
|
||||
id="rect5074" />
|
||||
<rect
|
||||
style="fill:#e9dcdc"
|
||||
x="468.33835"
|
||||
y="-229.53119"
|
||||
width="7.3681602"
|
||||
height="4.0611815"
|
||||
transform="scale(1,-1)"
|
||||
id="rect14000" />
|
||||
<rect
|
||||
style="fill:#8c8989"
|
||||
x="471.01767"
|
||||
y="-229.53119"
|
||||
width="1.6946768"
|
||||
height="4.0611815"
|
||||
transform="scale(1,-1)"
|
||||
id="rect14002" />
|
||||
<rect
|
||||
style="fill:#e9dcdc"
|
||||
x="468.33835"
|
||||
y="-236.0323"
|
||||
width="7.3681602"
|
||||
height="4.0611815"
|
||||
transform="scale(1,-1)"
|
||||
id="rect14006" />
|
||||
<rect
|
||||
style="fill:#8c8989"
|
||||
x="471.01767"
|
||||
y="-236.0323"
|
||||
width="1.6946768"
|
||||
height="4.0611815"
|
||||
transform="scale(1,-1)"
|
||||
id="rect14008" />
|
||||
<rect
|
||||
style="fill:#e9dcdc"
|
||||
x="-456.31073"
|
||||
y="-273.86774"
|
||||
width="5.7475319"
|
||||
height="3.9238191"
|
||||
transform="scale(-1,-1)"
|
||||
id="rect4867-0" />
|
||||
<rect
|
||||
style="fill:#8c8989"
|
||||
x="-454.2207"
|
||||
y="-273.86774"
|
||||
width="1.3219323"
|
||||
height="3.9238191"
|
||||
transform="scale(-1,-1)"
|
||||
id="rect4869-4" />
|
||||
<rect
|
||||
style="fill:#e9dcdc"
|
||||
x="-456.31073"
|
||||
y="-267.39597"
|
||||
width="5.7475319"
|
||||
height="3.9238191"
|
||||
transform="scale(-1,-1)"
|
||||
id="rect4877-3" />
|
||||
<rect
|
||||
style="fill:#8c8989"
|
||||
x="-454.2207"
|
||||
y="-267.39597"
|
||||
width="1.3219323"
|
||||
height="3.9238191"
|
||||
transform="scale(-1,-1)"
|
||||
id="rect4879-4" />
|
||||
<rect
|
||||
style="fill:#e9dcdc"
|
||||
x="-456.31073"
|
||||
y="-260.92419"
|
||||
width="5.7475319"
|
||||
height="3.9238191"
|
||||
transform="scale(-1,-1)"
|
||||
id="rect4883-6" />
|
||||
<rect
|
||||
style="fill:#8c8989"
|
||||
x="-454.2207"
|
||||
y="-260.92419"
|
||||
width="1.3219323"
|
||||
height="3.9238191"
|
||||
transform="scale(-1,-1)"
|
||||
id="rect4885-2" />
|
||||
<rect
|
||||
style="fill:#e9dcdc"
|
||||
x="466.42136"
|
||||
y="-260.92419"
|
||||
width="5.7475319"
|
||||
height="3.9238191"
|
||||
transform="scale(1,-1)"
|
||||
id="rect4889-3" />
|
||||
<rect
|
||||
style="fill:#8c8989"
|
||||
x="468.51135"
|
||||
y="-260.92419"
|
||||
width="1.3219323"
|
||||
height="3.9238191"
|
||||
transform="scale(1,-1)"
|
||||
id="rect4891-3" />
|
||||
<rect
|
||||
style="fill:#e9dcdc"
|
||||
x="466.42136"
|
||||
y="-273.86774"
|
||||
width="5.7475319"
|
||||
height="3.9238191"
|
||||
transform="scale(1,-1)"
|
||||
id="rect4901-7" />
|
||||
<rect
|
||||
style="fill:#8c8989"
|
||||
x="468.51135"
|
||||
y="-273.86774"
|
||||
width="1.3219323"
|
||||
height="3.9238191"
|
||||
transform="scale(1,-1)"
|
||||
id="rect4903-8" />
|
||||
<rect
|
||||
rx="0.97076511"
|
||||
id="rect4841-1"
|
||||
ry="0.97076511"
|
||||
height="20.580219"
|
||||
width="9.7708044"
|
||||
stroke-miterlimit="4"
|
||||
y="-274.67001"
|
||||
x="-466.37744"
|
||||
style="fill:#6a6a6a;stroke:#000000;stroke-width:1.0816052;stroke-miterlimit:4;stroke-dasharray:none"
|
||||
transform="scale(-1,-1)" />
|
||||
<rect
|
||||
style="fill:#d3d0ce;stroke-width:0;stroke-miterlimit:4"
|
||||
id="rect14080"
|
||||
height="5.5151954"
|
||||
width="3.868221"
|
||||
y="621.14215"
|
||||
x="-308.31299"
|
||||
transform="matrix(0,-1,1,0,0,0)" />
|
||||
<rect
|
||||
style="fill:#d3d0ce;stroke-width:0;stroke-miterlimit:4"
|
||||
id="rect14082"
|
||||
height="5.5151954"
|
||||
width="3.868221"
|
||||
y="621.14215"
|
||||
x="-316.98129"
|
||||
transform="matrix(0,-1,1,0,0,0)" />
|
||||
<rect
|
||||
id="rect14086"
|
||||
height="27.293268"
|
||||
width="35.702084"
|
||||
stroke-miterlimit="4"
|
||||
y="299.41049"
|
||||
x="488.68149"
|
||||
style="fill:#fffcfc;stroke:#828282;stroke-width:2.1680696;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-dasharray:none" />
|
||||
<rect
|
||||
style="fill:#e9dcdc"
|
||||
x="-298.90277"
|
||||
y="-500.82507"
|
||||
width="5.7624946"
|
||||
height="4.061182"
|
||||
transform="matrix(0,-1,-1,0,0,0)"
|
||||
id="rect14090" />
|
||||
<rect
|
||||
style="fill:#8c8989"
|
||||
x="-296.80731"
|
||||
y="-500.82507"
|
||||
width="1.3253738"
|
||||
height="4.061182"
|
||||
transform="matrix(0,-1,-1,0,0,0)"
|
||||
id="rect14092" />
|
||||
<rect
|
||||
style="fill:#e9dcdc"
|
||||
x="-298.90277"
|
||||
y="-507.52341"
|
||||
width="5.7624946"
|
||||
height="4.061182"
|
||||
transform="matrix(0,-1,-1,0,0,0)"
|
||||
id="rect14096" />
|
||||
<rect
|
||||
style="fill:#8c8989"
|
||||
x="-296.80731"
|
||||
y="-507.52341"
|
||||
width="1.3253738"
|
||||
height="4.061182"
|
||||
transform="matrix(0,-1,-1,0,0,0)"
|
||||
id="rect14098" />
|
||||
<rect
|
||||
style="fill:#e9dcdc"
|
||||
x="-298.90277"
|
||||
y="-514.22174"
|
||||
width="5.7624946"
|
||||
height="4.061182"
|
||||
transform="matrix(0,-1,-1,0,0,0)"
|
||||
id="rect14102" />
|
||||
<rect
|
||||
style="fill:#8c8989"
|
||||
x="-296.80731"
|
||||
y="-514.22174"
|
||||
width="1.3253738"
|
||||
height="4.061182"
|
||||
transform="matrix(0,-1,-1,0,0,0)"
|
||||
id="rect14104" />
|
||||
<rect
|
||||
style="fill:#e9dcdc"
|
||||
x="-298.90277"
|
||||
y="-520.9201"
|
||||
width="5.7624946"
|
||||
height="4.061182"
|
||||
transform="matrix(0,-1,-1,0,0,0)"
|
||||
id="rect14108" />
|
||||
<rect
|
||||
style="fill:#8c8989"
|
||||
x="-296.80731"
|
||||
y="-520.9201"
|
||||
width="1.3253738"
|
||||
height="4.061182"
|
||||
transform="matrix(0,-1,-1,0,0,0)"
|
||||
id="rect14110" />
|
||||
<rect
|
||||
id="rect14138"
|
||||
height="27.293268"
|
||||
width="35.702084"
|
||||
stroke-miterlimit="4"
|
||||
y="299.41049"
|
||||
x="581.19727"
|
||||
style="fill:#fffcfc;stroke:#828282;stroke-width:2.1680696;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-dasharray:none" />
|
||||
<rect
|
||||
style="fill:#e9dcdc"
|
||||
x="-298.90277"
|
||||
y="-591.34082"
|
||||
width="5.7624946"
|
||||
height="4.061182"
|
||||
transform="matrix(0,-1,-1,0,0,0)"
|
||||
id="rect14142" />
|
||||
<rect
|
||||
style="fill:#8c8989"
|
||||
x="-296.80731"
|
||||
y="-591.34082"
|
||||
width="1.3253738"
|
||||
height="4.061182"
|
||||
transform="matrix(0,-1,-1,0,0,0)"
|
||||
id="rect14144" />
|
||||
<rect
|
||||
style="fill:#e9dcdc"
|
||||
x="-298.90277"
|
||||
y="-598.03918"
|
||||
width="5.7624946"
|
||||
height="4.061182"
|
||||
transform="matrix(0,-1,-1,0,0,0)"
|
||||
id="rect14148" />
|
||||
<rect
|
||||
style="fill:#8c8989"
|
||||
x="-296.80731"
|
||||
y="-598.03918"
|
||||
width="1.3253738"
|
||||
height="4.061182"
|
||||
transform="matrix(0,-1,-1,0,0,0)"
|
||||
id="rect14150" />
|
||||
<rect
|
||||
style="fill:#e9dcdc"
|
||||
x="-298.90277"
|
||||
y="-604.73749"
|
||||
width="5.7624946"
|
||||
height="4.061182"
|
||||
transform="matrix(0,-1,-1,0,0,0)"
|
||||
id="rect14154" />
|
||||
<rect
|
||||
style="fill:#8c8989"
|
||||
x="-296.80731"
|
||||
y="-604.73749"
|
||||
width="1.3253738"
|
||||
height="4.061182"
|
||||
transform="matrix(0,-1,-1,0,0,0)"
|
||||
id="rect14156" />
|
||||
<rect
|
||||
style="fill:#e9dcdc"
|
||||
x="-298.90277"
|
||||
y="-611.43579"
|
||||
width="5.7624946"
|
||||
height="4.061182"
|
||||
transform="matrix(0,-1,-1,0,0,0)"
|
||||
id="rect14160" />
|
||||
<rect
|
||||
style="fill:#8c8989"
|
||||
x="-296.80731"
|
||||
y="-611.43579"
|
||||
width="1.3253738"
|
||||
height="4.061182"
|
||||
transform="matrix(0,-1,-1,0,0,0)"
|
||||
id="rect14162" />
|
||||
<rect
|
||||
id="rect14166"
|
||||
height="21.734783"
|
||||
width="16.967201"
|
||||
y="249.09335"
|
||||
x="631.93884"
|
||||
style="fill:#00440d;stroke-width:0;stroke-miterlimit:4" />
|
||||
<rect
|
||||
id="rect14168"
|
||||
height="21.734783"
|
||||
width="9.2903233"
|
||||
y="249.09335"
|
||||
x="650.15515"
|
||||
style="fill:#d3d0ce;stroke-width:0;stroke-miterlimit:4" />
|
||||
<rect
|
||||
id="rect14170"
|
||||
height="21.734783"
|
||||
width="9.2903233"
|
||||
y="249.09335"
|
||||
x="624.13184"
|
||||
style="fill:#d3d0ce;stroke-width:0;stroke-miterlimit:4" />
|
||||
<rect
|
||||
style="fill:#6a6a6a;stroke:#000000;stroke-width:0.75847471;stroke-miterlimit:4;stroke-dasharray:none"
|
||||
x="577.76172"
|
||||
y="112.47642"
|
||||
stroke-miterlimit="4"
|
||||
width="20.045404"
|
||||
height="30.880756"
|
||||
id="rect14172" />
|
||||
<rect
|
||||
id="rect14194"
|
||||
height="5.5151949"
|
||||
width="7.064651"
|
||||
y="135.60159"
|
||||
x="474.20758"
|
||||
style="fill:#312d29;stroke-width:0;stroke-miterlimit:4" />
|
||||
<rect
|
||||
id="rect14196"
|
||||
height="5.5151949"
|
||||
width="3.8682213"
|
||||
y="135.60159"
|
||||
x="481.79233"
|
||||
style="fill:#d3d0ce;stroke-width:0;stroke-miterlimit:4" />
|
||||
<rect
|
||||
id="rect14198"
|
||||
height="5.5151949"
|
||||
width="3.8682213"
|
||||
y="135.60159"
|
||||
x="470.957"
|
||||
style="fill:#d3d0ce;stroke-width:0;stroke-miterlimit:4" />
|
||||
<rect
|
||||
style="fill:#e9dcdc"
|
||||
x="308.06442"
|
||||
y="-563.91339"
|
||||
width="7.6110497"
|
||||
height="4.0624456"
|
||||
transform="matrix(0,1,-1,0,0,0)"
|
||||
id="rect14204" />
|
||||
<rect
|
||||
style="fill:#8c8989"
|
||||
x="310.83209"
|
||||
y="-563.91339"
|
||||
width="1.7505414"
|
||||
height="4.0624456"
|
||||
transform="matrix(0,1,-1,0,0,0)"
|
||||
id="rect14206" />
|
||||
<rect
|
||||
style="fill:#e9dcdc"
|
||||
x="308.06442"
|
||||
y="-557.21295"
|
||||
width="7.6110497"
|
||||
height="4.0624456"
|
||||
transform="matrix(0,1,-1,0,0,0)"
|
||||
id="rect14210" />
|
||||
<rect
|
||||
style="fill:#8c8989"
|
||||
x="310.83209"
|
||||
y="-557.21295"
|
||||
width="1.7505414"
|
||||
height="4.0624456"
|
||||
transform="matrix(0,1,-1,0,0,0)"
|
||||
id="rect14212" />
|
||||
<rect
|
||||
style="fill:#e9dcdc"
|
||||
x="308.06442"
|
||||
y="-550.51251"
|
||||
width="7.6110497"
|
||||
height="4.0624456"
|
||||
transform="matrix(0,1,-1,0,0,0)"
|
||||
id="rect14216" />
|
||||
<rect
|
||||
style="fill:#8c8989"
|
||||
x="310.83209"
|
||||
y="-550.51251"
|
||||
width="1.7505414"
|
||||
height="4.0624456"
|
||||
transform="matrix(0,1,-1,0,0,0)"
|
||||
id="rect14218" />
|
||||
<rect
|
||||
style="fill:#e9dcdc"
|
||||
x="-286.00735"
|
||||
y="-550.51251"
|
||||
width="7.6110497"
|
||||
height="4.0624456"
|
||||
transform="matrix(0,-1,-1,0,0,0)"
|
||||
id="rect14222" />
|
||||
<rect
|
||||
style="fill:#8c8989"
|
||||
x="-283.23969"
|
||||
y="-550.51251"
|
||||
width="1.7505414"
|
||||
height="4.0624456"
|
||||
transform="matrix(0,-1,-1,0,0,0)"
|
||||
id="rect14224" />
|
||||
<rect
|
||||
style="fill:#e9dcdc"
|
||||
x="-286.00735"
|
||||
y="-563.91339"
|
||||
width="7.6110497"
|
||||
height="4.0624456"
|
||||
transform="matrix(0,-1,-1,0,0,0)"
|
||||
id="rect14228" />
|
||||
<rect
|
||||
style="fill:#8c8989"
|
||||
x="-283.23969"
|
||||
y="-563.91339"
|
||||
width="1.7505414"
|
||||
height="4.0624456"
|
||||
transform="matrix(0,-1,-1,0,0,0)"
|
||||
id="rect14230" />
|
||||
<rect
|
||||
style="fill:#e9dcdc"
|
||||
x="-286.00735"
|
||||
y="-556.98328"
|
||||
width="7.6110497"
|
||||
height="4.0624456"
|
||||
transform="matrix(0,-1,-1,0,0,0)"
|
||||
id="rect14242" />
|
||||
<rect
|
||||
style="fill:#8c8989"
|
||||
x="-283.23969"
|
||||
y="-556.98328"
|
||||
width="1.7505414"
|
||||
height="4.0624456"
|
||||
transform="matrix(0,-1,-1,0,0,0)"
|
||||
id="rect14244" />
|
||||
<rect
|
||||
style="fill:#e9dcdc"
|
||||
x="-286.00735"
|
||||
y="-544.04181"
|
||||
width="7.6110497"
|
||||
height="4.0624456"
|
||||
transform="matrix(0,-1,-1,0,0,0)"
|
||||
id="rect14248" />
|
||||
<rect
|
||||
style="fill:#8c8989"
|
||||
x="-283.23969"
|
||||
y="-544.04181"
|
||||
width="1.7505414"
|
||||
height="4.0624456"
|
||||
transform="matrix(0,-1,-1,0,0,0)"
|
||||
id="rect14250" />
|
||||
<rect
|
||||
style="fill:#e9dcdc"
|
||||
x="308.06442"
|
||||
y="-544.04181"
|
||||
width="7.6110497"
|
||||
height="4.0624456"
|
||||
transform="matrix(0,1,-1,0,0,0)"
|
||||
id="rect14254" />
|
||||
<rect
|
||||
style="fill:#8c8989"
|
||||
x="310.83209"
|
||||
y="-544.04181"
|
||||
width="1.7505414"
|
||||
height="4.0624456"
|
||||
transform="matrix(0,1,-1,0,0,0)"
|
||||
id="rect14256" />
|
||||
<rect
|
||||
rx="1.2931794"
|
||||
id="rect14232"
|
||||
ry="1.2931794"
|
||||
height="27.404684"
|
||||
width="24.216976"
|
||||
stroke-miterlimit="4"
|
||||
y="-565.74445"
|
||||
x="284.95566"
|
||||
style="fill:#6a6a6a;stroke:#000000;stroke-width:1.08261442;stroke-miterlimit:4;stroke-dasharray:none"
|
||||
transform="matrix(0,1,-1,0,0,0)" />
|
||||
<g
|
||||
id="text29413-5"
|
||||
style="font-style:normal;font-variant:normal;font-weight:bold;font-stretch:normal;font-size:12.71438503px;line-height:125%;font-family:Arial;-inkscape-font-specification:'Arial Bold';letter-spacing:0px;word-spacing:0px;display:inline;fill:#000000;fill-opacity:1;stroke:none"
|
||||
transform="translate(-723.48677,-464.26477)">
|
||||
<path
|
||||
id="path29439-8"
|
||||
d="m 1398.0763,618.22131 l -1.7445,0 l 0,-6.57448 c -0.6374,0.596 -1.3886,1.03678 -2.2536,1.32235 l 0,-1.58309 c 0.4553,-0.14899 0.9499,-0.43043 1.4838,-0.84431 c 0.5339,-0.41802 0.9002,-0.90432 1.0988,-1.45893 l 1.4155,0 l 0,9.13846"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
id="path29441-1"
|
||||
d="m 1399.5042,632.49396 l 0,1.62033 l -6.1151,0 c 0.066,-0.61254 0.2649,-1.19197 0.596,-1.73829 c 0.3311,-0.55046 0.985,-1.27889 1.9618,-2.18528 c 0.7864,-0.73257 1.2685,-1.22922 1.4465,-1.48997 c 0.2401,-0.36007 0.3601,-0.71601 0.3601,-1.06781 c 0,-0.38904 -0.1056,-0.68703 -0.3166,-0.89398 c -0.207,-0.21107 -0.4946,-0.31661 -0.863,-0.31662 c -0.3642,1e-5 -0.6539,0.10969 -0.8691,0.32903 c -0.2152,0.21937 -0.3394,0.58358 -0.3725,1.09265 l -1.7383,-0.17383 c 0.1035,-0.9602 0.4284,-1.64931 0.9747,-2.06733 c 0.5463,-0.41801 1.2292,-0.62702 2.0487,-0.62703 c 0.8981,10e-6 1.6038,0.24213 2.117,0.72636 c 0.5132,0.48425 0.7698,1.08644 0.7698,1.80658 c 0,0.40975 -0.075,0.80087 -0.2235,1.17335 c -0.1449,0.36836 -0.3766,0.75534 -0.6953,1.16094 c -0.2111,0.26902 -0.5919,0.656 -1.1423,1.16093 c -0.5505,0.50493 -0.9002,0.84018 -1.0492,1.00573 c -0.1449,0.16555 -0.2628,0.32696 -0.3539,0.48424 l 3.4642,0"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
id="path29443-6"
|
||||
d="m 1393.5505,647.59229 l 1.6887,-0.20487 c 0.054,0.43043 0.1986,0.75947 0.4345,0.9871 c 0.236,0.22764 0.5215,0.34145 0.8568,0.34145 c 0.36,0 0.6622,-0.13658 0.9064,-0.40974 c 0.2483,-0.27316 0.3725,-0.64151 0.3725,-1.10506 c 0,-0.43871 -0.118,-0.78637 -0.3539,-1.04298 c -0.2359,-0.2566 -0.5236,-0.3849 -0.8629,-0.3849 c -0.2235,0 -0.4905,0.0435 -0.8009,0.13037 l 0.1925,-1.42168 c 0.4718,0.0124 0.8318,-0.089 1.0802,-0.3042 c 0.2483,-0.21935 0.3725,-0.50907 0.3725,-0.86915 c 0,-0.30626 -0.091,-0.55045 -0.2732,-0.73256 c -0.1821,-0.1821 -0.4242,-0.27316 -0.7263,-0.27316 c -0.298,0 -0.5526,0.10347 -0.7637,0.3104 c -0.211,0.20695 -0.3393,0.50908 -0.3849,0.9064 l -1.6079,-0.27316 c 0.1118,-0.55045 0.2794,-0.98916 0.5029,-1.31614 c 0.2276,-0.33109 0.5422,-0.58977 0.9436,-0.77602 c 0.4056,-0.19038 0.8588,-0.28557 1.3596,-0.28558 c 0.8567,10e-6 1.5438,0.27317 2.0611,0.81948 c 0.4263,0.447 0.6395,0.95193 0.6395,1.5148 c 0,0.7988 -0.4367,1.43617 -1.3099,1.91213 c 0.5214,0.11175 0.9374,0.36215 1.2478,0.75119 c 0.3145,0.38905 0.4718,0.8588 0.4718,1.40926 c 0,0.79879 -0.2918,1.47962 -0.8753,2.0425 c -0.5836,0.56287 -1.31,0.84431 -2.1791,0.84431 c -0.8236,0 -1.5065,-0.23591 -2.0487,-0.70773 c -0.5422,-0.47596 -0.8567,-1.09678 -0.9437,-1.86246"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
id="path29445-0"
|
||||
d="m 1397.0333,665.90026 l 0,-1.83142 l -3.7249,0 l 0,-1.52722 l 3.9484,-5.77983 l 1.4652,0 l 0,5.77363 l 1.1299,0 l 0,1.53342 l -1.1299,0 l 0,1.83142 l -1.6887,0 m 0,-3.36484 l 0,-3.11031 l -2.0921,3.11031 l 2.0921,0"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
id="path29447-1"
|
||||
d="m 1393.6375,679.45275 l 1.7383,-0.18004 c 0.05,0.39319 0.1965,0.70567 0.4407,0.93744 c 0.2442,0.22763 0.5257,0.34145 0.8443,0.34145 c 0.3643,0 0.6726,-0.14693 0.9251,-0.44078 c 0.2524,-0.29799 0.3787,-0.74498 0.3787,-1.34097 c 0,-0.55874 -0.1263,-0.97675 -0.3787,-1.25406 c -0.2484,-0.28143 -0.5733,-0.42215 -0.9747,-0.42216 c -0.5008,1e-5 -0.9499,0.22143 -1.3472,0.66428 l -1.4155,-0.20487 l 0.894,-4.73685 l 4.6127,0 l 0,1.63275 l -3.2903,0 l -0.2732,1.54584 c 0.389,-0.19451 0.7864,-0.29178 1.192,-0.29178 c 0.7739,0 1.4299,0.28144 1.968,0.84431 c 0.538,0.56288 0.807,1.29338 0.807,2.1915 c 0,0.74912 -0.2173,1.41754 -0.6518,2.00524 c -0.5919,0.80293 -1.4134,1.20439 -2.4647,1.20439 c -0.8402,0 -1.5251,-0.22556 -2.0549,-0.67669 c -0.5298,-0.45113 -0.8464,-1.05746 -0.9498,-1.819"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
id="path29449-56"
|
||||
d="m 1399.5228,690.81375 l -1.6886,0.18624 c -0.041,-0.34765 -0.149,-0.60425 -0.3228,-0.76981 c -0.1739,-0.16555 -0.3994,-0.24832 -0.6767,-0.24833 c -0.3684,10e-6 -0.6809,0.16556 -0.9375,0.49665 c -0.2524,0.33112 -0.4118,1.02022 -0.478,2.06733 c 0.4346,-0.5132 0.9747,-0.76981 1.6203,-0.76981 c 0.7285,0 1.3514,0.2773 1.8687,0.8319 c 0.5215,0.5546 0.7822,1.27061 0.7822,2.14803 c 0,0.93123 -0.2731,1.67829 -0.8194,2.24116 c -0.5464,0.56288 -1.2479,0.84431 -2.1046,0.84431 c -0.9188,0 -1.6742,-0.35593 -2.266,-1.0678 c -0.5919,-0.71602 -0.8878,-1.88729 -0.8878,-3.51384 c 0,-1.66793 0.3084,-2.87025 0.925,-3.60697 c 0.6167,-0.73669 1.4176,-1.10505 2.4026,-1.10505 c 0.6912,0 1.2623,0.19453 1.7135,0.58357 c 0.4552,0.38491 0.745,0.94572 0.8691,1.68242 m -3.9546,3.80562 c 0,0.56702 0.1304,1.00573 0.3911,1.31614 c 0.2608,0.30627 0.5588,0.45941 0.894,0.45941 c 0.3228,0 0.5918,-0.12624 0.8071,-0.3787 c 0.2152,-0.25247 0.3228,-0.66635 0.3228,-1.24164 c 0,-0.59185 -0.1159,-1.02435 -0.3477,-1.29752 c -0.2317,-0.27729 -0.5215,-0.41594 -0.8691,-0.41595 c -0.3353,10e-6 -0.6188,0.13245 -0.8505,0.39733 c -0.2318,0.26075 -0.3477,0.64772 -0.3477,1.16093"
|
||||
inkscape:connector-curvature="0" />
|
||||
</g>
|
||||
</g>
|
||||
</g>
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
|
Before Width: | Height: | Size: 2.7 MiB After Width: | Height: | Size: 2.8 MiB |
@ -95,6 +95,8 @@ int SetupWizard::nextId() const
|
||||
case PAGE_CONTROLLER:
|
||||
{
|
||||
switch (getControllerType()) {
|
||||
case CONTROLLER_CC:
|
||||
case CONTROLLER_CC3D:
|
||||
case CONTROLLER_REVO:
|
||||
case CONTROLLER_DISCOVERYF4:
|
||||
return PAGE_INPUT;
|
||||
@ -207,6 +209,8 @@ int SetupWizard::nextId() const
|
||||
case PAGE_SUMMARY:
|
||||
{
|
||||
switch (getControllerType()) {
|
||||
case CONTROLLER_CC:
|
||||
case CONTROLLER_CC3D:
|
||||
case CONTROLLER_REVO:
|
||||
case CONTROLLER_NANO:
|
||||
case CONTROLLER_DISCOVERYF4:
|
||||
@ -238,6 +242,12 @@ QString SetupWizard::getSummaryText()
|
||||
|
||||
summary.append("<b>").append(tr("Controller type: ")).append("</b>");
|
||||
switch (getControllerType()) {
|
||||
case CONTROLLER_CC:
|
||||
summary.append(tr("OpenPilot CopterControl"));
|
||||
break;
|
||||
case CONTROLLER_CC3D:
|
||||
summary.append(tr("OpenPilot CopterControl 3D"));
|
||||
break;
|
||||
case CONTROLLER_REVO:
|
||||
summary.append(tr("OpenPilot Revolution"));
|
||||
break;
|
||||
|
@ -100,9 +100,16 @@ bool VehicleConfigurationHelper::setupHardwareSettings(bool save)
|
||||
|
||||
bool VehicleConfigurationHelper::isApplicable(UAVObject *dataObj)
|
||||
{
|
||||
Q_UNUSED(dataObj);
|
||||
switch (m_configSource->getControllerType()) {
|
||||
case VehicleConfigurationSource::CONTROLLER_CC:
|
||||
case VehicleConfigurationSource::CONTROLLER_CC3D:
|
||||
if (dataObj->getName() == "EKFConfiguration") {
|
||||
return false;
|
||||
}
|
||||
default:
|
||||
return true;
|
||||
}
|
||||
}
|
||||
|
||||
void VehicleConfigurationHelper::addModifiedObject(UAVDataObject *object, QString description)
|
||||
{
|
||||
@ -129,6 +136,39 @@ void VehicleConfigurationHelper::applyHardwareConfiguration()
|
||||
data.OptionalModules[HwSettings::OPTIONALMODULES_AIRSPEED] = 0;
|
||||
|
||||
switch (m_configSource->getControllerType()) {
|
||||
case VehicleConfigurationSource::CONTROLLER_CC:
|
||||
case VehicleConfigurationSource::CONTROLLER_CC3D:
|
||||
// Reset all ports
|
||||
data.CC_RcvrPort = HwSettings::CC_RCVRPORT_DISABLEDONESHOT;
|
||||
|
||||
// Default mainport to be active telemetry link
|
||||
data.CC_MainPort = HwSettings::CC_MAINPORT_TELEMETRY;
|
||||
|
||||
data.CC_FlexiPort = HwSettings::CC_FLEXIPORT_DISABLED;
|
||||
switch (m_configSource->getInputType()) {
|
||||
case VehicleConfigurationSource::INPUT_PWM:
|
||||
data.CC_RcvrPort = HwSettings::CC_RCVRPORT_PWMNOONESHOT;
|
||||
break;
|
||||
case VehicleConfigurationSource::INPUT_PPM:
|
||||
if (m_configSource->getEscType() == VehicleConfigurationSource::ESC_ONESHOT ||
|
||||
m_configSource->getEscType() == VehicleConfigurationSource::ESC_SYNCHED) {
|
||||
data.CC_RcvrPort = HwSettings::CC_RCVRPORT_PPM_PIN8ONESHOT;
|
||||
} else {
|
||||
data.CC_RcvrPort = HwSettings::CC_RCVRPORT_PPMNOONESHOT;
|
||||
}
|
||||
break;
|
||||
case VehicleConfigurationSource::INPUT_SBUS:
|
||||
// We have to set teletry on flexport since s.bus needs the mainport.
|
||||
data.CC_MainPort = HwSettings::CC_MAINPORT_SBUS;
|
||||
data.CC_FlexiPort = HwSettings::CC_FLEXIPORT_TELEMETRY;
|
||||
break;
|
||||
case VehicleConfigurationSource::INPUT_DSM:
|
||||
data.CC_FlexiPort = HwSettings::CC_FLEXIPORT_DSM;
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
break;
|
||||
case VehicleConfigurationSource::CONTROLLER_REVO:
|
||||
case VehicleConfigurationSource::CONTROLLER_NANO:
|
||||
case VehicleConfigurationSource::CONTROLLER_DISCOVERYF4:
|
||||
@ -597,6 +637,20 @@ void VehicleConfigurationHelper::applySensorBiasConfiguration()
|
||||
addModifiedObject(accelGyroSettings, tr("Writing gyro and accelerometer bias settings"));
|
||||
|
||||
switch (m_configSource->getControllerType()) {
|
||||
case VehicleConfigurationSource::CONTROLLER_CC:
|
||||
case VehicleConfigurationSource::CONTROLLER_CC3D:
|
||||
{
|
||||
AttitudeSettings *copterControlCalibration = AttitudeSettings::GetInstance(m_uavoManager);
|
||||
Q_ASSERT(copterControlCalibration);
|
||||
AttitudeSettings::DataFields data = copterControlCalibration->getData();
|
||||
|
||||
data.AccelTau = DEFAULT_ENABLED_ACCEL_TAU;
|
||||
data.BiasCorrectGyro = AttitudeSettings::BIASCORRECTGYRO_TRUE;
|
||||
|
||||
copterControlCalibration->setData(data);
|
||||
addModifiedObject(copterControlCalibration, tr("Writing board settings"));
|
||||
break;
|
||||
}
|
||||
case VehicleConfigurationSource::CONTROLLER_REVO:
|
||||
case VehicleConfigurationSource::CONTROLLER_NANO:
|
||||
{
|
||||
|
@ -57,7 +57,7 @@ class VehicleConfigurationSource {
|
||||
public:
|
||||
VehicleConfigurationSource();
|
||||
|
||||
enum CONTROLLER_TYPE { CONTROLLER_UNKNOWN, CONTROLLER_REVO, CONTROLLER_NANO, CONTROLLER_OPLINK, CONTROLLER_DISCOVERYF4 };
|
||||
enum CONTROLLER_TYPE { CONTROLLER_UNKNOWN, CONTROLLER_CC, CONTROLLER_CC3D, CONTROLLER_REVO, CONTROLLER_NANO, CONTROLLER_OPLINK, CONTROLLER_DISCOVERYF4 };
|
||||
enum VEHICLE_TYPE { VEHICLE_UNKNOWN, VEHICLE_MULTI, VEHICLE_FIXEDWING, VEHICLE_HELI, VEHICLE_SURFACE };
|
||||
enum VEHICLE_SUB_TYPE { MULTI_ROTOR_UNKNOWN, MULTI_ROTOR_TRI_Y, MULTI_ROTOR_QUAD_X, MULTI_ROTOR_QUAD_PLUS, MULTI_ROTOR_QUAD_H,
|
||||
MULTI_ROTOR_HEXA, MULTI_ROTOR_HEXA_H, MULTI_ROTOR_HEXA_X, MULTI_ROTOR_HEXA_COAX_Y, MULTI_ROTOR_OCTO,
|
||||
|
@ -14,18 +14,43 @@ public:
|
||||
static QString idToBoardName(int id)
|
||||
{
|
||||
switch (id) {
|
||||
case 0x0101:
|
||||
// MB
|
||||
return QString("OpenPilot MainBoard");
|
||||
|
||||
break;
|
||||
case 0x0201:
|
||||
// INS
|
||||
return QString("OpenPilot INS");
|
||||
|
||||
break;
|
||||
case 0x0301:
|
||||
// OPLink Mini
|
||||
return QString("OPLink");
|
||||
|
||||
break;
|
||||
case 0x0401:
|
||||
// Coptercontrol
|
||||
return QString("CopterControl");
|
||||
|
||||
break;
|
||||
case 0x0402:
|
||||
// Coptercontrol 3D
|
||||
// It would be nice to say CC3D here but since currently we use string comparisons
|
||||
// for firmware compatibility and the filename path that would break
|
||||
return QString("CopterControl");
|
||||
|
||||
break;
|
||||
case 0x0901:
|
||||
// Revolution
|
||||
return QString("Revolution");
|
||||
|
||||
break;
|
||||
case 0x0903:
|
||||
// Revo Mini
|
||||
return QString("Revolution");
|
||||
|
||||
break;
|
||||
case 0x0904:
|
||||
return QString("DiscoveryF4");
|
||||
|
||||
@ -36,6 +61,8 @@ public:
|
||||
|
||||
default:
|
||||
return QString("");
|
||||
|
||||
break;
|
||||
}
|
||||
}
|
||||
deviceDescriptorStruct() {}
|
||||
|
@ -78,11 +78,6 @@ void DeviceWidget::populate()
|
||||
{
|
||||
int id = m_dfu->devices[deviceID].ID;
|
||||
|
||||
// Exclude CC/CC3D
|
||||
if ((id == 0x0401) || (id == 0x0402)) {
|
||||
return;
|
||||
}
|
||||
|
||||
myDevice->lbldevID->setText(tr("Device ID: ") + QString::number(id, 16));
|
||||
// DeviceID tells us what sort of HW we have detected:
|
||||
// display a nice icon:
|
||||
@ -91,10 +86,22 @@ void DeviceWidget::populate()
|
||||
myDevice->lblHWRev->setText(tr("HW Revision: ") + QString::number(id & 0x00FF, 16));
|
||||
|
||||
switch (id) {
|
||||
case 0x0101:
|
||||
case 0x0201:
|
||||
devicePic.load("");
|
||||
break;
|
||||
case 0x0301:
|
||||
devicePic.load(":/uploader/images/gcs-board-oplink.png");
|
||||
break;
|
||||
case 0x0401:
|
||||
devicePic.load(":/uploader/images/gcs-board-cc.png");
|
||||
break;
|
||||
case 0x0402:
|
||||
devicePic.load(":/uploader/images/gcs-board-cc3d.png");
|
||||
break;
|
||||
case 0x0903:
|
||||
devicePic.load(":/uploader/images/gcs-board-revo.png");
|
||||
break;
|
||||
case 0x0904:
|
||||
devicePic.load(":/uploader/images/gcs-board-revo.png");
|
||||
break;
|
||||
@ -357,7 +364,8 @@ void DeviceWidget::uploadFirmware()
|
||||
// - Check whether board type matches firmware:
|
||||
int board = m_dfu->devices[deviceID].ID;
|
||||
int firmwareBoard = ((desc.at(12) & 0xff) << 8) + (desc.at(13) & 0xff);
|
||||
if ((board == 0x901 && firmwareBoard == 0x902) || // L3GD20 revo supports Revolution firmware
|
||||
if ((board == 0x401 && firmwareBoard == 0x402) ||
|
||||
(board == 0x901 && firmwareBoard == 0x902) || // L3GD20 revo supports Revolution firmware
|
||||
(board == 0x902 && firmwareBoard == 0x903)) { // RevoMini1 supporetd by RevoMini2 firmware
|
||||
// These firmwares are designed to be backwards compatible
|
||||
} else if (firmwareBoard != board) {
|
||||
|
2466
ground/openpilotgcs/src/plugins/uploader/images/deviceID-0101.svg
Normal file
@ -0,0 +1,2466 @@
|
||||
<?xml version="1.0" encoding="UTF-8" standalone="no"?>
|
||||
<!-- Created with Inkscape (http://www.inkscape.org/) -->
|
||||
|
||||
<svg
|
||||
xmlns:dc="http://purl.org/dc/elements/1.1/"
|
||||
xmlns:cc="http://creativecommons.org/ns#"
|
||||
xmlns:rdf="http://www.w3.org/1999/02/22-rdf-syntax-ns#"
|
||||
xmlns:svg="http://www.w3.org/2000/svg"
|
||||
xmlns="http://www.w3.org/2000/svg"
|
||||
xmlns:sodipodi="http://sodipodi.sourceforge.net/DTD/sodipodi-0.dtd"
|
||||
xmlns:inkscape="http://www.inkscape.org/namespaces/inkscape"
|
||||
width="381.84375"
|
||||
height="236.375"
|
||||
id="svg2"
|
||||
version="1.1"
|
||||
inkscape:version="0.48.0 r9654"
|
||||
sodipodi:docname="deviceID-1.svg"
|
||||
style="display:inline">
|
||||
<defs
|
||||
id="defs4" />
|
||||
<sodipodi:namedview
|
||||
id="base"
|
||||
pagecolor="#ffffff"
|
||||
bordercolor="#666666"
|
||||
borderopacity="1.0"
|
||||
inkscape:pageopacity="0.0"
|
||||
inkscape:pageshadow="2"
|
||||
inkscape:zoom="1.4"
|
||||
inkscape:cx="116.34582"
|
||||
inkscape:cy="151.29577"
|
||||
inkscape:document-units="px"
|
||||
inkscape:current-layer="layer3"
|
||||
showgrid="false"
|
||||
inkscape:window-width="1366"
|
||||
inkscape:window-height="691"
|
||||
inkscape:window-x="0"
|
||||
inkscape:window-y="24"
|
||||
inkscape:window-maximized="1"
|
||||
fit-margin-top="0"
|
||||
fit-margin-left="0"
|
||||
fit-margin-right="0"
|
||||
fit-margin-bottom="0" />
|
||||
<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 />
|
||||
</cc:Work>
|
||||
</rdf:RDF>
|
||||
</metadata>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="layer3"
|
||||
inkscape:label="Mb pcb"
|
||||
style="display:inline"
|
||||
transform="translate(-195.96875,-338.1875)">
|
||||
<g
|
||||
id="device"
|
||||
inkscape:label="#g4184">
|
||||
<rect
|
||||
ry="10"
|
||||
y="348.28586"
|
||||
x="196.97975"
|
||||
height="225.26402"
|
||||
width="374.76657"
|
||||
id="rect2997"
|
||||
style="fill:#171717;fill-opacity:1;stroke:#000000;stroke-width:2;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
<rect
|
||||
y="339.19449"
|
||||
x="451.53818"
|
||||
height="26.263966"
|
||||
width="95.964493"
|
||||
id="rect3767"
|
||||
style="fill:#c89252;fill-opacity:1;stroke:#efc088;stroke-width:2;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
<rect
|
||||
y="377.58029"
|
||||
x="553.5636"
|
||||
height="93.944183"
|
||||
width="22.223356"
|
||||
id="rect3769"
|
||||
style="fill:#c89252;fill-opacity:1;stroke:#efc088;stroke-width:2;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
<rect
|
||||
y="489.70721"
|
||||
x="553.5636"
|
||||
height="78.791901"
|
||||
width="23.233509"
|
||||
id="rect3771"
|
||||
style="fill:#c89252;fill-opacity:1;stroke:#efc088;stroke-width:2;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
<rect
|
||||
ry="2.5"
|
||||
y="395.57648"
|
||||
x="415.71429"
|
||||
height="76.785713"
|
||||
width="76.428574"
|
||||
id="rect3773"
|
||||
style="fill:#6a6a6a;fill-opacity:1;stroke:#000000;stroke-width:2;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
<g
|
||||
id="g3875"
|
||||
style="display:inline">
|
||||
<g
|
||||
id="g3781"
|
||||
transform="matrix(1.4970318,0,0,1,-211.28069,0.21205357)">
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3777"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
<path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3779"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
</g>
|
||||
<g
|
||||
transform="matrix(1.4970318,0,0,1,-207.28069,0.21205357)"
|
||||
id="g3785">
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path3787"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path3789"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" />
|
||||
</g>
|
||||
<g
|
||||
id="g3791"
|
||||
transform="matrix(1.4970318,0,0,1,-203.28069,0.21205357)">
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3793"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
<path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3795"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
</g>
|
||||
<g
|
||||
transform="matrix(1.4970318,0,0,1,-199.28069,0.21205357)"
|
||||
id="g3797">
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path3799"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path3801"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" />
|
||||
</g>
|
||||
<g
|
||||
id="g3803"
|
||||
transform="matrix(1.4970318,0,0,1,-195.28069,0.21205357)">
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3805"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
<path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3807"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
</g>
|
||||
<g
|
||||
transform="matrix(1.4970318,0,0,1,-191.28069,0.21205357)"
|
||||
id="g3809">
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path3811"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path3813"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" />
|
||||
</g>
|
||||
<g
|
||||
id="g3815"
|
||||
transform="matrix(1.4970318,0,0,1,-187.28069,0.21205357)">
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3817"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
<path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3819"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
</g>
|
||||
<g
|
||||
transform="matrix(1.4970318,0,0,1,-183.28069,0.21205357)"
|
||||
id="g3821">
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path3823"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path3825"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" />
|
||||
</g>
|
||||
<g
|
||||
id="g3827"
|
||||
transform="matrix(1.4970318,0,0,1,-179.28069,0.21205357)">
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3829"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
<path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3831"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
</g>
|
||||
<g
|
||||
transform="matrix(1.4970318,0,0,1,-175.28069,0.21205357)"
|
||||
id="g3833">
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path3835"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path3837"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" />
|
||||
</g>
|
||||
<g
|
||||
id="g3839"
|
||||
transform="matrix(1.4970318,0,0,1,-171.28069,0.21205357)">
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3841"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
<path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3843"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
</g>
|
||||
<g
|
||||
transform="matrix(1.4970318,0,0,1,-167.28069,0.21205357)"
|
||||
id="g3845">
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path3847"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path3849"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" />
|
||||
</g>
|
||||
<g
|
||||
id="g3851"
|
||||
transform="matrix(1.4970318,0,0,1,-163.28069,0.21205357)">
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3853"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
<path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3855"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
</g>
|
||||
<g
|
||||
transform="matrix(1.4970318,0,0,1,-159.28069,0.21205357)"
|
||||
id="g3857">
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path3859"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path3861"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" />
|
||||
</g>
|
||||
<g
|
||||
id="g3863"
|
||||
transform="matrix(1.4970318,0,0,1,-155.28069,0.21205357)">
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3865"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
<path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3867"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
</g>
|
||||
<g
|
||||
transform="matrix(1.4970318,0,0,1,-151.28069,0.21205357)"
|
||||
id="g3869">
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path3871"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path3873"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" />
|
||||
</g>
|
||||
</g>
|
||||
<g
|
||||
transform="matrix(0,1,-1,0,887.93406,-17.85058)"
|
||||
id="g3925"
|
||||
style="display:inline">
|
||||
<g
|
||||
transform="matrix(1.4970318,0,0,1,-211.28069,0.21205357)"
|
||||
id="g3927">
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path3929"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path3931"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" />
|
||||
</g>
|
||||
<g
|
||||
id="g3933"
|
||||
transform="matrix(1.4970318,0,0,1,-207.28069,0.21205357)">
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3935"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
<path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3937"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
</g>
|
||||
<g
|
||||
transform="matrix(1.4970318,0,0,1,-203.28069,0.21205357)"
|
||||
id="g3939">
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path3941"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path3943"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" />
|
||||
</g>
|
||||
<g
|
||||
id="g3945"
|
||||
transform="matrix(1.4970318,0,0,1,-199.28069,0.21205357)">
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3947"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
<path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3949"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
</g>
|
||||
<g
|
||||
transform="matrix(1.4970318,0,0,1,-195.28069,0.21205357)"
|
||||
id="g3951">
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path3953"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path3955"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" />
|
||||
</g>
|
||||
<g
|
||||
id="g3957"
|
||||
transform="matrix(1.4970318,0,0,1,-191.28069,0.21205357)">
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3959"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
<path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3961"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
</g>
|
||||
<g
|
||||
transform="matrix(1.4970318,0,0,1,-187.28069,0.21205357)"
|
||||
id="g3963">
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path3965"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path3967"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" />
|
||||
</g>
|
||||
<g
|
||||
id="g3969"
|
||||
transform="matrix(1.4970318,0,0,1,-183.28069,0.21205357)">
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3971"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
<path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3973"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
</g>
|
||||
<g
|
||||
transform="matrix(1.4970318,0,0,1,-179.28069,0.21205357)"
|
||||
id="g3975">
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path3977"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path3979"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" />
|
||||
</g>
|
||||
<g
|
||||
id="g3981"
|
||||
transform="matrix(1.4970318,0,0,1,-175.28069,0.21205357)">
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3983"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
<path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3985"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
</g>
|
||||
<g
|
||||
transform="matrix(1.4970318,0,0,1,-171.28069,0.21205357)"
|
||||
id="g3987">
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path3989"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path3991"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" />
|
||||
</g>
|
||||
<g
|
||||
id="g3993"
|
||||
transform="matrix(1.4970318,0,0,1,-167.28069,0.21205357)">
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3995"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
<path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3997"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
</g>
|
||||
<g
|
||||
transform="matrix(1.4970318,0,0,1,-163.28069,0.21205357)"
|
||||
id="g3999">
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path4001"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path4003"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" />
|
||||
</g>
|
||||
<g
|
||||
id="g4005"
|
||||
transform="matrix(1.4970318,0,0,1,-159.28069,0.21205357)">
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4007"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
<path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4009"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
</g>
|
||||
<g
|
||||
transform="matrix(1.4970318,0,0,1,-155.28069,0.21205357)"
|
||||
id="g4011">
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path4013"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path4015"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" />
|
||||
</g>
|
||||
<g
|
||||
id="g4017"
|
||||
transform="matrix(1.4970318,0,0,1,-151.28069,0.21205357)">
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4019"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
<path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4021"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
</g>
|
||||
</g>
|
||||
<g
|
||||
id="g4023"
|
||||
transform="matrix(0,1,1,0,19.97685,-17.85058)"
|
||||
style="display:inline">
|
||||
<g
|
||||
id="g4025"
|
||||
transform="matrix(1.4970318,0,0,1,-211.28069,0.21205357)">
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4027"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
<path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4029"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
</g>
|
||||
<g
|
||||
transform="matrix(1.4970318,0,0,1,-207.28069,0.21205357)"
|
||||
id="g4031">
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path4033"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path4035"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" />
|
||||
</g>
|
||||
<g
|
||||
id="g4037"
|
||||
transform="matrix(1.4970318,0,0,1,-203.28069,0.21205357)">
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4039"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
<path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4041"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
</g>
|
||||
<g
|
||||
transform="matrix(1.4970318,0,0,1,-199.28069,0.21205357)"
|
||||
id="g4043">
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path4045"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path4047"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" />
|
||||
</g>
|
||||
<g
|
||||
id="g4049"
|
||||
transform="matrix(1.4970318,0,0,1,-195.28069,0.21205357)">
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4051"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
<path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4053"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
</g>
|
||||
<g
|
||||
transform="matrix(1.4970318,0,0,1,-191.28069,0.21205357)"
|
||||
id="g4055">
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path4057"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path4059"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" />
|
||||
</g>
|
||||
<g
|
||||
id="g4061"
|
||||
transform="matrix(1.4970318,0,0,1,-187.28069,0.21205357)">
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4063"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
<path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4065"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
</g>
|
||||
<g
|
||||
transform="matrix(1.4970318,0,0,1,-183.28069,0.21205357)"
|
||||
id="g4067">
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path4069"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path4071"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" />
|
||||
</g>
|
||||
<g
|
||||
id="g4073"
|
||||
transform="matrix(1.4970318,0,0,1,-179.28069,0.21205357)">
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4075"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
<path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4077"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
</g>
|
||||
<g
|
||||
transform="matrix(1.4970318,0,0,1,-175.28069,0.21205357)"
|
||||
id="g4079">
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path4081"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path4083"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" />
|
||||
</g>
|
||||
<g
|
||||
id="g4085"
|
||||
transform="matrix(1.4970318,0,0,1,-171.28069,0.21205357)">
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4087"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
<path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4089"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
</g>
|
||||
<g
|
||||
transform="matrix(1.4970318,0,0,1,-167.28069,0.21205357)"
|
||||
id="g4091">
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path4093"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path4095"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" />
|
||||
</g>
|
||||
<g
|
||||
id="g4097"
|
||||
transform="matrix(1.4970318,0,0,1,-163.28069,0.21205357)">
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4099"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
<path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4101"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
</g>
|
||||
<g
|
||||
transform="matrix(1.4970318,0,0,1,-159.28069,0.21205357)"
|
||||
id="g4103">
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path4105"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path4107"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" />
|
||||
</g>
|
||||
<g
|
||||
id="g4109"
|
||||
transform="matrix(1.4970318,0,0,1,-155.28069,0.21205357)">
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4111"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
<path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4113"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
</g>
|
||||
<g
|
||||
transform="matrix(1.4970318,0,0,1,-151.28069,0.21205357)"
|
||||
id="g4115">
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path4117"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path4119"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" />
|
||||
</g>
|
||||
</g>
|
||||
<g
|
||||
transform="matrix(1,0,0,-1,0,867.2199)"
|
||||
id="g4121"
|
||||
style="display:inline">
|
||||
<g
|
||||
transform="matrix(1.4970318,0,0,1,-211.28069,0.21205357)"
|
||||
id="g4123">
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path4125"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path4127"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" />
|
||||
</g>
|
||||
<g
|
||||
id="g4129"
|
||||
transform="matrix(1.4970318,0,0,1,-207.28069,0.21205357)">
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4131"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
<path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4133"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
</g>
|
||||
<g
|
||||
transform="matrix(1.4970318,0,0,1,-203.28069,0.21205357)"
|
||||
id="g4135">
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path4137"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path4139"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" />
|
||||
</g>
|
||||
<g
|
||||
id="g4141"
|
||||
transform="matrix(1.4970318,0,0,1,-199.28069,0.21205357)">
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4143"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
<path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4145"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
</g>
|
||||
<g
|
||||
transform="matrix(1.4970318,0,0,1,-195.28069,0.21205357)"
|
||||
id="g4147">
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path4149"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path4151"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" />
|
||||
</g>
|
||||
<g
|
||||
id="g4153"
|
||||
transform="matrix(1.4970318,0,0,1,-191.28069,0.21205357)">
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4155"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
<path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4157"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
</g>
|
||||
<g
|
||||
transform="matrix(1.4970318,0,0,1,-187.28069,0.21205357)"
|
||||
id="g4159">
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path4161"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path4163"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" />
|
||||
</g>
|
||||
<g
|
||||
id="g4165"
|
||||
transform="matrix(1.4970318,0,0,1,-183.28069,0.21205357)">
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4167"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
<path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4169"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
</g>
|
||||
<g
|
||||
transform="matrix(1.4970318,0,0,1,-179.28069,0.21205357)"
|
||||
id="g4171">
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path4173"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path4175"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" />
|
||||
</g>
|
||||
<g
|
||||
id="g4177"
|
||||
transform="matrix(1.4970318,0,0,1,-175.28069,0.21205357)">
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4179"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
<path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4181"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
</g>
|
||||
<g
|
||||
transform="matrix(1.4970318,0,0,1,-171.28069,0.21205357)"
|
||||
id="g4183">
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path4185"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path4187"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" />
|
||||
</g>
|
||||
<g
|
||||
id="g4189"
|
||||
transform="matrix(1.4970318,0,0,1,-167.28069,0.21205357)">
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4191"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
<path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4193"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
</g>
|
||||
<g
|
||||
transform="matrix(1.4970318,0,0,1,-163.28069,0.21205357)"
|
||||
id="g4195">
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path4197"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path4199"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" />
|
||||
</g>
|
||||
<g
|
||||
id="g4201"
|
||||
transform="matrix(1.4970318,0,0,1,-159.28069,0.21205357)">
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4203"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
<path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4205"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
</g>
|
||||
<g
|
||||
transform="matrix(1.4970318,0,0,1,-155.28069,0.21205357)"
|
||||
id="g4207">
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path4209"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path4211"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" />
|
||||
</g>
|
||||
<g
|
||||
id="g4213"
|
||||
transform="matrix(1.4970318,0,0,1,-151.28069,0.21205357)">
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4215"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
<path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4217"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
</g>
|
||||
</g>
|
||||
<g
|
||||
id="g4225"
|
||||
style="display:inline">
|
||||
<rect
|
||||
style="fill:#bc781e;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect4219"
|
||||
width="6.5178571"
|
||||
height="5.0892859"
|
||||
x="422.11606"
|
||||
y="365.75504" />
|
||||
<rect
|
||||
y="365.75504"
|
||||
x="428.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect4221"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
<rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect4223"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="418.58929"
|
||||
y="365.75504" />
|
||||
</g>
|
||||
<g
|
||||
transform="translate(84,24)"
|
||||
id="g4230"
|
||||
style="display:inline">
|
||||
<rect
|
||||
y="365.75504"
|
||||
x="422.11606"
|
||||
height="5.0892859"
|
||||
width="6.5178571"
|
||||
id="rect4232"
|
||||
style="fill:#bc781e;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
<rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect4234"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="428.58929"
|
||||
y="365.75504" />
|
||||
<rect
|
||||
y="365.75504"
|
||||
x="418.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect4236"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
</g>
|
||||
<g
|
||||
id="g4238"
|
||||
transform="translate(54,142)"
|
||||
style="display:inline">
|
||||
<rect
|
||||
style="fill:#bc781e;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect4240"
|
||||
width="6.5178571"
|
||||
height="5.0892859"
|
||||
x="422.11606"
|
||||
y="365.75504" />
|
||||
<rect
|
||||
y="365.75504"
|
||||
x="428.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect4242"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
<rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect4244"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="418.58929"
|
||||
y="365.75504" />
|
||||
</g>
|
||||
<g
|
||||
transform="translate(-10,136)"
|
||||
id="g4246"
|
||||
style="display:inline">
|
||||
<rect
|
||||
y="365.75504"
|
||||
x="422.11606"
|
||||
height="5.0892859"
|
||||
width="6.5178571"
|
||||
id="rect4248"
|
||||
style="fill:#bc781e;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
<rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect4250"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="428.58929"
|
||||
y="365.75504" />
|
||||
<rect
|
||||
y="365.75504"
|
||||
x="418.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect4252"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
</g>
|
||||
<g
|
||||
id="g4254"
|
||||
transform="translate(-184,192)"
|
||||
style="display:inline">
|
||||
<rect
|
||||
style="fill:#bc781e;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect4256"
|
||||
width="6.5178571"
|
||||
height="5.0892859"
|
||||
x="422.11606"
|
||||
y="365.75504" />
|
||||
<rect
|
||||
y="365.75504"
|
||||
x="428.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect4258"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
<rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect4260"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="418.58929"
|
||||
y="365.75504" />
|
||||
</g>
|
||||
<g
|
||||
transform="translate(-210,192)"
|
||||
id="g4262"
|
||||
style="display:inline">
|
||||
<rect
|
||||
y="365.75504"
|
||||
x="422.11606"
|
||||
height="5.0892859"
|
||||
width="6.5178571"
|
||||
id="rect4264"
|
||||
style="fill:#bc781e;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
<rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect4266"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="428.58929"
|
||||
y="365.75504" />
|
||||
<rect
|
||||
y="365.75504"
|
||||
x="418.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect4268"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
</g>
|
||||
<g
|
||||
id="g4270"
|
||||
transform="translate(-54,62)"
|
||||
style="display:inline">
|
||||
<rect
|
||||
style="fill:#bc781e;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect4272"
|
||||
width="6.5178571"
|
||||
height="5.0892859"
|
||||
x="422.11606"
|
||||
y="365.75504" />
|
||||
<rect
|
||||
y="365.75504"
|
||||
x="428.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect4274"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
<rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect4276"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="418.58929"
|
||||
y="365.75504" />
|
||||
</g>
|
||||
<g
|
||||
transform="matrix(0,1,-1,0,687.67469,10.92467)"
|
||||
id="g4278"
|
||||
style="display:inline">
|
||||
<rect
|
||||
y="365.75504"
|
||||
x="422.11606"
|
||||
height="5.0892859"
|
||||
width="6.5178571"
|
||||
id="rect4280"
|
||||
style="fill:#bc781e;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
<rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect4282"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="428.58929"
|
||||
y="365.75504" />
|
||||
<rect
|
||||
y="365.75504"
|
||||
x="418.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect4284"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
</g>
|
||||
<g
|
||||
id="g4286"
|
||||
transform="matrix(0,1,-1,0,763.67469,32.92467)"
|
||||
style="display:inline">
|
||||
<rect
|
||||
style="fill:#bc781e;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect4288"
|
||||
width="6.5178571"
|
||||
height="5.0892859"
|
||||
x="422.11606"
|
||||
y="365.75504" />
|
||||
<rect
|
||||
y="365.75504"
|
||||
x="428.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect4290"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
<rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect4292"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="418.58929"
|
||||
y="365.75504" />
|
||||
</g>
|
||||
<g
|
||||
transform="matrix(0,1,-1,0,881.67469,32.92467)"
|
||||
id="g4294"
|
||||
style="display:inline">
|
||||
<rect
|
||||
y="365.75504"
|
||||
x="422.11606"
|
||||
height="5.0892859"
|
||||
width="6.5178571"
|
||||
id="rect4296"
|
||||
style="fill:#bc781e;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
<rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect4298"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="428.58929"
|
||||
y="365.75504" />
|
||||
<rect
|
||||
y="365.75504"
|
||||
x="418.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect4300"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
</g>
|
||||
<g
|
||||
id="g4302"
|
||||
transform="matrix(0,1,-1,0,843.67469,108.92467)"
|
||||
style="display:inline">
|
||||
<rect
|
||||
style="fill:#bc781e;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect4304"
|
||||
width="6.5178571"
|
||||
height="5.0892859"
|
||||
x="422.11606"
|
||||
y="365.75504" />
|
||||
<rect
|
||||
y="365.75504"
|
||||
x="428.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect4306"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
<rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect4308"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="418.58929"
|
||||
y="365.75504" />
|
||||
</g>
|
||||
<g
|
||||
transform="translate(-50,-12)"
|
||||
id="g4318"
|
||||
style="display:inline">
|
||||
<rect
|
||||
y="365.75504"
|
||||
x="422.11606"
|
||||
height="5.0892859"
|
||||
width="6.5178571"
|
||||
id="rect4320"
|
||||
style="fill:#312d29;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
<rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect4322"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="428.58929"
|
||||
y="365.75504" />
|
||||
<rect
|
||||
y="365.75504"
|
||||
x="418.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect4324"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
</g>
|
||||
<g
|
||||
id="g4326"
|
||||
transform="translate(-122,98)"
|
||||
style="display:inline">
|
||||
<rect
|
||||
style="fill:#312d29;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect4328"
|
||||
width="6.5178571"
|
||||
height="5.0892859"
|
||||
x="422.11606"
|
||||
y="365.75504" />
|
||||
<rect
|
||||
y="365.75504"
|
||||
x="428.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect4330"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
<rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect4332"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="418.58929"
|
||||
y="365.75504" />
|
||||
</g>
|
||||
<g
|
||||
transform="translate(-120,114)"
|
||||
id="g4334"
|
||||
style="display:inline">
|
||||
<rect
|
||||
y="365.75504"
|
||||
x="422.11606"
|
||||
height="5.0892859"
|
||||
width="6.5178571"
|
||||
id="rect4336"
|
||||
style="fill:#312d29;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
<rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect4338"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="428.58929"
|
||||
y="365.75504" />
|
||||
<rect
|
||||
y="365.75504"
|
||||
x="418.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect4340"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
</g>
|
||||
<g
|
||||
id="g4342"
|
||||
transform="translate(-94,114)"
|
||||
style="display:inline">
|
||||
<rect
|
||||
style="fill:#312d29;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect4344"
|
||||
width="6.5178571"
|
||||
height="5.0892859"
|
||||
x="422.11606"
|
||||
y="365.75504" />
|
||||
<rect
|
||||
y="365.75504"
|
||||
x="428.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect4346"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
<rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect4348"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="418.58929"
|
||||
y="365.75504" />
|
||||
</g>
|
||||
<g
|
||||
transform="translate(-42,124)"
|
||||
id="g4350"
|
||||
style="display:inline">
|
||||
<rect
|
||||
y="365.75504"
|
||||
x="422.11606"
|
||||
height="5.0892859"
|
||||
width="6.5178571"
|
||||
id="rect4352"
|
||||
style="fill:#312d29;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
<rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect4354"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="428.58929"
|
||||
y="365.75504" />
|
||||
<rect
|
||||
y="365.75504"
|
||||
x="418.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect4356"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
</g>
|
||||
<g
|
||||
id="g4358"
|
||||
transform="translate(16,140)"
|
||||
style="display:inline">
|
||||
<rect
|
||||
style="fill:#312d29;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect4360"
|
||||
width="6.5178571"
|
||||
height="5.0892859"
|
||||
x="422.11606"
|
||||
y="365.75504" />
|
||||
<rect
|
||||
y="365.75504"
|
||||
x="428.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect4362"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
<rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect4364"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="418.58929"
|
||||
y="365.75504" />
|
||||
</g>
|
||||
<g
|
||||
transform="translate(74,194)"
|
||||
id="g4366"
|
||||
style="display:inline">
|
||||
<rect
|
||||
y="365.75504"
|
||||
x="422.11606"
|
||||
height="5.0892859"
|
||||
width="6.5178571"
|
||||
id="rect4368"
|
||||
style="fill:#312d29;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
<rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect4370"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="428.58929"
|
||||
y="365.75504" />
|
||||
<rect
|
||||
y="365.75504"
|
||||
x="418.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect4372"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
</g>
|
||||
<g
|
||||
id="g4374"
|
||||
transform="translate(-42,190)"
|
||||
style="display:inline">
|
||||
<rect
|
||||
style="fill:#312d29;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect4376"
|
||||
width="6.5178571"
|
||||
height="5.0892859"
|
||||
x="422.11606"
|
||||
y="365.75504" />
|
||||
<rect
|
||||
y="365.75504"
|
||||
x="428.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect4378"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
<rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect4380"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="418.58929"
|
||||
y="365.75504" />
|
||||
</g>
|
||||
<g
|
||||
transform="translate(-42,174)"
|
||||
id="g4382"
|
||||
style="display:inline">
|
||||
<rect
|
||||
y="365.75504"
|
||||
x="422.11606"
|
||||
height="5.0892859"
|
||||
width="6.5178571"
|
||||
id="rect4384"
|
||||
style="fill:#312d29;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
<rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect4386"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="428.58929"
|
||||
y="365.75504" />
|
||||
<rect
|
||||
y="365.75504"
|
||||
x="418.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect4388"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
</g>
|
||||
<g
|
||||
transform="translate(-158,158)"
|
||||
id="g4390"
|
||||
style="display:inline">
|
||||
<rect
|
||||
y="365.75504"
|
||||
x="422.11606"
|
||||
height="5.0892859"
|
||||
width="6.5178571"
|
||||
id="rect4392"
|
||||
style="fill:#312d29;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
<rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect4394"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="428.58929"
|
||||
y="365.75504" />
|
||||
<rect
|
||||
y="365.75504"
|
||||
x="418.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect4396"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
</g>
|
||||
<g
|
||||
id="g4398"
|
||||
transform="matrix(0,-1,1,0,1.07533,879.67469)"
|
||||
style="display:inline">
|
||||
<rect
|
||||
style="fill:#312d29;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect4400"
|
||||
width="6.5178571"
|
||||
height="5.0892859"
|
||||
x="422.11606"
|
||||
y="365.75504" />
|
||||
<rect
|
||||
y="365.75504"
|
||||
x="428.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect4402"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
<rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect4404"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="418.58929"
|
||||
y="365.75504" />
|
||||
</g>
|
||||
<g
|
||||
transform="matrix(0,-1,1,0,-30.92467,823.67469)"
|
||||
id="g4406"
|
||||
style="display:inline">
|
||||
<rect
|
||||
y="365.75504"
|
||||
x="422.11606"
|
||||
height="5.0892859"
|
||||
width="6.5178571"
|
||||
id="rect4408"
|
||||
style="fill:#312d29;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
<rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect4410"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="428.58929"
|
||||
y="365.75504" />
|
||||
<rect
|
||||
y="365.75504"
|
||||
x="418.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect4412"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
</g>
|
||||
<g
|
||||
id="g4414"
|
||||
transform="translate(-22,-12)"
|
||||
style="display:inline">
|
||||
<rect
|
||||
style="fill:#0052ff;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect4416"
|
||||
width="6.5178571"
|
||||
height="5.0892859"
|
||||
x="422.11606"
|
||||
y="365.75504" />
|
||||
<rect
|
||||
y="365.75504"
|
||||
x="428.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect4418"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
<rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect4420"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="418.58929"
|
||||
y="365.75504" />
|
||||
</g>
|
||||
<g
|
||||
transform="translate(-158,176)"
|
||||
id="g4422"
|
||||
style="display:inline">
|
||||
<rect
|
||||
y="365.75504"
|
||||
x="422.11606"
|
||||
height="5.0892859"
|
||||
width="6.5178571"
|
||||
id="rect4424"
|
||||
style="fill:#17c400;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
<rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect4426"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="428.58929"
|
||||
y="365.75504" />
|
||||
<rect
|
||||
y="365.75504"
|
||||
x="418.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect4428"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
</g>
|
||||
<g
|
||||
id="g4430"
|
||||
transform="translate(100,194)"
|
||||
style="display:inline">
|
||||
<rect
|
||||
style="fill:#ff7900;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect4432"
|
||||
width="6.5178571"
|
||||
height="5.0892859"
|
||||
x="422.11606"
|
||||
y="365.75504" />
|
||||
<rect
|
||||
y="365.75504"
|
||||
x="428.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect4434"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
<rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect4436"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="418.58929"
|
||||
y="365.75504" />
|
||||
<rect
|
||||
ry="2"
|
||||
transform="translate(-100,-194)"
|
||||
y="519.38043"
|
||||
x="423.38019"
|
||||
height="22.728426"
|
||||
width="36.11293"
|
||||
id="rect4438"
|
||||
style="fill:#beb6b1;fill-opacity:1;stroke:#ffcd00;stroke-width:1;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
<rect
|
||||
transform="translate(-100,-194)"
|
||||
y="525.44135"
|
||||
x="484.87323"
|
||||
height="14.647212"
|
||||
width="9.4701805"
|
||||
id="rect4440"
|
||||
style="fill:#484848;fill-opacity:1;stroke:#ffcd00;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
<rect
|
||||
style="fill:#9b9797;fill-opacity:1;stroke:#ffcd00;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect4442"
|
||||
width="9.4701805"
|
||||
height="2.2728434"
|
||||
x="384.87323"
|
||||
y="333.44135" />
|
||||
<path
|
||||
transform="translate(-100,-194)"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4446"
|
||||
d="m 292.06036,569.50927 0,-68.05903 6.18718,0 0,-6.43973 46.84582,0 0,6.566 7.32361,0 0,68.5641 z"
|
||||
style="fill:#b5bac0;fill-opacity:1;stroke:#000000;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
<path
|
||||
transform="translate(-100,-194)"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4448"
|
||||
d="m 307.08637,507.51115 30.30458,0"
|
||||
style="fill:none;stroke:#000000;stroke-width:3;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
<g
|
||||
id="g4458">
|
||||
<path
|
||||
style="fill:none;stroke:#000000;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 299.13142,535.29035 0,21.97082"
|
||||
id="path4450"
|
||||
inkscape:connector-curvature="0"
|
||||
transform="translate(-100,-194)" />
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4454"
|
||||
d="m 206.0153,341.29035 0,21.97082"
|
||||
style="fill:none;stroke:#000000;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
<path
|
||||
style="fill:none;stroke:#000000;stroke-width:4;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
d="m 298.63269,559.02893 7.97924,0"
|
||||
id="path4456"
|
||||
inkscape:connector-curvature="0"
|
||||
transform="translate(-100,-194)"
|
||||
sodipodi:nodetypes="cc" />
|
||||
</g>
|
||||
<g
|
||||
transform="translate(38,0)"
|
||||
id="g4463">
|
||||
<path
|
||||
transform="translate(-100,-194)"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4465"
|
||||
d="m 299.13142,535.29035 0,21.97082"
|
||||
style="fill:none;stroke:#000000;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
<path
|
||||
style="fill:none;stroke:#000000;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 206.0153,341.29035 0,21.97082"
|
||||
id="path4467"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
sodipodi:nodetypes="cc"
|
||||
transform="translate(-100,-194)"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4469"
|
||||
d="m 298.63269,559.02893 7.97924,0"
|
||||
style="fill:none;stroke:#000000;stroke-width:4;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
</g>
|
||||
<path
|
||||
sodipodi:nodetypes="cccccc"
|
||||
transform="translate(-100,-194)"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4471"
|
||||
d="m 312.85714,561.29075 0,-30.35714 c -0.63009,-2.35154 1.94091,-4.65364 3.66072,-3.66071 l 10.44643,0 c 1.73884,-1.00392 4.18145,1.50604 3.61607,3.61607 l 0,30.75893"
|
||||
style="fill:none;stroke:#000000;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
<g
|
||||
id="g4479">
|
||||
<path
|
||||
sodipodi:type="arc"
|
||||
style="fill:none;stroke:#f2edda;stroke-width:1.5;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="path4473"
|
||||
sodipodi:cx="225.89285"
|
||||
sodipodi:cy="542.54077"
|
||||
sodipodi:rx="5.1785712"
|
||||
sodipodi:ry="5.1785712"
|
||||
d="m 231.07142,542.54077 c 0,2.86005 -2.31852,5.17857 -5.17857,5.17857 -2.86004,0 -5.17857,-2.31852 -5.17857,-5.17857 0,-2.86004 2.31853,-5.17857 5.17857,-5.17857 2.86005,0 5.17857,2.31853 5.17857,5.17857 z"
|
||||
transform="translate(-100,-194)" />
|
||||
<path
|
||||
transform="translate(-82,-194)"
|
||||
d="m 231.07142,542.54077 c 0,2.86005 -2.31852,5.17857 -5.17857,5.17857 -2.86004,0 -5.17857,-2.31852 -5.17857,-5.17857 0,-2.86004 2.31853,-5.17857 5.17857,-5.17857 2.86005,0 5.17857,2.31853 5.17857,5.17857 z"
|
||||
sodipodi:ry="5.1785712"
|
||||
sodipodi:rx="5.1785712"
|
||||
sodipodi:cy="542.54077"
|
||||
sodipodi:cx="225.89285"
|
||||
id="path4475"
|
||||
style="fill:none;stroke:#f2edda;stroke-width:1.5;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
sodipodi:type="arc" />
|
||||
<path
|
||||
sodipodi:type="arc"
|
||||
style="fill:none;stroke:#f2edda;stroke-width:1.5;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="path4477"
|
||||
sodipodi:cx="225.89285"
|
||||
sodipodi:cy="542.54077"
|
||||
sodipodi:rx="5.1785712"
|
||||
sodipodi:ry="5.1785712"
|
||||
d="m 231.07142,542.54077 c 0,2.86005 -2.31852,5.17857 -5.17857,5.17857 -2.86004,0 -5.17857,-2.31852 -5.17857,-5.17857 0,-2.86004 2.31853,-5.17857 5.17857,-5.17857 2.86005,0 5.17857,2.31853 5.17857,5.17857 z"
|
||||
transform="translate(-118,-194)" />
|
||||
</g>
|
||||
<g
|
||||
transform="translate(0,-20)"
|
||||
id="g4484">
|
||||
<path
|
||||
transform="translate(-100,-194)"
|
||||
d="m 231.07142,542.54077 c 0,2.86005 -2.31852,5.17857 -5.17857,5.17857 -2.86004,0 -5.17857,-2.31852 -5.17857,-5.17857 0,-2.86004 2.31853,-5.17857 5.17857,-5.17857 2.86005,0 5.17857,2.31853 5.17857,5.17857 z"
|
||||
sodipodi:ry="5.1785712"
|
||||
sodipodi:rx="5.1785712"
|
||||
sodipodi:cy="542.54077"
|
||||
sodipodi:cx="225.89285"
|
||||
id="path4486"
|
||||
style="fill:none;stroke:#f2edda;stroke-width:1.5;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
sodipodi:type="arc" />
|
||||
<path
|
||||
sodipodi:type="arc"
|
||||
style="fill:none;stroke:#f2edda;stroke-width:1.5;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="path4488"
|
||||
sodipodi:cx="225.89285"
|
||||
sodipodi:cy="542.54077"
|
||||
sodipodi:rx="5.1785712"
|
||||
sodipodi:ry="5.1785712"
|
||||
d="m 231.07142,542.54077 c 0,2.86005 -2.31852,5.17857 -5.17857,5.17857 -2.86004,0 -5.17857,-2.31852 -5.17857,-5.17857 0,-2.86004 2.31853,-5.17857 5.17857,-5.17857 2.86005,0 5.17857,2.31853 5.17857,5.17857 z"
|
||||
transform="translate(-82,-194)" />
|
||||
<path
|
||||
transform="translate(-118,-194)"
|
||||
d="m 231.07142,542.54077 c 0,2.86005 -2.31852,5.17857 -5.17857,5.17857 -2.86004,0 -5.17857,-2.31852 -5.17857,-5.17857 0,-2.86004 2.31853,-5.17857 5.17857,-5.17857 2.86005,0 5.17857,2.31853 5.17857,5.17857 z"
|
||||
sodipodi:ry="5.1785712"
|
||||
sodipodi:rx="5.1785712"
|
||||
sodipodi:cy="542.54077"
|
||||
sodipodi:cx="225.89285"
|
||||
id="path4490"
|
||||
style="fill:none;stroke:#f2edda;stroke-width:1.5;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
sodipodi:type="arc" />
|
||||
</g>
|
||||
<g
|
||||
id="g4492"
|
||||
transform="translate(0,-40)">
|
||||
<path
|
||||
sodipodi:type="arc"
|
||||
style="fill:none;stroke:#f2edda;stroke-width:1.5;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="path4494"
|
||||
sodipodi:cx="225.89285"
|
||||
sodipodi:cy="542.54077"
|
||||
sodipodi:rx="5.1785712"
|
||||
sodipodi:ry="5.1785712"
|
||||
d="m 231.07142,542.54077 c 0,2.86005 -2.31852,5.17857 -5.17857,5.17857 -2.86004,0 -5.17857,-2.31852 -5.17857,-5.17857 0,-2.86004 2.31853,-5.17857 5.17857,-5.17857 2.86005,0 5.17857,2.31853 5.17857,5.17857 z"
|
||||
transform="translate(-100,-194)" />
|
||||
<path
|
||||
transform="translate(-82,-194)"
|
||||
d="m 231.07142,542.54077 c 0,2.86005 -2.31852,5.17857 -5.17857,5.17857 -2.86004,0 -5.17857,-2.31852 -5.17857,-5.17857 0,-2.86004 2.31853,-5.17857 5.17857,-5.17857 2.86005,0 5.17857,2.31853 5.17857,5.17857 z"
|
||||
sodipodi:ry="5.1785712"
|
||||
sodipodi:rx="5.1785712"
|
||||
sodipodi:cy="542.54077"
|
||||
sodipodi:cx="225.89285"
|
||||
id="path4496"
|
||||
style="fill:none;stroke:#f2edda;stroke-width:1.5;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
sodipodi:type="arc" />
|
||||
<path
|
||||
sodipodi:type="arc"
|
||||
style="fill:none;stroke:#f2edda;stroke-width:1.5;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="path4498"
|
||||
sodipodi:cx="225.89285"
|
||||
sodipodi:cy="542.54077"
|
||||
sodipodi:rx="5.1785712"
|
||||
sodipodi:ry="5.1785712"
|
||||
d="m 231.07142,542.54077 c 0,2.86005 -2.31852,5.17857 -5.17857,5.17857 -2.86004,0 -5.17857,-2.31852 -5.17857,-5.17857 0,-2.86004 2.31853,-5.17857 5.17857,-5.17857 2.86005,0 5.17857,2.31853 5.17857,5.17857 z"
|
||||
transform="translate(-118,-194)" />
|
||||
</g>
|
||||
<g
|
||||
transform="translate(0,-64)"
|
||||
id="g4500">
|
||||
<path
|
||||
transform="translate(-100,-194)"
|
||||
d="m 231.07142,542.54077 c 0,2.86005 -2.31852,5.17857 -5.17857,5.17857 -2.86004,0 -5.17857,-2.31852 -5.17857,-5.17857 0,-2.86004 2.31853,-5.17857 5.17857,-5.17857 2.86005,0 5.17857,2.31853 5.17857,5.17857 z"
|
||||
sodipodi:ry="5.1785712"
|
||||
sodipodi:rx="5.1785712"
|
||||
sodipodi:cy="542.54077"
|
||||
sodipodi:cx="225.89285"
|
||||
id="path4502"
|
||||
style="fill:none;stroke:#f2edda;stroke-width:1.5;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
sodipodi:type="arc" />
|
||||
<path
|
||||
sodipodi:type="arc"
|
||||
style="fill:none;stroke:#f2edda;stroke-width:1.5;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="path4504"
|
||||
sodipodi:cx="225.89285"
|
||||
sodipodi:cy="542.54077"
|
||||
sodipodi:rx="5.1785712"
|
||||
sodipodi:ry="5.1785712"
|
||||
d="m 231.07142,542.54077 c 0,2.86005 -2.31852,5.17857 -5.17857,5.17857 -2.86004,0 -5.17857,-2.31852 -5.17857,-5.17857 0,-2.86004 2.31853,-5.17857 5.17857,-5.17857 2.86005,0 5.17857,2.31853 5.17857,5.17857 z"
|
||||
transform="translate(-82,-194)" />
|
||||
<path
|
||||
transform="translate(-118,-194)"
|
||||
d="m 231.07142,542.54077 c 0,2.86005 -2.31852,5.17857 -5.17857,5.17857 -2.86004,0 -5.17857,-2.31852 -5.17857,-5.17857 0,-2.86004 2.31853,-5.17857 5.17857,-5.17857 2.86005,0 5.17857,2.31853 5.17857,5.17857 z"
|
||||
sodipodi:ry="5.1785712"
|
||||
sodipodi:rx="5.1785712"
|
||||
sodipodi:cy="542.54077"
|
||||
sodipodi:cx="225.89285"
|
||||
id="path4506"
|
||||
style="fill:none;stroke:#f2edda;stroke-width:1.5;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
sodipodi:type="arc" />
|
||||
</g>
|
||||
<g
|
||||
id="g4508"
|
||||
transform="translate(0,-82)">
|
||||
<path
|
||||
sodipodi:type="arc"
|
||||
style="fill:none;stroke:#f2edda;stroke-width:1.5;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="path4510"
|
||||
sodipodi:cx="225.89285"
|
||||
sodipodi:cy="542.54077"
|
||||
sodipodi:rx="5.1785712"
|
||||
sodipodi:ry="5.1785712"
|
||||
d="m 231.07142,542.54077 c 0,2.86005 -2.31852,5.17857 -5.17857,5.17857 -2.86004,0 -5.17857,-2.31852 -5.17857,-5.17857 0,-2.86004 2.31853,-5.17857 5.17857,-5.17857 2.86005,0 5.17857,2.31853 5.17857,5.17857 z"
|
||||
transform="translate(-100,-194)" />
|
||||
<path
|
||||
transform="translate(-82,-194)"
|
||||
d="m 231.07142,542.54077 c 0,2.86005 -2.31852,5.17857 -5.17857,5.17857 -2.86004,0 -5.17857,-2.31852 -5.17857,-5.17857 0,-2.86004 2.31853,-5.17857 5.17857,-5.17857 2.86005,0 5.17857,2.31853 5.17857,5.17857 z"
|
||||
sodipodi:ry="5.1785712"
|
||||
sodipodi:rx="5.1785712"
|
||||
sodipodi:cy="542.54077"
|
||||
sodipodi:cx="225.89285"
|
||||
id="path4512"
|
||||
style="fill:none;stroke:#f2edda;stroke-width:1.5;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
sodipodi:type="arc" />
|
||||
<path
|
||||
sodipodi:type="arc"
|
||||
style="fill:none;stroke:#f2edda;stroke-width:1.5;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="path4514"
|
||||
sodipodi:cx="225.89285"
|
||||
sodipodi:cy="542.54077"
|
||||
sodipodi:rx="5.1785712"
|
||||
sodipodi:ry="5.1785712"
|
||||
d="m 231.07142,542.54077 c 0,2.86005 -2.31852,5.17857 -5.17857,5.17857 -2.86004,0 -5.17857,-2.31852 -5.17857,-5.17857 0,-2.86004 2.31853,-5.17857 5.17857,-5.17857 2.86005,0 5.17857,2.31853 5.17857,5.17857 z"
|
||||
transform="translate(-118,-194)" />
|
||||
</g>
|
||||
<g
|
||||
transform="translate(0,-102)"
|
||||
id="g4516">
|
||||
<path
|
||||
transform="translate(-100,-194)"
|
||||
d="m 231.07142,542.54077 c 0,2.86005 -2.31852,5.17857 -5.17857,5.17857 -2.86004,0 -5.17857,-2.31852 -5.17857,-5.17857 0,-2.86004 2.31853,-5.17857 5.17857,-5.17857 2.86005,0 5.17857,2.31853 5.17857,5.17857 z"
|
||||
sodipodi:ry="5.1785712"
|
||||
sodipodi:rx="5.1785712"
|
||||
sodipodi:cy="542.54077"
|
||||
sodipodi:cx="225.89285"
|
||||
id="path4518"
|
||||
style="fill:none;stroke:#f2edda;stroke-width:1.5;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
sodipodi:type="arc" />
|
||||
<path
|
||||
sodipodi:type="arc"
|
||||
style="fill:none;stroke:#f2edda;stroke-width:1.5;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="path4520"
|
||||
sodipodi:cx="225.89285"
|
||||
sodipodi:cy="542.54077"
|
||||
sodipodi:rx="5.1785712"
|
||||
sodipodi:ry="5.1785712"
|
||||
d="m 231.07142,542.54077 c 0,2.86005 -2.31852,5.17857 -5.17857,5.17857 -2.86004,0 -5.17857,-2.31852 -5.17857,-5.17857 0,-2.86004 2.31853,-5.17857 5.17857,-5.17857 2.86005,0 5.17857,2.31853 5.17857,5.17857 z"
|
||||
transform="translate(-82,-194)" />
|
||||
<path
|
||||
transform="translate(-118,-194)"
|
||||
d="m 231.07142,542.54077 c 0,2.86005 -2.31852,5.17857 -5.17857,5.17857 -2.86004,0 -5.17857,-2.31852 -5.17857,-5.17857 0,-2.86004 2.31853,-5.17857 5.17857,-5.17857 2.86005,0 5.17857,2.31853 5.17857,5.17857 z"
|
||||
sodipodi:ry="5.1785712"
|
||||
sodipodi:rx="5.1785712"
|
||||
sodipodi:cy="542.54077"
|
||||
sodipodi:cx="225.89285"
|
||||
id="path4522"
|
||||
style="fill:none;stroke:#f2edda;stroke-width:1.5;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
sodipodi:type="arc" />
|
||||
</g>
|
||||
<g
|
||||
id="g4524"
|
||||
transform="translate(0,-126)">
|
||||
<path
|
||||
sodipodi:type="arc"
|
||||
style="fill:none;stroke:#f2edda;stroke-width:1.5;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="path4526"
|
||||
sodipodi:cx="225.89285"
|
||||
sodipodi:cy="542.54077"
|
||||
sodipodi:rx="5.1785712"
|
||||
sodipodi:ry="5.1785712"
|
||||
d="m 231.07142,542.54077 c 0,2.86005 -2.31852,5.17857 -5.17857,5.17857 -2.86004,0 -5.17857,-2.31852 -5.17857,-5.17857 0,-2.86004 2.31853,-5.17857 5.17857,-5.17857 2.86005,0 5.17857,2.31853 5.17857,5.17857 z"
|
||||
transform="translate(-100,-194)" />
|
||||
<path
|
||||
transform="translate(-82,-194)"
|
||||
d="m 231.07142,542.54077 c 0,2.86005 -2.31852,5.17857 -5.17857,5.17857 -2.86004,0 -5.17857,-2.31852 -5.17857,-5.17857 0,-2.86004 2.31853,-5.17857 5.17857,-5.17857 2.86005,0 5.17857,2.31853 5.17857,5.17857 z"
|
||||
sodipodi:ry="5.1785712"
|
||||
sodipodi:rx="5.1785712"
|
||||
sodipodi:cy="542.54077"
|
||||
sodipodi:cx="225.89285"
|
||||
id="path4528"
|
||||
style="fill:none;stroke:#f2edda;stroke-width:1.5;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
sodipodi:type="arc" />
|
||||
<path
|
||||
sodipodi:type="arc"
|
||||
style="fill:none;stroke:#f2edda;stroke-width:1.5;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="path4530"
|
||||
sodipodi:cx="225.89285"
|
||||
sodipodi:cy="542.54077"
|
||||
sodipodi:rx="5.1785712"
|
||||
sodipodi:ry="5.1785712"
|
||||
d="m 231.07142,542.54077 c 0,2.86005 -2.31852,5.17857 -5.17857,5.17857 -2.86004,0 -5.17857,-2.31852 -5.17857,-5.17857 0,-2.86004 2.31853,-5.17857 5.17857,-5.17857 2.86005,0 5.17857,2.31853 5.17857,5.17857 z"
|
||||
transform="translate(-118,-194)" />
|
||||
</g>
|
||||
<g
|
||||
transform="translate(0,-144)"
|
||||
id="g4532">
|
||||
<path
|
||||
transform="translate(-100,-194)"
|
||||
d="m 231.07142,542.54077 c 0,2.86005 -2.31852,5.17857 -5.17857,5.17857 -2.86004,0 -5.17857,-2.31852 -5.17857,-5.17857 0,-2.86004 2.31853,-5.17857 5.17857,-5.17857 2.86005,0 5.17857,2.31853 5.17857,5.17857 z"
|
||||
sodipodi:ry="5.1785712"
|
||||
sodipodi:rx="5.1785712"
|
||||
sodipodi:cy="542.54077"
|
||||
sodipodi:cx="225.89285"
|
||||
id="path4534"
|
||||
style="fill:none;stroke:#f2edda;stroke-width:1.5;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
sodipodi:type="arc" />
|
||||
<path
|
||||
sodipodi:type="arc"
|
||||
style="fill:none;stroke:#f2edda;stroke-width:1.5;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="path4536"
|
||||
sodipodi:cx="225.89285"
|
||||
sodipodi:cy="542.54077"
|
||||
sodipodi:rx="5.1785712"
|
||||
sodipodi:ry="5.1785712"
|
||||
d="m 231.07142,542.54077 c 0,2.86005 -2.31852,5.17857 -5.17857,5.17857 -2.86004,0 -5.17857,-2.31852 -5.17857,-5.17857 0,-2.86004 2.31853,-5.17857 5.17857,-5.17857 2.86005,0 5.17857,2.31853 5.17857,5.17857 z"
|
||||
transform="translate(-82,-194)" />
|
||||
<path
|
||||
transform="translate(-118,-194)"
|
||||
d="m 231.07142,542.54077 c 0,2.86005 -2.31852,5.17857 -5.17857,5.17857 -2.86004,0 -5.17857,-2.31852 -5.17857,-5.17857 0,-2.86004 2.31853,-5.17857 5.17857,-5.17857 2.86005,0 5.17857,2.31853 5.17857,5.17857 z"
|
||||
sodipodi:ry="5.1785712"
|
||||
sodipodi:rx="5.1785712"
|
||||
sodipodi:cy="542.54077"
|
||||
sodipodi:cx="225.89285"
|
||||
id="path4538"
|
||||
style="fill:none;stroke:#f2edda;stroke-width:1.5;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
sodipodi:type="arc" />
|
||||
</g>
|
||||
<g
|
||||
id="g4540"
|
||||
transform="translate(0,-162)">
|
||||
<path
|
||||
sodipodi:type="arc"
|
||||
style="fill:none;stroke:#f2edda;stroke-width:1.5;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="path4542"
|
||||
sodipodi:cx="225.89285"
|
||||
sodipodi:cy="542.54077"
|
||||
sodipodi:rx="5.1785712"
|
||||
sodipodi:ry="5.1785712"
|
||||
d="m 231.07142,542.54077 c 0,2.86005 -2.31852,5.17857 -5.17857,5.17857 -2.86004,0 -5.17857,-2.31852 -5.17857,-5.17857 0,-2.86004 2.31853,-5.17857 5.17857,-5.17857 2.86005,0 5.17857,2.31853 5.17857,5.17857 z"
|
||||
transform="translate(-100,-194)" />
|
||||
<path
|
||||
transform="translate(-82,-194)"
|
||||
d="m 231.07142,542.54077 c 0,2.86005 -2.31852,5.17857 -5.17857,5.17857 -2.86004,0 -5.17857,-2.31852 -5.17857,-5.17857 0,-2.86004 2.31853,-5.17857 5.17857,-5.17857 2.86005,0 5.17857,2.31853 5.17857,5.17857 z"
|
||||
sodipodi:ry="5.1785712"
|
||||
sodipodi:rx="5.1785712"
|
||||
sodipodi:cy="542.54077"
|
||||
sodipodi:cx="225.89285"
|
||||
id="path4544"
|
||||
style="fill:none;stroke:#f2edda;stroke-width:1.5;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
sodipodi:type="arc" />
|
||||
<path
|
||||
sodipodi:type="arc"
|
||||
style="fill:none;stroke:#f2edda;stroke-width:1.5;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="path4546"
|
||||
sodipodi:cx="225.89285"
|
||||
sodipodi:cy="542.54077"
|
||||
sodipodi:rx="5.1785712"
|
||||
sodipodi:ry="5.1785712"
|
||||
d="m 231.07142,542.54077 c 0,2.86005 -2.31852,5.17857 -5.17857,5.17857 -2.86004,0 -5.17857,-2.31852 -5.17857,-5.17857 0,-2.86004 2.31853,-5.17857 5.17857,-5.17857 2.86005,0 5.17857,2.31853 5.17857,5.17857 z"
|
||||
transform="translate(-118,-194)" />
|
||||
</g>
|
||||
<g
|
||||
transform="translate(24,-186)"
|
||||
id="g4548">
|
||||
<path
|
||||
transform="translate(-100,-194)"
|
||||
d="m 231.07142,542.54077 c 0,2.86005 -2.31852,5.17857 -5.17857,5.17857 -2.86004,0 -5.17857,-2.31852 -5.17857,-5.17857 0,-2.86004 2.31853,-5.17857 5.17857,-5.17857 2.86005,0 5.17857,2.31853 5.17857,5.17857 z"
|
||||
sodipodi:ry="5.1785712"
|
||||
sodipodi:rx="5.1785712"
|
||||
sodipodi:cy="542.54077"
|
||||
sodipodi:cx="225.89285"
|
||||
id="path4550"
|
||||
style="fill:none;stroke:#f2edda;stroke-width:1.5;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
sodipodi:type="arc" />
|
||||
<path
|
||||
sodipodi:type="arc"
|
||||
style="fill:none;stroke:#f2edda;stroke-width:1.5;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="path4552"
|
||||
sodipodi:cx="225.89285"
|
||||
sodipodi:cy="542.54077"
|
||||
sodipodi:rx="5.1785712"
|
||||
sodipodi:ry="5.1785712"
|
||||
d="m 231.07142,542.54077 c 0,2.86005 -2.31852,5.17857 -5.17857,5.17857 -2.86004,0 -5.17857,-2.31852 -5.17857,-5.17857 0,-2.86004 2.31853,-5.17857 5.17857,-5.17857 2.86005,0 5.17857,2.31853 5.17857,5.17857 z"
|
||||
transform="translate(-82,-194)" />
|
||||
<path
|
||||
transform="translate(-118,-194)"
|
||||
d="m 231.07142,542.54077 c 0,2.86005 -2.31852,5.17857 -5.17857,5.17857 -2.86004,0 -5.17857,-2.31852 -5.17857,-5.17857 0,-2.86004 2.31853,-5.17857 5.17857,-5.17857 2.86005,0 5.17857,2.31853 5.17857,5.17857 z"
|
||||
sodipodi:ry="5.1785712"
|
||||
sodipodi:rx="5.1785712"
|
||||
sodipodi:cy="542.54077"
|
||||
sodipodi:cx="225.89285"
|
||||
id="path4554"
|
||||
style="fill:none;stroke:#f2edda;stroke-width:1.5;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
sodipodi:type="arc" />
|
||||
</g>
|
||||
<rect
|
||||
transform="translate(-100,-194)"
|
||||
y="352.00504"
|
||||
x="208.21428"
|
||||
height="8.5714283"
|
||||
width="9.6428576"
|
||||
id="rect4556"
|
||||
style="fill:none;stroke:#f2edda;stroke-width:1.5;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
<rect
|
||||
ry="1.6"
|
||||
transform="translate(-100,-194)"
|
||||
y="418.43362"
|
||||
x="268.21429"
|
||||
height="36.07143"
|
||||
width="35.357143"
|
||||
id="rect4558"
|
||||
style="fill:#e5e5e5;fill-opacity:1;stroke:#f2edda;stroke-width:1.5;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
<path
|
||||
transform="translate(-100.71428,-194.17855)"
|
||||
d="m 288.21429,436.64789 c 0,0.98622 -0.71954,1.78571 -1.60714,1.78571 -0.8876,0 -1.60715,-0.79949 -1.60715,-1.78571 0,-0.98622 0.71955,-1.78572 1.60715,-1.78572 0.8876,0 1.60714,0.7995 1.60714,1.78572 z"
|
||||
sodipodi:ry="1.7857143"
|
||||
sodipodi:rx="1.6071428"
|
||||
sodipodi:cy="436.64789"
|
||||
sodipodi:cx="286.60715"
|
||||
id="path4560"
|
||||
style="fill:#000000;fill-opacity:1;stroke:none"
|
||||
sodipodi:type="arc" />
|
||||
</g>
|
||||
<rect
|
||||
y="372.52951"
|
||||
x="359.36176"
|
||||
height="48.487324"
|
||||
width="24.748737"
|
||||
id="rect4564"
|
||||
style="fill:#444444;fill-opacity:1;stroke:none;display:inline" />
|
||||
<g
|
||||
transform="translate(0.50508,0)"
|
||||
id="g4572"
|
||||
style="display:inline">
|
||||
<rect
|
||||
style="fill:#fffcfc;fill-opacity:1;stroke:none"
|
||||
id="rect4570"
|
||||
width="3.9143078"
|
||||
height="4.2931485"
|
||||
x="348.75516"
|
||||
y="377.95908" />
|
||||
<path
|
||||
style="fill:none;stroke:#f3c61b;stroke-width:2.13612175;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
d="m 358.85669,379.85312 -7.20209,0"
|
||||
id="path4568"
|
||||
inkscape:connector-curvature="0" />
|
||||
</g>
|
||||
<g
|
||||
transform="translate(0.50508,10)"
|
||||
id="g4576"
|
||||
style="display:inline">
|
||||
<rect
|
||||
y="377.95908"
|
||||
x="348.75516"
|
||||
height="4.2931485"
|
||||
width="3.9143078"
|
||||
id="rect4578"
|
||||
style="fill:#fffcfc;fill-opacity:1;stroke:none" />
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4580"
|
||||
d="m 358.85669,379.85312 -7.20209,0"
|
||||
style="fill:none;stroke:#f3c61b;stroke-width:2.13612175;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
</g>
|
||||
<g
|
||||
id="g4582"
|
||||
transform="translate(0.50508,20)"
|
||||
style="display:inline">
|
||||
<rect
|
||||
style="fill:#fffcfc;fill-opacity:1;stroke:none"
|
||||
id="rect4584"
|
||||
width="3.9143078"
|
||||
height="4.2931485"
|
||||
x="348.75516"
|
||||
y="377.95908" />
|
||||
<path
|
||||
style="fill:none;stroke:#f3c61b;stroke-width:2.13612175;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
d="m 358.85669,379.85312 -7.20209,0"
|
||||
id="path4586"
|
||||
inkscape:connector-curvature="0" />
|
||||
</g>
|
||||
<g
|
||||
transform="translate(0.50508,30)"
|
||||
id="g4588"
|
||||
style="display:inline">
|
||||
<rect
|
||||
y="377.95908"
|
||||
x="348.75516"
|
||||
height="4.2931485"
|
||||
width="3.9143078"
|
||||
id="rect4590"
|
||||
style="fill:#fffcfc;fill-opacity:1;stroke:none" />
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4592"
|
||||
d="m 358.85669,379.85312 -7.20209,0"
|
||||
style="fill:none;stroke:#f3c61b;stroke-width:2.13612175;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
</g>
|
||||
<g
|
||||
id="g4594"
|
||||
transform="translate(0.50508,40)"
|
||||
style="display:inline">
|
||||
<rect
|
||||
style="fill:#fffcfc;fill-opacity:1;stroke:none"
|
||||
id="rect4596"
|
||||
width="3.9143078"
|
||||
height="4.2931485"
|
||||
x="348.75516"
|
||||
y="377.95908" />
|
||||
<path
|
||||
style="fill:none;stroke:#f3c61b;stroke-width:2.13612175;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
d="m 358.85669,379.85312 -7.20209,0"
|
||||
id="path4598"
|
||||
inkscape:connector-curvature="0" />
|
||||
</g>
|
||||
<g
|
||||
transform="matrix(-1,0,0,1,742.80618,40)"
|
||||
id="g4600"
|
||||
style="display:inline">
|
||||
<rect
|
||||
y="377.95908"
|
||||
x="348.75516"
|
||||
height="4.2931485"
|
||||
width="3.9143078"
|
||||
id="rect4602"
|
||||
style="fill:#fffcfc;fill-opacity:1;stroke:none" />
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4604"
|
||||
d="m 358.85669,379.85312 -7.20209,0"
|
||||
style="fill:none;stroke:#f3c61b;stroke-width:2.13612175;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
</g>
|
||||
<g
|
||||
id="g4606"
|
||||
transform="matrix(-1,0,0,1,742.80618,30)"
|
||||
style="display:inline">
|
||||
<rect
|
||||
style="fill:#fffcfc;fill-opacity:1;stroke:none"
|
||||
id="rect4608"
|
||||
width="3.9143078"
|
||||
height="4.2931485"
|
||||
x="348.75516"
|
||||
y="377.95908" />
|
||||
<path
|
||||
style="fill:none;stroke:#f3c61b;stroke-width:2.13612175;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
d="m 358.85669,379.85312 -7.20209,0"
|
||||
id="path4610"
|
||||
inkscape:connector-curvature="0" />
|
||||
</g>
|
||||
<g
|
||||
transform="matrix(-1,0,0,1,742.80618,20)"
|
||||
id="g4612"
|
||||
style="display:inline">
|
||||
<rect
|
||||
y="377.95908"
|
||||
x="348.75516"
|
||||
height="4.2931485"
|
||||
width="3.9143078"
|
||||
id="rect4614"
|
||||
style="fill:#fffcfc;fill-opacity:1;stroke:none" />
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4616"
|
||||
d="m 358.85669,379.85312 -7.20209,0"
|
||||
style="fill:none;stroke:#f3c61b;stroke-width:2.13612175;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
</g>
|
||||
<g
|
||||
id="g4618"
|
||||
transform="matrix(-1,0,0,1,742.80618,10)"
|
||||
style="display:inline">
|
||||
<rect
|
||||
style="fill:#fffcfc;fill-opacity:1;stroke:none"
|
||||
id="rect4620"
|
||||
width="3.9143078"
|
||||
height="4.2931485"
|
||||
x="348.75516"
|
||||
y="377.95908" />
|
||||
<path
|
||||
style="fill:none;stroke:#f3c61b;stroke-width:2.13612175;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
d="m 358.85669,379.85312 -7.20209,0"
|
||||
id="path4622"
|
||||
inkscape:connector-curvature="0" />
|
||||
</g>
|
||||
<g
|
||||
transform="matrix(-1,0,0,1,742.80618,0)"
|
||||
id="g4624"
|
||||
style="display:inline">
|
||||
<rect
|
||||
y="377.95908"
|
||||
x="348.75516"
|
||||
height="4.2931485"
|
||||
width="3.9143078"
|
||||
id="rect4626"
|
||||
style="fill:#fffcfc;fill-opacity:1;stroke:none" />
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4628"
|
||||
d="m 358.85669,379.85312 -7.20209,0"
|
||||
style="fill:none;stroke:#f3c61b;stroke-width:2.13612175;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
</g>
|
||||
<path
|
||||
transform="translate(0,-0.50508)"
|
||||
d="m 367.82181,381.8103 a 1.8309015,1.7046324 0 1 1 -3.66181,0 1.8309015,1.7046324 0 1 1 3.66181,0 z"
|
||||
sodipodi:ry="1.7046324"
|
||||
sodipodi:rx="1.8309015"
|
||||
sodipodi:cy="381.8103"
|
||||
sodipodi:cx="365.99091"
|
||||
id="path4630"
|
||||
style="fill:#f3c61b;fill-opacity:1;stroke:none;display:inline"
|
||||
sodipodi:type="arc" />
|
||||
<path
|
||||
sodipodi:type="arc"
|
||||
style="fill:#f3c61b;fill-opacity:1;stroke:none;display:inline"
|
||||
id="path4632"
|
||||
sodipodi:cx="365.99091"
|
||||
sodipodi:cy="381.8103"
|
||||
sodipodi:rx="1.8309015"
|
||||
sodipodi:ry="1.7046324"
|
||||
d="m 367.82181,381.8103 a 1.8309015,1.7046324 0 1 1 -3.66181,0 1.8309015,1.7046324 0 1 1 3.66181,0 z"
|
||||
transform="translate(10,-0.50508)" />
|
||||
<path
|
||||
transform="translate(10,9.49492)"
|
||||
d="m 367.82181,381.8103 a 1.8309015,1.7046324 0 1 1 -3.66181,0 1.8309015,1.7046324 0 1 1 3.66181,0 z"
|
||||
sodipodi:ry="1.7046324"
|
||||
sodipodi:rx="1.8309015"
|
||||
sodipodi:cy="381.8103"
|
||||
sodipodi:cx="365.99091"
|
||||
id="path4634"
|
||||
style="fill:#f3c61b;fill-opacity:1;stroke:none;display:inline"
|
||||
sodipodi:type="arc" />
|
||||
<path
|
||||
sodipodi:type="arc"
|
||||
style="fill:#f3c61b;fill-opacity:1;stroke:none;display:inline"
|
||||
id="path4636"
|
||||
sodipodi:cx="365.99091"
|
||||
sodipodi:cy="381.8103"
|
||||
sodipodi:rx="1.8309015"
|
||||
sodipodi:ry="1.7046324"
|
||||
d="m 367.82181,381.8103 a 1.8309015,1.7046324 0 1 1 -3.66181,0 1.8309015,1.7046324 0 1 1 3.66181,0 z"
|
||||
transform="translate(0,9.49492)" />
|
||||
<path
|
||||
transform="translate(0,19.49492)"
|
||||
d="m 367.82181,381.8103 a 1.8309015,1.7046324 0 1 1 -3.66181,0 1.8309015,1.7046324 0 1 1 3.66181,0 z"
|
||||
sodipodi:ry="1.7046324"
|
||||
sodipodi:rx="1.8309015"
|
||||
sodipodi:cy="381.8103"
|
||||
sodipodi:cx="365.99091"
|
||||
id="path4638"
|
||||
style="fill:#f3c61b;fill-opacity:1;stroke:none;display:inline"
|
||||
sodipodi:type="arc" />
|
||||
<path
|
||||
sodipodi:type="arc"
|
||||
style="fill:#f3c61b;fill-opacity:1;stroke:none;display:inline"
|
||||
id="path4640"
|
||||
sodipodi:cx="365.99091"
|
||||
sodipodi:cy="381.8103"
|
||||
sodipodi:rx="1.8309015"
|
||||
sodipodi:ry="1.7046324"
|
||||
d="m 367.82181,381.8103 a 1.8309015,1.7046324 0 1 1 -3.66181,0 1.8309015,1.7046324 0 1 1 3.66181,0 z"
|
||||
transform="translate(10,19.49492)" />
|
||||
<path
|
||||
transform="translate(10,29.49492)"
|
||||
d="m 367.82181,381.8103 a 1.8309015,1.7046324 0 1 1 -3.66181,0 1.8309015,1.7046324 0 1 1 3.66181,0 z"
|
||||
sodipodi:ry="1.7046324"
|
||||
sodipodi:rx="1.8309015"
|
||||
sodipodi:cy="381.8103"
|
||||
sodipodi:cx="365.99091"
|
||||
id="path4642"
|
||||
style="fill:#f3c61b;fill-opacity:1;stroke:none;display:inline"
|
||||
sodipodi:type="arc" />
|
||||
<path
|
||||
sodipodi:type="arc"
|
||||
style="fill:#f3c61b;fill-opacity:1;stroke:none;display:inline"
|
||||
id="path4644"
|
||||
sodipodi:cx="365.99091"
|
||||
sodipodi:cy="381.8103"
|
||||
sodipodi:rx="1.8309015"
|
||||
sodipodi:ry="1.7046324"
|
||||
d="m 367.82181,381.8103 a 1.8309015,1.7046324 0 1 1 -3.66181,0 1.8309015,1.7046324 0 1 1 3.66181,0 z"
|
||||
transform="translate(0,29.49492)" />
|
||||
</g>
|
||||
</g>
|
||||
</svg>
|
After Width: | Height: | Size: 108 KiB |
2948
ground/openpilotgcs/src/plugins/uploader/images/deviceID-0201.svg
Normal file
@ -0,0 +1,2948 @@
|
||||
<?xml version="1.0" encoding="UTF-8" standalone="no"?>
|
||||
<!-- Created with Inkscape (http://www.inkscape.org/) -->
|
||||
|
||||
<svg
|
||||
xmlns:dc="http://purl.org/dc/elements/1.1/"
|
||||
xmlns:cc="http://creativecommons.org/ns#"
|
||||
xmlns:rdf="http://www.w3.org/1999/02/22-rdf-syntax-ns#"
|
||||
xmlns:svg="http://www.w3.org/2000/svg"
|
||||
xmlns="http://www.w3.org/2000/svg"
|
||||
xmlns:sodipodi="http://sodipodi.sourceforge.net/DTD/sodipodi-0.dtd"
|
||||
xmlns:inkscape="http://www.inkscape.org/namespaces/inkscape"
|
||||
width="370.71875"
|
||||
height="380.8125"
|
||||
id="svg2"
|
||||
version="1.1"
|
||||
inkscape:version="0.48.0 r9654"
|
||||
sodipodi:docname="ahrs-1.svg"
|
||||
style="display:inline">
|
||||
<defs
|
||||
id="defs4" />
|
||||
<sodipodi:namedview
|
||||
id="base"
|
||||
pagecolor="#ffffff"
|
||||
bordercolor="#666666"
|
||||
borderopacity="1.0"
|
||||
inkscape:pageopacity="0.0"
|
||||
inkscape:pageshadow="2"
|
||||
inkscape:zoom="0.98994949"
|
||||
inkscape:cx="153.7499"
|
||||
inkscape:cy="168.32049"
|
||||
inkscape:document-units="px"
|
||||
inkscape:current-layer="layer3"
|
||||
showgrid="false"
|
||||
inkscape:window-width="1366"
|
||||
inkscape:window-height="691"
|
||||
inkscape:window-x="0"
|
||||
inkscape:window-y="24"
|
||||
inkscape:window-maximized="1"
|
||||
fit-margin-top="0"
|
||||
fit-margin-left="0"
|
||||
fit-margin-right="0"
|
||||
fit-margin-bottom="0" />
|
||||
<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
|
||||
inkscape:groupmode="layer"
|
||||
id="layer3"
|
||||
inkscape:label="Mb pcb"
|
||||
style="display:inline"
|
||||
transform="translate(-191.9375,-268.5)">
|
||||
<g
|
||||
id="device"
|
||||
inkscape:label="#g5559">
|
||||
<rect
|
||||
ry="16.816143"
|
||||
y="269.49396"
|
||||
x="192.93918"
|
||||
height="378.80719"
|
||||
width="368.70566"
|
||||
id="rect2997"
|
||||
style="fill:#171717;fill-opacity:1;stroke:#000000;stroke-width:1.99999988;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
<g
|
||||
transform="translate(435.88082,119.70308)"
|
||||
id="g3471"
|
||||
style="display:inline">
|
||||
<rect
|
||||
style="fill:#6a6a6a;fill-opacity:1;stroke:#000000;stroke-width:2;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect3773"
|
||||
width="76.428574"
|
||||
height="76.785713"
|
||||
x="-104.28571"
|
||||
y="358.43362"
|
||||
ry="2.5" />
|
||||
<g
|
||||
id="g3875"
|
||||
transform="translate(-520,-37.142857)">
|
||||
<g
|
||||
transform="matrix(1.4970318,0,0,1,-211.28069,0.21205357)"
|
||||
id="g3781">
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path3777"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path3779"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" />
|
||||
</g>
|
||||
<g
|
||||
id="g3785"
|
||||
transform="matrix(1.4970318,0,0,1,-207.28069,0.21205357)">
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3787"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
<path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3789"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
</g>
|
||||
<g
|
||||
transform="matrix(1.4970318,0,0,1,-203.28069,0.21205357)"
|
||||
id="g3791">
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path3793"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path3795"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" />
|
||||
</g>
|
||||
<g
|
||||
id="g3797"
|
||||
transform="matrix(1.4970318,0,0,1,-199.28069,0.21205357)">
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3799"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
<path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3801"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
</g>
|
||||
<g
|
||||
transform="matrix(1.4970318,0,0,1,-195.28069,0.21205357)"
|
||||
id="g3803">
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path3805"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path3807"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" />
|
||||
</g>
|
||||
<g
|
||||
id="g3809"
|
||||
transform="matrix(1.4970318,0,0,1,-191.28069,0.21205357)">
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3811"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
<path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3813"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
</g>
|
||||
<g
|
||||
transform="matrix(1.4970318,0,0,1,-187.28069,0.21205357)"
|
||||
id="g3815">
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path3817"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path3819"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" />
|
||||
</g>
|
||||
<g
|
||||
id="g3821"
|
||||
transform="matrix(1.4970318,0,0,1,-183.28069,0.21205357)">
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3823"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
<path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3825"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
</g>
|
||||
<g
|
||||
transform="matrix(1.4970318,0,0,1,-179.28069,0.21205357)"
|
||||
id="g3827">
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path3829"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path3831"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" />
|
||||
</g>
|
||||
<g
|
||||
id="g3833"
|
||||
transform="matrix(1.4970318,0,0,1,-175.28069,0.21205357)">
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3835"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
<path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3837"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
</g>
|
||||
<g
|
||||
transform="matrix(1.4970318,0,0,1,-171.28069,0.21205357)"
|
||||
id="g3839">
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path3841"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path3843"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" />
|
||||
</g>
|
||||
<g
|
||||
id="g3845"
|
||||
transform="matrix(1.4970318,0,0,1,-167.28069,0.21205357)">
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3847"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
<path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3849"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
</g>
|
||||
<g
|
||||
transform="matrix(1.4970318,0,0,1,-163.28069,0.21205357)"
|
||||
id="g3851">
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path3853"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path3855"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" />
|
||||
</g>
|
||||
<g
|
||||
id="g3857"
|
||||
transform="matrix(1.4970318,0,0,1,-159.28069,0.21205357)">
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3859"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
<path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3861"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
</g>
|
||||
<g
|
||||
transform="matrix(1.4970318,0,0,1,-155.28069,0.21205357)"
|
||||
id="g3863">
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path3865"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path3867"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" />
|
||||
</g>
|
||||
<g
|
||||
id="g3869"
|
||||
transform="matrix(1.4970318,0,0,1,-151.28069,0.21205357)">
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3871"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
<path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3873"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
</g>
|
||||
</g>
|
||||
<g
|
||||
id="g3925"
|
||||
transform="matrix(0,1,-1,0,367.93406,-54.993437)">
|
||||
<g
|
||||
id="g3927"
|
||||
transform="matrix(1.4970318,0,0,1,-211.28069,0.21205357)">
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3929"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
<path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3931"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
</g>
|
||||
<g
|
||||
transform="matrix(1.4970318,0,0,1,-207.28069,0.21205357)"
|
||||
id="g3933">
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path3935"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path3937"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" />
|
||||
</g>
|
||||
<g
|
||||
id="g3939"
|
||||
transform="matrix(1.4970318,0,0,1,-203.28069,0.21205357)">
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3941"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
<path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3943"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
</g>
|
||||
<g
|
||||
transform="matrix(1.4970318,0,0,1,-199.28069,0.21205357)"
|
||||
id="g3945">
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path3947"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path3949"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" />
|
||||
</g>
|
||||
<g
|
||||
id="g3951"
|
||||
transform="matrix(1.4970318,0,0,1,-195.28069,0.21205357)">
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3953"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
<path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3955"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
</g>
|
||||
<g
|
||||
transform="matrix(1.4970318,0,0,1,-191.28069,0.21205357)"
|
||||
id="g3957">
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path3959"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path3961"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" />
|
||||
</g>
|
||||
<g
|
||||
id="g3963"
|
||||
transform="matrix(1.4970318,0,0,1,-187.28069,0.21205357)">
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3965"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
<path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3967"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
</g>
|
||||
<g
|
||||
transform="matrix(1.4970318,0,0,1,-183.28069,0.21205357)"
|
||||
id="g3969">
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path3971"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path3973"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" />
|
||||
</g>
|
||||
<g
|
||||
id="g3975"
|
||||
transform="matrix(1.4970318,0,0,1,-179.28069,0.21205357)">
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3977"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
<path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3979"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
</g>
|
||||
<g
|
||||
transform="matrix(1.4970318,0,0,1,-175.28069,0.21205357)"
|
||||
id="g3981">
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path3983"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path3985"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" />
|
||||
</g>
|
||||
<g
|
||||
id="g3987"
|
||||
transform="matrix(1.4970318,0,0,1,-171.28069,0.21205357)">
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3989"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
<path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3991"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
</g>
|
||||
<g
|
||||
transform="matrix(1.4970318,0,0,1,-167.28069,0.21205357)"
|
||||
id="g3993">
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path3995"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path3997"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" />
|
||||
</g>
|
||||
<g
|
||||
id="g3999"
|
||||
transform="matrix(1.4970318,0,0,1,-163.28069,0.21205357)">
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4001"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
<path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4003"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
</g>
|
||||
<g
|
||||
transform="matrix(1.4970318,0,0,1,-159.28069,0.21205357)"
|
||||
id="g4005">
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path4007"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path4009"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" />
|
||||
</g>
|
||||
<g
|
||||
id="g4011"
|
||||
transform="matrix(1.4970318,0,0,1,-155.28069,0.21205357)">
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4013"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
<path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4015"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
</g>
|
||||
<g
|
||||
transform="matrix(1.4970318,0,0,1,-151.28069,0.21205357)"
|
||||
id="g4017">
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path4019"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path4021"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" />
|
||||
</g>
|
||||
</g>
|
||||
<g
|
||||
transform="matrix(0,1,1,0,-500.02315,-54.993437)"
|
||||
id="g4023">
|
||||
<g
|
||||
transform="matrix(1.4970318,0,0,1,-211.28069,0.21205357)"
|
||||
id="g4025">
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path4027"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path4029"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" />
|
||||
</g>
|
||||
<g
|
||||
id="g4031"
|
||||
transform="matrix(1.4970318,0,0,1,-207.28069,0.21205357)">
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4033"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
<path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4035"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
</g>
|
||||
<g
|
||||
transform="matrix(1.4970318,0,0,1,-203.28069,0.21205357)"
|
||||
id="g4037">
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path4039"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path4041"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" />
|
||||
</g>
|
||||
<g
|
||||
id="g4043"
|
||||
transform="matrix(1.4970318,0,0,1,-199.28069,0.21205357)">
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4045"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
<path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4047"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
</g>
|
||||
<g
|
||||
transform="matrix(1.4970318,0,0,1,-195.28069,0.21205357)"
|
||||
id="g4049">
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path4051"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path4053"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" />
|
||||
</g>
|
||||
<g
|
||||
id="g4055"
|
||||
transform="matrix(1.4970318,0,0,1,-191.28069,0.21205357)">
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4057"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
<path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4059"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
</g>
|
||||
<g
|
||||
transform="matrix(1.4970318,0,0,1,-187.28069,0.21205357)"
|
||||
id="g4061">
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path4063"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path4065"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" />
|
||||
</g>
|
||||
<g
|
||||
id="g4067"
|
||||
transform="matrix(1.4970318,0,0,1,-183.28069,0.21205357)">
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4069"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
<path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4071"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
</g>
|
||||
<g
|
||||
transform="matrix(1.4970318,0,0,1,-179.28069,0.21205357)"
|
||||
id="g4073">
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path4075"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path4077"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" />
|
||||
</g>
|
||||
<g
|
||||
id="g4079"
|
||||
transform="matrix(1.4970318,0,0,1,-175.28069,0.21205357)">
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4081"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
<path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4083"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
</g>
|
||||
<g
|
||||
transform="matrix(1.4970318,0,0,1,-171.28069,0.21205357)"
|
||||
id="g4085">
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path4087"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path4089"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" />
|
||||
</g>
|
||||
<g
|
||||
id="g4091"
|
||||
transform="matrix(1.4970318,0,0,1,-167.28069,0.21205357)">
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4093"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
<path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4095"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
</g>
|
||||
<g
|
||||
transform="matrix(1.4970318,0,0,1,-163.28069,0.21205357)"
|
||||
id="g4097">
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path4099"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path4101"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" />
|
||||
</g>
|
||||
<g
|
||||
id="g4103"
|
||||
transform="matrix(1.4970318,0,0,1,-159.28069,0.21205357)">
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4105"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
<path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4107"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
</g>
|
||||
<g
|
||||
transform="matrix(1.4970318,0,0,1,-155.28069,0.21205357)"
|
||||
id="g4109">
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path4111"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path4113"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" />
|
||||
</g>
|
||||
<g
|
||||
id="g4115"
|
||||
transform="matrix(1.4970318,0,0,1,-151.28069,0.21205357)">
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4117"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
<path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4119"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
</g>
|
||||
</g>
|
||||
<g
|
||||
id="g4121"
|
||||
transform="matrix(1,0,0,-1,-520,830.07704)">
|
||||
<g
|
||||
id="g4123"
|
||||
transform="matrix(1.4970318,0,0,1,-211.28069,0.21205357)">
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4125"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
<path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4127"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
</g>
|
||||
<g
|
||||
transform="matrix(1.4970318,0,0,1,-207.28069,0.21205357)"
|
||||
id="g4129">
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path4131"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path4133"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" />
|
||||
</g>
|
||||
<g
|
||||
id="g4135"
|
||||
transform="matrix(1.4970318,0,0,1,-203.28069,0.21205357)">
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4137"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
<path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4139"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
</g>
|
||||
<g
|
||||
transform="matrix(1.4970318,0,0,1,-199.28069,0.21205357)"
|
||||
id="g4141">
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path4143"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path4145"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" />
|
||||
</g>
|
||||
<g
|
||||
id="g4147"
|
||||
transform="matrix(1.4970318,0,0,1,-195.28069,0.21205357)">
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4149"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
<path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4151"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
</g>
|
||||
<g
|
||||
transform="matrix(1.4970318,0,0,1,-191.28069,0.21205357)"
|
||||
id="g4153">
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path4155"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path4157"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" />
|
||||
</g>
|
||||
<g
|
||||
id="g4159"
|
||||
transform="matrix(1.4970318,0,0,1,-187.28069,0.21205357)">
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4161"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
<path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4163"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
</g>
|
||||
<g
|
||||
transform="matrix(1.4970318,0,0,1,-183.28069,0.21205357)"
|
||||
id="g4165">
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path4167"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path4169"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" />
|
||||
</g>
|
||||
<g
|
||||
id="g4171"
|
||||
transform="matrix(1.4970318,0,0,1,-179.28069,0.21205357)">
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4173"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
<path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4175"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
</g>
|
||||
<g
|
||||
transform="matrix(1.4970318,0,0,1,-175.28069,0.21205357)"
|
||||
id="g4177">
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path4179"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path4181"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" />
|
||||
</g>
|
||||
<g
|
||||
id="g4183"
|
||||
transform="matrix(1.4970318,0,0,1,-171.28069,0.21205357)">
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4185"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
<path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4187"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
</g>
|
||||
<g
|
||||
transform="matrix(1.4970318,0,0,1,-167.28069,0.21205357)"
|
||||
id="g4189">
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path4191"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path4193"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" />
|
||||
</g>
|
||||
<g
|
||||
id="g4195"
|
||||
transform="matrix(1.4970318,0,0,1,-163.28069,0.21205357)">
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4197"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
<path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4199"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
</g>
|
||||
<g
|
||||
transform="matrix(1.4970318,0,0,1,-159.28069,0.21205357)"
|
||||
id="g4201">
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path4203"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path4205"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" />
|
||||
</g>
|
||||
<g
|
||||
id="g4207"
|
||||
transform="matrix(1.4970318,0,0,1,-155.28069,0.21205357)">
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4209"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
<path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4211"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
</g>
|
||||
<g
|
||||
transform="matrix(1.4970318,0,0,1,-151.28069,0.21205357)"
|
||||
id="g4213">
|
||||
<path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path4215"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:0.86591274px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path4217"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" />
|
||||
</g>
|
||||
</g>
|
||||
<g
|
||||
id="g3963-6"
|
||||
transform="matrix(0,1.4970318,-1,0,421.89061,-156.72568)"
|
||||
style="display:inline" />
|
||||
<rect
|
||||
y="279.64172"
|
||||
x="-178.53194"
|
||||
height="40.925297"
|
||||
width="40.730717"
|
||||
id="rect4972"
|
||||
style="fill:#6a6a6a;fill-opacity:1;stroke:#000000;stroke-width:0.69999999;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
<rect
|
||||
style="fill:#6a6a6a;fill-opacity:1;stroke:#000000;stroke-width:0.69999999;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect4974"
|
||||
width="40.730717"
|
||||
height="40.925297"
|
||||
x="-162.53194"
|
||||
y="167.64172" />
|
||||
<rect
|
||||
y="220.02498"
|
||||
x="-48.531937"
|
||||
height="52.542053"
|
||||
width="40.730717"
|
||||
id="rect4976"
|
||||
style="fill:#6a6a6a;fill-opacity:1;stroke:#000000;stroke-width:0.69999999;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
<rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
style="fill:#6a6a6a;fill-opacity:1;stroke:#000000;stroke-width:0.69999999;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect4978"
|
||||
width="40.730717"
|
||||
height="52.542053"
|
||||
x="-310.66138"
|
||||
y="37.562393" />
|
||||
</g>
|
||||
<g
|
||||
transform="matrix(0,1,-1,0,611.68744,-5.73342)"
|
||||
id="g4294"
|
||||
style="display:inline">
|
||||
<rect
|
||||
y="365.75504"
|
||||
x="422.11606"
|
||||
height="5.0892859"
|
||||
width="6.5178571"
|
||||
id="rect4296"
|
||||
style="fill:#bc781e;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
<rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect4298"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="428.58929"
|
||||
y="365.75504" />
|
||||
<rect
|
||||
y="365.75504"
|
||||
x="418.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect4300"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
</g>
|
||||
<g
|
||||
id="g4302"
|
||||
transform="matrix(0,1,-1,0,611.06309,135.42142)"
|
||||
style="display:inline">
|
||||
<rect
|
||||
style="fill:#bc781e;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect4304"
|
||||
width="6.5178571"
|
||||
height="5.0892859"
|
||||
x="422.11606"
|
||||
y="365.75504" />
|
||||
<rect
|
||||
y="365.75504"
|
||||
x="428.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect4306"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
<rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect4308"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="418.58929"
|
||||
y="365.75504" />
|
||||
</g>
|
||||
<g
|
||||
transform="translate(-208,150.85714)"
|
||||
id="g4366"
|
||||
style="display:inline">
|
||||
<rect
|
||||
y="365.75504"
|
||||
x="422.11606"
|
||||
height="5.0892859"
|
||||
width="6.5178571"
|
||||
id="rect4368"
|
||||
style="fill:#312d29;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
<rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect4370"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="428.58929"
|
||||
y="365.75504" />
|
||||
<rect
|
||||
y="365.75504"
|
||||
x="418.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect4372"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
</g>
|
||||
<g
|
||||
id="g4414"
|
||||
transform="translate(-208.51135,168.54502)"
|
||||
style="display:inline">
|
||||
<rect
|
||||
style="fill:#0052ff;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect4416"
|
||||
width="6.5178571"
|
||||
height="5.0892859"
|
||||
x="422.11606"
|
||||
y="365.75504" />
|
||||
<rect
|
||||
y="365.75504"
|
||||
x="428.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect4418"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
<rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect4420"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="418.58929"
|
||||
y="365.75504" />
|
||||
</g>
|
||||
<g
|
||||
transform="translate(211.48864,30.30458)"
|
||||
id="g4796"
|
||||
style="display:inline">
|
||||
<rect
|
||||
style="fill:#ff7900;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect4432"
|
||||
width="6.5178571"
|
||||
height="5.0892859"
|
||||
x="2.1160583"
|
||||
y="522.61218" />
|
||||
<rect
|
||||
y="522.61218"
|
||||
x="8.5892944"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect4434"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
<rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect4436"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="-1.4107056"
|
||||
y="522.61218" />
|
||||
</g>
|
||||
<rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
style="fill:#beb6b1;fill-opacity:1;stroke:#ffcd00;stroke-width:1;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="rect4438"
|
||||
width="49.244915"
|
||||
height="29.799494"
|
||||
x="-533.37653"
|
||||
y="262.11063"
|
||||
ry="2.6222224" />
|
||||
<g
|
||||
transform="matrix(0,1,-1,0,558.71934,354.50506)"
|
||||
id="g4479"
|
||||
style="display:inline">
|
||||
<path
|
||||
transform="translate(-110,-194)"
|
||||
d="m 231.07142,542.54077 c 0,2.86005 -2.31852,5.17857 -5.17857,5.17857 -2.86004,0 -5.17857,-2.31852 -5.17857,-5.17857 0,-2.86004 2.31853,-5.17857 5.17857,-5.17857 2.86005,0 5.17857,2.31853 5.17857,5.17857 z"
|
||||
sodipodi:ry="5.1785712"
|
||||
sodipodi:rx="5.1785712"
|
||||
sodipodi:cy="542.54077"
|
||||
sodipodi:cx="225.89285"
|
||||
id="path4473"
|
||||
style="fill:none;stroke:#f2edda;stroke-width:1.5;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
sodipodi:type="arc" />
|
||||
<path
|
||||
sodipodi:type="arc"
|
||||
style="fill:none;stroke:#f2edda;stroke-width:1.5;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="path4475"
|
||||
sodipodi:cx="225.89285"
|
||||
sodipodi:cy="542.54077"
|
||||
sodipodi:rx="5.1785712"
|
||||
sodipodi:ry="5.1785712"
|
||||
d="m 231.07142,542.54077 c 0,2.86005 -2.31852,5.17857 -5.17857,5.17857 -2.86004,0 -5.17857,-2.31852 -5.17857,-5.17857 0,-2.86004 2.31853,-5.17857 5.17857,-5.17857 2.86005,0 5.17857,2.31853 5.17857,5.17857 z"
|
||||
transform="translate(-82,-194)" />
|
||||
<path
|
||||
transform="translate(-164,-194)"
|
||||
d="m 231.07142,542.54077 c 0,2.86005 -2.31852,5.17857 -5.17857,5.17857 -2.86004,0 -5.17857,-2.31852 -5.17857,-5.17857 0,-2.86004 2.31853,-5.17857 5.17857,-5.17857 2.86005,0 5.17857,2.31853 5.17857,5.17857 z"
|
||||
sodipodi:ry="5.1785712"
|
||||
sodipodi:rx="5.1785712"
|
||||
sodipodi:cy="542.54077"
|
||||
sodipodi:cx="225.89285"
|
||||
id="path4477"
|
||||
style="fill:none;stroke:#f2edda;stroke-width:1.5;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
sodipodi:type="arc" />
|
||||
<path
|
||||
sodipodi:type="arc"
|
||||
style="fill:none;stroke:#f2edda;stroke-width:1.5;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="path5016"
|
||||
sodipodi:cx="225.89285"
|
||||
sodipodi:cy="542.54077"
|
||||
sodipodi:rx="5.1785712"
|
||||
sodipodi:ry="5.1785712"
|
||||
d="m 231.07142,542.54077 c 0,2.86005 -2.31852,5.17857 -5.17857,5.17857 -2.86004,0 -5.17857,-2.31852 -5.17857,-5.17857 0,-2.86004 2.31853,-5.17857 5.17857,-5.17857 2.86005,0 5.17857,2.31853 5.17857,5.17857 z"
|
||||
transform="translate(-136,-194)" />
|
||||
</g>
|
||||
<g
|
||||
transform="translate(654,162)"
|
||||
id="g3874"
|
||||
style="display:inline">
|
||||
<rect
|
||||
style="fill:#444444;fill-opacity:1;stroke:none"
|
||||
id="rect4564"
|
||||
width="24.748737"
|
||||
height="48.487324"
|
||||
x="-160.63824"
|
||||
y="335.38666" />
|
||||
<g
|
||||
id="g4572"
|
||||
transform="translate(-519.49492,-37.142857)">
|
||||
<rect
|
||||
y="377.95908"
|
||||
x="348.75516"
|
||||
height="4.2931485"
|
||||
width="3.9143078"
|
||||
id="rect4570"
|
||||
style="fill:#fffcfc;fill-opacity:1;stroke:none" />
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4568"
|
||||
d="m 358.85669,379.85312 -7.20209,0"
|
||||
style="fill:none;stroke:#f3c61b;stroke-width:2.13612175;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
</g>
|
||||
<g
|
||||
id="g4576"
|
||||
transform="translate(-519.49492,-27.142857)">
|
||||
<rect
|
||||
style="fill:#fffcfc;fill-opacity:1;stroke:none"
|
||||
id="rect4578"
|
||||
width="3.9143078"
|
||||
height="4.2931485"
|
||||
x="348.75516"
|
||||
y="377.95908" />
|
||||
<path
|
||||
style="fill:none;stroke:#f3c61b;stroke-width:2.13612175;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
d="m 358.85669,379.85312 -7.20209,0"
|
||||
id="path4580"
|
||||
inkscape:connector-curvature="0" />
|
||||
</g>
|
||||
<g
|
||||
transform="translate(-519.49492,-17.142857)"
|
||||
id="g4582">
|
||||
<rect
|
||||
y="377.95908"
|
||||
x="348.75516"
|
||||
height="4.2931485"
|
||||
width="3.9143078"
|
||||
id="rect4584"
|
||||
style="fill:#fffcfc;fill-opacity:1;stroke:none" />
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4586"
|
||||
d="m 358.85669,379.85312 -7.20209,0"
|
||||
style="fill:none;stroke:#f3c61b;stroke-width:2.13612175;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
</g>
|
||||
<g
|
||||
id="g4588"
|
||||
transform="translate(-519.49492,-7.1428571)">
|
||||
<rect
|
||||
style="fill:#fffcfc;fill-opacity:1;stroke:none"
|
||||
id="rect4590"
|
||||
width="3.9143078"
|
||||
height="4.2931485"
|
||||
x="348.75516"
|
||||
y="377.95908" />
|
||||
<path
|
||||
style="fill:none;stroke:#f3c61b;stroke-width:2.13612175;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
d="m 358.85669,379.85312 -7.20209,0"
|
||||
id="path4592"
|
||||
inkscape:connector-curvature="0" />
|
||||
</g>
|
||||
<g
|
||||
transform="translate(-519.49492,2.8571429)"
|
||||
id="g4594">
|
||||
<rect
|
||||
y="377.95908"
|
||||
x="348.75516"
|
||||
height="4.2931485"
|
||||
width="3.9143078"
|
||||
id="rect4596"
|
||||
style="fill:#fffcfc;fill-opacity:1;stroke:none" />
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4598"
|
||||
d="m 358.85669,379.85312 -7.20209,0"
|
||||
style="fill:none;stroke:#f3c61b;stroke-width:2.13612175;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
</g>
|
||||
<g
|
||||
id="g4600"
|
||||
transform="matrix(-1,0,0,1,222.80618,2.8571429)">
|
||||
<rect
|
||||
style="fill:#fffcfc;fill-opacity:1;stroke:none"
|
||||
id="rect4602"
|
||||
width="3.9143078"
|
||||
height="4.2931485"
|
||||
x="348.75516"
|
||||
y="377.95908" />
|
||||
<path
|
||||
style="fill:none;stroke:#f3c61b;stroke-width:2.13612175;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
d="m 358.85669,379.85312 -7.20209,0"
|
||||
id="path4604"
|
||||
inkscape:connector-curvature="0" />
|
||||
</g>
|
||||
<g
|
||||
transform="matrix(-1,0,0,1,222.80618,-7.1428571)"
|
||||
id="g4606">
|
||||
<rect
|
||||
y="377.95908"
|
||||
x="348.75516"
|
||||
height="4.2931485"
|
||||
width="3.9143078"
|
||||
id="rect4608"
|
||||
style="fill:#fffcfc;fill-opacity:1;stroke:none" />
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4610"
|
||||
d="m 358.85669,379.85312 -7.20209,0"
|
||||
style="fill:none;stroke:#f3c61b;stroke-width:2.13612175;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
</g>
|
||||
<g
|
||||
id="g4612"
|
||||
transform="matrix(-1,0,0,1,222.80618,-17.142857)">
|
||||
<rect
|
||||
style="fill:#fffcfc;fill-opacity:1;stroke:none"
|
||||
id="rect4614"
|
||||
width="3.9143078"
|
||||
height="4.2931485"
|
||||
x="348.75516"
|
||||
y="377.95908" />
|
||||
<path
|
||||
style="fill:none;stroke:#f3c61b;stroke-width:2.13612175;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
d="m 358.85669,379.85312 -7.20209,0"
|
||||
id="path4616"
|
||||
inkscape:connector-curvature="0" />
|
||||
</g>
|
||||
<g
|
||||
transform="matrix(-1,0,0,1,222.80618,-27.142857)"
|
||||
id="g4618">
|
||||
<rect
|
||||
y="377.95908"
|
||||
x="348.75516"
|
||||
height="4.2931485"
|
||||
width="3.9143078"
|
||||
id="rect4620"
|
||||
style="fill:#fffcfc;fill-opacity:1;stroke:none" />
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4622"
|
||||
d="m 358.85669,379.85312 -7.20209,0"
|
||||
style="fill:none;stroke:#f3c61b;stroke-width:2.13612175;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
</g>
|
||||
<g
|
||||
id="g4624"
|
||||
transform="matrix(-1,0,0,1,222.80618,-37.142857)">
|
||||
<rect
|
||||
style="fill:#fffcfc;fill-opacity:1;stroke:none"
|
||||
id="rect4626"
|
||||
width="3.9143078"
|
||||
height="4.2931485"
|
||||
x="348.75516"
|
||||
y="377.95908" />
|
||||
<path
|
||||
style="fill:none;stroke:#f3c61b;stroke-width:2.13612175;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
d="m 358.85669,379.85312 -7.20209,0"
|
||||
id="path4628"
|
||||
inkscape:connector-curvature="0" />
|
||||
</g>
|
||||
<path
|
||||
sodipodi:type="arc"
|
||||
style="fill:#f3c61b;fill-opacity:1;stroke:none"
|
||||
id="path4630"
|
||||
sodipodi:cx="365.99091"
|
||||
sodipodi:cy="381.8103"
|
||||
sodipodi:rx="1.8309015"
|
||||
sodipodi:ry="1.7046324"
|
||||
d="m 367.82181,381.8103 c 0,0.94145 -0.81973,1.70464 -1.8309,1.70464 -1.01118,0 -1.83091,-0.76319 -1.83091,-1.70464 0,-0.94144 0.81973,-1.70463 1.83091,-1.70463 1.01117,0 1.8309,0.76319 1.8309,1.70463 z"
|
||||
transform="translate(-520,-37.647933)" />
|
||||
<path
|
||||
transform="translate(-510,-37.647933)"
|
||||
d="m 367.82181,381.8103 c 0,0.94145 -0.81973,1.70464 -1.8309,1.70464 -1.01118,0 -1.83091,-0.76319 -1.83091,-1.70464 0,-0.94144 0.81973,-1.70463 1.83091,-1.70463 1.01117,0 1.8309,0.76319 1.8309,1.70463 z"
|
||||
sodipodi:ry="1.7046324"
|
||||
sodipodi:rx="1.8309015"
|
||||
sodipodi:cy="381.8103"
|
||||
sodipodi:cx="365.99091"
|
||||
id="path4632"
|
||||
style="fill:#f3c61b;fill-opacity:1;stroke:none"
|
||||
sodipodi:type="arc" />
|
||||
<path
|
||||
sodipodi:type="arc"
|
||||
style="fill:#f3c61b;fill-opacity:1;stroke:none"
|
||||
id="path4634"
|
||||
sodipodi:cx="365.99091"
|
||||
sodipodi:cy="381.8103"
|
||||
sodipodi:rx="1.8309015"
|
||||
sodipodi:ry="1.7046324"
|
||||
d="m 367.82181,381.8103 c 0,0.94145 -0.81973,1.70464 -1.8309,1.70464 -1.01118,0 -1.83091,-0.76319 -1.83091,-1.70464 0,-0.94144 0.81973,-1.70463 1.83091,-1.70463 1.01117,0 1.8309,0.76319 1.8309,1.70463 z"
|
||||
transform="translate(-510,-27.647933)" />
|
||||
<path
|
||||
transform="translate(-520,-27.647933)"
|
||||
d="m 367.82181,381.8103 c 0,0.94145 -0.81973,1.70464 -1.8309,1.70464 -1.01118,0 -1.83091,-0.76319 -1.83091,-1.70464 0,-0.94144 0.81973,-1.70463 1.83091,-1.70463 1.01117,0 1.8309,0.76319 1.8309,1.70463 z"
|
||||
sodipodi:ry="1.7046324"
|
||||
sodipodi:rx="1.8309015"
|
||||
sodipodi:cy="381.8103"
|
||||
sodipodi:cx="365.99091"
|
||||
id="path4636"
|
||||
style="fill:#f3c61b;fill-opacity:1;stroke:none"
|
||||
sodipodi:type="arc" />
|
||||
<path
|
||||
sodipodi:type="arc"
|
||||
style="fill:#f3c61b;fill-opacity:1;stroke:none"
|
||||
id="path4638"
|
||||
sodipodi:cx="365.99091"
|
||||
sodipodi:cy="381.8103"
|
||||
sodipodi:rx="1.8309015"
|
||||
sodipodi:ry="1.7046324"
|
||||
d="m 367.82181,381.8103 c 0,0.94145 -0.81973,1.70464 -1.8309,1.70464 -1.01118,0 -1.83091,-0.76319 -1.83091,-1.70464 0,-0.94144 0.81973,-1.70463 1.83091,-1.70463 1.01117,0 1.8309,0.76319 1.8309,1.70463 z"
|
||||
transform="translate(-520,-17.647933)" />
|
||||
<path
|
||||
transform="translate(-510,-17.647933)"
|
||||
d="m 367.82181,381.8103 c 0,0.94145 -0.81973,1.70464 -1.8309,1.70464 -1.01118,0 -1.83091,-0.76319 -1.83091,-1.70464 0,-0.94144 0.81973,-1.70463 1.83091,-1.70463 1.01117,0 1.8309,0.76319 1.8309,1.70463 z"
|
||||
sodipodi:ry="1.7046324"
|
||||
sodipodi:rx="1.8309015"
|
||||
sodipodi:cy="381.8103"
|
||||
sodipodi:cx="365.99091"
|
||||
id="path4640"
|
||||
style="fill:#f3c61b;fill-opacity:1;stroke:none"
|
||||
sodipodi:type="arc" />
|
||||
<path
|
||||
sodipodi:type="arc"
|
||||
style="fill:#f3c61b;fill-opacity:1;stroke:none"
|
||||
id="path4642"
|
||||
sodipodi:cx="365.99091"
|
||||
sodipodi:cy="381.8103"
|
||||
sodipodi:rx="1.8309015"
|
||||
sodipodi:ry="1.7046324"
|
||||
d="m 367.82181,381.8103 c 0,0.94145 -0.81973,1.70464 -1.8309,1.70464 -1.01118,0 -1.83091,-0.76319 -1.83091,-1.70464 0,-0.94144 0.81973,-1.70463 1.83091,-1.70463 1.01117,0 1.8309,0.76319 1.8309,1.70463 z"
|
||||
transform="translate(-510,-7.6479331)" />
|
||||
<path
|
||||
transform="translate(-520,-7.6479331)"
|
||||
d="m 367.82181,381.8103 c 0,0.94145 -0.81973,1.70464 -1.8309,1.70464 -1.01118,0 -1.83091,-0.76319 -1.83091,-1.70464 0,-0.94144 0.81973,-1.70463 1.83091,-1.70463 1.01117,0 1.8309,0.76319 1.8309,1.70463 z"
|
||||
sodipodi:ry="1.7046324"
|
||||
sodipodi:rx="1.8309015"
|
||||
sodipodi:cy="381.8103"
|
||||
sodipodi:cx="365.99091"
|
||||
id="path4644"
|
||||
style="fill:#f3c61b;fill-opacity:1;stroke:none"
|
||||
sodipodi:type="arc" />
|
||||
</g>
|
||||
<g
|
||||
id="g3730"
|
||||
transform="matrix(0,1,-1,0,593.68744,-47.73342)"
|
||||
style="display:inline">
|
||||
<rect
|
||||
style="fill:#bc781e;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect3732"
|
||||
width="6.5178571"
|
||||
height="5.0892859"
|
||||
x="422.11606"
|
||||
y="365.75504" />
|
||||
<rect
|
||||
y="365.75504"
|
||||
x="428.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect3734"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
<rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect3736"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="418.58929"
|
||||
y="365.75504" />
|
||||
</g>
|
||||
<g
|
||||
transform="matrix(0,1,-1,0,573.68744,-47.73342)"
|
||||
id="g3738"
|
||||
style="display:inline">
|
||||
<rect
|
||||
y="365.75504"
|
||||
x="422.11606"
|
||||
height="5.0892859"
|
||||
width="6.5178571"
|
||||
id="rect3740"
|
||||
style="fill:#bc781e;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
<rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect3742"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="428.58929"
|
||||
y="365.75504" />
|
||||
<rect
|
||||
y="365.75504"
|
||||
x="418.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect3744"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
</g>
|
||||
<g
|
||||
id="g3746"
|
||||
transform="matrix(0,1,-1,0,637.68744,-47.73342)"
|
||||
style="display:inline">
|
||||
<rect
|
||||
style="fill:#bc781e;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect3748"
|
||||
width="6.5178571"
|
||||
height="5.0892859"
|
||||
x="422.11606"
|
||||
y="365.75504" />
|
||||
<rect
|
||||
y="365.75504"
|
||||
x="428.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect3750"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
<rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect3752"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="418.58929"
|
||||
y="365.75504" />
|
||||
</g>
|
||||
<g
|
||||
transform="matrix(0,1,-1,0,657.68744,-47.73342)"
|
||||
id="g3754"
|
||||
style="display:inline">
|
||||
<rect
|
||||
y="365.75504"
|
||||
x="422.11606"
|
||||
height="5.0892859"
|
||||
width="6.5178571"
|
||||
id="rect3756"
|
||||
style="fill:#bc781e;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
<rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect3758"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="428.58929"
|
||||
y="365.75504" />
|
||||
<rect
|
||||
y="365.75504"
|
||||
x="418.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect3760"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
</g>
|
||||
<g
|
||||
id="g3762"
|
||||
transform="matrix(0,1,-1,0,681.68744,-27.73342)"
|
||||
style="display:inline">
|
||||
<rect
|
||||
style="fill:#bc781e;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect3764"
|
||||
width="6.5178571"
|
||||
height="5.0892859"
|
||||
x="422.11606"
|
||||
y="365.75504" />
|
||||
<rect
|
||||
y="365.75504"
|
||||
x="428.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect3766"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
<rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect3768"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="418.58929"
|
||||
y="365.75504" />
|
||||
</g>
|
||||
<g
|
||||
transform="matrix(0,1,-1,0,685.68744,10.26658)"
|
||||
id="g3770"
|
||||
style="display:inline">
|
||||
<rect
|
||||
y="365.75504"
|
||||
x="422.11606"
|
||||
height="5.0892859"
|
||||
width="6.5178571"
|
||||
id="rect3772"
|
||||
style="fill:#bc781e;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
<rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect3774"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="428.58929"
|
||||
y="365.75504" />
|
||||
<rect
|
||||
y="365.75504"
|
||||
x="418.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect3776"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
</g>
|
||||
<g
|
||||
id="g3778"
|
||||
transform="matrix(0,1,-1,0,671.68744,138.26658)"
|
||||
style="display:inline">
|
||||
<rect
|
||||
style="fill:#bc781e;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect3780"
|
||||
width="6.5178571"
|
||||
height="5.0892859"
|
||||
x="422.11606"
|
||||
y="365.75504" />
|
||||
<rect
|
||||
y="365.75504"
|
||||
x="428.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect3782"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
<rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect3784"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="418.58929"
|
||||
y="365.75504" />
|
||||
</g>
|
||||
<g
|
||||
transform="matrix(0,1,-1,0,737.68744,-25.73342)"
|
||||
id="g3786"
|
||||
style="display:inline">
|
||||
<rect
|
||||
y="365.75504"
|
||||
x="422.11606"
|
||||
height="5.0892859"
|
||||
width="6.5178571"
|
||||
id="rect3788"
|
||||
style="fill:#bc781e;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
<rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect3790"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="428.58929"
|
||||
y="365.75504" />
|
||||
<rect
|
||||
y="365.75504"
|
||||
x="418.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect3792"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
</g>
|
||||
<g
|
||||
id="g3794"
|
||||
transform="matrix(0,1,-1,0,777.68744,-3.73342)"
|
||||
style="display:inline">
|
||||
<rect
|
||||
style="fill:#bc781e;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect3796"
|
||||
width="6.5178571"
|
||||
height="5.0892859"
|
||||
x="422.11606"
|
||||
y="365.75504" />
|
||||
<rect
|
||||
y="365.75504"
|
||||
x="428.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect3798"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
<rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect3800"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="418.58929"
|
||||
y="365.75504" />
|
||||
</g>
|
||||
<g
|
||||
transform="matrix(0,1,-1,0,805.68744,62.26658)"
|
||||
id="g3802"
|
||||
style="display:inline">
|
||||
<rect
|
||||
y="365.75504"
|
||||
x="422.11606"
|
||||
height="5.0892859"
|
||||
width="6.5178571"
|
||||
id="rect3804"
|
||||
style="fill:#bc781e;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
<rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect3806"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="428.58929"
|
||||
y="365.75504" />
|
||||
<rect
|
||||
y="365.75504"
|
||||
x="418.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect3808"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
</g>
|
||||
<g
|
||||
id="g3810"
|
||||
transform="matrix(0,1,-1,0,819.68744,-17.73342)"
|
||||
style="display:inline">
|
||||
<rect
|
||||
style="fill:#bc781e;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect3812"
|
||||
width="6.5178571"
|
||||
height="5.0892859"
|
||||
x="422.11606"
|
||||
y="365.75504" />
|
||||
<rect
|
||||
y="365.75504"
|
||||
x="428.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect3814"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
<rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect3816"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="418.58929"
|
||||
y="365.75504" />
|
||||
</g>
|
||||
<g
|
||||
transform="matrix(0,1,-1,0,819.68744,-77.73342)"
|
||||
id="g3818"
|
||||
style="display:inline">
|
||||
<rect
|
||||
y="365.75504"
|
||||
x="422.11606"
|
||||
height="5.0892859"
|
||||
width="6.5178571"
|
||||
id="rect3820"
|
||||
style="fill:#bc781e;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
<rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect3822"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="428.58929"
|
||||
y="365.75504" />
|
||||
<rect
|
||||
y="365.75504"
|
||||
x="418.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect3824"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
</g>
|
||||
<g
|
||||
id="g3826"
|
||||
transform="matrix(0,1,-1,0,841.68744,-77.73342)"
|
||||
style="display:inline">
|
||||
<rect
|
||||
style="fill:#bc781e;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect3828"
|
||||
width="6.5178571"
|
||||
height="5.0892859"
|
||||
x="422.11606"
|
||||
y="365.75504" />
|
||||
<rect
|
||||
y="365.75504"
|
||||
x="428.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect3830"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
<rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect3832"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="418.58929"
|
||||
y="365.75504" />
|
||||
</g>
|
||||
<g
|
||||
transform="matrix(0,1,-1,0,755.68744,-115.73342)"
|
||||
id="g3834"
|
||||
style="display:inline">
|
||||
<rect
|
||||
y="365.75504"
|
||||
x="422.11606"
|
||||
height="5.0892859"
|
||||
width="6.5178571"
|
||||
id="rect3836"
|
||||
style="fill:#bc781e;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
<rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect3838"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="428.58929"
|
||||
y="365.75504" />
|
||||
<rect
|
||||
y="365.75504"
|
||||
x="418.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect3840"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
</g>
|
||||
<g
|
||||
id="g3842"
|
||||
transform="matrix(0,1,-1,0,625.68744,-121.73342)"
|
||||
style="display:inline">
|
||||
<rect
|
||||
style="fill:#bc781e;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect3844"
|
||||
width="6.5178571"
|
||||
height="5.0892859"
|
||||
x="422.11606"
|
||||
y="365.75504" />
|
||||
<rect
|
||||
y="365.75504"
|
||||
x="428.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect3846"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
<rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect3848"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="418.58929"
|
||||
y="365.75504" />
|
||||
</g>
|
||||
<g
|
||||
transform="matrix(0,1,-1,0,863.68744,-65.73342)"
|
||||
id="g3850"
|
||||
style="display:inline">
|
||||
<rect
|
||||
y="365.75504"
|
||||
x="422.11606"
|
||||
height="5.0892859"
|
||||
width="6.5178571"
|
||||
id="rect3852"
|
||||
style="fill:#bc781e;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
<rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect3854"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="428.58929"
|
||||
y="365.75504" />
|
||||
<rect
|
||||
y="365.75504"
|
||||
x="418.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect3856"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
</g>
|
||||
<g
|
||||
id="g3858"
|
||||
transform="matrix(0,1,-1,0,889.68744,-65.73342)"
|
||||
style="display:inline">
|
||||
<rect
|
||||
style="fill:#bc781e;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect3860"
|
||||
width="6.5178571"
|
||||
height="5.0892859"
|
||||
x="422.11606"
|
||||
y="365.75504" />
|
||||
<rect
|
||||
y="365.75504"
|
||||
x="428.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect3862"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
<rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect3864"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="418.58929"
|
||||
y="365.75504" />
|
||||
</g>
|
||||
<g
|
||||
transform="matrix(0,1,-1,0,621.68744,190.26658)"
|
||||
id="g3866"
|
||||
style="display:inline">
|
||||
<rect
|
||||
y="365.75504"
|
||||
x="422.11606"
|
||||
height="5.0892859"
|
||||
width="6.5178571"
|
||||
id="rect3868"
|
||||
style="fill:#bc781e;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
<rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect3870"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="428.58929"
|
||||
y="365.75504" />
|
||||
<rect
|
||||
y="365.75504"
|
||||
x="418.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect3872"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
</g>
|
||||
<g
|
||||
transform="translate(-140,-21.14286)"
|
||||
id="g3915"
|
||||
style="display:inline">
|
||||
<rect
|
||||
y="365.75504"
|
||||
x="422.11606"
|
||||
height="5.0892859"
|
||||
width="6.5178571"
|
||||
id="rect3917"
|
||||
style="fill:#bc781e;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
<rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect3919"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="428.58929"
|
||||
y="365.75504" />
|
||||
<rect
|
||||
y="365.75504"
|
||||
x="418.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect3921"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
</g>
|
||||
<g
|
||||
id="g3923"
|
||||
transform="translate(-68,-17.14286)"
|
||||
style="display:inline">
|
||||
<rect
|
||||
style="fill:#bc781e;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect3925"
|
||||
width="6.5178571"
|
||||
height="5.0892859"
|
||||
x="422.11606"
|
||||
y="365.75504" />
|
||||
<rect
|
||||
y="365.75504"
|
||||
x="428.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect3927"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
<rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect3929"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="418.58929"
|
||||
y="365.75504" />
|
||||
</g>
|
||||
<g
|
||||
transform="translate(-68,4.85714)"
|
||||
id="g3931"
|
||||
style="display:inline">
|
||||
<rect
|
||||
y="365.75504"
|
||||
x="422.11606"
|
||||
height="5.0892859"
|
||||
width="6.5178571"
|
||||
id="rect3933"
|
||||
style="fill:#bc781e;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
<rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect3935"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="428.58929"
|
||||
y="365.75504" />
|
||||
<rect
|
||||
y="365.75504"
|
||||
x="418.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect3937"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
</g>
|
||||
<g
|
||||
id="g3940"
|
||||
transform="translate(74,82.85714)"
|
||||
style="display:inline">
|
||||
<rect
|
||||
style="fill:#bc781e;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect3942"
|
||||
width="6.5178571"
|
||||
height="5.0892859"
|
||||
x="422.11606"
|
||||
y="365.75504" />
|
||||
<rect
|
||||
y="365.75504"
|
||||
x="428.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect3944"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
<rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect3946"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="418.58929"
|
||||
y="365.75504" />
|
||||
</g>
|
||||
<g
|
||||
transform="translate(112,82.85714)"
|
||||
id="g3948"
|
||||
style="display:inline">
|
||||
<rect
|
||||
y="365.75504"
|
||||
x="422.11606"
|
||||
height="5.0892859"
|
||||
width="6.5178571"
|
||||
id="rect3950"
|
||||
style="fill:#bc781e;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
<rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect3952"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="428.58929"
|
||||
y="365.75504" />
|
||||
<rect
|
||||
y="365.75504"
|
||||
x="418.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect3954"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
</g>
|
||||
<g
|
||||
id="g3956"
|
||||
transform="translate(76,110.85714)"
|
||||
style="display:inline">
|
||||
<rect
|
||||
style="fill:#bc781e;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect3958"
|
||||
width="6.5178571"
|
||||
height="5.0892859"
|
||||
x="422.11606"
|
||||
y="365.75504" />
|
||||
<rect
|
||||
y="365.75504"
|
||||
x="428.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect3960"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
<rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect3962"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="418.58929"
|
||||
y="365.75504" />
|
||||
</g>
|
||||
<g
|
||||
transform="translate(42,210.85714)"
|
||||
id="g3964"
|
||||
style="display:inline">
|
||||
<rect
|
||||
y="365.75504"
|
||||
x="422.11606"
|
||||
height="5.0892859"
|
||||
width="6.5178571"
|
||||
id="rect3966"
|
||||
style="fill:#bc781e;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
<rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect3968"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="428.58929"
|
||||
y="365.75504" />
|
||||
<rect
|
||||
y="365.75504"
|
||||
x="418.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect3970"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
</g>
|
||||
<g
|
||||
id="g3972"
|
||||
transform="translate(0,190.85714)"
|
||||
style="display:inline">
|
||||
<rect
|
||||
style="fill:#bc781e;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect3974"
|
||||
width="6.5178571"
|
||||
height="5.0892859"
|
||||
x="422.11606"
|
||||
y="365.75504" />
|
||||
<rect
|
||||
y="365.75504"
|
||||
x="428.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect3976"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
<rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect3978"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="418.58929"
|
||||
y="365.75504" />
|
||||
</g>
|
||||
<g
|
||||
transform="matrix(0,1.5210261,-2.1909167,0,1090.3626,-84.90041)"
|
||||
id="g3980"
|
||||
style="display:inline">
|
||||
<rect
|
||||
y="365.75504"
|
||||
x="422.11606"
|
||||
height="5.0892859"
|
||||
width="6.5178571"
|
||||
id="rect3982"
|
||||
style="fill:#a9814d;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
<rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect3984"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="428.58929"
|
||||
y="365.75504" />
|
||||
<rect
|
||||
y="365.75504"
|
||||
x="418.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect3986"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
</g>
|
||||
<g
|
||||
id="g4764"
|
||||
transform="matrix(0,1.5210261,-2.1909167,0,1080.3626,-30.90041)"
|
||||
style="display:inline">
|
||||
<rect
|
||||
style="fill:#a9814d;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect4766"
|
||||
width="6.5178571"
|
||||
height="5.0892859"
|
||||
x="422.11606"
|
||||
y="365.75504" />
|
||||
<rect
|
||||
y="365.75504"
|
||||
x="428.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect4768"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
<rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect4770"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="418.58929"
|
||||
y="365.75504" />
|
||||
</g>
|
||||
<g
|
||||
transform="matrix(0,1.5210261,-2.1909167,0,1296.3626,-40.90041)"
|
||||
id="g4772"
|
||||
style="display:inline">
|
||||
<rect
|
||||
y="365.75504"
|
||||
x="422.11606"
|
||||
height="5.0892859"
|
||||
width="6.5178571"
|
||||
id="rect4774"
|
||||
style="fill:#a9814d;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
<rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect4776"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="428.58929"
|
||||
y="365.75504" />
|
||||
<rect
|
||||
y="365.75504"
|
||||
x="418.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect4778"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
</g>
|
||||
<g
|
||||
id="g4780"
|
||||
transform="matrix(1.5210261,0,0,2.1909167,-191.55781,-172.80784)"
|
||||
style="display:inline">
|
||||
<rect
|
||||
style="fill:#a9814d;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect4782"
|
||||
width="6.5178571"
|
||||
height="5.0892859"
|
||||
x="422.11606"
|
||||
y="365.75504" />
|
||||
<rect
|
||||
y="365.75504"
|
||||
x="428.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect4784"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
<rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect4786"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="418.58929"
|
||||
y="365.75504" />
|
||||
</g>
|
||||
<g
|
||||
id="g4788"
|
||||
transform="matrix(0,1.5210261,-2.1909167,0,1146.3626,-206.90042)"
|
||||
style="display:inline">
|
||||
<rect
|
||||
style="fill:#a9814d;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect4790"
|
||||
width="6.5178571"
|
||||
height="5.0892859"
|
||||
x="422.11606"
|
||||
y="365.75504" />
|
||||
<rect
|
||||
y="365.75504"
|
||||
x="428.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect4792"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
<rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect4794"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="418.58929"
|
||||
y="365.75504" />
|
||||
</g>
|
||||
<g
|
||||
id="g4801"
|
||||
transform="translate(-208,206.85714)"
|
||||
style="display:inline">
|
||||
<rect
|
||||
style="fill:#312d29;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect4803"
|
||||
width="6.5178571"
|
||||
height="5.0892859"
|
||||
x="422.11606"
|
||||
y="365.75504" />
|
||||
<rect
|
||||
y="365.75504"
|
||||
x="428.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect4805"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
<rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect4807"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="418.58929"
|
||||
y="365.75504" />
|
||||
</g>
|
||||
<g
|
||||
transform="translate(-160,220.85714)"
|
||||
id="g4809"
|
||||
style="display:inline">
|
||||
<rect
|
||||
y="365.75504"
|
||||
x="422.11606"
|
||||
height="5.0892859"
|
||||
width="6.5178571"
|
||||
id="rect4811"
|
||||
style="fill:#312d29;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
<rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect4813"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="428.58929"
|
||||
y="365.75504" />
|
||||
<rect
|
||||
y="365.75504"
|
||||
x="418.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect4815"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
</g>
|
||||
<g
|
||||
id="g4817"
|
||||
transform="matrix(0,-1,1,0,-106.92467,984.53183)"
|
||||
style="display:inline">
|
||||
<rect
|
||||
style="fill:#312d29;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect4819"
|
||||
width="6.5178571"
|
||||
height="5.0892859"
|
||||
x="422.11606"
|
||||
y="365.75504" />
|
||||
<rect
|
||||
y="365.75504"
|
||||
x="428.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect4821"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
<rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect4823"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="418.58929"
|
||||
y="365.75504" />
|
||||
</g>
|
||||
<g
|
||||
transform="matrix(0,-1,1,0,61.07533,846.53183)"
|
||||
id="g4825"
|
||||
style="display:inline">
|
||||
<rect
|
||||
y="365.75504"
|
||||
x="422.11606"
|
||||
height="5.0892859"
|
||||
width="6.5178571"
|
||||
id="rect4827"
|
||||
style="fill:#312d29;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
<rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect4829"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="428.58929"
|
||||
y="365.75504" />
|
||||
<rect
|
||||
y="365.75504"
|
||||
x="418.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect4831"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
</g>
|
||||
<g
|
||||
id="g4833"
|
||||
transform="matrix(0,-1,1,0,179.07533,830.53183)"
|
||||
style="display:inline">
|
||||
<rect
|
||||
style="fill:#312d29;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect4835"
|
||||
width="6.5178571"
|
||||
height="5.0892859"
|
||||
x="422.11606"
|
||||
y="365.75504" />
|
||||
<rect
|
||||
y="365.75504"
|
||||
x="428.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect4837"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
<rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect4839"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="418.58929"
|
||||
y="365.75504" />
|
||||
</g>
|
||||
<g
|
||||
id="g4920"
|
||||
style="display:inline">
|
||||
<g
|
||||
style="display:inline"
|
||||
id="g4871"
|
||||
transform="matrix(0,1.4970318,-1,0,849.26635,-33.0226)">
|
||||
<rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-386.60983"
|
||||
height="4.0486217"
|
||||
width="10.985409"
|
||||
id="rect4867"
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none" />
|
||||
<rect
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none"
|
||||
id="rect4869"
|
||||
width="2.5253813"
|
||||
height="4.0486217"
|
||||
x="-383.45309"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" />
|
||||
</g>
|
||||
<g
|
||||
style="display:inline"
|
||||
transform="matrix(0,1.4970318,-1,0,849.26635,-23.0226)"
|
||||
id="g4875">
|
||||
<rect
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none"
|
||||
id="rect4877"
|
||||
width="10.985409"
|
||||
height="4.0486217"
|
||||
x="-386.60983"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" />
|
||||
<rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-383.45309"
|
||||
height="4.0486217"
|
||||
width="2.5253813"
|
||||
id="rect4879"
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none" />
|
||||
</g>
|
||||
<g
|
||||
style="display:inline"
|
||||
id="g4881"
|
||||
transform="matrix(0,1.4970318,-1,0,849.26635,-13.0226)">
|
||||
<rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-386.60983"
|
||||
height="4.0486217"
|
||||
width="10.985409"
|
||||
id="rect4883"
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none" />
|
||||
<rect
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none"
|
||||
id="rect4885"
|
||||
width="2.5253813"
|
||||
height="4.0486217"
|
||||
x="-383.45309"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" />
|
||||
</g>
|
||||
<g
|
||||
style="display:inline"
|
||||
transform="matrix(0,1.4970318,1,0,55.91598,-13.0226)"
|
||||
id="g4887">
|
||||
<rect
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none"
|
||||
id="rect4889"
|
||||
width="10.985409"
|
||||
height="4.0486217"
|
||||
x="-386.60983"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" />
|
||||
<rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-383.45309"
|
||||
height="4.0486217"
|
||||
width="2.5253813"
|
||||
id="rect4891"
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none" />
|
||||
</g>
|
||||
<g
|
||||
style="display:inline"
|
||||
id="g4899"
|
||||
transform="matrix(0,1.4970318,1,0,55.91598,-33.0226)">
|
||||
<rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-386.60983"
|
||||
height="4.0486217"
|
||||
width="10.985409"
|
||||
id="rect4901"
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none" />
|
||||
<rect
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none"
|
||||
id="rect4903"
|
||||
width="2.5253813"
|
||||
height="4.0486217"
|
||||
x="-383.45309"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" />
|
||||
</g>
|
||||
<rect
|
||||
style="fill:#6a6a6a;fill-opacity:1;stroke:#000000;stroke-width:2;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect4841"
|
||||
width="18.687822"
|
||||
height="31.819805"
|
||||
x="443.12988"
|
||||
y="590.15265"
|
||||
ry="1.5" />
|
||||
</g>
|
||||
<g
|
||||
transform="matrix(0,1,-1,0,904.65372,155.47139)"
|
||||
id="g4938"
|
||||
style="display:inline">
|
||||
<g
|
||||
transform="matrix(0,1.4970318,-1,0,849.26635,-33.0226)"
|
||||
id="g4940"
|
||||
style="display:inline">
|
||||
<rect
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none"
|
||||
id="rect4942"
|
||||
width="10.985409"
|
||||
height="4.0486217"
|
||||
x="-386.60983"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" />
|
||||
<rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-383.45309"
|
||||
height="4.0486217"
|
||||
width="2.5253813"
|
||||
id="rect4944"
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none" />
|
||||
</g>
|
||||
<g
|
||||
id="g4946"
|
||||
transform="matrix(0,1.4970318,-1,0,849.26635,-23.0226)"
|
||||
style="display:inline">
|
||||
<rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-386.60983"
|
||||
height="4.0486217"
|
||||
width="10.985409"
|
||||
id="rect4948"
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none" />
|
||||
<rect
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none"
|
||||
id="rect4950"
|
||||
width="2.5253813"
|
||||
height="4.0486217"
|
||||
x="-383.45309"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" />
|
||||
</g>
|
||||
<g
|
||||
transform="matrix(0,1.4970318,-1,0,849.26635,-13.0226)"
|
||||
id="g4952"
|
||||
style="display:inline">
|
||||
<rect
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none"
|
||||
id="rect4954"
|
||||
width="10.985409"
|
||||
height="4.0486217"
|
||||
x="-386.60983"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" />
|
||||
<rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-383.45309"
|
||||
height="4.0486217"
|
||||
width="2.5253813"
|
||||
id="rect4956"
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none" />
|
||||
</g>
|
||||
<g
|
||||
id="g4958"
|
||||
transform="matrix(0,1.4970318,1,0,55.91598,-13.0226)"
|
||||
style="display:inline">
|
||||
<rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-386.60983"
|
||||
height="4.0486217"
|
||||
width="10.985409"
|
||||
id="rect4960"
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none" />
|
||||
<rect
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none"
|
||||
id="rect4962"
|
||||
width="2.5253813"
|
||||
height="4.0486217"
|
||||
x="-383.45309"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" />
|
||||
</g>
|
||||
<g
|
||||
transform="matrix(0,1.4970318,1,0,55.91598,-33.0226)"
|
||||
id="g4964"
|
||||
style="display:inline">
|
||||
<rect
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none"
|
||||
id="rect4966"
|
||||
width="10.985409"
|
||||
height="4.0486217"
|
||||
x="-386.60983"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" />
|
||||
<rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-383.45309"
|
||||
height="4.0486217"
|
||||
width="2.5253813"
|
||||
id="rect4968"
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none" />
|
||||
</g>
|
||||
<rect
|
||||
ry="1.5"
|
||||
y="590.15265"
|
||||
x="443.12988"
|
||||
height="31.819805"
|
||||
width="18.687822"
|
||||
id="rect4970"
|
||||
style="fill:#6a6a6a;fill-opacity:1;stroke:#000000;stroke-width:2;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
</g>
|
||||
<g
|
||||
id="g4980"
|
||||
transform="matrix(0,-1,1,0,63.07533,738.53183)"
|
||||
style="display:inline">
|
||||
<rect
|
||||
style="fill:#312d29;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect4982"
|
||||
width="6.5178571"
|
||||
height="5.0892859"
|
||||
x="422.11606"
|
||||
y="365.75504" />
|
||||
<rect
|
||||
y="365.75504"
|
||||
x="428.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect4984"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
<rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect4986"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="418.58929"
|
||||
y="365.75504" />
|
||||
</g>
|
||||
<path
|
||||
sodipodi:nodetypes="cccccccc"
|
||||
transform="translate(188.57143,331.57648)"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4988"
|
||||
d="m 170.71578,-0.54828875 15.65736,0 0,-32.82995725 17.1726,0 -25.00128,-25.001276 -25.75889,25.75889 17.93021,0 z"
|
||||
style="fill:#ffffff;fill-opacity:1;stroke:#ffffff;stroke-width:2;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
<g
|
||||
transform="matrix(0,-1,1,0,-64.92467,932.53183)"
|
||||
id="g4992"
|
||||
style="display:inline">
|
||||
<rect
|
||||
y="365.75504"
|
||||
x="422.11606"
|
||||
height="5.0892859"
|
||||
width="6.5178571"
|
||||
id="rect4994"
|
||||
style="fill:#312d29;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
<rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect4996"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="428.58929"
|
||||
y="365.75504" />
|
||||
<rect
|
||||
y="365.75504"
|
||||
x="418.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect4998"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
</g>
|
||||
<g
|
||||
id="g5000"
|
||||
transform="matrix(0,-1,1,0,-120.92467,914.53183)"
|
||||
style="display:inline">
|
||||
<rect
|
||||
style="fill:#878380;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect5002"
|
||||
width="6.5178571"
|
||||
height="5.0892859"
|
||||
x="422.11606"
|
||||
y="365.75504" />
|
||||
<rect
|
||||
y="365.75504"
|
||||
x="428.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect5004"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
<rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect5006"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="418.58929"
|
||||
y="365.75504" />
|
||||
</g>
|
||||
<g
|
||||
transform="matrix(0,-1,1,0,-120.92467,952.53183)"
|
||||
id="g5008"
|
||||
style="display:inline">
|
||||
<rect
|
||||
y="365.75504"
|
||||
x="422.11606"
|
||||
height="5.0892859"
|
||||
width="6.5178571"
|
||||
id="rect5010"
|
||||
style="fill:#878380;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
<rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect5012"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="428.58929"
|
||||
y="365.75504" />
|
||||
<rect
|
||||
y="365.75504"
|
||||
x="418.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect5014"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
</g>
|
||||
<rect
|
||||
transform="translate(188.57143,331.57648)"
|
||||
y="269.42856"
|
||||
x="140.71428"
|
||||
height="52.142857"
|
||||
width="89.285713"
|
||||
id="rect5020"
|
||||
style="fill:#fffcfc;fill-opacity:1;stroke:#828282;stroke-width:2;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
<g
|
||||
transform="matrix(-1.4970318,0,0,1,974.62682,213.03078)"
|
||||
id="g4964-3"
|
||||
style="display:inline">
|
||||
<rect
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none"
|
||||
id="rect4966-2"
|
||||
width="10.985409"
|
||||
height="4.0486217"
|
||||
x="-386.60983"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" />
|
||||
<rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-383.45309"
|
||||
height="4.0486217"
|
||||
width="2.5253813"
|
||||
id="rect4968-1"
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none" />
|
||||
</g>
|
||||
<g
|
||||
style="display:inline"
|
||||
id="g5046"
|
||||
transform="matrix(-1.4970318,0,0,1,984.62682,213.03078)">
|
||||
<rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-386.60983"
|
||||
height="4.0486217"
|
||||
width="10.985409"
|
||||
id="rect5048"
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none" />
|
||||
<rect
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none"
|
||||
id="rect5050"
|
||||
width="2.5253813"
|
||||
height="4.0486217"
|
||||
x="-383.45309"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" />
|
||||
</g>
|
||||
<g
|
||||
transform="matrix(-1.4970318,0,0,1,994.62682,213.03078)"
|
||||
id="g5052"
|
||||
style="display:inline">
|
||||
<rect
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none"
|
||||
id="rect5054"
|
||||
width="10.985409"
|
||||
height="4.0486217"
|
||||
x="-386.60983"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" />
|
||||
<rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-383.45309"
|
||||
height="4.0486217"
|
||||
width="2.5253813"
|
||||
id="rect5056"
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none" />
|
||||
</g>
|
||||
<g
|
||||
style="display:inline"
|
||||
id="g5058"
|
||||
transform="matrix(-1.4970318,0,0,1,1004.6268,213.03078)">
|
||||
<rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-386.60983"
|
||||
height="4.0486217"
|
||||
width="10.985409"
|
||||
id="rect5060"
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none" />
|
||||
<rect
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none"
|
||||
id="rect5062"
|
||||
width="2.5253813"
|
||||
height="4.0486217"
|
||||
x="-383.45309"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" />
|
||||
</g>
|
||||
<g
|
||||
transform="matrix(-1.4970318,0,0,1,1014.6268,213.03078)"
|
||||
id="g5064"
|
||||
style="display:inline">
|
||||
<rect
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none"
|
||||
id="rect5066"
|
||||
width="10.985409"
|
||||
height="4.0486217"
|
||||
x="-386.60983"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" />
|
||||
<rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-383.45309"
|
||||
height="4.0486217"
|
||||
width="2.5253813"
|
||||
id="rect5068"
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none" />
|
||||
</g>
|
||||
<g
|
||||
style="display:inline"
|
||||
id="g5070"
|
||||
transform="matrix(-1.4970318,0,0,1,1024.6268,213.03078)">
|
||||
<rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-386.60983"
|
||||
height="4.0486217"
|
||||
width="10.985409"
|
||||
id="rect5072"
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none" />
|
||||
<rect
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none"
|
||||
id="rect5074"
|
||||
width="2.5253813"
|
||||
height="4.0486217"
|
||||
x="-383.45309"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" />
|
||||
</g>
|
||||
</g>
|
||||
</g>
|
||||
</svg>
|
After Width: | Height: | Size: 122 KiB |
After Width: | Height: | Size: 239 KiB |
2646
ground/openpilotgcs/src/plugins/uploader/images/deviceID-0401.svg
Normal file
@ -0,0 +1,2646 @@
|
||||
<?xml version="1.0" encoding="UTF-8" standalone="no"?>
|
||||
<!-- Created with Inkscape (http://www.inkscape.org/) -->
|
||||
|
||||
<svg
|
||||
xmlns:dc="http://purl.org/dc/elements/1.1/"
|
||||
xmlns:cc="http://creativecommons.org/ns#"
|
||||
xmlns:rdf="http://www.w3.org/1999/02/22-rdf-syntax-ns#"
|
||||
xmlns:svg="http://www.w3.org/2000/svg"
|
||||
xmlns="http://www.w3.org/2000/svg"
|
||||
xmlns:sodipodi="http://sodipodi.sourceforge.net/DTD/sodipodi-0.dtd"
|
||||
xmlns:inkscape="http://www.inkscape.org/namespaces/inkscape"
|
||||
id="svg3578"
|
||||
version="1.1"
|
||||
inkscape:version="0.48.0 r9654"
|
||||
width="217.16675"
|
||||
height="212.0625"
|
||||
xml:space="preserve"
|
||||
sodipodi:docname="CopterControl-v1.svg"><metadata
|
||||
id="metadata3584"><rdf:RDF><cc:Work
|
||||
rdf:about=""><dc:format>image/svg+xml</dc:format><dc:type
|
||||
rdf:resource="http://purl.org/dc/dcmitype/StillImage" /><dc:title></dc:title></cc:Work></rdf:RDF></metadata><defs
|
||||
id="defs3582"><clipPath
|
||||
clipPathUnits="userSpaceOnUse"
|
||||
id="clipPath3596"><path
|
||||
d="M 0,0 662,0 662,675 0,675 0,0 z"
|
||||
id="path3598"
|
||||
inkscape:connector-curvature="0" /></clipPath></defs><sodipodi:namedview
|
||||
pagecolor="#ffffff"
|
||||
bordercolor="#666666"
|
||||
borderopacity="1"
|
||||
objecttolerance="10"
|
||||
gridtolerance="10"
|
||||
guidetolerance="10"
|
||||
inkscape:pageopacity="0"
|
||||
inkscape:pageshadow="2"
|
||||
inkscape:window-width="1366"
|
||||
inkscape:window-height="691"
|
||||
id="namedview3580"
|
||||
showgrid="false"
|
||||
inkscape:zoom="1.4596704"
|
||||
inkscape:cx="74.195835"
|
||||
inkscape:cy="113.87434"
|
||||
inkscape:window-x="0"
|
||||
inkscape:window-y="24"
|
||||
inkscape:window-maximized="1"
|
||||
inkscape:current-layer="layer2"
|
||||
fit-margin-top="0"
|
||||
fit-margin-left="0"
|
||||
fit-margin-right="0"
|
||||
fit-margin-bottom="0" /><g
|
||||
inkscape:groupmode="layer"
|
||||
id="layer2"
|
||||
inkscape:label="Rendering#1"
|
||||
style="display:inline"
|
||||
transform="translate(-40.177007,-31.1875)"><g
|
||||
id="device"
|
||||
inkscape:label="#g15334"><rect
|
||||
rx="13.079585"
|
||||
ry="10"
|
||||
y="32.199471"
|
||||
x="46.668976"
|
||||
height="210.03767"
|
||||
width="209.67079"
|
||||
id="rect9798"
|
||||
style="fill:#171717;fill-opacity:1;stroke:#000000;stroke-width:2;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><g
|
||||
transform="translate(-311.74173,-199.45)"
|
||||
id="g4318"
|
||||
style="display:inline"><rect
|
||||
y="365.75504"
|
||||
x="422.11606"
|
||||
height="5.0892859"
|
||||
width="6.5178571"
|
||||
id="rect4320"
|
||||
style="fill:#312d29;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect4322"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="428.58929"
|
||||
y="365.75504" /><rect
|
||||
y="365.75504"
|
||||
x="418.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect4324"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /></g><g
|
||||
transform="matrix(0,-1,1,0,-158.96398,620.23853)"
|
||||
id="g4406"
|
||||
style="display:inline"><rect
|
||||
y="365.75504"
|
||||
x="422.11606"
|
||||
height="5.0892859"
|
||||
width="6.5178571"
|
||||
id="rect4408"
|
||||
style="fill:#312d29;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect4410"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="428.58929"
|
||||
y="365.75504" /><rect
|
||||
y="365.75504"
|
||||
x="418.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect4412"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /></g><g
|
||||
style="display:inline"
|
||||
id="g10505"
|
||||
transform="translate(-238.1085,-287.13166)"><rect
|
||||
style="fill:#312d29;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect10507"
|
||||
width="6.5178571"
|
||||
height="5.0892859"
|
||||
x="422.11606"
|
||||
y="365.75504" /><rect
|
||||
y="365.75504"
|
||||
x="428.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect10509"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect10511"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="418.58929"
|
||||
y="365.75504" /></g><g
|
||||
transform="translate(-297.20885,-185.40155)"
|
||||
id="g10513"
|
||||
style="display:inline"><rect
|
||||
y="365.75504"
|
||||
x="422.11606"
|
||||
height="5.0892859"
|
||||
width="6.5178571"
|
||||
id="rect10515"
|
||||
style="fill:#312d29;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect10517"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="428.58929"
|
||||
y="365.75504" /><rect
|
||||
y="365.75504"
|
||||
x="418.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect10519"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /></g><g
|
||||
id="g4225"
|
||||
style="display:inline"
|
||||
transform="translate(-324.12933,-188.57649)"><rect
|
||||
style="fill:#bc781e;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect4219"
|
||||
width="6.5178571"
|
||||
height="5.0892859"
|
||||
x="422.11606"
|
||||
y="365.75504" /><rect
|
||||
y="365.75504"
|
||||
x="428.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect4221"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect4223"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="418.58929"
|
||||
y="365.75504" /></g><g
|
||||
transform="translate(-229.42344,-179.37234)"
|
||||
style="display:inline"
|
||||
id="g10548"><rect
|
||||
y="365.75504"
|
||||
x="422.11606"
|
||||
height="5.0892859"
|
||||
width="6.5178571"
|
||||
id="rect10550"
|
||||
style="fill:#bc781e;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect10552"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="428.58929"
|
||||
y="365.75504" /><rect
|
||||
y="365.75504"
|
||||
x="418.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect10554"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /></g><g
|
||||
id="g10556"
|
||||
style="display:inline"
|
||||
transform="translate(-230.15008,-167.50383)"><rect
|
||||
style="fill:#bc781e;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect10558"
|
||||
width="6.5178571"
|
||||
height="5.0892859"
|
||||
x="422.11606"
|
||||
y="365.75504" /><rect
|
||||
y="365.75504"
|
||||
x="428.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect10560"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect10562"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="418.58929"
|
||||
y="365.75504" /></g><g
|
||||
transform="translate(-235.23659,-253.7322)"
|
||||
style="display:inline"
|
||||
id="g10564"><rect
|
||||
y="365.75504"
|
||||
x="422.11606"
|
||||
height="5.0892859"
|
||||
width="6.5178571"
|
||||
id="rect10566"
|
||||
style="fill:#bc781e;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect10568"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="428.58929"
|
||||
y="365.75504" /><rect
|
||||
y="365.75504"
|
||||
x="418.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect10570"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /></g><g
|
||||
id="g10572"
|
||||
style="display:inline"
|
||||
transform="translate(-214.16393,-327.60763)"><rect
|
||||
style="fill:#bc781e;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect10574"
|
||||
width="6.5178571"
|
||||
height="5.0892859"
|
||||
x="422.11606"
|
||||
y="365.75504" /><rect
|
||||
y="365.75504"
|
||||
x="428.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect10576"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect10578"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="418.58929"
|
||||
y="365.75504" /></g><g
|
||||
id="g4414"
|
||||
transform="translate(-365.77251,-288.34483)"
|
||||
style="display:inline"><rect
|
||||
style="fill:#0052ff;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect4416"
|
||||
width="6.5178571"
|
||||
height="5.0892859"
|
||||
x="422.11606"
|
||||
y="365.75504" /><rect
|
||||
y="365.75504"
|
||||
x="428.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect4418"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect4420"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="418.58929"
|
||||
y="365.75504" /></g><g
|
||||
id="g10667"
|
||||
style="display:inline"
|
||||
transform="translate(-466.1013,-470.16522)"><rect
|
||||
style="fill:#ff7900;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect4432"
|
||||
width="6.5178571"
|
||||
height="5.0892859"
|
||||
x="522.11609"
|
||||
y="559.755" /><rect
|
||||
y="559.755"
|
||||
x="528.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect4434"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect4436"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="518.58929"
|
||||
y="559.755" /></g><g
|
||||
transform="matrix(0,1,-1,0,476.81179,-372.57224)"
|
||||
id="g4278"
|
||||
style="display:inline"><rect
|
||||
y="365.75504"
|
||||
x="422.11606"
|
||||
height="5.0892859"
|
||||
width="6.5178571"
|
||||
id="rect4280"
|
||||
style="fill:#bc781e;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect4282"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="428.58929"
|
||||
y="365.75504" /><rect
|
||||
y="365.75504"
|
||||
x="418.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect4284"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /></g><g
|
||||
style="display:inline"
|
||||
id="g10761"
|
||||
transform="matrix(0,1,-1,0,476.81179,-340.57224)"><rect
|
||||
style="fill:#bc781e;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect10763"
|
||||
width="6.5178571"
|
||||
height="5.0892859"
|
||||
x="422.11606"
|
||||
y="365.75504" /><rect
|
||||
y="365.75504"
|
||||
x="428.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect10765"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect10767"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="418.58929"
|
||||
y="365.75504" /></g><g
|
||||
transform="matrix(0,1,-1,0,531.29622,-332.15009)"
|
||||
id="g10769"
|
||||
style="display:inline"><rect
|
||||
y="365.75504"
|
||||
x="422.11606"
|
||||
height="5.0892859"
|
||||
width="6.5178571"
|
||||
id="rect10771"
|
||||
style="fill:#bc781e;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect10773"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="428.58929"
|
||||
y="365.75504" /><rect
|
||||
y="365.75504"
|
||||
x="418.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect10775"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /></g><g
|
||||
style="display:inline"
|
||||
id="g10777"
|
||||
transform="matrix(0,1,-1,0,453.06093,-235.02206)"><rect
|
||||
style="fill:#bc781e;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect10779"
|
||||
width="6.5178571"
|
||||
height="5.0892859"
|
||||
x="422.11606"
|
||||
y="365.75504" /><rect
|
||||
y="365.75504"
|
||||
x="428.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect10781"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect10783"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="418.58929"
|
||||
y="365.75504" /></g><g
|
||||
transform="matrix(0,1,-1,0,453.06093,-213.9494)"
|
||||
id="g10785"
|
||||
style="display:inline"><rect
|
||||
y="365.75504"
|
||||
x="422.11606"
|
||||
height="5.0892859"
|
||||
width="6.5178571"
|
||||
id="rect10787"
|
||||
style="fill:#bc781e;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect10789"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="428.58929"
|
||||
y="365.75504" /><rect
|
||||
y="365.75504"
|
||||
x="418.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect10791"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /></g><g
|
||||
style="display:inline"
|
||||
id="g10793"
|
||||
transform="matrix(0,1,-1,0,497.6284,-222.66912)"><rect
|
||||
style="fill:#bc781e;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect10795"
|
||||
width="6.5178571"
|
||||
height="5.0892859"
|
||||
x="422.11606"
|
||||
y="365.75504" /><rect
|
||||
y="365.75504"
|
||||
x="428.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect10797"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect10799"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="418.58929"
|
||||
y="365.75504" /></g><g
|
||||
style="display:inline"
|
||||
id="g10801"
|
||||
transform="matrix(0,-1,1,0,-252.45879,579.30427)"><rect
|
||||
style="fill:#312d29;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect10803"
|
||||
width="6.5178571"
|
||||
height="5.0892859"
|
||||
x="422.11606"
|
||||
y="365.75504" /><rect
|
||||
y="365.75504"
|
||||
x="428.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect10805"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect10807"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="418.58929"
|
||||
y="365.75504" /></g><g
|
||||
transform="matrix(0,-1,1,0,-263.11623,579.54648)"
|
||||
id="g10809"
|
||||
style="display:inline"><rect
|
||||
y="365.75504"
|
||||
x="422.11606"
|
||||
height="5.0892859"
|
||||
width="6.5178571"
|
||||
id="rect10811"
|
||||
style="fill:#312d29;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect10813"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="428.58929"
|
||||
y="365.75504" /><rect
|
||||
y="365.75504"
|
||||
x="418.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect10815"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /></g><g
|
||||
style="display:inline"
|
||||
id="g10817"
|
||||
transform="matrix(0,-1,1,0,-273.53145,580.27312)"><rect
|
||||
style="fill:#312d29;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect10819"
|
||||
width="6.5178571"
|
||||
height="5.0892859"
|
||||
x="422.11606"
|
||||
y="365.75504" /><rect
|
||||
y="365.75504"
|
||||
x="428.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect10821"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect10823"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="418.58929"
|
||||
y="365.75504" /></g><g
|
||||
transform="matrix(0,-1,1,0,-272.56259,546.12087)"
|
||||
id="g10825"
|
||||
style="display:inline"><rect
|
||||
y="365.75504"
|
||||
x="422.11606"
|
||||
height="5.0892859"
|
||||
width="6.5178571"
|
||||
id="rect10827"
|
||||
style="fill:#312d29;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect10829"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="428.58929"
|
||||
y="365.75504" /><rect
|
||||
y="365.75504"
|
||||
x="418.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect10831"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /></g><g
|
||||
style="display:inline"
|
||||
id="g10833"
|
||||
transform="matrix(0,-1,1,0,-257.06086,546.36308)"><rect
|
||||
style="fill:#312d29;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect10835"
|
||||
width="6.5178571"
|
||||
height="5.0892859"
|
||||
x="422.11606"
|
||||
y="365.75504" /><rect
|
||||
y="365.75504"
|
||||
x="428.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect10837"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect10839"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="418.58929"
|
||||
y="365.75504" /></g><g
|
||||
id="g10887"><path
|
||||
sodipodi:type="arc"
|
||||
style="fill:none;stroke:#f2edda;stroke-width:1.5;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="path4550"
|
||||
sodipodi:cx="225.89285"
|
||||
sodipodi:cy="542.54077"
|
||||
sodipodi:rx="5.1785712"
|
||||
sodipodi:ry="5.1785712"
|
||||
d="m 231.07142,542.54077 c 0,2.86005 -2.31852,5.17857 -5.17857,5.17857 -2.86004,0 -5.17857,-2.31852 -5.17857,-5.17857 0,-2.86004 2.31853,-5.17857 5.17857,-5.17857 2.86005,0 5.17857,2.31853 5.17857,5.17857 z"
|
||||
transform="translate(20.6651,-466.48541)" /><path
|
||||
sodipodi:type="arc"
|
||||
style="fill:none;stroke:#f2edda;stroke-width:1.5;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="path4554"
|
||||
sodipodi:cx="225.89285"
|
||||
sodipodi:cy="542.54077"
|
||||
sodipodi:rx="5.1785712"
|
||||
sodipodi:ry="5.1785712"
|
||||
d="m 231.07142,542.54077 c 0,2.86005 -2.31852,5.17857 -5.17857,5.17857 -2.86004,0 -5.17857,-2.31852 -5.17857,-5.17857 0,-2.86004 2.31853,-5.17857 5.17857,-5.17857 2.86005,0 5.17857,2.31853 5.17857,5.17857 z"
|
||||
transform="translate(4.6651,-466.48541)" /><rect
|
||||
y="71.519623"
|
||||
x="210.81711"
|
||||
height="8.5714283"
|
||||
width="9.6428576"
|
||||
id="rect4556"
|
||||
style="fill:none;stroke:#f2edda;stroke-width:1.5;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" /></g><g
|
||||
transform="translate(0,14)"
|
||||
id="g10892"><path
|
||||
transform="translate(20.6651,-466.48541)"
|
||||
d="m 231.07142,542.54077 c 0,2.86005 -2.31852,5.17857 -5.17857,5.17857 -2.86004,0 -5.17857,-2.31852 -5.17857,-5.17857 0,-2.86004 2.31853,-5.17857 5.17857,-5.17857 2.86005,0 5.17857,2.31853 5.17857,5.17857 z"
|
||||
sodipodi:ry="5.1785712"
|
||||
sodipodi:rx="5.1785712"
|
||||
sodipodi:cy="542.54077"
|
||||
sodipodi:cx="225.89285"
|
||||
id="path10894"
|
||||
style="fill:none;stroke:#f2edda;stroke-width:1.5;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
sodipodi:type="arc" /><path
|
||||
transform="translate(4.6651,-466.48541)"
|
||||
d="m 231.07142,542.54077 c 0,2.86005 -2.31852,5.17857 -5.17857,5.17857 -2.86004,0 -5.17857,-2.31852 -5.17857,-5.17857 0,-2.86004 2.31853,-5.17857 5.17857,-5.17857 2.86005,0 5.17857,2.31853 5.17857,5.17857 z"
|
||||
sodipodi:ry="5.1785712"
|
||||
sodipodi:rx="5.1785712"
|
||||
sodipodi:cy="542.54077"
|
||||
sodipodi:cx="225.89285"
|
||||
id="path10896"
|
||||
style="fill:none;stroke:#f2edda;stroke-width:1.5;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
sodipodi:type="arc" /><rect
|
||||
style="fill:none;stroke:#f2edda;stroke-width:1.5;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="rect10898"
|
||||
width="9.6428576"
|
||||
height="8.5714283"
|
||||
x="210.81711"
|
||||
y="71.519623" /></g><g
|
||||
id="g10900"
|
||||
transform="translate(0,30)"><path
|
||||
sodipodi:type="arc"
|
||||
style="fill:none;stroke:#f2edda;stroke-width:1.5;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="path10902"
|
||||
sodipodi:cx="225.89285"
|
||||
sodipodi:cy="542.54077"
|
||||
sodipodi:rx="5.1785712"
|
||||
sodipodi:ry="5.1785712"
|
||||
d="m 231.07142,542.54077 c 0,2.86005 -2.31852,5.17857 -5.17857,5.17857 -2.86004,0 -5.17857,-2.31852 -5.17857,-5.17857 0,-2.86004 2.31853,-5.17857 5.17857,-5.17857 2.86005,0 5.17857,2.31853 5.17857,5.17857 z"
|
||||
transform="translate(20.6651,-466.48541)" /><path
|
||||
sodipodi:type="arc"
|
||||
style="fill:none;stroke:#f2edda;stroke-width:1.5;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="path10904"
|
||||
sodipodi:cx="225.89285"
|
||||
sodipodi:cy="542.54077"
|
||||
sodipodi:rx="5.1785712"
|
||||
sodipodi:ry="5.1785712"
|
||||
d="m 231.07142,542.54077 c 0,2.86005 -2.31852,5.17857 -5.17857,5.17857 -2.86004,0 -5.17857,-2.31852 -5.17857,-5.17857 0,-2.86004 2.31853,-5.17857 5.17857,-5.17857 2.86005,0 5.17857,2.31853 5.17857,5.17857 z"
|
||||
transform="translate(4.6651,-466.48541)" /><rect
|
||||
y="71.519623"
|
||||
x="210.81711"
|
||||
height="8.5714283"
|
||||
width="9.6428576"
|
||||
id="rect10906"
|
||||
style="fill:none;stroke:#f2edda;stroke-width:1.5;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" /></g><g
|
||||
transform="translate(0,46)"
|
||||
id="g10908"><path
|
||||
transform="translate(20.6651,-466.48541)"
|
||||
d="m 231.07142,542.54077 c 0,2.86005 -2.31852,5.17857 -5.17857,5.17857 -2.86004,0 -5.17857,-2.31852 -5.17857,-5.17857 0,-2.86004 2.31853,-5.17857 5.17857,-5.17857 2.86005,0 5.17857,2.31853 5.17857,5.17857 z"
|
||||
sodipodi:ry="5.1785712"
|
||||
sodipodi:rx="5.1785712"
|
||||
sodipodi:cy="542.54077"
|
||||
sodipodi:cx="225.89285"
|
||||
id="path10910"
|
||||
style="fill:none;stroke:#f2edda;stroke-width:1.5;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
sodipodi:type="arc" /><path
|
||||
transform="translate(4.6651,-466.48541)"
|
||||
d="m 231.07142,542.54077 c 0,2.86005 -2.31852,5.17857 -5.17857,5.17857 -2.86004,0 -5.17857,-2.31852 -5.17857,-5.17857 0,-2.86004 2.31853,-5.17857 5.17857,-5.17857 2.86005,0 5.17857,2.31853 5.17857,5.17857 z"
|
||||
sodipodi:ry="5.1785712"
|
||||
sodipodi:rx="5.1785712"
|
||||
sodipodi:cy="542.54077"
|
||||
sodipodi:cx="225.89285"
|
||||
id="path10912"
|
||||
style="fill:none;stroke:#f2edda;stroke-width:1.5;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
sodipodi:type="arc" /><rect
|
||||
style="fill:none;stroke:#f2edda;stroke-width:1.5;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="rect10914"
|
||||
width="9.6428576"
|
||||
height="8.5714283"
|
||||
x="210.81711"
|
||||
y="71.519623" /></g><g
|
||||
id="g10916"
|
||||
transform="translate(0,62)"><path
|
||||
sodipodi:type="arc"
|
||||
style="fill:none;stroke:#f2edda;stroke-width:1.5;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="path10918"
|
||||
sodipodi:cx="225.89285"
|
||||
sodipodi:cy="542.54077"
|
||||
sodipodi:rx="5.1785712"
|
||||
sodipodi:ry="5.1785712"
|
||||
d="m 231.07142,542.54077 c 0,2.86005 -2.31852,5.17857 -5.17857,5.17857 -2.86004,0 -5.17857,-2.31852 -5.17857,-5.17857 0,-2.86004 2.31853,-5.17857 5.17857,-5.17857 2.86005,0 5.17857,2.31853 5.17857,5.17857 z"
|
||||
transform="translate(20.6651,-466.48541)" /><path
|
||||
sodipodi:type="arc"
|
||||
style="fill:none;stroke:#f2edda;stroke-width:1.5;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="path10920"
|
||||
sodipodi:cx="225.89285"
|
||||
sodipodi:cy="542.54077"
|
||||
sodipodi:rx="5.1785712"
|
||||
sodipodi:ry="5.1785712"
|
||||
d="m 231.07142,542.54077 c 0,2.86005 -2.31852,5.17857 -5.17857,5.17857 -2.86004,0 -5.17857,-2.31852 -5.17857,-5.17857 0,-2.86004 2.31853,-5.17857 5.17857,-5.17857 2.86005,0 5.17857,2.31853 5.17857,5.17857 z"
|
||||
transform="translate(4.6651,-466.48541)" /><rect
|
||||
y="71.519623"
|
||||
x="210.81711"
|
||||
height="8.5714283"
|
||||
width="9.6428576"
|
||||
id="rect10922"
|
||||
style="fill:none;stroke:#f2edda;stroke-width:1.5;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" /></g><g
|
||||
transform="translate(0,76)"
|
||||
id="g10924"><path
|
||||
transform="translate(20.6651,-466.48541)"
|
||||
d="m 231.07142,542.54077 c 0,2.86005 -2.31852,5.17857 -5.17857,5.17857 -2.86004,0 -5.17857,-2.31852 -5.17857,-5.17857 0,-2.86004 2.31853,-5.17857 5.17857,-5.17857 2.86005,0 5.17857,2.31853 5.17857,5.17857 z"
|
||||
sodipodi:ry="5.1785712"
|
||||
sodipodi:rx="5.1785712"
|
||||
sodipodi:cy="542.54077"
|
||||
sodipodi:cx="225.89285"
|
||||
id="path10926"
|
||||
style="fill:none;stroke:#f2edda;stroke-width:1.5;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
sodipodi:type="arc" /><path
|
||||
transform="translate(4.6651,-466.48541)"
|
||||
d="m 231.07142,542.54077 c 0,2.86005 -2.31852,5.17857 -5.17857,5.17857 -2.86004,0 -5.17857,-2.31852 -5.17857,-5.17857 0,-2.86004 2.31853,-5.17857 5.17857,-5.17857 2.86005,0 5.17857,2.31853 5.17857,5.17857 z"
|
||||
sodipodi:ry="5.1785712"
|
||||
sodipodi:rx="5.1785712"
|
||||
sodipodi:cy="542.54077"
|
||||
sodipodi:cx="225.89285"
|
||||
id="path10928"
|
||||
style="fill:none;stroke:#f2edda;stroke-width:1.5;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
sodipodi:type="arc" /><rect
|
||||
style="fill:none;stroke:#f2edda;stroke-width:1.5;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="rect10930"
|
||||
width="9.6428576"
|
||||
height="8.5714283"
|
||||
x="210.81711"
|
||||
y="71.519623" /></g><g
|
||||
style="display:inline"
|
||||
transform="matrix(0,1.2406633,-1.7870765,0,753.06413,-443.20477)"
|
||||
id="g4788"><rect
|
||||
y="365.75504"
|
||||
x="422.11606"
|
||||
height="5.0892859"
|
||||
width="6.5178571"
|
||||
id="rect4790"
|
||||
style="fill:#a9814d;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect4792"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="428.58929"
|
||||
y="365.75504" /><rect
|
||||
y="365.75504"
|
||||
x="418.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect4794"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /></g><g
|
||||
id="g12054"
|
||||
transform="matrix(0,1.2406633,-1.7870765,0,753.06413,-475.20477)"
|
||||
style="display:inline"><rect
|
||||
style="fill:#a9814d;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect12056"
|
||||
width="6.5178571"
|
||||
height="5.0892859"
|
||||
x="422.11606"
|
||||
y="365.75504" /><rect
|
||||
y="365.75504"
|
||||
x="428.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect12058"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect12060"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="418.58929"
|
||||
y="365.75504" /></g><g
|
||||
style="display:inline"
|
||||
transform="matrix(1.2406633,0,0,1.7870765,-460.86273,-457.63731)"
|
||||
id="g12062"><rect
|
||||
y="365.75504"
|
||||
x="422.11606"
|
||||
height="5.0892859"
|
||||
width="6.5178571"
|
||||
id="rect12064"
|
||||
style="fill:#a9814d;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect12066"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="428.58929"
|
||||
y="365.75504" /><rect
|
||||
y="365.75504"
|
||||
x="418.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect12068"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /></g><g
|
||||
id="g12070"
|
||||
transform="matrix(1.2406633,0,0,1.7870765,-426.86273,-457.63731)"
|
||||
style="display:inline"><rect
|
||||
style="fill:#a9814d;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect12072"
|
||||
width="6.5178571"
|
||||
height="5.0892859"
|
||||
x="422.11606"
|
||||
y="365.75504" /><rect
|
||||
y="365.75504"
|
||||
x="428.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect12074"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect12076"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="418.58929"
|
||||
y="365.75504" /></g><g
|
||||
id="g12796"><g
|
||||
transform="translate(-0.3633218,-0.12110727)"
|
||||
id="g12766"><path
|
||||
d="m 133.77917,39.752694 0,-2.686385"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path5376"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 130.94256,39.752694 0,-2.686385"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path5378"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 145.57351,39.752694 0,-2.686385"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path5386"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 142.58758,39.752694 0,-2.686385"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path5388"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 139.75097,39.752694 0,-2.686385"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path5390"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 130.94256,69.7503 0,-2.686344"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path5454"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 133.77917,69.7503 0,-2.686344"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path5456"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 139.75097,69.7503 0,-2.686344"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path5466"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 142.58758,69.7503 0,-2.686344"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path5468"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 145.57351,69.7503 0,-2.686344"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path5470"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 124.82147,57.810942 2.6873,0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path5612"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 124.82147,60.64656 2.6873,0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path5614"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 124.82147,63.63141 2.6873,0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path5616"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 149.0073,63.63141 2.53802,0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path5618"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 149.0073,60.64656 2.53802,0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path5620"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 149.0073,57.810942 2.53802,0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path5622"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 124.82147,46.020858 2.6873,0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path5624"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 124.82147,49.005667 2.6873,0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path5626"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 124.82147,51.841284 2.6873,0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path5628"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 149.0073,51.841284 2.53802,0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path5630"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 149.0073,49.005667 2.53802,0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path5632"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 149.0073,46.020858 2.53802,0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path5634"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 136.76509,39.752694 0,-2.686385"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path5636"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 124.82147,54.826134 2.6873,0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path5726"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 136.76509,69.7503 0,-2.686344"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path5728"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 149.0073,54.826134 2.53802,0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path5730"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 124.82147,43.036008 2.6873,0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path5738"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 149.0073,43.036008 2.53802,0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path5740"
|
||||
inkscape:connector-curvature="0" /></g><rect
|
||||
style="fill:#6a6a6a;fill-opacity:1;stroke:#000000;stroke-width:0.69999999;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="rect4974"
|
||||
width="24.34742"
|
||||
height="31.192205"
|
||||
x="125.66183"
|
||||
y="37.711323" /></g><g
|
||||
id="g12828"><g
|
||||
id="g12830"
|
||||
transform="translate(-0.3633218,-0.12110727)"><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path12832"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
d="m 133.77917,39.752694 0,-2.686385" /><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path12834"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
d="m 130.94256,39.752694 0,-2.686385" /><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path12836"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
d="m 145.57351,39.752694 0,-2.686385" /><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path12838"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
d="m 142.58758,39.752694 0,-2.686385" /><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path12840"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
d="m 139.75097,39.752694 0,-2.686385" /><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path12842"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
d="m 130.94256,69.7503 0,-2.686344" /><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path12844"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
d="m 133.77917,69.7503 0,-2.686344" /><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path12846"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
d="m 139.75097,69.7503 0,-2.686344" /><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path12848"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
d="m 142.58758,69.7503 0,-2.686344" /><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path12850"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
d="m 145.57351,69.7503 0,-2.686344" /><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path12852"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
d="m 124.82147,57.810942 2.6873,0" /><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path12854"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
d="m 124.82147,60.64656 2.6873,0" /><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path12856"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
d="m 124.82147,63.63141 2.6873,0" /><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path12858"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
d="m 149.0073,63.63141 2.53802,0" /><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path12860"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
d="m 149.0073,60.64656 2.53802,0" /><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path12862"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
d="m 149.0073,57.810942 2.53802,0" /><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path12864"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
d="m 124.82147,46.020858 2.6873,0" /><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path12866"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
d="m 124.82147,49.005667 2.6873,0" /><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path12868"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
d="m 124.82147,51.841284 2.6873,0" /><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path12870"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
d="m 149.0073,51.841284 2.53802,0" /><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path12872"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
d="m 149.0073,49.005667 2.53802,0" /><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path12874"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
d="m 149.0073,46.020858 2.53802,0" /><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path12876"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
d="m 136.76509,39.752694 0,-2.686385" /><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path12878"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
d="m 124.82147,54.826134 2.6873,0" /><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path12880"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
d="m 136.76509,69.7503 0,-2.686344" /><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path12882"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
d="m 149.0073,54.826134 2.53802,0" /><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path12884"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
d="m 124.82147,43.036008 2.6873,0" /><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path12886"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
d="m 149.0073,43.036008 2.53802,0" /></g><rect
|
||||
y="37.711323"
|
||||
x="125.66183"
|
||||
height="31.192205"
|
||||
width="24.34742"
|
||||
id="rect12888"
|
||||
style="fill:#6a6a6a;fill-opacity:1;stroke:#000000;stroke-width:0.69999999;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" /></g><g
|
||||
transform="translate(0.68508616,38.685086)"
|
||||
id="g12890"><g
|
||||
transform="translate(-0.3633218,-0.12110727)"
|
||||
id="g12892"><path
|
||||
d="m 133.77917,39.752694 0,-2.686385"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path12894"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 130.94256,39.752694 0,-2.686385"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path12896"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 145.57351,39.752694 0,-2.686385"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path12898"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 142.58758,39.752694 0,-2.686385"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path12900"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 139.75097,39.752694 0,-2.686385"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path12902"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 130.94256,69.7503 0,-2.686344"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path12904"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 133.77917,69.7503 0,-2.686344"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path12906"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 139.75097,69.7503 0,-2.686344"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path12908"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 142.58758,69.7503 0,-2.686344"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path12910"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 145.57351,69.7503 0,-2.686344"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path12912"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 124.82147,57.810942 2.6873,0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path12914"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 124.82147,60.64656 2.6873,0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path12916"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 124.82147,63.63141 2.6873,0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path12918"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 149.0073,63.63141 2.53802,0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path12920"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 149.0073,60.64656 2.53802,0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path12922"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 149.0073,57.810942 2.53802,0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path12924"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 124.82147,46.020858 2.6873,0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path12926"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 124.82147,49.005667 2.6873,0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path12928"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 124.82147,51.841284 2.6873,0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path12930"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 149.0073,51.841284 2.53802,0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path12932"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 149.0073,49.005667 2.53802,0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path12934"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 149.0073,46.020858 2.53802,0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path12936"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 136.76509,39.752694 0,-2.686385"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path12938"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 124.82147,54.826134 2.6873,0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path12940"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 136.76509,69.7503 0,-2.686344"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path12942"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 149.0073,54.826134 2.53802,0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path12944"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 124.82147,43.036008 2.6873,0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path12946"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 149.0073,43.036008 2.53802,0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path12948"
|
||||
inkscape:connector-curvature="0" /></g><rect
|
||||
style="fill:#6a6a6a;fill-opacity:1;stroke:#000000;stroke-width:0.69999999;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="rect12950"
|
||||
width="24.34742"
|
||||
height="31.192205"
|
||||
x="125.66183"
|
||||
y="37.711323" /></g><g
|
||||
id="g12952"
|
||||
style="display:inline"
|
||||
transform="matrix(0.55313316,0,0,0.55313316,202.151,-66.0335)"><rect
|
||||
style="fill:#6a6a6a;fill-opacity:1;stroke:#000000;stroke-width:3.61576581;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect3773"
|
||||
width="76.428574"
|
||||
height="76.785713"
|
||||
x="-104.28571"
|
||||
y="358.43362"
|
||||
ry="2.5" /><g
|
||||
id="g3875"
|
||||
transform="translate(-520,-37.142857)"><g
|
||||
transform="matrix(1.4970318,0,0,1,-211.28069,0.21205357)"
|
||||
id="g3781"><path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path3777"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path3779"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" /></g><g
|
||||
id="g3785"
|
||||
transform="matrix(1.4970318,0,0,1,-207.28069,0.21205357)"><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3787"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3789"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
|
||||
transform="matrix(1.4970318,0,0,1,-203.28069,0.21205357)"
|
||||
id="g3791"><path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path3793"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path3795"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" /></g><g
|
||||
id="g3797"
|
||||
transform="matrix(1.4970318,0,0,1,-199.28069,0.21205357)"><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3799"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3801"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
|
||||
transform="matrix(1.4970318,0,0,1,-195.28069,0.21205357)"
|
||||
id="g3803"><path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path3805"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path3807"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" /></g><g
|
||||
id="g3809"
|
||||
transform="matrix(1.4970318,0,0,1,-191.28069,0.21205357)"><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3811"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3813"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
|
||||
transform="matrix(1.4970318,0,0,1,-187.28069,0.21205357)"
|
||||
id="g3815"><path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path3817"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path3819"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" /></g><g
|
||||
id="g3821"
|
||||
transform="matrix(1.4970318,0,0,1,-183.28069,0.21205357)"><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3823"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3825"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
|
||||
transform="matrix(1.4970318,0,0,1,-179.28069,0.21205357)"
|
||||
id="g3827"><path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path3829"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path3831"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" /></g><g
|
||||
id="g3833"
|
||||
transform="matrix(1.4970318,0,0,1,-175.28069,0.21205357)"><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3835"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3837"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
|
||||
transform="matrix(1.4970318,0,0,1,-171.28069,0.21205357)"
|
||||
id="g3839"><path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path3841"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path3843"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" /></g><g
|
||||
id="g3845"
|
||||
transform="matrix(1.4970318,0,0,1,-167.28069,0.21205357)"><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3847"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3849"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
|
||||
transform="matrix(1.4970318,0,0,1,-163.28069,0.21205357)"
|
||||
id="g3851"><path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path3853"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path3855"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" /></g><g
|
||||
id="g3857"
|
||||
transform="matrix(1.4970318,0,0,1,-159.28069,0.21205357)"><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3859"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3861"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
|
||||
transform="matrix(1.4970318,0,0,1,-155.28069,0.21205357)"
|
||||
id="g3863"><path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path3865"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path3867"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" /></g><g
|
||||
id="g3869"
|
||||
transform="matrix(1.4970318,0,0,1,-151.28069,0.21205357)"><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3871"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3873"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g></g><g
|
||||
id="g3925"
|
||||
transform="matrix(0,1,-1,0,367.93406,-54.993437)"><g
|
||||
id="g3927"
|
||||
transform="matrix(1.4970318,0,0,1,-211.28069,0.21205357)"><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3929"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3931"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
|
||||
transform="matrix(1.4970318,0,0,1,-207.28069,0.21205357)"
|
||||
id="g3933"><path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path3935"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path3937"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" /></g><g
|
||||
id="g3939"
|
||||
transform="matrix(1.4970318,0,0,1,-203.28069,0.21205357)"><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3941"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3943"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
|
||||
transform="matrix(1.4970318,0,0,1,-199.28069,0.21205357)"
|
||||
id="g3945"><path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path3947"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path3949"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" /></g><g
|
||||
id="g3951"
|
||||
transform="matrix(1.4970318,0,0,1,-195.28069,0.21205357)"><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3953"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3955"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
|
||||
transform="matrix(1.4970318,0,0,1,-191.28069,0.21205357)"
|
||||
id="g3957"><path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path3959"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path3961"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" /></g><g
|
||||
id="g3963"
|
||||
transform="matrix(1.4970318,0,0,1,-187.28069,0.21205357)"><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3965"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3967"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
|
||||
transform="matrix(1.4970318,0,0,1,-183.28069,0.21205357)"
|
||||
id="g3969"><path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path3971"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path3973"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" /></g><g
|
||||
id="g3975"
|
||||
transform="matrix(1.4970318,0,0,1,-179.28069,0.21205357)"><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3977"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3979"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
|
||||
transform="matrix(1.4970318,0,0,1,-175.28069,0.21205357)"
|
||||
id="g3981"><path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path3983"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path3985"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" /></g><g
|
||||
id="g3987"
|
||||
transform="matrix(1.4970318,0,0,1,-171.28069,0.21205357)"><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3989"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3991"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
|
||||
transform="matrix(1.4970318,0,0,1,-167.28069,0.21205357)"
|
||||
id="g3993"><path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path3995"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path3997"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" /></g><g
|
||||
id="g3999"
|
||||
transform="matrix(1.4970318,0,0,1,-163.28069,0.21205357)"><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4001"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4003"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
|
||||
transform="matrix(1.4970318,0,0,1,-159.28069,0.21205357)"
|
||||
id="g4005"><path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path4007"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path4009"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" /></g><g
|
||||
id="g4011"
|
||||
transform="matrix(1.4970318,0,0,1,-155.28069,0.21205357)"><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4013"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4015"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
|
||||
transform="matrix(1.4970318,0,0,1,-151.28069,0.21205357)"
|
||||
id="g4017"><path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path4019"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path4021"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" /></g></g><g
|
||||
transform="matrix(0,1,1,0,-500.02315,-54.993437)"
|
||||
id="g4023"><g
|
||||
transform="matrix(1.4970318,0,0,1,-211.28069,0.21205357)"
|
||||
id="g4025"><path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path4027"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path4029"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" /></g><g
|
||||
id="g4031"
|
||||
transform="matrix(1.4970318,0,0,1,-207.28069,0.21205357)"><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4033"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4035"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
|
||||
transform="matrix(1.4970318,0,0,1,-203.28069,0.21205357)"
|
||||
id="g4037"><path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path4039"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path4041"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" /></g><g
|
||||
id="g4043"
|
||||
transform="matrix(1.4970318,0,0,1,-199.28069,0.21205357)"><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4045"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4047"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
|
||||
transform="matrix(1.4970318,0,0,1,-195.28069,0.21205357)"
|
||||
id="g4049"><path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path4051"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path4053"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" /></g><g
|
||||
id="g4055"
|
||||
transform="matrix(1.4970318,0,0,1,-191.28069,0.21205357)"><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4057"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4059"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
|
||||
transform="matrix(1.4970318,0,0,1,-187.28069,0.21205357)"
|
||||
id="g4061"><path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path4063"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path4065"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" /></g><g
|
||||
id="g4067"
|
||||
transform="matrix(1.4970318,0,0,1,-183.28069,0.21205357)"><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4069"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4071"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
|
||||
transform="matrix(1.4970318,0,0,1,-179.28069,0.21205357)"
|
||||
id="g4073"><path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path4075"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path4077"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" /></g><g
|
||||
id="g4079"
|
||||
transform="matrix(1.4970318,0,0,1,-175.28069,0.21205357)"><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4081"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4083"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
|
||||
transform="matrix(1.4970318,0,0,1,-171.28069,0.21205357)"
|
||||
id="g4085"><path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path4087"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path4089"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" /></g><g
|
||||
id="g4091"
|
||||
transform="matrix(1.4970318,0,0,1,-167.28069,0.21205357)"><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4093"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4095"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
|
||||
transform="matrix(1.4970318,0,0,1,-163.28069,0.21205357)"
|
||||
id="g4097"><path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path4099"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path4101"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" /></g><g
|
||||
id="g4103"
|
||||
transform="matrix(1.4970318,0,0,1,-159.28069,0.21205357)"><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4105"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4107"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
|
||||
transform="matrix(1.4970318,0,0,1,-155.28069,0.21205357)"
|
||||
id="g4109"><path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path4111"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path4113"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" /></g><g
|
||||
id="g4115"
|
||||
transform="matrix(1.4970318,0,0,1,-151.28069,0.21205357)"><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4117"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4119"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g></g><g
|
||||
id="g4121"
|
||||
transform="matrix(1,0,0,-1,-520,830.07704)"><g
|
||||
id="g4123"
|
||||
transform="matrix(1.4970318,0,0,1,-211.28069,0.21205357)"><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4125"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4127"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
|
||||
transform="matrix(1.4970318,0,0,1,-207.28069,0.21205357)"
|
||||
id="g4129"><path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path4131"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path4133"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" /></g><g
|
||||
id="g4135"
|
||||
transform="matrix(1.4970318,0,0,1,-203.28069,0.21205357)"><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4137"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4139"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
|
||||
transform="matrix(1.4970318,0,0,1,-199.28069,0.21205357)"
|
||||
id="g4141"><path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path4143"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path4145"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" /></g><g
|
||||
id="g4147"
|
||||
transform="matrix(1.4970318,0,0,1,-195.28069,0.21205357)"><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4149"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4151"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
|
||||
transform="matrix(1.4970318,0,0,1,-191.28069,0.21205357)"
|
||||
id="g4153"><path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path4155"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path4157"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" /></g><g
|
||||
id="g4159"
|
||||
transform="matrix(1.4970318,0,0,1,-187.28069,0.21205357)"><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4161"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4163"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
|
||||
transform="matrix(1.4970318,0,0,1,-183.28069,0.21205357)"
|
||||
id="g4165"><path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path4167"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path4169"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" /></g><g
|
||||
id="g4171"
|
||||
transform="matrix(1.4970318,0,0,1,-179.28069,0.21205357)"><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4173"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4175"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
|
||||
transform="matrix(1.4970318,0,0,1,-175.28069,0.21205357)"
|
||||
id="g4177"><path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path4179"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path4181"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" /></g><g
|
||||
id="g4183"
|
||||
transform="matrix(1.4970318,0,0,1,-171.28069,0.21205357)"><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4185"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4187"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
|
||||
transform="matrix(1.4970318,0,0,1,-167.28069,0.21205357)"
|
||||
id="g4189"><path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path4191"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path4193"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" /></g><g
|
||||
id="g4195"
|
||||
transform="matrix(1.4970318,0,0,1,-163.28069,0.21205357)"><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4197"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4199"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
|
||||
transform="matrix(1.4970318,0,0,1,-159.28069,0.21205357)"
|
||||
id="g4201"><path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path4203"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path4205"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" /></g><g
|
||||
id="g4207"
|
||||
transform="matrix(1.4970318,0,0,1,-155.28069,0.21205357)"><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4209"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4211"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
|
||||
transform="matrix(1.4970318,0,0,1,-151.28069,0.21205357)"
|
||||
id="g4213"><path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path4215"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path4217"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" /></g></g></g><g
|
||||
style="display:inline"
|
||||
id="g4920"
|
||||
transform="matrix(0.41419929,0,0,0.41419929,-10.368172,-50.871127)"><g
|
||||
transform="matrix(0,1.4970318,-1,0,849.26635,-33.0226)"
|
||||
id="g4871"
|
||||
style="display:inline"><rect
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none"
|
||||
id="rect4867"
|
||||
width="10.985409"
|
||||
height="4.0486217"
|
||||
x="-386.60983"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-383.45309"
|
||||
height="4.0486217"
|
||||
width="2.5253813"
|
||||
id="rect4869"
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none" /></g><g
|
||||
id="g4875"
|
||||
transform="matrix(0,1.4970318,-1,0,849.26635,-23.0226)"
|
||||
style="display:inline"><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-386.60983"
|
||||
height="4.0486217"
|
||||
width="10.985409"
|
||||
id="rect4877"
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none" /><rect
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none"
|
||||
id="rect4879"
|
||||
width="2.5253813"
|
||||
height="4.0486217"
|
||||
x="-383.45309"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /></g><g
|
||||
transform="matrix(0,1.4970318,-1,0,849.26635,-13.0226)"
|
||||
id="g4881"
|
||||
style="display:inline"><rect
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none"
|
||||
id="rect4883"
|
||||
width="10.985409"
|
||||
height="4.0486217"
|
||||
x="-386.60983"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-383.45309"
|
||||
height="4.0486217"
|
||||
width="2.5253813"
|
||||
id="rect4885"
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none" /></g><g
|
||||
id="g4887"
|
||||
transform="matrix(0,1.4970318,1,0,55.91598,-13.0226)"
|
||||
style="display:inline"><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-386.60983"
|
||||
height="4.0486217"
|
||||
width="10.985409"
|
||||
id="rect4889"
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none" /><rect
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none"
|
||||
id="rect4891"
|
||||
width="2.5253813"
|
||||
height="4.0486217"
|
||||
x="-383.45309"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /></g><g
|
||||
transform="matrix(0,1.4970318,1,0,55.91598,-33.0226)"
|
||||
id="g4899"
|
||||
style="display:inline"><rect
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none"
|
||||
id="rect4901"
|
||||
width="10.985409"
|
||||
height="4.0486217"
|
||||
x="-386.60983"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-383.45309"
|
||||
height="4.0486217"
|
||||
width="2.5253813"
|
||||
id="rect4903"
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none" /></g><rect
|
||||
ry="1.5"
|
||||
y="590.15265"
|
||||
x="443.12988"
|
||||
height="31.819805"
|
||||
width="18.687822"
|
||||
id="rect4841"
|
||||
style="fill:#6a6a6a;fill-opacity:1;stroke:#000000;stroke-width:2.41429687;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /></g><g
|
||||
transform="matrix(0,0.41419929,-0.41419929,0,462.12545,-133.30339)"
|
||||
id="g13877"
|
||||
style="display:inline"><g
|
||||
style="display:inline"
|
||||
id="g13879"
|
||||
transform="matrix(0,1.4970318,-1,0,849.26635,-33.0226)"><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-386.60983"
|
||||
height="4.0486217"
|
||||
width="10.985409"
|
||||
id="rect13881"
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none" /><rect
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none"
|
||||
id="rect13883"
|
||||
width="2.5253813"
|
||||
height="4.0486217"
|
||||
x="-383.45309"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /></g><g
|
||||
style="display:inline"
|
||||
transform="matrix(0,1.4970318,-1,0,849.26635,-23.0226)"
|
||||
id="g13885"><rect
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none"
|
||||
id="rect13887"
|
||||
width="10.985409"
|
||||
height="4.0486217"
|
||||
x="-386.60983"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-383.45309"
|
||||
height="4.0486217"
|
||||
width="2.5253813"
|
||||
id="rect13889"
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none" /></g><g
|
||||
style="display:inline"
|
||||
id="g13891"
|
||||
transform="matrix(0,1.4970318,-1,0,849.26635,-13.0226)"><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-386.60983"
|
||||
height="4.0486217"
|
||||
width="10.985409"
|
||||
id="rect13893"
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none" /><rect
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none"
|
||||
id="rect13895"
|
||||
width="2.5253813"
|
||||
height="4.0486217"
|
||||
x="-383.45309"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /></g><g
|
||||
style="display:inline"
|
||||
transform="matrix(0,1.4970318,1,0,55.91598,-13.0226)"
|
||||
id="g13897"><rect
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none"
|
||||
id="rect13899"
|
||||
width="10.985409"
|
||||
height="4.0486217"
|
||||
x="-386.60983"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-383.45309"
|
||||
height="4.0486217"
|
||||
width="2.5253813"
|
||||
id="rect13901"
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none" /></g><g
|
||||
style="display:inline"
|
||||
id="g13903"
|
||||
transform="matrix(0,1.4970318,1,0,55.91598,-33.0226)"><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-386.60983"
|
||||
height="4.0486217"
|
||||
width="10.985409"
|
||||
id="rect13905"
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none" /><rect
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none"
|
||||
id="rect13907"
|
||||
width="2.5253813"
|
||||
height="4.0486217"
|
||||
x="-383.45309"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /></g><rect
|
||||
style="fill:#6a6a6a;fill-opacity:1;stroke:#000000;stroke-width:2.41429687;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect13909"
|
||||
width="18.687822"
|
||||
height="31.819805"
|
||||
x="443.12988"
|
||||
y="590.15265"
|
||||
ry="1.5" /></g><g
|
||||
id="g13760"
|
||||
style="display:inline"
|
||||
transform="matrix(0,0.61819183,-0.61819183,0,444.94676,-97.125819)"><rect
|
||||
transform="translate(188.57143,331.57648)"
|
||||
y="269.42856"
|
||||
x="140.71428"
|
||||
height="52.142857"
|
||||
width="89.285713"
|
||||
id="rect5020"
|
||||
style="fill:#fffcfc;fill-opacity:1;stroke:#828282;stroke-width:3.23524165;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" /><g
|
||||
transform="matrix(-1.4970318,0,0,1,971.39158,213.03078)"
|
||||
id="g4964-3"
|
||||
style="display:inline"><rect
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none"
|
||||
id="rect4966-2"
|
||||
width="10.985409"
|
||||
height="4.0486217"
|
||||
x="-386.60983"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-383.45309"
|
||||
height="4.0486217"
|
||||
width="2.5253813"
|
||||
id="rect4968-1"
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none" /></g><g
|
||||
style="display:inline"
|
||||
id="g5046"
|
||||
transform="matrix(-1.4970318,0,0,1,981.39158,213.03078)"><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-386.60983"
|
||||
height="4.0486217"
|
||||
width="10.985409"
|
||||
id="rect5048"
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none" /><rect
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none"
|
||||
id="rect5050"
|
||||
width="2.5253813"
|
||||
height="4.0486217"
|
||||
x="-383.45309"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /></g><g
|
||||
transform="matrix(-1.4970318,0,0,1,991.39158,213.03078)"
|
||||
id="g5052"
|
||||
style="display:inline"><rect
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none"
|
||||
id="rect5054"
|
||||
width="10.985409"
|
||||
height="4.0486217"
|
||||
x="-386.60983"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-383.45309"
|
||||
height="4.0486217"
|
||||
width="2.5253813"
|
||||
id="rect5056"
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none" /></g><g
|
||||
style="display:inline"
|
||||
id="g5058"
|
||||
transform="matrix(-1.4970318,0,0,1,1001.3916,213.03078)"><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-386.60983"
|
||||
height="4.0486217"
|
||||
width="10.985409"
|
||||
id="rect5060"
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none" /><rect
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none"
|
||||
id="rect5062"
|
||||
width="2.5253813"
|
||||
height="4.0486217"
|
||||
x="-383.45309"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /></g><g
|
||||
transform="matrix(-1.4970318,0,0,1,1011.3916,213.03078)"
|
||||
id="g5064"
|
||||
style="display:inline"><rect
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none"
|
||||
id="rect5066"
|
||||
width="10.985409"
|
||||
height="4.0486217"
|
||||
x="-386.60983"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-383.45309"
|
||||
height="4.0486217"
|
||||
width="2.5253813"
|
||||
id="rect5068"
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none" /></g><g
|
||||
style="display:inline"
|
||||
id="g5070"
|
||||
transform="matrix(-1.4970318,0,0,1,1021.3916,213.03078)"><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-386.60983"
|
||||
height="4.0486217"
|
||||
width="10.985409"
|
||||
id="rect5072"
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none" /><rect
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none"
|
||||
id="rect5074"
|
||||
width="2.5253813"
|
||||
height="4.0486217"
|
||||
x="-383.45309"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /></g><g
|
||||
style="display:inline"
|
||||
id="g13998"
|
||||
transform="matrix(-1.4970318,0,0,1,1031.0972,213.03078)"><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-386.60983"
|
||||
height="4.0486217"
|
||||
width="10.985409"
|
||||
id="rect14000"
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none" /><rect
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none"
|
||||
id="rect14002"
|
||||
width="2.5253813"
|
||||
height="4.0486217"
|
||||
x="-383.45309"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /></g><g
|
||||
transform="matrix(-1.4970318,0,0,1,1040.8028,213.03078)"
|
||||
id="g14004"
|
||||
style="display:inline"><rect
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none"
|
||||
id="rect14006"
|
||||
width="10.985409"
|
||||
height="4.0486217"
|
||||
x="-386.60983"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-383.45309"
|
||||
height="4.0486217"
|
||||
width="2.5253813"
|
||||
id="rect14008"
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none" /></g></g><g
|
||||
style="display:inline"
|
||||
id="g4920-2"
|
||||
transform="matrix(-0.48222043,0,0,-0.59728256,285.82656,546.58597)"><g
|
||||
transform="matrix(0,1.4970318,-1,0,849.26635,-33.0226)"
|
||||
id="g4871-7"
|
||||
style="display:inline"><rect
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none"
|
||||
id="rect4867-0"
|
||||
width="10.985409"
|
||||
height="4.0486217"
|
||||
x="-386.60983"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-383.45309"
|
||||
height="4.0486217"
|
||||
width="2.5253813"
|
||||
id="rect4869-4"
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none" /></g><g
|
||||
id="g4875-1"
|
||||
transform="matrix(0,1.4970318,-1,0,849.26635,-23.0226)"
|
||||
style="display:inline"><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-386.60983"
|
||||
height="4.0486217"
|
||||
width="10.985409"
|
||||
id="rect4877-3"
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none" /><rect
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none"
|
||||
id="rect4879-4"
|
||||
width="2.5253813"
|
||||
height="4.0486217"
|
||||
x="-383.45309"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /></g><g
|
||||
transform="matrix(0,1.4970318,-1,0,849.26635,-13.0226)"
|
||||
id="g4881-9"
|
||||
style="display:inline"><rect
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none"
|
||||
id="rect4883-6"
|
||||
width="10.985409"
|
||||
height="4.0486217"
|
||||
x="-386.60983"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-383.45309"
|
||||
height="4.0486217"
|
||||
width="2.5253813"
|
||||
id="rect4885-2"
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none" /></g><g
|
||||
id="g4887-8"
|
||||
transform="matrix(0,1.4970318,1,0,55.91598,-13.0226)"
|
||||
style="display:inline"><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-386.60983"
|
||||
height="4.0486217"
|
||||
width="10.985409"
|
||||
id="rect4889-3"
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none" /><rect
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none"
|
||||
id="rect4891-3"
|
||||
width="2.5253813"
|
||||
height="4.0486217"
|
||||
x="-383.45309"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /></g><g
|
||||
transform="matrix(0,1.4970318,1,0,55.91598,-33.0226)"
|
||||
id="g4899-7"
|
||||
style="display:inline"><rect
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none"
|
||||
id="rect4901-7"
|
||||
width="10.985409"
|
||||
height="4.0486217"
|
||||
x="-386.60983"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-383.45309"
|
||||
height="4.0486217"
|
||||
width="2.5253813"
|
||||
id="rect4903-8"
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none" /></g><rect
|
||||
ry="1.5"
|
||||
y="590.15265"
|
||||
x="443.12988"
|
||||
height="31.819805"
|
||||
width="18.687822"
|
||||
id="rect4841-1"
|
||||
style="fill:#6a6a6a;fill-opacity:1;stroke:#000000;stroke-width:1.86331928;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /></g><g
|
||||
style="display:inline"
|
||||
id="g14076"
|
||||
transform="matrix(0,-1,1,0,-150.96398,652.23853)"><rect
|
||||
y="365.75504"
|
||||
x="426.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect14080"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect14082"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="418.58929"
|
||||
y="365.75504" /></g><g
|
||||
transform="matrix(0.61819183,0,0,0.48347584,-108.7519,-76.23362)"
|
||||
style="display:inline"
|
||||
id="g14084"><rect
|
||||
style="fill:#fffcfc;fill-opacity:1;stroke:#828282;stroke-width:3.65831399;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="rect14086"
|
||||
width="53.268898"
|
||||
height="52.142857"
|
||||
x="329.28571"
|
||||
y="601.00507" /><g
|
||||
style="display:inline"
|
||||
id="g14088"
|
||||
transform="matrix(-1.4970318,0,0,1,971.39158,213.03078)"><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-386.60983"
|
||||
height="4.0486217"
|
||||
width="10.985409"
|
||||
id="rect14090"
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none" /><rect
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none"
|
||||
id="rect14092"
|
||||
width="2.5253813"
|
||||
height="4.0486217"
|
||||
x="-383.45309"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /></g><g
|
||||
transform="matrix(-1.4970318,0,0,1,981.39158,213.03078)"
|
||||
id="g14094"
|
||||
style="display:inline"><rect
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none"
|
||||
id="rect14096"
|
||||
width="10.985409"
|
||||
height="4.0486217"
|
||||
x="-386.60983"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-383.45309"
|
||||
height="4.0486217"
|
||||
width="2.5253813"
|
||||
id="rect14098"
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none" /></g><g
|
||||
style="display:inline"
|
||||
id="g14100"
|
||||
transform="matrix(-1.4970318,0,0,1,991.39158,213.03078)"><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-386.60983"
|
||||
height="4.0486217"
|
||||
width="10.985409"
|
||||
id="rect14102"
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none" /><rect
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none"
|
||||
id="rect14104"
|
||||
width="2.5253813"
|
||||
height="4.0486217"
|
||||
x="-383.45309"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /></g><g
|
||||
transform="matrix(-1.4970318,0,0,1,1001.3916,213.03078)"
|
||||
id="g14106"
|
||||
style="display:inline"><rect
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none"
|
||||
id="rect14108"
|
||||
width="10.985409"
|
||||
height="4.0486217"
|
||||
x="-386.60983"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-383.45309"
|
||||
height="4.0486217"
|
||||
width="2.5253813"
|
||||
id="rect14110"
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none" /></g></g><g
|
||||
id="g14136"
|
||||
style="display:inline"
|
||||
transform="matrix(0.61819183,0,0,0.48347584,-30.7519,-76.23362)"><rect
|
||||
y="601.00507"
|
||||
x="329.28571"
|
||||
height="52.142857"
|
||||
width="53.268898"
|
||||
id="rect14138"
|
||||
style="fill:#fffcfc;fill-opacity:1;stroke:#828282;stroke-width:3.65831399;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" /><g
|
||||
transform="matrix(-1.4970318,0,0,1,971.39158,213.03078)"
|
||||
id="g14140"
|
||||
style="display:inline"><rect
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none"
|
||||
id="rect14142"
|
||||
width="10.985409"
|
||||
height="4.0486217"
|
||||
x="-386.60983"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-383.45309"
|
||||
height="4.0486217"
|
||||
width="2.5253813"
|
||||
id="rect14144"
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none" /></g><g
|
||||
style="display:inline"
|
||||
id="g14146"
|
||||
transform="matrix(-1.4970318,0,0,1,981.39158,213.03078)"><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-386.60983"
|
||||
height="4.0486217"
|
||||
width="10.985409"
|
||||
id="rect14148"
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none" /><rect
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none"
|
||||
id="rect14150"
|
||||
width="2.5253813"
|
||||
height="4.0486217"
|
||||
x="-383.45309"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /></g><g
|
||||
transform="matrix(-1.4970318,0,0,1,991.39158,213.03078)"
|
||||
id="g14152"
|
||||
style="display:inline"><rect
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none"
|
||||
id="rect14154"
|
||||
width="10.985409"
|
||||
height="4.0486217"
|
||||
x="-386.60983"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-383.45309"
|
||||
height="4.0486217"
|
||||
width="2.5253813"
|
||||
id="rect14156"
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none" /></g><g
|
||||
style="display:inline"
|
||||
id="g14158"
|
||||
transform="matrix(-1.4970318,0,0,1,1001.3916,213.03078)"><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-386.60983"
|
||||
height="4.0486217"
|
||||
width="10.985409"
|
||||
id="rect14160"
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none" /><rect
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none"
|
||||
id="rect14162"
|
||||
width="2.5253813"
|
||||
height="4.0486217"
|
||||
x="-383.45309"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /></g></g><g
|
||||
style="display:inline"
|
||||
transform="matrix(2.4017041,0,0,3.9408912,-788.51882,-1271.7817)"
|
||||
id="g14164"><rect
|
||||
y="365.75504"
|
||||
x="422.11606"
|
||||
height="5.0892859"
|
||||
width="6.5178571"
|
||||
id="rect14166"
|
||||
style="fill:#00440d;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect14168"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="428.58929"
|
||||
y="365.75504" /><rect
|
||||
y="365.75504"
|
||||
x="418.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect14170"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /></g><rect
|
||||
style="fill:#6a6a6a;fill-opacity:1;stroke:#000000;stroke-width:0.69999999;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="rect14172"
|
||||
width="18.524187"
|
||||
height="28.45186"
|
||||
x="174.85481"
|
||||
y="44.491241" /><g
|
||||
style="display:inline"
|
||||
id="g14192"
|
||||
transform="translate(-342.57061,-300.15766)"><rect
|
||||
style="fill:#312d29;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect14194"
|
||||
width="6.5178571"
|
||||
height="5.0892859"
|
||||
x="422.11606"
|
||||
y="365.75504" /><rect
|
||||
y="365.75504"
|
||||
x="428.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect14196"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect14198"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="418.58929"
|
||||
y="365.75504" /></g><g
|
||||
style="display:inline"
|
||||
id="g14200"
|
||||
transform="matrix(0,0.63857044,-0.6183842,0,527.83252,-72.180508)"><g
|
||||
transform="matrix(0,1.4970318,-1,0,852.39835,-33.0226)"
|
||||
id="g14202"
|
||||
style="display:inline"><rect
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none"
|
||||
id="rect14204"
|
||||
width="10.985409"
|
||||
height="4.0486217"
|
||||
x="-386.60983"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-383.45309"
|
||||
height="4.0486217"
|
||||
width="2.5253813"
|
||||
id="rect14206"
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none" /></g><g
|
||||
id="g14208"
|
||||
transform="matrix(0,1.4970318,-1,0,852.39835,-23.0226)"
|
||||
style="display:inline"><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-386.60983"
|
||||
height="4.0486217"
|
||||
width="10.985409"
|
||||
id="rect14210"
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none" /><rect
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none"
|
||||
id="rect14212"
|
||||
width="2.5253813"
|
||||
height="4.0486217"
|
||||
x="-383.45309"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /></g><g
|
||||
transform="matrix(0,1.4970318,-1,0,852.39835,-13.0226)"
|
||||
id="g14214"
|
||||
style="display:inline"><rect
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none"
|
||||
id="rect14216"
|
||||
width="10.985409"
|
||||
height="4.0486217"
|
||||
x="-386.60983"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-383.45309"
|
||||
height="4.0486217"
|
||||
width="2.5253813"
|
||||
id="rect14218"
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none" /></g><g
|
||||
id="g14220"
|
||||
transform="matrix(0,1.4970318,1,0,46.519992,-13.0226)"
|
||||
style="display:inline"><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-386.60983"
|
||||
height="4.0486217"
|
||||
width="10.985409"
|
||||
id="rect14222"
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none" /><rect
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none"
|
||||
id="rect14224"
|
||||
width="2.5253813"
|
||||
height="4.0486217"
|
||||
x="-383.45309"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /></g><g
|
||||
transform="matrix(0,1.4970318,1,0,46.519992,-33.0226)"
|
||||
id="g14226"
|
||||
style="display:inline"><rect
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none"
|
||||
id="rect14228"
|
||||
width="10.985409"
|
||||
height="4.0486217"
|
||||
x="-386.60983"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-383.45309"
|
||||
height="4.0486217"
|
||||
width="2.5253813"
|
||||
id="rect14230"
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none" /></g><g
|
||||
style="display:inline"
|
||||
transform="matrix(0,1.4970318,1,0,46.519992,-22.679788)"
|
||||
id="g14240"><rect
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none"
|
||||
id="rect14242"
|
||||
width="10.985409"
|
||||
height="4.0486217"
|
||||
x="-386.60983"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-383.45309"
|
||||
height="4.0486217"
|
||||
width="2.5253813"
|
||||
id="rect14244"
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none" /></g><g
|
||||
style="display:inline"
|
||||
transform="matrix(0,1.4970318,1,0,46.519992,-3.365413)"
|
||||
id="g14246"><rect
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none"
|
||||
id="rect14248"
|
||||
width="10.985409"
|
||||
height="4.0486217"
|
||||
x="-386.60983"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-383.45309"
|
||||
height="4.0486217"
|
||||
width="2.5253813"
|
||||
id="rect14250"
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none" /></g><g
|
||||
style="display:inline"
|
||||
id="g14252"
|
||||
transform="matrix(0,1.4970318,-1,0,852.39835,-3.365413)"><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-386.60983"
|
||||
height="4.0486217"
|
||||
width="10.985409"
|
||||
id="rect14254"
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none" /><rect
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none"
|
||||
id="rect14256"
|
||||
width="2.5253813"
|
||||
height="4.0486217"
|
||||
x="-383.45309"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /></g><rect
|
||||
ry="1.9272836"
|
||||
y="590.15265"
|
||||
x="432.12994"
|
||||
height="40.883862"
|
||||
width="34.998043"
|
||||
id="rect14232"
|
||||
style="fill:#6a6a6a;fill-opacity:1;stroke:#000000;stroke-width:1.59135258;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /></g></g></g></svg>
|
After Width: | Height: | Size: 139 KiB |
2389
ground/openpilotgcs/src/plugins/uploader/images/deviceID-0402.svg
Normal file
@ -0,0 +1,2389 @@
|
||||
<?xml version="1.0" encoding="UTF-8" standalone="no"?>
|
||||
<!-- Created with Inkscape (http://www.inkscape.org/) -->
|
||||
|
||||
<svg
|
||||
xmlns:dc="http://purl.org/dc/elements/1.1/"
|
||||
xmlns:cc="http://creativecommons.org/ns#"
|
||||
xmlns:rdf="http://www.w3.org/1999/02/22-rdf-syntax-ns#"
|
||||
xmlns:svg="http://www.w3.org/2000/svg"
|
||||
xmlns="http://www.w3.org/2000/svg"
|
||||
xmlns:sodipodi="http://sodipodi.sourceforge.net/DTD/sodipodi-0.dtd"
|
||||
xmlns:inkscape="http://www.inkscape.org/namespaces/inkscape"
|
||||
id="svg3578"
|
||||
version="1.1"
|
||||
inkscape:version="0.48.2 r9819"
|
||||
width="217.16675"
|
||||
height="212.0625"
|
||||
xml:space="preserve"
|
||||
sodipodi:docname="deviceID-0402.svg"><metadata
|
||||
id="metadata3584"><rdf:RDF><cc:Work
|
||||
rdf:about=""><dc:format>image/svg+xml</dc:format><dc:type
|
||||
rdf:resource="http://purl.org/dc/dcmitype/StillImage" /><dc:title /></cc:Work></rdf:RDF></metadata><defs
|
||||
id="defs3582"><clipPath
|
||||
clipPathUnits="userSpaceOnUse"
|
||||
id="clipPath3596"><path
|
||||
d="M 0,0 662,0 662,675 0,675 0,0 z"
|
||||
id="path3598"
|
||||
inkscape:connector-curvature="0" /></clipPath></defs><sodipodi:namedview
|
||||
pagecolor="#ffffff"
|
||||
bordercolor="#666666"
|
||||
borderopacity="1"
|
||||
objecttolerance="10"
|
||||
gridtolerance="10"
|
||||
guidetolerance="10"
|
||||
inkscape:pageopacity="0"
|
||||
inkscape:pageshadow="2"
|
||||
inkscape:window-width="1680"
|
||||
inkscape:window-height="930"
|
||||
id="namedview3580"
|
||||
showgrid="false"
|
||||
inkscape:zoom="1.4596704"
|
||||
inkscape:cx="74.195835"
|
||||
inkscape:cy="113.87434"
|
||||
inkscape:window-x="0"
|
||||
inkscape:window-y="0"
|
||||
inkscape:window-maximized="1"
|
||||
inkscape:current-layer="device"
|
||||
fit-margin-top="0"
|
||||
fit-margin-left="0"
|
||||
fit-margin-right="0"
|
||||
fit-margin-bottom="0" /><g
|
||||
inkscape:groupmode="layer"
|
||||
id="layer2"
|
||||
inkscape:label="Rendering#1"
|
||||
style="display:inline"
|
||||
transform="translate(-40.177007,-31.1875)"><g
|
||||
id="device"
|
||||
inkscape:label="#g15334"><rect
|
||||
rx="13.079585"
|
||||
ry="10"
|
||||
y="32.199471"
|
||||
x="46.668976"
|
||||
height="210.03767"
|
||||
width="209.67079"
|
||||
id="rect9798"
|
||||
style="fill:#171717;fill-opacity:1;stroke:#000000;stroke-width:2;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><g
|
||||
transform="translate(-311.74173,-199.45)"
|
||||
id="g4318"
|
||||
style="display:inline"><rect
|
||||
y="365.75504"
|
||||
x="422.11606"
|
||||
height="5.0892859"
|
||||
width="6.5178571"
|
||||
id="rect4320"
|
||||
style="fill:#312d29;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect4322"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="428.58929"
|
||||
y="365.75504" /><rect
|
||||
y="365.75504"
|
||||
x="418.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect4324"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /></g><g
|
||||
transform="matrix(0,-1,1,0,-158.96398,620.23853)"
|
||||
id="g4406"
|
||||
style="display:inline"><rect
|
||||
y="365.75504"
|
||||
x="422.11606"
|
||||
height="5.0892859"
|
||||
width="6.5178571"
|
||||
id="rect4408"
|
||||
style="fill:#312d29;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect4410"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="428.58929"
|
||||
y="365.75504" /><rect
|
||||
y="365.75504"
|
||||
x="418.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect4412"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /></g><g
|
||||
style="display:inline"
|
||||
id="g10505"
|
||||
transform="translate(-238.1085,-287.13166)"><rect
|
||||
style="fill:#312d29;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect10507"
|
||||
width="6.5178571"
|
||||
height="5.0892859"
|
||||
x="422.11606"
|
||||
y="365.75504" /><rect
|
||||
y="365.75504"
|
||||
x="428.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect10509"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect10511"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="418.58929"
|
||||
y="365.75504" /></g><g
|
||||
transform="translate(-297.20885,-185.40155)"
|
||||
id="g10513"
|
||||
style="display:inline"><rect
|
||||
y="365.75504"
|
||||
x="422.11606"
|
||||
height="5.0892859"
|
||||
width="6.5178571"
|
||||
id="rect10515"
|
||||
style="fill:#312d29;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect10517"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="428.58929"
|
||||
y="365.75504" /><rect
|
||||
y="365.75504"
|
||||
x="418.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect10519"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /></g><g
|
||||
id="g4225"
|
||||
style="display:inline"
|
||||
transform="translate(-324.12933,-188.57649)"><rect
|
||||
style="fill:#bc781e;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect4219"
|
||||
width="6.5178571"
|
||||
height="5.0892859"
|
||||
x="422.11606"
|
||||
y="365.75504" /><rect
|
||||
y="365.75504"
|
||||
x="428.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect4221"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect4223"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="418.58929"
|
||||
y="365.75504" /></g><g
|
||||
transform="translate(-229.42344,-179.37234)"
|
||||
style="display:inline"
|
||||
id="g10548"><rect
|
||||
y="365.75504"
|
||||
x="422.11606"
|
||||
height="5.0892859"
|
||||
width="6.5178571"
|
||||
id="rect10550"
|
||||
style="fill:#bc781e;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect10552"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="428.58929"
|
||||
y="365.75504" /><rect
|
||||
y="365.75504"
|
||||
x="418.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect10554"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /></g><g
|
||||
id="g10556"
|
||||
style="display:inline"
|
||||
transform="translate(-230.15008,-167.50383)"><rect
|
||||
style="fill:#bc781e;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect10558"
|
||||
width="6.5178571"
|
||||
height="5.0892859"
|
||||
x="422.11606"
|
||||
y="365.75504" /><rect
|
||||
y="365.75504"
|
||||
x="428.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect10560"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect10562"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="418.58929"
|
||||
y="365.75504" /></g><g
|
||||
transform="translate(-235.23659,-253.7322)"
|
||||
style="display:inline"
|
||||
id="g10564"><rect
|
||||
y="365.75504"
|
||||
x="422.11606"
|
||||
height="5.0892859"
|
||||
width="6.5178571"
|
||||
id="rect10566"
|
||||
style="fill:#bc781e;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect10568"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="428.58929"
|
||||
y="365.75504" /><rect
|
||||
y="365.75504"
|
||||
x="418.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect10570"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /></g><g
|
||||
id="g10572"
|
||||
style="display:inline"
|
||||
transform="translate(-214.16393,-327.60763)"><rect
|
||||
style="fill:#bc781e;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect10574"
|
||||
width="6.5178571"
|
||||
height="5.0892859"
|
||||
x="422.11606"
|
||||
y="365.75504" /><rect
|
||||
y="365.75504"
|
||||
x="428.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect10576"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect10578"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="418.58929"
|
||||
y="365.75504" /></g><g
|
||||
id="g4414"
|
||||
transform="translate(-365.77251,-288.34483)"
|
||||
style="display:inline"><rect
|
||||
style="fill:#0052ff;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect4416"
|
||||
width="6.5178571"
|
||||
height="5.0892859"
|
||||
x="422.11606"
|
||||
y="365.75504" /><rect
|
||||
y="365.75504"
|
||||
x="428.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect4418"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect4420"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="418.58929"
|
||||
y="365.75504" /></g><g
|
||||
id="g10667"
|
||||
style="display:inline"
|
||||
transform="translate(-466.1013,-470.16522)"><rect
|
||||
style="fill:#ff7900;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect4432"
|
||||
width="6.5178571"
|
||||
height="5.0892859"
|
||||
x="522.11609"
|
||||
y="559.755" /><rect
|
||||
y="559.755"
|
||||
x="528.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect4434"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect4436"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="518.58929"
|
||||
y="559.755" /></g><g
|
||||
transform="matrix(0,1,-1,0,476.81179,-372.57224)"
|
||||
id="g4278"
|
||||
style="display:inline"><rect
|
||||
y="365.75504"
|
||||
x="422.11606"
|
||||
height="5.0892859"
|
||||
width="6.5178571"
|
||||
id="rect4280"
|
||||
style="fill:#bc781e;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect4282"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="428.58929"
|
||||
y="365.75504" /><rect
|
||||
y="365.75504"
|
||||
x="418.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect4284"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /></g><g
|
||||
style="display:inline"
|
||||
id="g10761"
|
||||
transform="matrix(0,1,-1,0,476.81179,-340.57224)"><rect
|
||||
style="fill:#bc781e;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect10763"
|
||||
width="6.5178571"
|
||||
height="5.0892859"
|
||||
x="422.11606"
|
||||
y="365.75504" /><rect
|
||||
y="365.75504"
|
||||
x="428.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect10765"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect10767"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="418.58929"
|
||||
y="365.75504" /></g><g
|
||||
style="display:inline"
|
||||
id="g10777"
|
||||
transform="matrix(0,1,-1,0,453.06093,-235.02206)"><rect
|
||||
style="fill:#bc781e;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect10779"
|
||||
width="6.5178571"
|
||||
height="5.0892859"
|
||||
x="422.11606"
|
||||
y="365.75504" /><rect
|
||||
y="365.75504"
|
||||
x="428.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect10781"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect10783"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="418.58929"
|
||||
y="365.75504" /></g><g
|
||||
transform="matrix(0,1,-1,0,453.06093,-213.9494)"
|
||||
id="g10785"
|
||||
style="display:inline"><rect
|
||||
y="365.75504"
|
||||
x="422.11606"
|
||||
height="5.0892859"
|
||||
width="6.5178571"
|
||||
id="rect10787"
|
||||
style="fill:#bc781e;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect10789"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="428.58929"
|
||||
y="365.75504" /><rect
|
||||
y="365.75504"
|
||||
x="418.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect10791"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /></g><g
|
||||
style="display:inline"
|
||||
id="g10793"
|
||||
transform="matrix(0,1,-1,0,497.6284,-222.66912)"><rect
|
||||
style="fill:#bc781e;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect10795"
|
||||
width="6.5178571"
|
||||
height="5.0892859"
|
||||
x="422.11606"
|
||||
y="365.75504" /><rect
|
||||
y="365.75504"
|
||||
x="428.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect10797"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect10799"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="418.58929"
|
||||
y="365.75504" /></g><g
|
||||
style="display:inline"
|
||||
id="g10801"
|
||||
transform="matrix(0,-1,1,0,-252.45879,579.30427)"><rect
|
||||
style="fill:#312d29;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect10803"
|
||||
width="6.5178571"
|
||||
height="5.0892859"
|
||||
x="422.11606"
|
||||
y="365.75504" /><rect
|
||||
y="365.75504"
|
||||
x="428.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect10805"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect10807"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="418.58929"
|
||||
y="365.75504" /></g><g
|
||||
transform="matrix(0,-1,1,0,-263.11623,579.54648)"
|
||||
id="g10809"
|
||||
style="display:inline"><rect
|
||||
y="365.75504"
|
||||
x="422.11606"
|
||||
height="5.0892859"
|
||||
width="6.5178571"
|
||||
id="rect10811"
|
||||
style="fill:#312d29;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect10813"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="428.58929"
|
||||
y="365.75504" /><rect
|
||||
y="365.75504"
|
||||
x="418.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect10815"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /></g><g
|
||||
style="display:inline"
|
||||
id="g10817"
|
||||
transform="matrix(0,-1,1,0,-273.53145,580.27312)"><rect
|
||||
style="fill:#312d29;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect10819"
|
||||
width="6.5178571"
|
||||
height="5.0892859"
|
||||
x="422.11606"
|
||||
y="365.75504" /><rect
|
||||
y="365.75504"
|
||||
x="428.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect10821"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect10823"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="418.58929"
|
||||
y="365.75504" /></g><g
|
||||
transform="matrix(0,-1,1,0,-272.56259,546.12087)"
|
||||
id="g10825"
|
||||
style="display:inline"><rect
|
||||
y="365.75504"
|
||||
x="422.11606"
|
||||
height="5.0892859"
|
||||
width="6.5178571"
|
||||
id="rect10827"
|
||||
style="fill:#312d29;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect10829"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="428.58929"
|
||||
y="365.75504" /><rect
|
||||
y="365.75504"
|
||||
x="418.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect10831"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /></g><g
|
||||
style="display:inline"
|
||||
id="g10833"
|
||||
transform="matrix(0,-1,1,0,-257.06086,546.36308)"><rect
|
||||
style="fill:#312d29;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect10835"
|
||||
width="6.5178571"
|
||||
height="5.0892859"
|
||||
x="422.11606"
|
||||
y="365.75504" /><rect
|
||||
y="365.75504"
|
||||
x="428.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect10837"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect10839"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="418.58929"
|
||||
y="365.75504" /></g><g
|
||||
id="g10887"><path
|
||||
sodipodi:type="arc"
|
||||
style="fill:none;stroke:#f2edda;stroke-width:1.5;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="path4550"
|
||||
sodipodi:cx="225.89285"
|
||||
sodipodi:cy="542.54077"
|
||||
sodipodi:rx="5.1785712"
|
||||
sodipodi:ry="5.1785712"
|
||||
d="m 231.07142,542.54077 c 0,2.86005 -2.31852,5.17857 -5.17857,5.17857 -2.86004,0 -5.17857,-2.31852 -5.17857,-5.17857 0,-2.86004 2.31853,-5.17857 5.17857,-5.17857 2.86005,0 5.17857,2.31853 5.17857,5.17857 z"
|
||||
transform="translate(20.6651,-466.48541)" /><path
|
||||
sodipodi:type="arc"
|
||||
style="fill:none;stroke:#f2edda;stroke-width:1.5;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="path4554"
|
||||
sodipodi:cx="225.89285"
|
||||
sodipodi:cy="542.54077"
|
||||
sodipodi:rx="5.1785712"
|
||||
sodipodi:ry="5.1785712"
|
||||
d="m 231.07142,542.54077 c 0,2.86005 -2.31852,5.17857 -5.17857,5.17857 -2.86004,0 -5.17857,-2.31852 -5.17857,-5.17857 0,-2.86004 2.31853,-5.17857 5.17857,-5.17857 2.86005,0 5.17857,2.31853 5.17857,5.17857 z"
|
||||
transform="translate(4.6651,-466.48541)" /><rect
|
||||
y="71.519623"
|
||||
x="210.81711"
|
||||
height="8.5714283"
|
||||
width="9.6428576"
|
||||
id="rect4556"
|
||||
style="fill:none;stroke:#f2edda;stroke-width:1.5;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" /></g><g
|
||||
transform="translate(0,14)"
|
||||
id="g10892"><path
|
||||
transform="translate(20.6651,-466.48541)"
|
||||
d="m 231.07142,542.54077 c 0,2.86005 -2.31852,5.17857 -5.17857,5.17857 -2.86004,0 -5.17857,-2.31852 -5.17857,-5.17857 0,-2.86004 2.31853,-5.17857 5.17857,-5.17857 2.86005,0 5.17857,2.31853 5.17857,5.17857 z"
|
||||
sodipodi:ry="5.1785712"
|
||||
sodipodi:rx="5.1785712"
|
||||
sodipodi:cy="542.54077"
|
||||
sodipodi:cx="225.89285"
|
||||
id="path10894"
|
||||
style="fill:none;stroke:#f2edda;stroke-width:1.5;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
sodipodi:type="arc" /><path
|
||||
transform="translate(4.6651,-466.48541)"
|
||||
d="m 231.07142,542.54077 c 0,2.86005 -2.31852,5.17857 -5.17857,5.17857 -2.86004,0 -5.17857,-2.31852 -5.17857,-5.17857 0,-2.86004 2.31853,-5.17857 5.17857,-5.17857 2.86005,0 5.17857,2.31853 5.17857,5.17857 z"
|
||||
sodipodi:ry="5.1785712"
|
||||
sodipodi:rx="5.1785712"
|
||||
sodipodi:cy="542.54077"
|
||||
sodipodi:cx="225.89285"
|
||||
id="path10896"
|
||||
style="fill:none;stroke:#f2edda;stroke-width:1.5;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
sodipodi:type="arc" /><rect
|
||||
style="fill:none;stroke:#f2edda;stroke-width:1.5;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="rect10898"
|
||||
width="9.6428576"
|
||||
height="8.5714283"
|
||||
x="210.81711"
|
||||
y="71.519623" /></g><g
|
||||
id="g10900"
|
||||
transform="translate(0,30)"><path
|
||||
sodipodi:type="arc"
|
||||
style="fill:none;stroke:#f2edda;stroke-width:1.5;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="path10902"
|
||||
sodipodi:cx="225.89285"
|
||||
sodipodi:cy="542.54077"
|
||||
sodipodi:rx="5.1785712"
|
||||
sodipodi:ry="5.1785712"
|
||||
d="m 231.07142,542.54077 c 0,2.86005 -2.31852,5.17857 -5.17857,5.17857 -2.86004,0 -5.17857,-2.31852 -5.17857,-5.17857 0,-2.86004 2.31853,-5.17857 5.17857,-5.17857 2.86005,0 5.17857,2.31853 5.17857,5.17857 z"
|
||||
transform="translate(20.6651,-466.48541)" /><path
|
||||
sodipodi:type="arc"
|
||||
style="fill:none;stroke:#f2edda;stroke-width:1.5;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="path10904"
|
||||
sodipodi:cx="225.89285"
|
||||
sodipodi:cy="542.54077"
|
||||
sodipodi:rx="5.1785712"
|
||||
sodipodi:ry="5.1785712"
|
||||
d="m 231.07142,542.54077 c 0,2.86005 -2.31852,5.17857 -5.17857,5.17857 -2.86004,0 -5.17857,-2.31852 -5.17857,-5.17857 0,-2.86004 2.31853,-5.17857 5.17857,-5.17857 2.86005,0 5.17857,2.31853 5.17857,5.17857 z"
|
||||
transform="translate(4.6651,-466.48541)" /><rect
|
||||
y="71.519623"
|
||||
x="210.81711"
|
||||
height="8.5714283"
|
||||
width="9.6428576"
|
||||
id="rect10906"
|
||||
style="fill:none;stroke:#f2edda;stroke-width:1.5;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" /></g><g
|
||||
transform="translate(0,46)"
|
||||
id="g10908"><path
|
||||
transform="translate(20.6651,-466.48541)"
|
||||
d="m 231.07142,542.54077 c 0,2.86005 -2.31852,5.17857 -5.17857,5.17857 -2.86004,0 -5.17857,-2.31852 -5.17857,-5.17857 0,-2.86004 2.31853,-5.17857 5.17857,-5.17857 2.86005,0 5.17857,2.31853 5.17857,5.17857 z"
|
||||
sodipodi:ry="5.1785712"
|
||||
sodipodi:rx="5.1785712"
|
||||
sodipodi:cy="542.54077"
|
||||
sodipodi:cx="225.89285"
|
||||
id="path10910"
|
||||
style="fill:none;stroke:#f2edda;stroke-width:1.5;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
sodipodi:type="arc" /><path
|
||||
transform="translate(4.6651,-466.48541)"
|
||||
d="m 231.07142,542.54077 c 0,2.86005 -2.31852,5.17857 -5.17857,5.17857 -2.86004,0 -5.17857,-2.31852 -5.17857,-5.17857 0,-2.86004 2.31853,-5.17857 5.17857,-5.17857 2.86005,0 5.17857,2.31853 5.17857,5.17857 z"
|
||||
sodipodi:ry="5.1785712"
|
||||
sodipodi:rx="5.1785712"
|
||||
sodipodi:cy="542.54077"
|
||||
sodipodi:cx="225.89285"
|
||||
id="path10912"
|
||||
style="fill:none;stroke:#f2edda;stroke-width:1.5;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
sodipodi:type="arc" /><rect
|
||||
style="fill:none;stroke:#f2edda;stroke-width:1.5;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="rect10914"
|
||||
width="9.6428576"
|
||||
height="8.5714283"
|
||||
x="210.81711"
|
||||
y="71.519623" /></g><g
|
||||
id="g10916"
|
||||
transform="translate(0,62)"><path
|
||||
sodipodi:type="arc"
|
||||
style="fill:none;stroke:#f2edda;stroke-width:1.5;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="path10918"
|
||||
sodipodi:cx="225.89285"
|
||||
sodipodi:cy="542.54077"
|
||||
sodipodi:rx="5.1785712"
|
||||
sodipodi:ry="5.1785712"
|
||||
d="m 231.07142,542.54077 c 0,2.86005 -2.31852,5.17857 -5.17857,5.17857 -2.86004,0 -5.17857,-2.31852 -5.17857,-5.17857 0,-2.86004 2.31853,-5.17857 5.17857,-5.17857 2.86005,0 5.17857,2.31853 5.17857,5.17857 z"
|
||||
transform="translate(20.6651,-466.48541)" /><path
|
||||
sodipodi:type="arc"
|
||||
style="fill:none;stroke:#f2edda;stroke-width:1.5;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="path10920"
|
||||
sodipodi:cx="225.89285"
|
||||
sodipodi:cy="542.54077"
|
||||
sodipodi:rx="5.1785712"
|
||||
sodipodi:ry="5.1785712"
|
||||
d="m 231.07142,542.54077 c 0,2.86005 -2.31852,5.17857 -5.17857,5.17857 -2.86004,0 -5.17857,-2.31852 -5.17857,-5.17857 0,-2.86004 2.31853,-5.17857 5.17857,-5.17857 2.86005,0 5.17857,2.31853 5.17857,5.17857 z"
|
||||
transform="translate(4.6651,-466.48541)" /><rect
|
||||
y="71.519623"
|
||||
x="210.81711"
|
||||
height="8.5714283"
|
||||
width="9.6428576"
|
||||
id="rect10922"
|
||||
style="fill:none;stroke:#f2edda;stroke-width:1.5;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" /></g><g
|
||||
transform="translate(0,76)"
|
||||
id="g10924"><path
|
||||
transform="translate(20.6651,-466.48541)"
|
||||
d="m 231.07142,542.54077 c 0,2.86005 -2.31852,5.17857 -5.17857,5.17857 -2.86004,0 -5.17857,-2.31852 -5.17857,-5.17857 0,-2.86004 2.31853,-5.17857 5.17857,-5.17857 2.86005,0 5.17857,2.31853 5.17857,5.17857 z"
|
||||
sodipodi:ry="5.1785712"
|
||||
sodipodi:rx="5.1785712"
|
||||
sodipodi:cy="542.54077"
|
||||
sodipodi:cx="225.89285"
|
||||
id="path10926"
|
||||
style="fill:none;stroke:#f2edda;stroke-width:1.5;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
sodipodi:type="arc" /><path
|
||||
transform="translate(4.6651,-466.48541)"
|
||||
d="m 231.07142,542.54077 c 0,2.86005 -2.31852,5.17857 -5.17857,5.17857 -2.86004,0 -5.17857,-2.31852 -5.17857,-5.17857 0,-2.86004 2.31853,-5.17857 5.17857,-5.17857 2.86005,0 5.17857,2.31853 5.17857,5.17857 z"
|
||||
sodipodi:ry="5.1785712"
|
||||
sodipodi:rx="5.1785712"
|
||||
sodipodi:cy="542.54077"
|
||||
sodipodi:cx="225.89285"
|
||||
id="path10928"
|
||||
style="fill:none;stroke:#f2edda;stroke-width:1.5;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
sodipodi:type="arc" /><rect
|
||||
style="fill:none;stroke:#f2edda;stroke-width:1.5;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="rect10930"
|
||||
width="9.6428576"
|
||||
height="8.5714283"
|
||||
x="210.81711"
|
||||
y="71.519623" /></g><g
|
||||
style="display:inline"
|
||||
transform="matrix(0,1.2406633,-1.7870765,0,753.06413,-443.20477)"
|
||||
id="g4788"><rect
|
||||
y="365.75504"
|
||||
x="422.11606"
|
||||
height="5.0892859"
|
||||
width="6.5178571"
|
||||
id="rect4790"
|
||||
style="fill:#a9814d;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect4792"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="428.58929"
|
||||
y="365.75504" /><rect
|
||||
y="365.75504"
|
||||
x="418.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect4794"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /></g><g
|
||||
id="g12054"
|
||||
transform="matrix(0,1.2406633,-1.7870765,0,753.06413,-475.20477)"
|
||||
style="display:inline"><rect
|
||||
style="fill:#a9814d;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect12056"
|
||||
width="6.5178571"
|
||||
height="5.0892859"
|
||||
x="422.11606"
|
||||
y="365.75504" /><rect
|
||||
y="365.75504"
|
||||
x="428.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect12058"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect12060"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="418.58929"
|
||||
y="365.75504" /></g><g
|
||||
style="display:inline"
|
||||
transform="matrix(1.2406633,0,0,1.7870765,-460.86273,-457.63731)"
|
||||
id="g12062"><rect
|
||||
y="365.75504"
|
||||
x="422.11606"
|
||||
height="5.0892859"
|
||||
width="6.5178571"
|
||||
id="rect12064"
|
||||
style="fill:#a9814d;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect12066"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="428.58929"
|
||||
y="365.75504" /><rect
|
||||
y="365.75504"
|
||||
x="418.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect12068"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /></g><g
|
||||
id="g12070"
|
||||
transform="matrix(1.2406633,0,0,1.7870765,-426.86273,-457.63731)"
|
||||
style="display:inline"><rect
|
||||
style="fill:#a9814d;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect12072"
|
||||
width="6.5178571"
|
||||
height="5.0892859"
|
||||
x="422.11606"
|
||||
y="365.75504" /><rect
|
||||
y="365.75504"
|
||||
x="428.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect12074"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect12076"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="418.58929"
|
||||
y="365.75504" /></g><g
|
||||
id="g12796"
|
||||
transform="matrix(1.2994908,0,0,1,-24.942522,8.9061202)"><g
|
||||
transform="translate(-0.3633218,-0.12110727)"
|
||||
id="g12766"><path
|
||||
d="m 133.77917,39.752694 0,-2.686385"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path5376"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 130.94256,39.752694 0,-2.686385"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path5378"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 145.57351,39.752694 0,-2.686385"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path5386"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 142.58758,39.752694 0,-2.686385"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path5388"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 139.75097,39.752694 0,-2.686385"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path5390"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 130.94256,69.7503 0,-2.686344"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path5454"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 133.77917,69.7503 0,-2.686344"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path5456"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 139.75097,69.7503 0,-2.686344"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path5466"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 142.58758,69.7503 0,-2.686344"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path5468"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 145.57351,69.7503 0,-2.686344"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path5470"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 124.82147,57.810942 2.6873,0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path5612"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 124.82147,60.64656 2.6873,0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path5614"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 124.82147,63.63141 2.6873,0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path5616"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 149.0073,63.63141 2.53802,0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path5618"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 149.0073,60.64656 2.53802,0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path5620"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 149.0073,57.810942 2.53802,0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path5622"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 124.82147,46.020858 2.6873,0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path5624"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 124.82147,49.005667 2.6873,0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path5626"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 124.82147,51.841284 2.6873,0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path5628"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 149.0073,51.841284 2.53802,0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path5630"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 149.0073,49.005667 2.53802,0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path5632"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 149.0073,46.020858 2.53802,0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path5634"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 136.76509,39.752694 0,-2.686385"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path5636"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 124.82147,54.826134 2.6873,0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path5726"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 136.76509,69.7503 0,-2.686344"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path5728"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 149.0073,54.826134 2.53802,0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path5730"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 124.82147,43.036008 2.6873,0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path5738"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 149.0073,43.036008 2.53802,0"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.49294174;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="path5740"
|
||||
inkscape:connector-curvature="0" /></g><rect
|
||||
style="fill:#6a6a6a;fill-opacity:1;stroke:#000000;stroke-width:0.69999999;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="rect4974"
|
||||
width="24.34742"
|
||||
height="31.192205"
|
||||
x="125.66183"
|
||||
y="37.711323" /></g><g
|
||||
id="g12952"
|
||||
style="display:inline"
|
||||
transform="matrix(0.55313316,0,0,0.55313316,202.151,-66.0335)"><rect
|
||||
style="fill:#6a6a6a;fill-opacity:1;stroke:#000000;stroke-width:3.61576581;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect3773"
|
||||
width="76.428574"
|
||||
height="76.785713"
|
||||
x="-104.28571"
|
||||
y="358.43362"
|
||||
ry="2.5" /><g
|
||||
id="g3875"
|
||||
transform="translate(-520,-37.142857)"><g
|
||||
transform="matrix(1.4970318,0,0,1,-211.28069,0.21205357)"
|
||||
id="g3781"><path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path3777"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path3779"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" /></g><g
|
||||
id="g3785"
|
||||
transform="matrix(1.4970318,0,0,1,-207.28069,0.21205357)"><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3787"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3789"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
|
||||
transform="matrix(1.4970318,0,0,1,-203.28069,0.21205357)"
|
||||
id="g3791"><path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path3793"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path3795"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" /></g><g
|
||||
id="g3797"
|
||||
transform="matrix(1.4970318,0,0,1,-199.28069,0.21205357)"><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3799"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3801"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
|
||||
transform="matrix(1.4970318,0,0,1,-195.28069,0.21205357)"
|
||||
id="g3803"><path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path3805"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path3807"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" /></g><g
|
||||
id="g3809"
|
||||
transform="matrix(1.4970318,0,0,1,-191.28069,0.21205357)"><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3811"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3813"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
|
||||
transform="matrix(1.4970318,0,0,1,-187.28069,0.21205357)"
|
||||
id="g3815"><path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path3817"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path3819"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" /></g><g
|
||||
id="g3821"
|
||||
transform="matrix(1.4970318,0,0,1,-183.28069,0.21205357)"><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3823"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3825"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
|
||||
transform="matrix(1.4970318,0,0,1,-179.28069,0.21205357)"
|
||||
id="g3827"><path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path3829"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path3831"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" /></g><g
|
||||
id="g3833"
|
||||
transform="matrix(1.4970318,0,0,1,-175.28069,0.21205357)"><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3835"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3837"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
|
||||
transform="matrix(1.4970318,0,0,1,-171.28069,0.21205357)"
|
||||
id="g3839"><path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path3841"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path3843"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" /></g><g
|
||||
id="g3845"
|
||||
transform="matrix(1.4970318,0,0,1,-167.28069,0.21205357)"><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3847"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3849"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
|
||||
transform="matrix(1.4970318,0,0,1,-163.28069,0.21205357)"
|
||||
id="g3851"><path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path3853"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path3855"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" /></g><g
|
||||
id="g3857"
|
||||
transform="matrix(1.4970318,0,0,1,-159.28069,0.21205357)"><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3859"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3861"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
|
||||
transform="matrix(1.4970318,0,0,1,-155.28069,0.21205357)"
|
||||
id="g3863"><path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path3865"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path3867"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" /></g><g
|
||||
id="g3869"
|
||||
transform="matrix(1.4970318,0,0,1,-151.28069,0.21205357)"><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3871"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3873"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g></g><g
|
||||
id="g3925"
|
||||
transform="matrix(0,1,-1,0,367.93406,-54.993437)"><g
|
||||
id="g3927"
|
||||
transform="matrix(1.4970318,0,0,1,-211.28069,0.21205357)"><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3929"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3931"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
|
||||
transform="matrix(1.4970318,0,0,1,-207.28069,0.21205357)"
|
||||
id="g3933"><path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path3935"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path3937"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" /></g><g
|
||||
id="g3939"
|
||||
transform="matrix(1.4970318,0,0,1,-203.28069,0.21205357)"><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3941"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3943"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
|
||||
transform="matrix(1.4970318,0,0,1,-199.28069,0.21205357)"
|
||||
id="g3945"><path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path3947"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path3949"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" /></g><g
|
||||
id="g3951"
|
||||
transform="matrix(1.4970318,0,0,1,-195.28069,0.21205357)"><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3953"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3955"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
|
||||
transform="matrix(1.4970318,0,0,1,-191.28069,0.21205357)"
|
||||
id="g3957"><path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path3959"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path3961"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" /></g><g
|
||||
id="g3963"
|
||||
transform="matrix(1.4970318,0,0,1,-187.28069,0.21205357)"><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3965"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3967"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
|
||||
transform="matrix(1.4970318,0,0,1,-183.28069,0.21205357)"
|
||||
id="g3969"><path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path3971"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path3973"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" /></g><g
|
||||
id="g3975"
|
||||
transform="matrix(1.4970318,0,0,1,-179.28069,0.21205357)"><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3977"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3979"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
|
||||
transform="matrix(1.4970318,0,0,1,-175.28069,0.21205357)"
|
||||
id="g3981"><path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path3983"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path3985"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" /></g><g
|
||||
id="g3987"
|
||||
transform="matrix(1.4970318,0,0,1,-171.28069,0.21205357)"><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3989"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3991"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
|
||||
transform="matrix(1.4970318,0,0,1,-167.28069,0.21205357)"
|
||||
id="g3993"><path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path3995"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path3997"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" /></g><g
|
||||
id="g3999"
|
||||
transform="matrix(1.4970318,0,0,1,-163.28069,0.21205357)"><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4001"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4003"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
|
||||
transform="matrix(1.4970318,0,0,1,-159.28069,0.21205357)"
|
||||
id="g4005"><path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path4007"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path4009"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" /></g><g
|
||||
id="g4011"
|
||||
transform="matrix(1.4970318,0,0,1,-155.28069,0.21205357)"><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4013"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4015"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
|
||||
transform="matrix(1.4970318,0,0,1,-151.28069,0.21205357)"
|
||||
id="g4017"><path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path4019"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path4021"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" /></g></g><g
|
||||
transform="matrix(0,1,1,0,-500.02315,-54.993437)"
|
||||
id="g4023"><g
|
||||
transform="matrix(1.4970318,0,0,1,-211.28069,0.21205357)"
|
||||
id="g4025"><path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path4027"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path4029"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" /></g><g
|
||||
id="g4031"
|
||||
transform="matrix(1.4970318,0,0,1,-207.28069,0.21205357)"><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4033"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4035"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
|
||||
transform="matrix(1.4970318,0,0,1,-203.28069,0.21205357)"
|
||||
id="g4037"><path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path4039"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path4041"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" /></g><g
|
||||
id="g4043"
|
||||
transform="matrix(1.4970318,0,0,1,-199.28069,0.21205357)"><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4045"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4047"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
|
||||
transform="matrix(1.4970318,0,0,1,-195.28069,0.21205357)"
|
||||
id="g4049"><path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path4051"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path4053"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" /></g><g
|
||||
id="g4055"
|
||||
transform="matrix(1.4970318,0,0,1,-191.28069,0.21205357)"><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4057"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4059"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
|
||||
transform="matrix(1.4970318,0,0,1,-187.28069,0.21205357)"
|
||||
id="g4061"><path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path4063"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path4065"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" /></g><g
|
||||
id="g4067"
|
||||
transform="matrix(1.4970318,0,0,1,-183.28069,0.21205357)"><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4069"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4071"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
|
||||
transform="matrix(1.4970318,0,0,1,-179.28069,0.21205357)"
|
||||
id="g4073"><path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path4075"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path4077"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" /></g><g
|
||||
id="g4079"
|
||||
transform="matrix(1.4970318,0,0,1,-175.28069,0.21205357)"><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4081"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4083"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
|
||||
transform="matrix(1.4970318,0,0,1,-171.28069,0.21205357)"
|
||||
id="g4085"><path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path4087"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path4089"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" /></g><g
|
||||
id="g4091"
|
||||
transform="matrix(1.4970318,0,0,1,-167.28069,0.21205357)"><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4093"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4095"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
|
||||
transform="matrix(1.4970318,0,0,1,-163.28069,0.21205357)"
|
||||
id="g4097"><path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path4099"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path4101"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" /></g><g
|
||||
id="g4103"
|
||||
transform="matrix(1.4970318,0,0,1,-159.28069,0.21205357)"><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4105"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4107"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
|
||||
transform="matrix(1.4970318,0,0,1,-155.28069,0.21205357)"
|
||||
id="g4109"><path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path4111"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path4113"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" /></g><g
|
||||
id="g4115"
|
||||
transform="matrix(1.4970318,0,0,1,-151.28069,0.21205357)"><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4117"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4119"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g></g><g
|
||||
id="g4121"
|
||||
transform="matrix(1,0,0,-1,-520,830.07704)"><g
|
||||
id="g4123"
|
||||
transform="matrix(1.4970318,0,0,1,-211.28069,0.21205357)"><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4125"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4127"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
|
||||
transform="matrix(1.4970318,0,0,1,-207.28069,0.21205357)"
|
||||
id="g4129"><path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path4131"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path4133"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" /></g><g
|
||||
id="g4135"
|
||||
transform="matrix(1.4970318,0,0,1,-203.28069,0.21205357)"><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4137"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4139"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
|
||||
transform="matrix(1.4970318,0,0,1,-199.28069,0.21205357)"
|
||||
id="g4141"><path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path4143"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path4145"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" /></g><g
|
||||
id="g4147"
|
||||
transform="matrix(1.4970318,0,0,1,-195.28069,0.21205357)"><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4149"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4151"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
|
||||
transform="matrix(1.4970318,0,0,1,-191.28069,0.21205357)"
|
||||
id="g4153"><path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path4155"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path4157"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" /></g><g
|
||||
id="g4159"
|
||||
transform="matrix(1.4970318,0,0,1,-187.28069,0.21205357)"><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4161"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4163"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
|
||||
transform="matrix(1.4970318,0,0,1,-183.28069,0.21205357)"
|
||||
id="g4165"><path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path4167"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path4169"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" /></g><g
|
||||
id="g4171"
|
||||
transform="matrix(1.4970318,0,0,1,-179.28069,0.21205357)"><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4173"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4175"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
|
||||
transform="matrix(1.4970318,0,0,1,-175.28069,0.21205357)"
|
||||
id="g4177"><path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path4179"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path4181"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" /></g><g
|
||||
id="g4183"
|
||||
transform="matrix(1.4970318,0,0,1,-171.28069,0.21205357)"><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4185"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4187"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
|
||||
transform="matrix(1.4970318,0,0,1,-167.28069,0.21205357)"
|
||||
id="g4189"><path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path4191"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path4193"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" /></g><g
|
||||
id="g4195"
|
||||
transform="matrix(1.4970318,0,0,1,-163.28069,0.21205357)"><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4197"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4199"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
|
||||
transform="matrix(1.4970318,0,0,1,-159.28069,0.21205357)"
|
||||
id="g4201"><path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path4203"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path4205"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" /></g><g
|
||||
id="g4207"
|
||||
transform="matrix(1.4970318,0,0,1,-155.28069,0.21205357)"><path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4209"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /><path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4211"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1" /></g><g
|
||||
transform="matrix(1.4970318,0,0,1,-151.28069,0.21205357)"
|
||||
id="g4213"><path
|
||||
style="fill:none;stroke:#e9dcdc;stroke-width:1.80788291px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.9087,394.32647 0,-7.85715"
|
||||
id="path4215"
|
||||
inkscape:connector-curvature="0" /><path
|
||||
style="fill:none;stroke:#8c8989;stroke-width:1.56546891px;stroke-linecap:square;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 423.84066,392.00721 0.13607,0"
|
||||
id="path4217"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" /></g></g></g><g
|
||||
style="display:inline"
|
||||
id="g4920"
|
||||
transform="matrix(0.41419929,0,0,0.41419929,-10.368172,-50.871127)"><g
|
||||
transform="matrix(0,1.4970318,-1,0,849.26635,-33.0226)"
|
||||
id="g4871"
|
||||
style="display:inline"><rect
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none"
|
||||
id="rect4867"
|
||||
width="10.985409"
|
||||
height="4.0486217"
|
||||
x="-386.60983"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-383.45309"
|
||||
height="4.0486217"
|
||||
width="2.5253813"
|
||||
id="rect4869"
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none" /></g><g
|
||||
id="g4875"
|
||||
transform="matrix(0,1.4970318,-1,0,849.26635,-23.0226)"
|
||||
style="display:inline"><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-386.60983"
|
||||
height="4.0486217"
|
||||
width="10.985409"
|
||||
id="rect4877"
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none" /><rect
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none"
|
||||
id="rect4879"
|
||||
width="2.5253813"
|
||||
height="4.0486217"
|
||||
x="-383.45309"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /></g><g
|
||||
transform="matrix(0,1.4970318,-1,0,849.26635,-13.0226)"
|
||||
id="g4881"
|
||||
style="display:inline"><rect
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none"
|
||||
id="rect4883"
|
||||
width="10.985409"
|
||||
height="4.0486217"
|
||||
x="-386.60983"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-383.45309"
|
||||
height="4.0486217"
|
||||
width="2.5253813"
|
||||
id="rect4885"
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none" /></g><g
|
||||
id="g4887"
|
||||
transform="matrix(0,1.4970318,1,0,55.91598,-13.0226)"
|
||||
style="display:inline"><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-386.60983"
|
||||
height="4.0486217"
|
||||
width="10.985409"
|
||||
id="rect4889"
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none" /><rect
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none"
|
||||
id="rect4891"
|
||||
width="2.5253813"
|
||||
height="4.0486217"
|
||||
x="-383.45309"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /></g><g
|
||||
transform="matrix(0,1.4970318,1,0,55.91598,-33.0226)"
|
||||
id="g4899"
|
||||
style="display:inline"><rect
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none"
|
||||
id="rect4901"
|
||||
width="10.985409"
|
||||
height="4.0486217"
|
||||
x="-386.60983"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-383.45309"
|
||||
height="4.0486217"
|
||||
width="2.5253813"
|
||||
id="rect4903"
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none" /></g><rect
|
||||
ry="1.5"
|
||||
y="590.15265"
|
||||
x="443.12988"
|
||||
height="31.819805"
|
||||
width="18.687822"
|
||||
id="rect4841"
|
||||
style="fill:#6a6a6a;fill-opacity:1;stroke:#000000;stroke-width:2.41429687;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /></g><g
|
||||
transform="matrix(0,0.41419929,-0.41419929,0,462.12545,-133.30339)"
|
||||
id="g13877"
|
||||
style="display:inline"><g
|
||||
style="display:inline"
|
||||
id="g13879"
|
||||
transform="matrix(0,1.4970318,-1,0,849.26635,-33.0226)"><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-386.60983"
|
||||
height="4.0486217"
|
||||
width="10.985409"
|
||||
id="rect13881"
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none" /><rect
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none"
|
||||
id="rect13883"
|
||||
width="2.5253813"
|
||||
height="4.0486217"
|
||||
x="-383.45309"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /></g><g
|
||||
style="display:inline"
|
||||
transform="matrix(0,1.4970318,-1,0,849.26635,-23.0226)"
|
||||
id="g13885"><rect
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none"
|
||||
id="rect13887"
|
||||
width="10.985409"
|
||||
height="4.0486217"
|
||||
x="-386.60983"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-383.45309"
|
||||
height="4.0486217"
|
||||
width="2.5253813"
|
||||
id="rect13889"
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none" /></g><g
|
||||
style="display:inline"
|
||||
id="g13891"
|
||||
transform="matrix(0,1.4970318,-1,0,849.26635,-13.0226)"><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-386.60983"
|
||||
height="4.0486217"
|
||||
width="10.985409"
|
||||
id="rect13893"
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none" /><rect
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none"
|
||||
id="rect13895"
|
||||
width="2.5253813"
|
||||
height="4.0486217"
|
||||
x="-383.45309"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /></g><g
|
||||
style="display:inline"
|
||||
transform="matrix(0,1.4970318,1,0,55.91598,-13.0226)"
|
||||
id="g13897"><rect
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none"
|
||||
id="rect13899"
|
||||
width="10.985409"
|
||||
height="4.0486217"
|
||||
x="-386.60983"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-383.45309"
|
||||
height="4.0486217"
|
||||
width="2.5253813"
|
||||
id="rect13901"
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none" /></g><g
|
||||
style="display:inline"
|
||||
id="g13903"
|
||||
transform="matrix(0,1.4970318,1,0,55.91598,-33.0226)"><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-386.60983"
|
||||
height="4.0486217"
|
||||
width="10.985409"
|
||||
id="rect13905"
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none" /><rect
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none"
|
||||
id="rect13907"
|
||||
width="2.5253813"
|
||||
height="4.0486217"
|
||||
x="-383.45309"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /></g><rect
|
||||
style="fill:#6a6a6a;fill-opacity:1;stroke:#000000;stroke-width:2.41429687;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect13909"
|
||||
width="18.687822"
|
||||
height="31.819805"
|
||||
x="443.12988"
|
||||
y="590.15265"
|
||||
ry="1.5" /></g><g
|
||||
id="g13760"
|
||||
style="display:inline"
|
||||
transform="matrix(0,0.61819183,-0.61819183,0,444.94676,-97.125819)"><rect
|
||||
transform="translate(188.57143,331.57648)"
|
||||
y="269.42856"
|
||||
x="140.71428"
|
||||
height="52.142857"
|
||||
width="89.285713"
|
||||
id="rect5020"
|
||||
style="fill:#fffcfc;fill-opacity:1;stroke:#828282;stroke-width:3.23524165;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" /><g
|
||||
transform="matrix(-1.4970318,0,0,1,971.39158,213.03078)"
|
||||
id="g4964-3"
|
||||
style="display:inline"><rect
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none"
|
||||
id="rect4966-2"
|
||||
width="10.985409"
|
||||
height="4.0486217"
|
||||
x="-386.60983"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-383.45309"
|
||||
height="4.0486217"
|
||||
width="2.5253813"
|
||||
id="rect4968-1"
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none" /></g><g
|
||||
style="display:inline"
|
||||
id="g5046"
|
||||
transform="matrix(-1.4970318,0,0,1,981.39158,213.03078)"><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-386.60983"
|
||||
height="4.0486217"
|
||||
width="10.985409"
|
||||
id="rect5048"
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none" /><rect
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none"
|
||||
id="rect5050"
|
||||
width="2.5253813"
|
||||
height="4.0486217"
|
||||
x="-383.45309"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /></g><g
|
||||
transform="matrix(-1.4970318,0,0,1,991.39158,213.03078)"
|
||||
id="g5052"
|
||||
style="display:inline"><rect
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none"
|
||||
id="rect5054"
|
||||
width="10.985409"
|
||||
height="4.0486217"
|
||||
x="-386.60983"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-383.45309"
|
||||
height="4.0486217"
|
||||
width="2.5253813"
|
||||
id="rect5056"
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none" /></g><g
|
||||
style="display:inline"
|
||||
id="g5058"
|
||||
transform="matrix(-1.4970318,0,0,1,1001.3916,213.03078)"><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-386.60983"
|
||||
height="4.0486217"
|
||||
width="10.985409"
|
||||
id="rect5060"
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none" /><rect
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none"
|
||||
id="rect5062"
|
||||
width="2.5253813"
|
||||
height="4.0486217"
|
||||
x="-383.45309"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /></g><g
|
||||
transform="matrix(-1.4970318,0,0,1,1011.3916,213.03078)"
|
||||
id="g5064"
|
||||
style="display:inline"><rect
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none"
|
||||
id="rect5066"
|
||||
width="10.985409"
|
||||
height="4.0486217"
|
||||
x="-386.60983"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-383.45309"
|
||||
height="4.0486217"
|
||||
width="2.5253813"
|
||||
id="rect5068"
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none" /></g><g
|
||||
style="display:inline"
|
||||
id="g5070"
|
||||
transform="matrix(-1.4970318,0,0,1,1021.3916,213.03078)"><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-386.60983"
|
||||
height="4.0486217"
|
||||
width="10.985409"
|
||||
id="rect5072"
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none" /><rect
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none"
|
||||
id="rect5074"
|
||||
width="2.5253813"
|
||||
height="4.0486217"
|
||||
x="-383.45309"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /></g><g
|
||||
style="display:inline"
|
||||
id="g13998"
|
||||
transform="matrix(-1.4970318,0,0,1,1031.0972,213.03078)"><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-386.60983"
|
||||
height="4.0486217"
|
||||
width="10.985409"
|
||||
id="rect14000"
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none" /><rect
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none"
|
||||
id="rect14002"
|
||||
width="2.5253813"
|
||||
height="4.0486217"
|
||||
x="-383.45309"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /></g><g
|
||||
transform="matrix(-1.4970318,0,0,1,1040.8028,213.03078)"
|
||||
id="g14004"
|
||||
style="display:inline"><rect
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none"
|
||||
id="rect14006"
|
||||
width="10.985409"
|
||||
height="4.0486217"
|
||||
x="-386.60983"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-383.45309"
|
||||
height="4.0486217"
|
||||
width="2.5253813"
|
||||
id="rect14008"
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none" /></g></g><g
|
||||
style="display:inline"
|
||||
id="g4920-2"
|
||||
transform="matrix(-0.48222043,0,0,-0.59728256,285.82656,546.58597)"><g
|
||||
transform="matrix(0,1.4970318,-1,0,849.26635,-33.0226)"
|
||||
id="g4871-7"
|
||||
style="display:inline"><rect
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none"
|
||||
id="rect4867-0"
|
||||
width="10.985409"
|
||||
height="4.0486217"
|
||||
x="-386.60983"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-383.45309"
|
||||
height="4.0486217"
|
||||
width="2.5253813"
|
||||
id="rect4869-4"
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none" /></g><g
|
||||
id="g4875-1"
|
||||
transform="matrix(0,1.4970318,-1,0,849.26635,-23.0226)"
|
||||
style="display:inline"><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-386.60983"
|
||||
height="4.0486217"
|
||||
width="10.985409"
|
||||
id="rect4877-3"
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none" /><rect
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none"
|
||||
id="rect4879-4"
|
||||
width="2.5253813"
|
||||
height="4.0486217"
|
||||
x="-383.45309"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /></g><g
|
||||
transform="matrix(0,1.4970318,-1,0,849.26635,-13.0226)"
|
||||
id="g4881-9"
|
||||
style="display:inline"><rect
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none"
|
||||
id="rect4883-6"
|
||||
width="10.985409"
|
||||
height="4.0486217"
|
||||
x="-386.60983"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-383.45309"
|
||||
height="4.0486217"
|
||||
width="2.5253813"
|
||||
id="rect4885-2"
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none" /></g><g
|
||||
id="g4887-8"
|
||||
transform="matrix(0,1.4970318,1,0,55.91598,-13.0226)"
|
||||
style="display:inline"><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-386.60983"
|
||||
height="4.0486217"
|
||||
width="10.985409"
|
||||
id="rect4889-3"
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none" /><rect
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none"
|
||||
id="rect4891-3"
|
||||
width="2.5253813"
|
||||
height="4.0486217"
|
||||
x="-383.45309"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /></g><g
|
||||
transform="matrix(0,1.4970318,1,0,55.91598,-33.0226)"
|
||||
id="g4899-7"
|
||||
style="display:inline"><rect
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none"
|
||||
id="rect4901-7"
|
||||
width="10.985409"
|
||||
height="4.0486217"
|
||||
x="-386.60983"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-383.45309"
|
||||
height="4.0486217"
|
||||
width="2.5253813"
|
||||
id="rect4903-8"
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none" /></g><rect
|
||||
ry="1.5"
|
||||
y="590.15265"
|
||||
x="443.12988"
|
||||
height="31.819805"
|
||||
width="18.687822"
|
||||
id="rect4841-1"
|
||||
style="fill:#6a6a6a;fill-opacity:1;stroke:#000000;stroke-width:1.86331928;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /></g><g
|
||||
style="display:inline"
|
||||
id="g14076"
|
||||
transform="matrix(0,-1,1,0,-150.96398,652.23853)"><rect
|
||||
y="365.75504"
|
||||
x="426.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect14080"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect14082"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="418.58929"
|
||||
y="365.75504" /></g><g
|
||||
transform="matrix(0.61819183,0,0,0.48347584,-108.7519,-76.23362)"
|
||||
style="display:inline"
|
||||
id="g14084"><rect
|
||||
style="fill:#fffcfc;fill-opacity:1;stroke:#828282;stroke-width:3.65831399;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="rect14086"
|
||||
width="53.268898"
|
||||
height="52.142857"
|
||||
x="329.28571"
|
||||
y="601.00507" /><g
|
||||
style="display:inline"
|
||||
id="g14088"
|
||||
transform="matrix(-1.4970318,0,0,1,971.39158,213.03078)"><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-386.60983"
|
||||
height="4.0486217"
|
||||
width="10.985409"
|
||||
id="rect14090"
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none" /><rect
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none"
|
||||
id="rect14092"
|
||||
width="2.5253813"
|
||||
height="4.0486217"
|
||||
x="-383.45309"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /></g><g
|
||||
transform="matrix(-1.4970318,0,0,1,981.39158,213.03078)"
|
||||
id="g14094"
|
||||
style="display:inline"><rect
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none"
|
||||
id="rect14096"
|
||||
width="10.985409"
|
||||
height="4.0486217"
|
||||
x="-386.60983"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-383.45309"
|
||||
height="4.0486217"
|
||||
width="2.5253813"
|
||||
id="rect14098"
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none" /></g><g
|
||||
style="display:inline"
|
||||
id="g14100"
|
||||
transform="matrix(-1.4970318,0,0,1,991.39158,213.03078)"><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-386.60983"
|
||||
height="4.0486217"
|
||||
width="10.985409"
|
||||
id="rect14102"
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none" /><rect
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none"
|
||||
id="rect14104"
|
||||
width="2.5253813"
|
||||
height="4.0486217"
|
||||
x="-383.45309"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /></g><g
|
||||
transform="matrix(-1.4970318,0,0,1,1001.3916,213.03078)"
|
||||
id="g14106"
|
||||
style="display:inline"><rect
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none"
|
||||
id="rect14108"
|
||||
width="10.985409"
|
||||
height="4.0486217"
|
||||
x="-386.60983"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-383.45309"
|
||||
height="4.0486217"
|
||||
width="2.5253813"
|
||||
id="rect14110"
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none" /></g></g><g
|
||||
id="g14136"
|
||||
style="display:inline"
|
||||
transform="matrix(0.61819183,0,0,0.48347584,-30.7519,-76.23362)"><rect
|
||||
y="601.00507"
|
||||
x="329.28571"
|
||||
height="52.142857"
|
||||
width="53.268898"
|
||||
id="rect14138"
|
||||
style="fill:#fffcfc;fill-opacity:1;stroke:#828282;stroke-width:3.65831399;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" /><g
|
||||
transform="matrix(-1.4970318,0,0,1,971.39158,213.03078)"
|
||||
id="g14140"
|
||||
style="display:inline"><rect
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none"
|
||||
id="rect14142"
|
||||
width="10.985409"
|
||||
height="4.0486217"
|
||||
x="-386.60983"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-383.45309"
|
||||
height="4.0486217"
|
||||
width="2.5253813"
|
||||
id="rect14144"
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none" /></g><g
|
||||
style="display:inline"
|
||||
id="g14146"
|
||||
transform="matrix(-1.4970318,0,0,1,981.39158,213.03078)"><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-386.60983"
|
||||
height="4.0486217"
|
||||
width="10.985409"
|
||||
id="rect14148"
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none" /><rect
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none"
|
||||
id="rect14150"
|
||||
width="2.5253813"
|
||||
height="4.0486217"
|
||||
x="-383.45309"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /></g><g
|
||||
transform="matrix(-1.4970318,0,0,1,991.39158,213.03078)"
|
||||
id="g14152"
|
||||
style="display:inline"><rect
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none"
|
||||
id="rect14154"
|
||||
width="10.985409"
|
||||
height="4.0486217"
|
||||
x="-386.60983"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-383.45309"
|
||||
height="4.0486217"
|
||||
width="2.5253813"
|
||||
id="rect14156"
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none" /></g><g
|
||||
style="display:inline"
|
||||
id="g14158"
|
||||
transform="matrix(-1.4970318,0,0,1,1001.3916,213.03078)"><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-386.60983"
|
||||
height="4.0486217"
|
||||
width="10.985409"
|
||||
id="rect14160"
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none" /><rect
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none"
|
||||
id="rect14162"
|
||||
width="2.5253813"
|
||||
height="4.0486217"
|
||||
x="-383.45309"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /></g></g><g
|
||||
style="display:inline"
|
||||
transform="matrix(2.4017041,0,0,3.9408912,-788.51882,-1271.7817)"
|
||||
id="g14164"><rect
|
||||
y="365.75504"
|
||||
x="422.11606"
|
||||
height="5.0892859"
|
||||
width="6.5178571"
|
||||
id="rect14166"
|
||||
style="fill:#00440d;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect14168"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="428.58929"
|
||||
y="365.75504" /><rect
|
||||
y="365.75504"
|
||||
x="418.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect14170"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /></g><g
|
||||
style="display:inline"
|
||||
id="g14192"
|
||||
transform="translate(-342.57061,-300.15766)"><rect
|
||||
style="fill:#312d29;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect14194"
|
||||
width="6.5178571"
|
||||
height="5.0892859"
|
||||
x="422.11606"
|
||||
y="365.75504" /><rect
|
||||
y="365.75504"
|
||||
x="428.58929"
|
||||
height="5.0892859"
|
||||
width="3.5714285"
|
||||
id="rect14196"
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /><rect
|
||||
style="fill:#d3d0ce;fill-opacity:1;stroke:#8c8989;stroke-width:0;stroke-linecap:square;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect14198"
|
||||
width="3.5714285"
|
||||
height="5.0892859"
|
||||
x="418.58929"
|
||||
y="365.75504" /></g><g
|
||||
style="display:inline"
|
||||
id="g14200"
|
||||
transform="matrix(0,0.63857044,-0.6183842,0,527.83252,-72.180508)"><g
|
||||
transform="matrix(0,1.4970318,-1,0,852.39835,-33.0226)"
|
||||
id="g14202"
|
||||
style="display:inline"><rect
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none"
|
||||
id="rect14204"
|
||||
width="10.985409"
|
||||
height="4.0486217"
|
||||
x="-386.60983"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-383.45309"
|
||||
height="4.0486217"
|
||||
width="2.5253813"
|
||||
id="rect14206"
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none" /></g><g
|
||||
id="g14208"
|
||||
transform="matrix(0,1.4970318,-1,0,852.39835,-23.0226)"
|
||||
style="display:inline"><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-386.60983"
|
||||
height="4.0486217"
|
||||
width="10.985409"
|
||||
id="rect14210"
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none" /><rect
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none"
|
||||
id="rect14212"
|
||||
width="2.5253813"
|
||||
height="4.0486217"
|
||||
x="-383.45309"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /></g><g
|
||||
transform="matrix(0,1.4970318,-1,0,852.39835,-13.0226)"
|
||||
id="g14214"
|
||||
style="display:inline"><rect
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none"
|
||||
id="rect14216"
|
||||
width="10.985409"
|
||||
height="4.0486217"
|
||||
x="-386.60983"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-383.45309"
|
||||
height="4.0486217"
|
||||
width="2.5253813"
|
||||
id="rect14218"
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none" /></g><g
|
||||
id="g14220"
|
||||
transform="matrix(0,1.4970318,1,0,46.519992,-13.0226)"
|
||||
style="display:inline"><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-386.60983"
|
||||
height="4.0486217"
|
||||
width="10.985409"
|
||||
id="rect14222"
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none" /><rect
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none"
|
||||
id="rect14224"
|
||||
width="2.5253813"
|
||||
height="4.0486217"
|
||||
x="-383.45309"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /></g><g
|
||||
transform="matrix(0,1.4970318,1,0,46.519992,-33.0226)"
|
||||
id="g14226"
|
||||
style="display:inline"><rect
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none"
|
||||
id="rect14228"
|
||||
width="10.985409"
|
||||
height="4.0486217"
|
||||
x="-386.60983"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-383.45309"
|
||||
height="4.0486217"
|
||||
width="2.5253813"
|
||||
id="rect14230"
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none" /></g><g
|
||||
style="display:inline"
|
||||
transform="matrix(0,1.4970318,1,0,46.519992,-22.679788)"
|
||||
id="g14240"><rect
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none"
|
||||
id="rect14242"
|
||||
width="10.985409"
|
||||
height="4.0486217"
|
||||
x="-386.60983"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-383.45309"
|
||||
height="4.0486217"
|
||||
width="2.5253813"
|
||||
id="rect14244"
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none" /></g><g
|
||||
style="display:inline"
|
||||
transform="matrix(0,1.4970318,1,0,46.519992,-3.365413)"
|
||||
id="g14246"><rect
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none"
|
||||
id="rect14248"
|
||||
width="10.985409"
|
||||
height="4.0486217"
|
||||
x="-386.60983"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-383.45309"
|
||||
height="4.0486217"
|
||||
width="2.5253813"
|
||||
id="rect14250"
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none" /></g><g
|
||||
style="display:inline"
|
||||
id="g14252"
|
||||
transform="matrix(0,1.4970318,-1,0,852.39835,-3.365413)"><rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
y="417.41403"
|
||||
x="-386.60983"
|
||||
height="4.0486217"
|
||||
width="10.985409"
|
||||
id="rect14254"
|
||||
style="fill:#e9dcdc;fill-opacity:1;stroke:none" /><rect
|
||||
style="fill:#8c8989;fill-opacity:1;stroke:none"
|
||||
id="rect14256"
|
||||
width="2.5253813"
|
||||
height="4.0486217"
|
||||
x="-383.45309"
|
||||
y="417.41403"
|
||||
transform="matrix(0,-1,1,0,0,0)" /></g><rect
|
||||
ry="1.9272836"
|
||||
y="590.15265"
|
||||
x="432.12994"
|
||||
height="40.883862"
|
||||
width="34.998043"
|
||||
id="rect14232"
|
||||
style="fill:#6a6a6a;fill-opacity:1;stroke:#000000;stroke-width:1.59135258;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /></g><text
|
||||
xml:space="preserve"
|
||||
style="font-size:18px;font-style:normal;font-variant:normal;font-weight:bold;font-stretch:normal;text-align:start;line-height:125%;letter-spacing:0px;word-spacing:0px;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;font-family:Arial;-inkscape-font-specification:Sans Bold"
|
||||
x="123.07243"
|
||||
y="109.6582"
|
||||
id="text3548"
|
||||
sodipodi:linespacing="125%"><tspan
|
||||
sodipodi:role="line"
|
||||
id="tspan3550"
|
||||
x="123.07243"
|
||||
y="109.6582"
|
||||
style="font-size:20px;fill:#ffffff">CC3D</tspan></text>
|
||||
</g></g></svg>
|
After Width: | Height: | Size: 120 KiB |
BIN
ground/openpilotgcs/src/plugins/uploader/images/gcs-board-cc.png
Normal file
After Width: | Height: | Size: 237 KiB |
After Width: | Height: | Size: 242 KiB |
BIN
ground/openpilotgcs/src/plugins/uploader/images/pipx.png
Normal file
After Width: | Height: | Size: 180 KiB |
@ -1074,6 +1074,7 @@ int DFUObject::receiveData(void *data, int size)
|
||||
#define BOARD_ID_MB 1
|
||||
#define BOARD_ID_INS 2
|
||||
#define BOARD_ID_PIP 3
|
||||
#define BOARD_ID_CC 4
|
||||
#define BOARD_ID_REVO 9
|
||||
|
||||
/**
|
||||
@ -1097,6 +1098,9 @@ OP_DFU::eBoardType DFUObject::GetBoardType(int boardNum)
|
||||
case BOARD_ID_PIP: // PIP RF Modem
|
||||
brdType = eBoardPip;
|
||||
break;
|
||||
case BOARD_ID_CC: // CopterControl family
|
||||
brdType = eBoardCC;
|
||||
break;
|
||||
case BOARD_ID_REVO: // Revo board
|
||||
brdType = eBoardRevo;
|
||||
break;
|
||||
|
@ -92,6 +92,7 @@ enum eBoardType {
|
||||
eBoardMainbrd = 1,
|
||||
eBoardINS,
|
||||
eBoardPip = 3,
|
||||
eBoardCC = 4,
|
||||
eBoardRevo = 9,
|
||||
};
|
||||
|
||||
|
@ -72,9 +72,19 @@ void RunningDeviceWidget::populate()
|
||||
myDevice->devicePicture->scene()->clear();
|
||||
|
||||
switch (id) {
|
||||
case 0x0101:
|
||||
case 0x0201:
|
||||
devicePic.load("");
|
||||
break;
|
||||
case 0x0301:
|
||||
devicePic.load(":/uploader/images/gcs-board-oplink.png");
|
||||
break;
|
||||
case 0x0401:
|
||||
devicePic.load(":/uploader/images/gcs-board-cc.png");
|
||||
break;
|
||||
case 0x0402:
|
||||
devicePic.load(":/uploader/images/gcs-board-cc3d.png");
|
||||
break;
|
||||
case 0x0903:
|
||||
devicePic.load(":/uploader/images/gcs-board-revo.png");
|
||||
break;
|
||||
|
@ -5,9 +5,17 @@
|
||||
<file>images/process-stop.svg</file>
|
||||
<file>images/dialog-apply.svg</file>
|
||||
<file>images/gtk-info.svg</file>
|
||||
<file>images/deviceID-0401.svg</file>
|
||||
<file>images/deviceID-0301.svg</file>
|
||||
<file>images/deviceID-0201.svg</file>
|
||||
<file>images/deviceID-0101.svg</file>
|
||||
<file>images/application-certificate.svg</file>
|
||||
<file>images/warning.svg</file>
|
||||
<file>images/error.svg</file>
|
||||
<file>images/deviceID-0402.svg</file>
|
||||
<file>images/gcs-board-cc.png</file>
|
||||
<file>images/gcs-board-cc3d.png</file>
|
||||
<file>images/pipx.png</file>
|
||||
<file>images/gcs-board-oplink.png</file>
|
||||
<file>images/gcs-board-revo.png</file>
|
||||
<file>images/gcs-board-nano.png</file>
|
||||
|
@ -752,6 +752,10 @@ bool UploaderGadgetWidget::autoUpdate(bool erase)
|
||||
case 0x301:
|
||||
filename = "fw_oplinkmini";
|
||||
break;
|
||||
case 0x401:
|
||||
case 0x402:
|
||||
filename = "fw_coptercontrol";
|
||||
break;
|
||||
case 0x501:
|
||||
filename = "fw_osd";
|
||||
break;
|
||||
@ -813,6 +817,7 @@ bool UploaderGadgetWidget::autoUpdate(bool erase)
|
||||
commonSystemBoot(false, erase);
|
||||
|
||||
// Wait for board to connect to GCS again after boot and erase
|
||||
// For older board like CC3D this can take some time
|
||||
// Theres a special case with OPLink
|
||||
if (!telemetryManager->isConnected() && !m_oplinkwatchdog.isConnected()) {
|
||||
progressUpdate(erase ? BOOTING_AND_ERASING : BOOTING, QVariant());
|
||||
|
@ -182,11 +182,18 @@ void UsageTrackerPlugin::collectUsageParameters(QMap<QString, QString> ¶mete
|
||||
parameters["conf_receiver"] = getUAVFieldValue(objManager, "ManualControlSettings", "ChannelGroups", 0);
|
||||
parameters["conf_vehicle"] = getUAVFieldValue(objManager, "SystemSettings", "AirframeType");
|
||||
|
||||
// Revolution family
|
||||
parameters["conf_rport"] = getUAVFieldValue(objManager, "HwSettings", "RM_RcvrPort");
|
||||
parameters["conf_mport"] = getUAVFieldValue(objManager, "HwSettings", "RM_MainPort");
|
||||
parameters["conf_fport"] = getUAVFieldValue(objManager, "HwSettings", "RM_FlexiPort");
|
||||
parameters["conf_fusion"] = getUAVFieldValue(objManager, "RevoSettings", "FusionAlgorithm");
|
||||
if ((boardModel & 0xff00) == 0x0400) {
|
||||
// CopterControl family
|
||||
parameters["conf_rport"] = getUAVFieldValue(objManager, "HwSettings", "CC_RcvrPort");
|
||||
parameters["conf_mport"] = getUAVFieldValue(objManager, "HwSettings", "CC_MainPort");
|
||||
parameters["conf_fport"] = getUAVFieldValue(objManager, "HwSettings", "CC_FlexiPort");
|
||||
} else if ((boardModel & 0xff00) == 0x0900) {
|
||||
// Revolution family
|
||||
parameters["conf_rport"] = getUAVFieldValue(objManager, "HwSettings", "RM_RcvrPort");
|
||||
parameters["conf_mport"] = getUAVFieldValue(objManager, "HwSettings", "RM_MainPort");
|
||||
parameters["conf_fport"] = getUAVFieldValue(objManager, "HwSettings", "RM_FlexiPort");
|
||||
parameters["conf_fusion"] = getUAVFieldValue(objManager, "RevoSettings", "FusionAlgorithm");
|
||||
}
|
||||
|
||||
parameters["conf_uport"] = getUAVFieldValue(objManager, "HwSettings", "USB_HIDPort");
|
||||
parameters["conf_vport"] = getUAVFieldValue(objManager, "HwSettings", "USB_VCPPort");
|
||||
|
@ -1,6 +1,10 @@
|
||||
<xml>
|
||||
<object name="HwSettings" singleinstance="true" settings="true" category="System">
|
||||
<description>Selection of optional hardware configurations.</description>
|
||||
<field name="CC_RcvrPort" units="function" type="enum" elements="1" options="Disabled+OneShot,PWM+NoOneShot,PPM+NoOneShot,PPM+PWM+NoOneShot,PPM+Outputs+NoOneShot,PPM_PIN8+OneShot, Outputs+OneShot" defaultvalue="PWM+NoOneShot"/>
|
||||
<field name="CC_MainPort" units="function" type="enum" elements="1" options="Disabled,Telemetry,GPS,S.Bus,DSM,DebugConsole,ComBridge,OsdHk" defaultvalue="Telemetry"/>
|
||||
<field name="CC_FlexiPort" units="function" type="enum" elements="1" options="Disabled,Telemetry,GPS,I2C,PPM,DSM,DebugConsole,ComBridge,OsdHk" defaultvalue="Disabled"/>
|
||||
|
||||
<field name="RV_RcvrPort" units="function" type="enum" elements="1" options="Disabled,PWM,PPM,PPM+Outputs,Outputs" defaultvalue="PWM"/>
|
||||
<field name="RV_AuxPort" units="function" type="enum" elements="1" options="Disabled,Telemetry,DSM,ComAux,ComBridge,OsdHk" defaultvalue="Disabled"/>
|
||||
<field name="RV_AuxSBusPort" units="function" type="enum" elements="1" options="Disabled,S.Bus,DSM,ComAux,ComBridge,OsdHk" defaultvalue="Disabled"/>
|
||||
|