]> git.tdb.fi Git - model-railway-devices.git/commitdiff
Reorganize the directory structure
authorMikko Rasa <tdb@tdb.fi>
Mon, 13 May 2013 17:18:01 +0000 (20:18 +0300)
committerMikko Rasa <tdb@tdb.fi>
Mon, 13 May 2013 17:18:01 +0000 (20:18 +0300)
These were forked off the r2c2 repo since especially the s88w stuff is not
tied to it.

31 files changed:
.gitignore [new file with mode: 0644]
common/build.mk [new file with mode: 0644]
common/delay.h [new file with mode: 0644]
common/eeprom.c [new file with mode: 0644]
common/eeprom.h [new file with mode: 0644]
common/lcd.c [new file with mode: 0644]
common/lcd.h [new file with mode: 0644]
common/serial.c [new file with mode: 0644]
common/serial.h [new file with mode: 0644]
common/timer.c [new file with mode: 0644]
common/timer.h [new file with mode: 0644]
firmware/Makefile [deleted file]
firmware/ctrl.c [deleted file]
firmware/delay.h [deleted file]
firmware/eeprom.c [deleted file]
firmware/eeprom.h [deleted file]
firmware/lcd.c [deleted file]
firmware/lcd.h [deleted file]
firmware/s88w-r.c [deleted file]
firmware/s88w-t.c [deleted file]
firmware/s88w-t.svg [deleted file]
firmware/serial.c [deleted file]
firmware/serial.h [deleted file]
firmware/timer.c [deleted file]
firmware/timer.h [deleted file]
misc/Makefile [new file with mode: 0644]
misc/ctrl.c [new file with mode: 0644]
s88w/Makefile [new file with mode: 0644]
s88w/s88w-r.c [new file with mode: 0644]
s88w/s88w-t.c [new file with mode: 0644]
s88w/s88w-t.svg [new file with mode: 0644]

diff --git a/.gitignore b/.gitignore
new file mode 100644 (file)
index 0000000..d6c2e45
--- /dev/null
@@ -0,0 +1,2 @@
+*.elf
+*.hex
diff --git a/common/build.mk b/common/build.mk
new file mode 100644 (file)
index 0000000..96d0f93
--- /dev/null
@@ -0,0 +1,42 @@
+MCU := atmega328p
+CLOCK := 16000000
+CC := avr-gcc
+CFLAGS := -Wall -Os -ffunction-sections -fdata-sections -mmcu=$(MCU) -DF_CPU=$(CLOCK) $(patsubst %,-D%,$(FEATURES)) -I../common
+LDFLAGS := -Os -Wl,--gc-sections -mmcu=$(MCU)
+AVRDUDE := avrdude
+OBJCOPY := avr-objcopy
+ifeq ($(MCU),atmega168)
+BAUD := 19200
+else
+BAUD := 57600
+endif
+
+VPATH := ../common
+
+help:
+       @echo "Targets:"
+       @echo "  %.hex:    Build firmware from %.c"
+       @echo "  upload-%: Upload firmware to AVR"
+       @echo "  clean:    Clean all built files"
+       @echo
+       @echo "Variables:"
+       @echo "  MCU:      Microcontroller type"
+       @echo "            Arduino Duemilanove = atmega328p (default)"
+       @echo "            Arduino Mini = atmega168"
+
+%.hex: %.elf
+       $(OBJCOPY) -O ihex $< $@
+
+%.elf: %.o
+       $(CC) $(LDFLAGS) -o $@ $^
+
+%.o: %.c
+       $(CC) -c $(CFLAGS) -o $@ $<
+
+upload-%: %.hex
+       $(AVRDUDE) -p$(MCU) -carduino -P/dev/ttyUSB0 -b$(BAUD) -D -Uflash:w:$<:i
+
+clean:
+       $(RM) *.hex
+       $(RM) *.elf
+       $(RM) *.o
diff --git a/common/delay.h b/common/delay.h
new file mode 100644 (file)
index 0000000..725d22b
--- /dev/null
@@ -0,0 +1,45 @@
+#ifndef DELAY_H_
+#define DELAY_H_
+
+static inline void __attribute__((always_inline)) delay_loop8(uint8_t count)
+{
+       __asm__ volatile (
+               "1: dec %0" "\n\t"
+               "brne 1b"
+               : "=r" (count)
+               : "0" (count)
+       );
+}
+
+static inline void __attribute__((always_inline)) delay_loop16(uint16_t count)
+{
+       __asm__ volatile (
+               "1: sbiw %0, 1" "\n\t"
+               "brne 1b"
+               : "=r" (count)
+               : "0" (count)
+       );
+}
+
+static inline void __attribute__((always_inline)) delay_us(uint16_t us)
+{
+       uint16_t clocks = F_CPU/1000000*us;
+       if(clocks<768)
+               delay_loop8(clocks/3);
+       else
+               delay_loop16(clocks/4);
+}
+
+static inline void __attribute__((always_inline)) delay_ms(uint16_t ms)
+{
+       if(ms<0x40000/(F_CPU/1000))
+               delay_loop16(F_CPU/1000*ms/4);
+       else
+       {
+               uint16_t i = ms*10;
+               while(--i)
+                       delay_loop16(F_CPU/40000);
+       }
+}
+
+#endif
diff --git a/common/eeprom.c b/common/eeprom.c
new file mode 100644 (file)
index 0000000..9027ed0
--- /dev/null
@@ -0,0 +1,29 @@
+#include <avr/io.h>
+#include "eeprom.h"
+
+#define BIT(n) (1<<(n))
+
+static void eeprom_wait(void)
+{
+       while(EECR&BIT(EEPE)) ;
+}
+
+void eeprom_write(uint16_t addr, uint8_t data)
+{
+       eeprom_wait();
+       EEARH = addr>>8;
+       EEARL = addr;
+       EEDR = data;
+       EECR = BIT(EEMPE);
+       EECR |= BIT(EEPE);
+       eeprom_wait();
+}
+
+uint8_t eeprom_read(uint16_t addr)
+{
+       eeprom_wait();
+       EEARH = addr>>8;
+       EEARL = addr;
+       EECR = BIT(EERE);
+       return EEDR;
+}
diff --git a/common/eeprom.h b/common/eeprom.h
new file mode 100644 (file)
index 0000000..903ce96
--- /dev/null
@@ -0,0 +1,7 @@
+#ifndef EEPROM_H_
+#define EEPROM_H_
+
+void eeprom_write(uint16_t, uint8_t);
+uint8_t eeprom_read(uint16_t);
+
+#endif
diff --git a/common/lcd.c b/common/lcd.c
new file mode 100644 (file)
index 0000000..f4e0387
--- /dev/null
@@ -0,0 +1,208 @@
+/*
+ATMega pinout (with LCD_SHIFTREG):
+B0 - HD44780 RS
+B1 - HD44780 clock
+B2 - shift reg data
+B3 - shift reg clock
+
+ATMega pinout (without LCD_SHIFTREG):
+D4 - HD44780 RS
+D5 - HD44780 clock
+D6 - HD44780 data 0
+D7 - HD44780 data 1
+B0 - HD44780 data 2
+B1 - HD44780 data 3
+B2 - HD44780 data 4
+B3 - HD44780 data 5
+B4 - HD44780 data 6
+B5 - HD44780 data 7
+
+In both cases, HD44780 R/W needs to be connected to ground.
+*/
+#include <avr/io.h>
+#include "delay.h"
+#include "lcd.h"
+#include "timer.h"
+
+#ifdef LCD_SHIFTREG
+#define CLOCK_PORT PORTB
+#define CLOCK_BIT 0x02
+#define REGSEL_PORT PORTB
+#define REGSEL_BIT 0x01
+#else
+#define CLOCK_PORT PORTD
+#define CLOCK_BIT 0x20
+#define REGSEL_PORT PORTD
+#define REGSEL_BIT 0x10
+#endif
+
+#ifndef LCD_BUFSIZE
+#define LCD_BUFSIZE 32
+#endif
+
+#define NOP() __asm__("nop")
+
+#ifdef LCD_ASYNC
+static volatile uint8_t lcd_busy = 0;
+static uint8_t lcd_buffer[LCD_BUFSIZE];
+static volatile uint8_t lcd_buf_head = 0;
+static volatile uint8_t lcd_buf_tail = 0;
+#endif
+
+static void lcd_clock(void)
+{
+       delay_us(1);
+       CLOCK_PORT |= CLOCK_BIT;
+       delay_us(1);
+       CLOCK_PORT &= ~CLOCK_BIT;
+}
+
+static void lcd_set_data(uint8_t d)
+{
+#ifdef LCD_SHIFTREG
+       uint8_t i;
+       for(i=0; i<8; ++i)
+       {
+               PORTB = (PORTB&~0x04)|((d&1)<<2);
+               PORTB |= 0x08;
+               NOP();
+               PORTB &= ~0x08;
+               d >>= 1;
+       }
+#else
+       PORTD = (PORTD&0x3F) | (d<<6);
+       PORTB = (PORTB&0xC0) | (d>>2);
+#endif
+}
+
+static void lcd_command(uint8_t c)
+{
+       REGSEL_PORT &= ~REGSEL_BIT;
+       lcd_set_data(c);
+       lcd_clock();
+}
+
+static void lcd_delay(uint16_t us)
+{
+#ifdef LCD_ASYNC
+       lcd_busy = 1;
+       timer_start_us(0, us);
+#else
+       delay_us(us);
+#endif
+}
+
+#ifdef LCD_ASYNC
+static void lcd_wait(void)
+{
+       while(lcd_busy) ;
+}
+
+static void lcd_buffer_push(uint8_t byte)
+{
+       while((lcd_buf_head+1)%sizeof(lcd_buffer)==lcd_buf_tail) ;
+       lcd_buffer[lcd_buf_head] = byte;
+       lcd_buf_head = (lcd_buf_head+1)%sizeof(lcd_buffer);
+}
+
+static uint8_t lcd_buffer_pop(void)
+{
+       uint8_t byte = lcd_buffer[lcd_buf_tail];
+       lcd_buf_tail = (lcd_buf_tail+1)%sizeof(lcd_buffer);
+       return byte;
+}
+
+static void lcd_timer(void)
+{
+       if(lcd_busy)
+       {
+               if(lcd_buf_head!=lcd_buf_tail)
+               {
+                       uint8_t byte = lcd_buffer_pop();
+                       if(byte==0xFF)
+                       {
+                               REGSEL_PORT |= REGSEL_BIT;
+                               byte = lcd_buffer_pop();
+                       }
+                       else if(byte>=0x80)
+                               REGSEL_PORT &= ~REGSEL_BIT;
+                       else
+                               REGSEL_PORT |= REGSEL_BIT;
+                       lcd_set_data(byte);
+                       lcd_clock();
+                       lcd_delay(50);
+               }
+               else
+               {
+                       lcd_busy = 0;
+                       timer_stop(0);
+               }
+       }
+}
+
+TIMER_SET_CALLBACK(0, lcd_timer)
+#endif
+
+void lcd_init(void)
+{
+#ifdef LCD_SHIFTREG
+       DDRB |= 0x0F;
+       PORTB &= ~0x0F;
+#else
+       DDRD |= 0xF0;
+       PORTD &= ~0xF0;
+       DDRB |= 0x3F;
+       PORTB &= ~0x3F;
+#endif
+
+       delay_ms(20);
+       lcd_command(0x38);
+       delay_us(50);
+       lcd_command(0x0C);
+       delay_us(50);
+}
+
+void lcd_clear(void)
+{
+#ifdef LCD_ASYNC
+       lcd_wait();
+#endif
+       lcd_command(0x01);
+       lcd_delay(1700);
+}
+
+void lcd_gotoxy(uint8_t x, uint8_t y)
+{
+       uint8_t a = x+10*y;
+       if(y&1)
+               a += 54;
+
+#ifdef LCD_ASYNC
+       if(lcd_busy)
+       {
+               lcd_buffer_push(a|0x80);
+               return;
+       }
+#endif
+
+       lcd_command(a|0x80);
+       lcd_delay(50);
+}
+
+void lcd_write(uint8_t c)
+{
+#ifdef LCD_ASYNC
+       if(lcd_busy)
+       {
+               if(c>=0x80)
+                       lcd_buffer_push(0xFF);
+               lcd_buffer_push(c);
+               return;
+       }
+#endif
+
+       REGSEL_PORT |= REGSEL_BIT;
+       lcd_set_data(c);
+       lcd_clock();
+       lcd_delay(50);
+}
diff --git a/common/lcd.h b/common/lcd.h
new file mode 100644 (file)
index 0000000..abb1017
--- /dev/null
@@ -0,0 +1,9 @@
+#ifndef LCD_H_
+#define LCD_H_
+
+void lcd_init(void);
+void lcd_clear(void);
+void lcd_gotoxy(uint8_t, uint8_t);
+void lcd_write(uint8_t);
+
+#endif
diff --git a/common/serial.c b/common/serial.c
new file mode 100644 (file)
index 0000000..2bf6901
--- /dev/null
@@ -0,0 +1,22 @@
+#include <avr/io.h>
+#include "serial.h"
+
+#define BIT(n) (1<<(n))
+
+void serial_init(uint16_t baud)
+{
+       DDRD = (DDRD&~0x03) | 0x02;
+       PORTD &= ~0x03;
+
+       baud = (F_CPU/16+baud/2)/baud-1;
+       UBRR0H = baud>>8;
+       UBRR0L = baud;
+       UCSR0C = BIT(UCSZ00) | BIT(UCSZ01);  // 8N1
+       UCSR0B = BIT(RXEN0) | BIT(TXEN0) | BIT(RXCIE0);
+}
+
+void serial_write(uint8_t c)
+{
+       while(!(UCSR0A&(1<<UDRE0))) ;
+       UDR0 = c;
+}
diff --git a/common/serial.h b/common/serial.h
new file mode 100644 (file)
index 0000000..04ea50b
--- /dev/null
@@ -0,0 +1,16 @@
+#ifndef SERIAL_H_
+#define SERIAL_H_
+
+#include <avr/interrupt.h>
+
+#define SERIAL_SET_CALLBACK(f) \
+       ISR(USART_RX_vect) \
+       { \
+               char c = UDR0; \
+               f(c); \
+       }
+
+void serial_init(uint16_t);
+void serial_write(uint8_t);
+
+#endif
diff --git a/common/timer.c b/common/timer.c
new file mode 100644 (file)
index 0000000..99625f8
--- /dev/null
@@ -0,0 +1,101 @@
+#include <avr/io.h>
+#include "timer.h"
+
+#define BIT(n) (1<<(n))
+
+static void timer_start(uint8_t num, uint32_t period)
+{
+       uint8_t cs;
+
+       if(num==0)
+       {
+               if(period<0x100)
+               {
+                       cs = BIT(CS00);
+               }
+               else if(period<0x800)
+               {
+                       cs = BIT(CS01);
+                       period /= 8;
+               }
+               else if(period<0x4000)
+               {
+                       cs = BIT(CS01) | BIT(CS00);
+                       period /= 64;
+               }
+               else if(period<0x10000)
+               {
+                       cs = BIT(CS02);
+                       period /= 256;
+               }
+               else
+               {
+                       cs = BIT(CS02) | BIT(CS00);
+                       period /= 1024;
+                       if(period>0xFF)
+                               period = 0xFF;
+               }
+               TCCR0A = BIT(WGM01);
+               TCCR0B = cs;
+               OCR0A = period;
+               TIMSK0 = BIT(OCIE0A);
+       }
+       if(num==1)
+       {
+               if(period<0x10000)
+               {
+                       cs = BIT(CS10);
+               }
+               else if(period<0x80000)
+               {
+                       cs = BIT(CS11);
+                       period /= 8;
+               }
+               else if(period<0x400000)
+               {
+                       cs = BIT(CS11) | BIT(CS10);
+                       period /= 64;
+               }
+               else if(period<0x1000000)
+               {
+                       cs = BIT(CS12);
+                       period /= 256;
+               }
+               else
+               {
+                       cs = BIT(CS12) | BIT(CS10);
+                       period /= 1024;
+                       if(period>0xFFFF)
+                               period = 0xFFFF;
+               }
+               TCCR1A = 0;
+               TCCR1B = BIT(WGM12) | cs;
+               OCR1AH = period>>8;
+               OCR1AL = period;
+               TIMSK1 = BIT(OCIE1A);
+       }
+}
+
+void timer_start_hz(uint8_t num, uint32_t freq_p, uint8_t freq_q)
+{
+       timer_start(num, F_CPU*freq_q/freq_p);
+}
+
+void timer_start_us(uint8_t num, uint32_t us)
+{
+       timer_start(num, F_CPU/1000000*us);
+}
+
+void timer_stop(uint8_t num)
+{
+       if(num==0)
+       {
+               TCCR0B = 0;
+               TIMSK0 = 0;
+       }
+       else if(num==1)
+       {
+               TCCR1B = 0;
+               TIMSK1 = 0;
+       }
+}
diff --git a/common/timer.h b/common/timer.h
new file mode 100644 (file)
index 0000000..2869caa
--- /dev/null
@@ -0,0 +1,16 @@
+#ifndef TIMER_H_
+#define TIMER_H_
+
+#include <avr/interrupt.h>
+
+#define TIMER_SET_CALLBACK(n, f) \
+       ISR(TIMER ## n ## _COMPA_vect) \
+       { \
+               f(); \
+       }
+
+void timer_start_hz(uint8_t, uint32_t, uint8_t);
+void timer_start_us(uint8_t, uint32_t);
+void timer_stop(uint8_t);
+
+#endif
diff --git a/firmware/Makefile b/firmware/Makefile
deleted file mode 100644 (file)
index b92db65..0000000
+++ /dev/null
@@ -1,44 +0,0 @@
-MCU := atmega328p
-CLOCK := 16000000
-CC := avr-gcc
-FEATURES := LCD_SHIFTREG LCD_ASYNC
-CFLAGS := -Wall -Os -ffunction-sections -fdata-sections -mmcu=$(MCU) -DF_CPU=$(CLOCK) $(patsubst %,-D%,$(FEATURES))
-LDFLAGS := -Os -Wl,--gc-sections -mmcu=$(MCU)
-AVRDUDE := avrdude
-OBJCOPY := avr-objcopy
-ifeq ($(MCU),atmega168)
-BAUD := 19200
-else
-BAUD := 57600
-endif
-
-help:
-       @echo "Targets:"
-       @echo "  %.hex:    Build firmware from %.c"
-       @echo "  upload-%: Upload firmware to AVR"
-       @echo "  clean:    Clean all built files"
-       @echo
-       @echo "Variables:"
-       @echo "  MCU:      Microcontroller type"
-       @echo "            Arduino Duemilanove = atmega328p (default)"
-       @echo "            Arduino Mini = atmega168"
-
-%.hex: %.elf
-       $(OBJCOPY) -O ihex $< $@
-
-%.elf: %.o
-       $(CC) $(LDFLAGS) -o $@ $^
-
-%.o: %.c
-       $(CC) -c $(CFLAGS) -o $@ $<
-
-upload-%: %.hex
-       $(AVRDUDE) -p$(MCU) -carduino -P/dev/ttyUSB0 -b$(BAUD) -D -Uflash:w:$<:i
-
-clean:
-       $(RM) *.hex
-       $(RM) *.elf
-       $(RM) *.o
-
-s88w-t.elf: serial.o timer.o eeprom.o
-s88w-r.elf: serial.o lcd.o timer.o
diff --git a/firmware/ctrl.c b/firmware/ctrl.c
deleted file mode 100644 (file)
index 0ac212e..0000000
+++ /dev/null
@@ -1,221 +0,0 @@
-#include <avr/io.h>
-#include <avr/interrupt.h>
-
-#define BIT(n) (1<<(n))
-#define NOP() __asm__("nop");
-
-uint8_t digits[11] =
-{
-       0x3F,
-       0x06,
-       0x5B,
-       0x4F,
-       0x66,
-       0x6D,
-       0x7D,
-       0x07,
-       0x7F,
-       0x6F,
-       0x40
-};
-
-uint16_t read_input(void);
-uint16_t read_input_filtered(void);
-void write_serial(uint8_t);
-void write_7seg(uint8_t);
-
-uint8_t speed = 0;
-uint16_t funcs = 0;
-volatile uint8_t ticks = 0;
-volatile uint8_t rx_buf[3];
-volatile uint8_t rx_fill = 0;
-
-ISR(TIMER1_COMPA_vect)
-{
-       if(ticks<255)
-               ++ticks;
-}
-
-ISR(USART_RX_vect)
-{
-       uint8_t c = UDR0;
-       if(rx_fill==0)
-       {
-               if(c=='A' || c=='S')
-                       rx_buf[rx_fill++] = c;
-       }
-       else
-       {
-               rx_buf[rx_fill++] = c;
-               if(rx_buf[0]=='A' && rx_fill==3)
-               {
-                       uint8_t n = (rx_buf[1]-'0')*10+(rx_buf[2]-'0');
-                       write_7seg(n/10);
-                       write_7seg(n%10);
-                       rx_fill = 0;
-               }
-               else if(rx_buf[0]=='S' && rx_fill==3)
-               {
-                       speed = (rx_buf[1]-'0')*10+(rx_buf[2]-'0');
-                       rx_fill = 0;
-               }
-       }
-}
-
-int main()
-{
-       uint16_t state = 0;
-
-       DDRD = 0x02;   // 00000010
-       PORTD = 0xFC;  // 11111100
-       DDRB = 0x3F;   // 00111111
-       PORTB = 0x0F;  // 00001111
-
-       write_7seg(10);
-       write_7seg(10);
-
-       // 9600 baud, 8N1
-       UBRR0H = 0;
-       UBRR0L = 103;
-       UCSR0C = BIT(UCSZ00) | BIT(UCSZ01);
-       UCSR0B = BIT(RXEN0) | BIT(TXEN0) | BIT(RXCIE0);
-
-       TCCR1A = 0;
-       TCCR1B = BIT(WGM12) | BIT(CS12);
-       OCR1AH = 24;
-       OCR1AL = 106;
-       TIMSK1 = BIT(OCIE1A);
-
-       sei();
-
-       while(1)
-       {
-               uint16_t toggled;
-               uint8_t i;
-               uint16_t input;
-
-               input = read_input_filtered();
-               input ^= 0xFFFC;
-
-               toggled = state^input;
-               state = input;
-
-               if((toggled&3)==2 && (state&1))
-               {
-                       uint8_t action = 0;
-                       if(state&2)
-                       {
-                               if(speed<14)
-                               {
-                                       ++speed;
-                                       action = 1;
-                               }
-                       }
-                       else
-                       {
-                               if(speed>0)
-                               {
-                                       --speed;
-                                       action = 1;
-                               }
-                               else if(ticks>10)
-                                       action = 2;
-                       }
-
-                       if(action==1)
-                       {
-                               write_serial('S');
-                               write_serial('0'+speed/10);
-                               write_serial('0'+speed%10);
-                       }
-                       else if(action==2)
-                               write_serial('R');
-
-                       ticks = 0;
-               }
-
-               for(i=0; i<14; ++i)
-               {
-                       uint16_t bit = 4<<i;
-                       if(toggled&~state&bit)
-                       {
-                               if(i==0)
-                                       write_serial('N');
-                               else if(i==1)
-                                       write_serial('P');
-                               else
-                               {
-                                       uint8_t f = i-2;
-                                       uint16_t fbit = 1<<f;
-                                       funcs ^= fbit;
-                                       write_serial((funcs&fbit) ? 'H' : 'L');
-                                       write_serial('0'+f);
-                               }
-                       }
-               }
-       }
-}
-
-uint16_t read_input(void)
-{
-       uint8_t row;
-       uint16_t input = 0;
-
-       for(row=0; row<4; ++row)
-       {
-               uint8_t pins;
-
-               PORTB = (PORTB|0x0F)&~(1<<row);
-               NOP();
-               NOP();
-               NOP();
-               NOP();
-               NOP();
-               NOP();
-               pins = PIND>>2;
-               input |= pins&3;
-               input |= (pins&0x3C)<<(row*4);
-       }
-
-       return input;
-}
-
-uint16_t read_input_filtered(void)
-{
-       uint16_t valid = 0xFFFF;
-       uint16_t prev;
-       uint16_t input;
-       uint8_t i;
-
-       prev = read_input();
-       for(i=0; i<20; ++i)
-       {
-               input = read_input();
-               valid &= ~(input^prev);
-               prev = input;
-       }
-
-       return input&valid;
-}
-
-void write_serial(uint8_t c)
-{
-       while(!(UCSR0A&(1<<UDRE0))) ;
-       UDR0 = c;
-}
-
-void write_7seg(uint8_t n)
-{
-       uint8_t segs = ~digits[n];
-       uint8_t i;
-       for(i=0; i<8; ++i)
-       {
-               PORTB &= ~0x20;
-               if(segs&0x80)
-                       PORTB |= 0x10;
-               else
-                       PORTB &= ~0x10;
-               PORTB |= 0x20;
-               segs <<= 1;
-       }
-}
diff --git a/firmware/delay.h b/firmware/delay.h
deleted file mode 100644 (file)
index 725d22b..0000000
+++ /dev/null
@@ -1,45 +0,0 @@
-#ifndef DELAY_H_
-#define DELAY_H_
-
-static inline void __attribute__((always_inline)) delay_loop8(uint8_t count)
-{
-       __asm__ volatile (
-               "1: dec %0" "\n\t"
-               "brne 1b"
-               : "=r" (count)
-               : "0" (count)
-       );
-}
-
-static inline void __attribute__((always_inline)) delay_loop16(uint16_t count)
-{
-       __asm__ volatile (
-               "1: sbiw %0, 1" "\n\t"
-               "brne 1b"
-               : "=r" (count)
-               : "0" (count)
-       );
-}
-
-static inline void __attribute__((always_inline)) delay_us(uint16_t us)
-{
-       uint16_t clocks = F_CPU/1000000*us;
-       if(clocks<768)
-               delay_loop8(clocks/3);
-       else
-               delay_loop16(clocks/4);
-}
-
-static inline void __attribute__((always_inline)) delay_ms(uint16_t ms)
-{
-       if(ms<0x40000/(F_CPU/1000))
-               delay_loop16(F_CPU/1000*ms/4);
-       else
-       {
-               uint16_t i = ms*10;
-               while(--i)
-                       delay_loop16(F_CPU/40000);
-       }
-}
-
-#endif
diff --git a/firmware/eeprom.c b/firmware/eeprom.c
deleted file mode 100644 (file)
index 9027ed0..0000000
+++ /dev/null
@@ -1,29 +0,0 @@
-#include <avr/io.h>
-#include "eeprom.h"
-
-#define BIT(n) (1<<(n))
-
-static void eeprom_wait(void)
-{
-       while(EECR&BIT(EEPE)) ;
-}
-
-void eeprom_write(uint16_t addr, uint8_t data)
-{
-       eeprom_wait();
-       EEARH = addr>>8;
-       EEARL = addr;
-       EEDR = data;
-       EECR = BIT(EEMPE);
-       EECR |= BIT(EEPE);
-       eeprom_wait();
-}
-
-uint8_t eeprom_read(uint16_t addr)
-{
-       eeprom_wait();
-       EEARH = addr>>8;
-       EEARL = addr;
-       EECR = BIT(EERE);
-       return EEDR;
-}
diff --git a/firmware/eeprom.h b/firmware/eeprom.h
deleted file mode 100644 (file)
index 903ce96..0000000
+++ /dev/null
@@ -1,7 +0,0 @@
-#ifndef EEPROM_H_
-#define EEPROM_H_
-
-void eeprom_write(uint16_t, uint8_t);
-uint8_t eeprom_read(uint16_t);
-
-#endif
diff --git a/firmware/lcd.c b/firmware/lcd.c
deleted file mode 100644 (file)
index f4e0387..0000000
+++ /dev/null
@@ -1,208 +0,0 @@
-/*
-ATMega pinout (with LCD_SHIFTREG):
-B0 - HD44780 RS
-B1 - HD44780 clock
-B2 - shift reg data
-B3 - shift reg clock
-
-ATMega pinout (without LCD_SHIFTREG):
-D4 - HD44780 RS
-D5 - HD44780 clock
-D6 - HD44780 data 0
-D7 - HD44780 data 1
-B0 - HD44780 data 2
-B1 - HD44780 data 3
-B2 - HD44780 data 4
-B3 - HD44780 data 5
-B4 - HD44780 data 6
-B5 - HD44780 data 7
-
-In both cases, HD44780 R/W needs to be connected to ground.
-*/
-#include <avr/io.h>
-#include "delay.h"
-#include "lcd.h"
-#include "timer.h"
-
-#ifdef LCD_SHIFTREG
-#define CLOCK_PORT PORTB
-#define CLOCK_BIT 0x02
-#define REGSEL_PORT PORTB
-#define REGSEL_BIT 0x01
-#else
-#define CLOCK_PORT PORTD
-#define CLOCK_BIT 0x20
-#define REGSEL_PORT PORTD
-#define REGSEL_BIT 0x10
-#endif
-
-#ifndef LCD_BUFSIZE
-#define LCD_BUFSIZE 32
-#endif
-
-#define NOP() __asm__("nop")
-
-#ifdef LCD_ASYNC
-static volatile uint8_t lcd_busy = 0;
-static uint8_t lcd_buffer[LCD_BUFSIZE];
-static volatile uint8_t lcd_buf_head = 0;
-static volatile uint8_t lcd_buf_tail = 0;
-#endif
-
-static void lcd_clock(void)
-{
-       delay_us(1);
-       CLOCK_PORT |= CLOCK_BIT;
-       delay_us(1);
-       CLOCK_PORT &= ~CLOCK_BIT;
-}
-
-static void lcd_set_data(uint8_t d)
-{
-#ifdef LCD_SHIFTREG
-       uint8_t i;
-       for(i=0; i<8; ++i)
-       {
-               PORTB = (PORTB&~0x04)|((d&1)<<2);
-               PORTB |= 0x08;
-               NOP();
-               PORTB &= ~0x08;
-               d >>= 1;
-       }
-#else
-       PORTD = (PORTD&0x3F) | (d<<6);
-       PORTB = (PORTB&0xC0) | (d>>2);
-#endif
-}
-
-static void lcd_command(uint8_t c)
-{
-       REGSEL_PORT &= ~REGSEL_BIT;
-       lcd_set_data(c);
-       lcd_clock();
-}
-
-static void lcd_delay(uint16_t us)
-{
-#ifdef LCD_ASYNC
-       lcd_busy = 1;
-       timer_start_us(0, us);
-#else
-       delay_us(us);
-#endif
-}
-
-#ifdef LCD_ASYNC
-static void lcd_wait(void)
-{
-       while(lcd_busy) ;
-}
-
-static void lcd_buffer_push(uint8_t byte)
-{
-       while((lcd_buf_head+1)%sizeof(lcd_buffer)==lcd_buf_tail) ;
-       lcd_buffer[lcd_buf_head] = byte;
-       lcd_buf_head = (lcd_buf_head+1)%sizeof(lcd_buffer);
-}
-
-static uint8_t lcd_buffer_pop(void)
-{
-       uint8_t byte = lcd_buffer[lcd_buf_tail];
-       lcd_buf_tail = (lcd_buf_tail+1)%sizeof(lcd_buffer);
-       return byte;
-}
-
-static void lcd_timer(void)
-{
-       if(lcd_busy)
-       {
-               if(lcd_buf_head!=lcd_buf_tail)
-               {
-                       uint8_t byte = lcd_buffer_pop();
-                       if(byte==0xFF)
-                       {
-                               REGSEL_PORT |= REGSEL_BIT;
-                               byte = lcd_buffer_pop();
-                       }
-                       else if(byte>=0x80)
-                               REGSEL_PORT &= ~REGSEL_BIT;
-                       else
-                               REGSEL_PORT |= REGSEL_BIT;
-                       lcd_set_data(byte);
-                       lcd_clock();
-                       lcd_delay(50);
-               }
-               else
-               {
-                       lcd_busy = 0;
-                       timer_stop(0);
-               }
-       }
-}
-
-TIMER_SET_CALLBACK(0, lcd_timer)
-#endif
-
-void lcd_init(void)
-{
-#ifdef LCD_SHIFTREG
-       DDRB |= 0x0F;
-       PORTB &= ~0x0F;
-#else
-       DDRD |= 0xF0;
-       PORTD &= ~0xF0;
-       DDRB |= 0x3F;
-       PORTB &= ~0x3F;
-#endif
-
-       delay_ms(20);
-       lcd_command(0x38);
-       delay_us(50);
-       lcd_command(0x0C);
-       delay_us(50);
-}
-
-void lcd_clear(void)
-{
-#ifdef LCD_ASYNC
-       lcd_wait();
-#endif
-       lcd_command(0x01);
-       lcd_delay(1700);
-}
-
-void lcd_gotoxy(uint8_t x, uint8_t y)
-{
-       uint8_t a = x+10*y;
-       if(y&1)
-               a += 54;
-
-#ifdef LCD_ASYNC
-       if(lcd_busy)
-       {
-               lcd_buffer_push(a|0x80);
-               return;
-       }
-#endif
-
-       lcd_command(a|0x80);
-       lcd_delay(50);
-}
-
-void lcd_write(uint8_t c)
-{
-#ifdef LCD_ASYNC
-       if(lcd_busy)
-       {
-               if(c>=0x80)
-                       lcd_buffer_push(0xFF);
-               lcd_buffer_push(c);
-               return;
-       }
-#endif
-
-       REGSEL_PORT |= REGSEL_BIT;
-       lcd_set_data(c);
-       lcd_clock();
-       lcd_delay(50);
-}
diff --git a/firmware/lcd.h b/firmware/lcd.h
deleted file mode 100644 (file)
index abb1017..0000000
+++ /dev/null
@@ -1,9 +0,0 @@
-#ifndef LCD_H_
-#define LCD_H_
-
-void lcd_init(void);
-void lcd_clear(void);
-void lcd_gotoxy(uint8_t, uint8_t);
-void lcd_write(uint8_t);
-
-#endif
diff --git a/firmware/s88w-r.c b/firmware/s88w-r.c
deleted file mode 100644 (file)
index 0198974..0000000
+++ /dev/null
@@ -1,219 +0,0 @@
-/*
-Firmware for wireless S88 receiver module
-
-S88 pinout:
-1 - DATA
-2 - GND
-3 - CLOCK
-4 - LOAD
-5 - RESET
-6 - POWER
-
-ATMega pinout:
-D0 - serial RX
-D1 - serial TX
-D2 - S88 DATA
-D3 - S88 CLOCK
-D4 - S88 LOAD
-D5 - S88 RESET
-*/
-
-#include <avr/io.h>
-#include <avr/interrupt.h>
-#include "lcd.h"
-#include "serial.h"
-#include "delay.h"
-
-#define DATA_OUT PORTD2
-#define CLOCK    PIND3
-#define LOAD     PIND4
-#define RESET    PIND5
-
-#define LCD_DISABLE PINB4
-
-#define BIT(n)   (1<<(n))
-
-void receive(uint8_t);
-uint8_t hexdigit(uint8_t);
-uint8_t decode_hex(uint8_t);
-
-volatile uint8_t rx_buf[7];
-volatile uint8_t rx_fill = 0xFF;
-volatile uint8_t input[128] = { 0 };
-volatile uint8_t latch[128] = { 0 };
-volatile uint8_t lcd_enabled = 0;
-uint8_t log_row = 0;
-uint8_t log_col = 0;
-
-int main()
-{
-       uint8_t clock_high = 0;
-       uint8_t bits = 0;
-       uint8_t n_bits = 8;
-       uint8_t offset = 0;
-       uint8_t i;
-
-       DDRD = 0x06;   // 00000110
-       PORTD = 0xC0;  // 11000000
-       DDRB = 0x20;   // 00100000
-       PORTB = 0x1F;  // 00011111
-
-       serial_init(9600);
-       lcd_init();
-
-       sei();
-
-       while(1)
-       {
-               uint8_t b_pins, d_pins;
-
-               b_pins = PINB;
-               d_pins = PIND;
-
-               if(d_pins&BIT(CLOCK))
-               {
-                       if(!clock_high)
-                       {
-                               if(d_pins&BIT(LOAD))
-                               {
-                                       offset = 0;
-                                       bits = latch[0];
-                                       n_bits = 8;
-                               }
-                               else
-                               {
-                                       bits >>= 1;
-                                       if(!--n_bits)
-                                       {
-                                               ++offset;
-                                               bits = latch[offset];
-                                               n_bits = 8;
-                                       }
-                               }
-
-                               if(bits&1)
-                                       PORTD |= BIT(DATA_OUT);
-                               else
-                                       PORTD &= ~BIT(DATA_OUT);
-
-                               clock_high = 1;
-                       }
-               }
-               else if(clock_high)
-                       clock_high = 0;
-
-               if(d_pins&BIT(RESET))
-               {
-                       uint8_t i;
-                       for(i=0; i<128; ++i)
-                               latch[i] = input[i];
-               }
-
-               if(b_pins&BIT(LCD_DISABLE))
-               {
-                       if(lcd_enabled)
-                       {
-                               lcd_enabled = 0;
-
-                               lcd_clear();
-                       }
-               }
-               else if(!lcd_enabled)
-               {
-                       lcd_enabled = 1;
-                       log_row = 0;
-                       log_col = 0;
-
-                       lcd_clear();
-                       for(i=0; i<20; ++i)
-                               lcd_write(hexdigit(input[9-i/2]>>(4-i%2*4)));
-                       lcd_gotoxy(0, 1);
-                       lcd_write(255);
-               }
-       }
-}
-
-void receive(uint8_t c)
-{
-       if(rx_fill==0xFF)
-       {
-               if(c==':')
-                       rx_fill = 0;
-       }
-       else if(c=='.')
-       {
-               if(rx_fill>=4)
-               {
-                       uint16_t offset;
-                       uint8_t nibbles;
-                       uint8_t i;
-
-                       offset = (decode_hex(rx_buf[0])<<8) | (decode_hex(rx_buf[1])<<4) | decode_hex(rx_buf[2]);
-                       nibbles = (offset&3);
-                       offset >>= 2;
-                       if(rx_fill>3+nibbles)
-                       {
-                               for(i=0; i<=nibbles; ++i)
-                               {
-                                       uint16_t j = offset+nibbles-i;
-                                       uint8_t shift = 4*(j&1);
-                                       uint8_t bits = decode_hex(rx_buf[3+i]);
-                                       input[j/2] = (input[j/2]&~(0xF<<shift)) | (bits<<shift);
-                                       latch[j/2] = input[j/2];
-                               }
-
-                               if(lcd_enabled)
-                               {
-                                       lcd_gotoxy(19-offset-nibbles, 0);
-                                       for(i=0; i<=nibbles; ++i)
-                                               lcd_write(rx_buf[3+i]);
-                               }
-                       }
-               }
-               rx_fill = 0xFF;
-       }
-       else
-       {
-               if(rx_fill<sizeof(rx_buf))
-                       rx_buf[rx_fill++] = c;
-               else
-                       rx_fill = 0xFF;
-       }
-
-       if(lcd_enabled)
-       {
-               lcd_gotoxy(log_col, 1+log_row);
-               lcd_write(c);
-               ++log_col;
-               if(log_col>=20)
-               {
-                       log_col = 0;
-                       ++log_row;
-                       if(log_row>=3)
-                               log_row = 0;
-                       lcd_gotoxy(log_col, 1+log_row);
-               }
-               lcd_write(255);
-       }
-}
-
-SERIAL_SET_CALLBACK(receive)
-
-uint8_t hexdigit(uint8_t n)
-{
-       n &= 0xF;
-       if(n<10)
-               return '0'+n;
-       else
-               return 'A'+(n-0xA);
-}
-
-uint8_t decode_hex(uint8_t c)
-{
-       if(c>='0' && c<='9')
-               return c-'0';
-       else if(c>='A' && c<='F')
-               return 0xA+(c-'A');
-       else
-               return 0;
-}
diff --git a/firmware/s88w-t.c b/firmware/s88w-t.c
deleted file mode 100644 (file)
index 692eac5..0000000
+++ /dev/null
@@ -1,177 +0,0 @@
-/*
-Firmware for wireless S88 transmitter module
-
-ATMega pinout:
-D0 - serial RX
-D1 - serial TX
-D2 - input 1
-D3 - input 2
-D4 - input 3
-D5 - input 4
-D6 - input 5
-D7 - input 6
-B0 - input 7
-B1 - input 8
-B2 - input 9
-B3 - input 10
-B4 - input 11
-B5 - input 12
-
-Inputs are pulled high by internal pull-up resistors.  Connect to GND to
-activate.
-
-The module can be configured by sending a string of form ":Shhh." over the
-serial port, where hhh is a hex number.  Lower two bits indicate the number of
-inputs (00=4, 01=8, 10=12, 11=16) and upper ten bits indicate offset of lowest
-input in multiples of 4 bits.  At the moment there are no provisions for
-having 16 physical inputs.
-
-Example: ":S016." would configure the module to have 12 inputs at offset 20.
-*/
-
-#include <avr/io.h>
-#include <avr/interrupt.h>
-#include "eeprom.h"
-#include "serial.h"
-#include "timer.h"
-
-#define BIT(n) (1<<(n))
-
-void receive(uint8_t);
-void send_state(void);
-uint8_t hexdigit(uint8_t);
-uint8_t decode_hex(uint8_t);
-
-uint8_t rx_buf[4];
-uint8_t rx_fill = 0xFF;
-volatile uint8_t nibbles = 2;
-volatile uint8_t offset = 0;
-volatile uint16_t state = 0;
-volatile uint8_t time_since_send = 0;
-
-int main()
-{
-       if(eeprom_read(0)==0xA5)
-       {
-               offset = eeprom_read(1)<<8;
-               offset |= eeprom_read(2);
-               nibbles = eeprom_read(3);
-       }
-
-       DDRD = 0x02;   // 00000010
-       PORTD = 0xFC;  // 11111100
-       DDRB = 0x00;   // 00000000
-       PORTB = 0x3F;  // 00111111
-
-       serial_init(9600);
-       timer_start_hz(1, 100, 1);
-
-       sei();
-
-       while(1)
-       {
-               uint8_t i, j;
-               uint16_t input = 0;
-               uint16_t valid = 0xFFF;
-
-               for(i=0; i<100; ++i)
-               {
-                       uint16_t pins = 0;
-                       for(j=0; j<100; ++j)
-                               pins |= ~((PIND>>2) | ((PINB&0x3F)<<6));
-
-                       if(i==0)
-                               input = pins;
-
-                       valid &= ~(pins^input);
-               }
-
-               input &= valid;
-               input |= state&~valid;
-               input &= (1<<(nibbles*4))-1;
-
-               if(input!=state && time_since_send>5)
-               {
-                       state = input;
-                       send_state();
-               }
-       }
-
-       return 0;
-}
-
-void receive(uint8_t c)
-{
-       if(rx_fill==0xFF)
-       {
-               if(c==':')
-                       rx_fill = 0;
-       }
-       else if(c=='.')
-       {
-               if(rx_buf[0]=='S' && rx_fill==4)
-               {
-                       offset = (decode_hex(rx_buf[1])<<8) | (decode_hex(rx_buf[2])<<4) | decode_hex(rx_buf[3]);
-                       nibbles = (offset&3)+1;
-                       offset &= 0xFFC;
-
-                       eeprom_write(0, 0xA5);
-                       eeprom_write(1, offset>>8);
-                       eeprom_write(2, offset);
-                       eeprom_write(3, nibbles);
-               }
-               rx_fill = 0xFF;
-       }
-       else
-       {
-               if(rx_fill<sizeof(rx_buf))
-                       rx_buf[rx_fill++] = c;
-               else
-                       rx_fill = 0xFF;
-       }
-}
-
-SERIAL_SET_CALLBACK(receive)
-
-void send_state(void)
-{
-       uint8_t i;
-
-       serial_write(':');
-       serial_write(hexdigit(offset>>8));
-       serial_write(hexdigit(offset>>4));
-       serial_write(hexdigit(offset|(nibbles-1)));
-       for(i=nibbles; i--;)
-               serial_write(hexdigit(state>>(i*4)));
-       serial_write('.');
-
-       time_since_send = 0;
-}
-
-void timer(void)
-{
-       ++time_since_send;
-       if(time_since_send>200)
-               send_state();
-}
-
-TIMER_SET_CALLBACK(1, timer)
-
-uint8_t hexdigit(uint8_t n)
-{
-       n &= 0xF;
-       if(n<10)
-               return '0'+n;
-       else
-               return 'A'+(n-0xA);
-}
-
-uint8_t decode_hex(uint8_t c)
-{
-       if(c>='0' && c<='9')
-               return c-'0';
-       else if(c>='A' && c<='F')
-               return 0xA+(c-'A');
-       else
-               return 0;
-}
diff --git a/firmware/s88w-t.svg b/firmware/s88w-t.svg
deleted file mode 100644 (file)
index edd250b..0000000
+++ /dev/null
@@ -1,2365 +0,0 @@
-<?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="744.09448"
-   height="524.40942"
-   id="svg2"
-   sodipodi:version="0.32"
-   inkscape:version="0.47 r22583"
-   version="1.0"
-   sodipodi:docname="s88w-t.svg"
-   inkscape:output_extension="org.inkscape.output.svg.inkscape"
-   inkscape:export-filename="/home/tdb/prog/r2c2/firmware/s88w-t.png"
-   inkscape:export-xdpi="254.05862"
-   inkscape:export-ydpi="254.05862">
-  <defs
-     id="defs4">
-    <marker
-       style="overflow:visible"
-       inkscape:stockid="InfiniteLineEnd"
-       id="InfiniteLineEnd"
-       refX="0"
-       refY="0"
-       orient="auto">
-      <g
-         id="g3456">
-        <circle
-           id="circle3458"
-           r="0.80000001"
-           cy="0"
-           cx="3"
-           sodipodi:cx="3"
-           sodipodi:cy="0"
-           sodipodi:rx="0.80000001"
-           sodipodi:ry="0.80000001" />
-        <circle
-           id="circle3460"
-           r="0.80000001"
-           cy="0"
-           cx="6.5"
-           sodipodi:cx="6.5"
-           sodipodi:cy="0"
-           sodipodi:rx="0.80000001"
-           sodipodi:ry="0.80000001" />
-        <circle
-           id="circle3462"
-           r="0.80000001"
-           cy="0"
-           cx="10"
-           sodipodi:cx="10"
-           sodipodi:cy="0"
-           sodipodi:rx="0.80000001"
-           sodipodi:ry="0.80000001" />
-      </g>
-    </marker>
-    <marker
-       inkscape:stockid="DotS"
-       orient="auto"
-       refY="0"
-       refX="0"
-       id="DotS"
-       style="overflow:visible">
-      <path
-         id="path3288"
-         d="M -2.5,-1 C -2.5,1.76 -4.74,4 -7.5,4 C -10.26,4 -12.5,1.76 -12.5,-1 C -12.5,-3.76 -10.26,-6 -7.5,-6 C -4.74,-6 -2.5,-3.76 -2.5,-1 z"
-         style="fill-rule:evenodd;stroke:#000000;stroke-width:1pt;marker-start:none;marker-end:none"
-         transform="matrix(0.2,0,0,0.2,1.48,0.2)" />
-    </marker>
-    <marker
-       inkscape:stockid="DotM"
-       orient="auto"
-       refY="0"
-       refX="0"
-       id="DotM"
-       style="overflow:visible">
-      <path
-         id="path3285"
-         d="M -2.5,-1 C -2.5,1.76 -4.74,4 -7.5,4 C -10.26,4 -12.5,1.76 -12.5,-1 C -12.5,-3.76 -10.26,-6 -7.5,-6 C -4.74,-6 -2.5,-3.76 -2.5,-1 z"
-         style="fill-rule:evenodd;stroke:#000000;stroke-width:1pt;marker-start:none;marker-end:none"
-         transform="matrix(0.4,0,0,0.4,2.96,0.4)" />
-    </marker>
-    <marker
-       inkscape:stockid="Arrow1Send"
-       orient="auto"
-       refY="0"
-       refX="0"
-       id="Arrow1Send"
-       style="overflow:visible">
-      <path
-         id="path3235"
-         d="M 0,0 L 5,-5 L -12.5,0 L 5,5 L 0,0 z"
-         style="fill-rule:evenodd;stroke:#000000;stroke-width:1pt;marker-start:none"
-         transform="matrix(-0.2,0,0,-0.2,-1.2,0)" />
-    </marker>
-    <inkscape:perspective
-       sodipodi:type="inkscape:persp3d"
-       inkscape:vp_x="0 : 526.18109 : 1"
-       inkscape:vp_y="0 : 1000 : 0"
-       inkscape:vp_z="744.09448 : 526.18109 : 1"
-       inkscape:persp3d-origin="372.04724 : 350.78739 : 1"
-       id="perspective10" />
-  </defs>
-  <sodipodi:namedview
-     id="base"
-     pagecolor="#ffffff"
-     bordercolor="#666666"
-     borderopacity="1.0"
-     gridtolerance="10000"
-     guidetolerance="10"
-     objecttolerance="10"
-     inkscape:pageopacity="0.0"
-     inkscape:pageshadow="2"
-     inkscape:zoom="2.0926789"
-     inkscape:cx="370.20287"
-     inkscape:cy="272.41936"
-     inkscape:document-units="mm"
-     inkscape:current-layer="layer1"
-     showgrid="true"
-     units="mm"
-     inkscape:window-width="1880"
-     inkscape:window-height="1142"
-     inkscape:window-x="1600"
-     inkscape:window-y="0"
-     inkscape:window-maximized="1">
-    <inkscape:grid
-       type="xygrid"
-       id="grid2383"
-       visible="true"
-       enabled="true"
-       units="mm"
-       spacingx="1mm"
-       spacingy="1mm"
-       dotted="false" />
-    <inkscape:grid
-       type="xygrid"
-       id="grid3205"
-       visible="true"
-       enabled="true"
-       units="mm"
-       spacingx="0.5mm"
-       spacingy="0.5mm"
-       dotted="true"
-       color="#00ff00"
-       opacity="0.1254902"
-       empspacing="10"
-       empcolor="#00ff00"
-       empopacity="0.25098039" />
-  </sodipodi:namedview>
-  <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:label="Layer 1"
-     inkscape:groupmode="layer"
-     id="layer1">
-    <rect
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866142;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       id="rect2385"
-       width="14.173293"
-       height="141.69885"
-       x="106.22831"
-       y="191.22704" />
-    <text
-       xml:space="preserve"
-       style="font-size:10px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
-       x="109.84251"
-       y="187.79518"
-       id="text3157"
-       sodipodi:linespacing="125%"><tspan
-         sodipodi:role="line"
-         id="tspan3159"
-         x="109.84251"
-         y="187.79518">J1</tspan></text>
-    <path
-       sodipodi:type="arc"
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       id="path3161"
-       sodipodi:cx="148.81889"
-       sodipodi:cy="651.96851"
-       sodipodi:rx="3.5433071"
-       sodipodi:ry="3.5433071"
-       d="M 152.3622,651.96851 A 3.5433071,3.5433071 0 1 1 145.27559,651.96851 A 3.5433071,3.5433071 0 1 1 152.3622,651.96851 z"
-       transform="translate(-35.433069,-453.5434)" />
-    <path
-       d="M 152.3622,651.96851 A 3.5433071,3.5433071 0 1 1 145.27559,651.96851 A 3.5433071,3.5433071 0 1 1 152.3622,651.96851 z"
-       sodipodi:ry="3.5433071"
-       sodipodi:rx="3.5433071"
-       sodipodi:cy="651.96851"
-       sodipodi:cx="148.81889"
-       id="path3163"
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       sodipodi:type="arc"
-       transform="translate(-35.433083,-411.02371)" />
-    <path
-       transform="translate(-35.433069,-439.37017)"
-       sodipodi:type="arc"
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       id="path3165"
-       sodipodi:cx="148.81889"
-       sodipodi:cy="651.96851"
-       sodipodi:rx="3.5433071"
-       sodipodi:ry="3.5433071"
-       d="M 152.3622,651.96851 A 3.5433071,3.5433071 0 1 1 145.27559,651.96851 A 3.5433071,3.5433071 0 1 1 152.3622,651.96851 z" />
-    <path
-       d="M 152.3622,651.96851 A 3.5433071,3.5433071 0 1 1 145.27559,651.96851 A 3.5433071,3.5433071 0 1 1 152.3622,651.96851 z"
-       sodipodi:ry="3.5433071"
-       sodipodi:rx="3.5433071"
-       sodipodi:cy="651.96851"
-       sodipodi:cx="148.81889"
-       id="path3167"
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       sodipodi:type="arc"
-       transform="translate(-35.433069,-425.19694)" />
-    <path
-       d="M 152.3622,651.96851 A 3.5433071,3.5433071 0 1 1 145.27559,651.96851 A 3.5433071,3.5433071 0 1 1 152.3622,651.96851 z"
-       sodipodi:ry="3.5433071"
-       sodipodi:rx="3.5433071"
-       sodipodi:cy="651.96851"
-       sodipodi:cx="148.81889"
-       id="path3169"
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       sodipodi:type="arc"
-       transform="translate(-35.433069,-396.85048)" />
-    <path
-       transform="translate(-35.433083,-368.50403)"
-       sodipodi:type="arc"
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       id="path3171"
-       sodipodi:cx="148.81889"
-       sodipodi:cy="651.96851"
-       sodipodi:rx="3.5433071"
-       sodipodi:ry="3.5433071"
-       d="M 152.3622,651.96851 A 3.5433071,3.5433071 0 1 1 145.27559,651.96851 A 3.5433071,3.5433071 0 1 1 152.3622,651.96851 z" />
-    <path
-       d="M 152.3622,651.96851 A 3.5433071,3.5433071 0 1 1 145.27559,651.96851 A 3.5433071,3.5433071 0 1 1 152.3622,651.96851 z"
-       sodipodi:ry="3.5433071"
-       sodipodi:rx="3.5433071"
-       sodipodi:cy="651.96851"
-       sodipodi:cx="148.81889"
-       id="path3173"
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       sodipodi:type="arc"
-       transform="translate(-35.433069,-382.67726)" />
-    <path
-       transform="translate(-35.433069,-354.3308)"
-       sodipodi:type="arc"
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       id="path3175"
-       sodipodi:cx="148.81889"
-       sodipodi:cy="651.96851"
-       sodipodi:rx="3.5433071"
-       sodipodi:ry="3.5433071"
-       d="M 152.3622,651.96851 A 3.5433071,3.5433071 0 1 1 145.27559,651.96851 A 3.5433071,3.5433071 0 1 1 152.3622,651.96851 z" />
-    <path
-       transform="translate(-35.433069,-340.15757)"
-       sodipodi:type="arc"
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       id="path3177"
-       sodipodi:cx="148.81889"
-       sodipodi:cy="651.96851"
-       sodipodi:rx="3.5433071"
-       sodipodi:ry="3.5433071"
-       d="M 152.3622,651.96851 A 3.5433071,3.5433071 0 1 1 145.27559,651.96851 A 3.5433071,3.5433071 0 1 1 152.3622,651.96851 z" />
-    <path
-       d="M 152.3622,651.96851 A 3.5433071,3.5433071 0 1 1 145.27559,651.96851 A 3.5433071,3.5433071 0 1 1 152.3622,651.96851 z"
-       sodipodi:ry="3.5433071"
-       sodipodi:rx="3.5433071"
-       sodipodi:cy="651.96851"
-       sodipodi:cx="148.81889"
-       id="path3179"
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       sodipodi:type="arc"
-       transform="translate(-35.433083,-325.98434)" />
-    <path
-       style="fill:none;fill-rule:evenodd;stroke:#000000;stroke-width:0.70866144;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 116.92914,198.4251 L 141.73229,198.4251"
-       id="path3185" />
-    <path
-       style="fill:none;fill-rule:evenodd;stroke:#000000;stroke-width:0.70866144;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 141.7323,198.42512 L 143.50396,194.88179 L 147.04727,201.96841 L 150.59057,194.88179 L 154.13388,201.96841 L 157.67719,194.88179 L 161.22049,201.96841 L 162.99214,198.42512"
-       id="path3187"
-       sodipodi:nodetypes="cccccccc" />
-    <text
-       xml:space="preserve"
-       style="font-size:10px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
-       x="138.18898"
-       y="191.33849"
-       id="text3189"
-       sodipodi:linespacing="125%"><tspan
-         sodipodi:role="line"
-         x="138.18898"
-         y="191.33849"
-         id="tspan3193">3.3kΩ</tspan></text>
-    <rect
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866142;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       id="rect3197"
-       width="35.34045"
-       height="113.5481"
-       x="237.40158"
-       y="184.25194" />
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 237.40148,219.70325 L 248.0314,219.70325 L 248.0314,233.87648 L 237.40148,233.87648"
-       id="path3207" />
-    <path
-       style="fill:#000000;fill-opacity:1;stroke:none;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 244.48809,223.24656 L 251.5747,223.24656 L 248.0314,230.33317 L 244.48809,223.24656 z"
-       id="path3209" />
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 244.48809,230.33317 L 251.5747,230.33317"
-       id="path3211" />
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;marker-end:url(#Arrow1Send);stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 253.34636,225.01821 L 256.88967,226.78986"
-       id="path3213" />
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;marker-end:url(#Arrow1Send);stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 251.5747,228.56152 L 255.11801,230.33317"
-       id="path3215" />
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 272.83456,219.70323 L 263.97632,219.70321 L 263.97632,221.47487 L 260.433,225.01819"
-       id="path4510"
-       sodipodi:nodetypes="cccc" />
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 260.43299,228.5615 L 263.97632,232.10479 L 263.97632,233.87644 L 272.83456,233.87646"
-       id="path4512"
-       sodipodi:nodetypes="cccc" />
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 260.43299,221.47489 L 260.43299,232.10481"
-       id="path4514" />
-    <path
-       style="fill:#000000;fill-opacity:1;stroke:none;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 260.43302,230.33313 L 262.20468,228.56148 L 263.97633,232.10479 L 260.43302,230.33313 z"
-       id="path4516" />
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 166.53543,325.98416 L 166.53543,347.24401"
-       id="path4520"
-       sodipodi:nodetypes="cc" />
-    <path
-       id="path4524"
-       d="M 162.99213,333.07078 L 170.07874,333.07078 L 166.53544,340.15739 L 162.99213,333.07078 z"
-       style="fill:#000000;fill-opacity:1;stroke:none;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
-    <path
-       id="path4526"
-       d="M 162.99213,340.15739 L 170.07874,340.15739"
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
-    <path
-       sodipodi:nodetypes="cc"
-       id="path4528"
-       d="M 187.79527,325.98416 L 187.79527,347.24401"
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
-    <path
-       style="fill:#000000;fill-opacity:1;stroke:none;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 184.25197,333.07078 L 191.33858,333.07078 L 187.79528,340.15739 L 184.25197,333.07078 z"
-       id="path4530" />
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 184.25196,340.15739 L 191.33857,340.15739"
-       id="path4532" />
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 166.53543,325.98416 L 187.79528,325.98416"
-       id="path4534"
-       sodipodi:nodetypes="cc" />
-    <path
-       id="path4536"
-       d="M 173.62205,329.52747 L 173.62205,322.44086 L 180.70866,325.98416 L 173.62205,329.52747 z"
-       style="fill:#000000;fill-opacity:1;stroke:none;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
-    <path
-       id="path4538"
-       d="M 180.70866,329.52747 L 180.70866,322.44086"
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
-    <path
-       sodipodi:nodetypes="cc"
-       id="path4540"
-       d="M 166.53543,347.24401 L 187.79528,347.24401"
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
-    <path
-       style="fill:#000000;fill-opacity:1;stroke:none;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 173.62205,350.78732 L 173.62205,343.70071 L 180.70866,347.24401 L 173.62205,350.78732 z"
-       id="path4542" />
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 180.70866,350.78732 L 180.70866,343.70071"
-       id="path4544" />
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;marker-end:url(#DotS);stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 116.92914,325.98416 L 141.73229,325.98416 L 141.73229,347.24401 L 166.53544,347.24401"
-       id="path4546"
-       sodipodi:nodetypes="cccc" />
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;marker-end:url(#DotS);stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 116.92914,311.81094 L 187.79528,311.81094 L 187.79528,325.98416"
-       id="path5600"
-       sodipodi:nodetypes="ccc" />
-    <rect
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866142;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       id="rect6691"
-       width="53.287567"
-       height="60.217022"
-       x="258.66144"
-       y="340.17661" />
-    <text
-       xml:space="preserve"
-       style="font-size:10px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
-       x="265.74808"
-       y="409.25186"
-       id="text6697"
-       sodipodi:linespacing="125%"><tspan
-         sodipodi:role="line"
-         id="tspan6699"
-         x="265.74808"
-         y="409.25186">LM2574</tspan></text>
-    <text
-       xml:space="preserve"
-       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
-       x="262.20474"
-       y="350.78732"
-       id="text6701"
-       sodipodi:linespacing="125%"><tspan
-         sodipodi:role="line"
-         id="tspan6703"
-         x="262.20474"
-         y="350.78732">VIN</tspan></text>
-    <text
-       xml:space="preserve"
-       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
-       x="262.20477"
-       y="364.9606"
-       id="text6705"
-       sodipodi:linespacing="125%"><tspan
-         sodipodi:role="line"
-         id="tspan6707"
-         x="262.20477"
-         y="364.9606">GND</tspan></text>
-    <text
-       xml:space="preserve"
-       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
-       x="262.20477"
-       y="379.13376"
-       id="text6709"
-       sodipodi:linespacing="125%"><tspan
-         sodipodi:role="line"
-         id="tspan6711"
-         x="262.20477"
-         y="379.13376">OFF</tspan></text>
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;marker-start:url(#DotS);stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 187.79528,347.24401 L 258.66142,347.24401"
-       id="path7799"
-       sodipodi:nodetypes="cc" />
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;marker-start:url(#DotS);marker-end:none;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 166.53544,325.98416 L 155.90552,325.98416 L 155.90552,400.39361"
-       id="path8343"
-       sodipodi:nodetypes="ccc" />
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 150.59056,400.39361 L 161.22048,400.39361"
-       id="path8345"
-       sodipodi:nodetypes="cc" />
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 152.36221,403.93691 L 159.44882,403.93691"
-       id="path8347"
-       sodipodi:nodetypes="cc" />
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 154.13386,407.48022 C 155.90551,407.48022 157.67717,407.48022 157.67717,407.48022"
-       id="path8349"
-       sodipodi:nodetypes="cc" />
-    <text
-       xml:space="preserve"
-       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
-       x="287.00787"
-       y="350.78738"
-       id="text9095"
-       sodipodi:linespacing="125%"><tspan
-         sodipodi:role="line"
-         id="tspan9097"
-         x="287.00787"
-         y="350.78738">VOUT</tspan></text>
-    <text
-       xml:space="preserve"
-       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
-       x="299.40945"
-       y="379.13382"
-       id="text9099"
-       sodipodi:linespacing="125%"><tspan
-         sodipodi:role="line"
-         id="tspan9101"
-         x="299.40945"
-         y="379.13382">FB</tspan></text>
-    <text
-       xml:space="preserve"
-       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
-       x="251.57478"
-       y="345.47238"
-       id="text9103"
-       sodipodi:linespacing="125%"><tspan
-         sodipodi:role="line"
-         id="tspan9105"
-         x="251.57478"
-         y="345.47238">5</tspan></text>
-    <text
-       xml:space="preserve"
-       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
-       x="251.57481"
-       y="359.6456"
-       id="text9107"
-       sodipodi:linespacing="125%"><tspan
-         sodipodi:role="line"
-         id="tspan9109"
-         x="251.57481"
-         y="359.6456">4</tspan></text>
-    <text
-       xml:space="preserve"
-       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
-       x="315.35434"
-       y="345.47241"
-       id="text9111"
-       sodipodi:linespacing="125%"><tspan
-         sodipodi:role="line"
-         id="tspan9113"
-         x="315.35434"
-         y="345.47241">1</tspan></text>
-    <text
-       xml:space="preserve"
-       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
-       x="315.35434"
-       y="373.81888"
-       id="text9115"
-       sodipodi:linespacing="125%"><tspan
-         sodipodi:role="line"
-         id="tspan9117"
-         x="315.35434"
-         y="373.81888">7</tspan></text>
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;marker-end:url(#DotS);stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 258.66142,361.41724 L 240.94488,361.41724 L 240.94489,389.76369"
-       id="path9119"
-       sodipodi:nodetypes="ccc" />
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;marker-end:url(#DotS);stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 258.66144,375.59048 L 240.9449,375.59048"
-       id="path9127" />
-    <text
-       xml:space="preserve"
-       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
-       x="262.20477"
-       y="393.30698"
-       id="text9671"
-       sodipodi:linespacing="125%"><tspan
-         sodipodi:role="line"
-         id="tspan9673"
-         x="262.20477"
-         y="393.30698">SIG GND</tspan></text>
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;marker-end:url(#DotS);stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 258.66144,389.7637 L 155.90552,389.76369"
-       id="path9675"
-       sodipodi:nodetypes="cc" />
-    <path
-       id="path10761"
-       d="M 237.4015,248.04969 L 248.03142,248.04969 L 248.03142,262.22292 L 237.4015,262.22292"
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
-    <path
-       id="path10763"
-       d="M 244.48811,251.593 L 251.57472,251.593 L 248.03142,258.67961 L 244.48811,251.593 z"
-       style="fill:#000000;fill-opacity:1;stroke:none;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
-    <path
-       id="path10765"
-       d="M 244.48811,258.67961 L 251.57472,258.67961"
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
-    <path
-       id="path10767"
-       d="M 253.34638,253.36465 L 256.88969,255.1363"
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;marker-end:url(#Arrow1Send);stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
-    <path
-       id="path10769"
-       d="M 251.57472,256.90796 L 255.11803,258.67961"
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;marker-end:url(#Arrow1Send);stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
-    <path
-       sodipodi:nodetypes="cccc"
-       id="path10771"
-       d="M 272.83458,248.04967 L 263.97634,248.04965 L 263.97634,249.82131 L 260.43302,253.36463"
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
-    <path
-       sodipodi:nodetypes="cccc"
-       id="path10773"
-       d="M 260.43301,256.90794 L 263.97634,260.45123 L 263.97634,262.22288 L 272.83458,262.2229"
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
-    <path
-       id="path10775"
-       d="M 260.43301,249.82133 L 260.43301,260.45125"
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
-    <path
-       id="path10777"
-       d="M 260.43304,258.67957 L 262.2047,256.90792 L 263.97635,260.45123 L 260.43304,258.67957 z"
-       style="fill:#000000;fill-opacity:1;stroke:none;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 237.40145,276.39619 L 248.03137,276.39619 L 248.03137,290.56942 L 237.40145,290.56942"
-       id="path10779" />
-    <path
-       style="fill:#000000;fill-opacity:1;stroke:none;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 244.48806,279.9395 L 251.57467,279.9395 L 248.03137,287.02611 L 244.48806,279.9395 z"
-       id="path10781" />
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 244.48806,287.02611 L 251.57467,287.02611"
-       id="path10783" />
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;marker-end:url(#Arrow1Send);stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 253.34633,281.71115 L 256.88964,283.4828"
-       id="path10785" />
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;marker-end:url(#Arrow1Send);stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 251.57467,285.25446 L 255.11798,287.02611"
-       id="path10787" />
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 272.83453,276.39617 L 263.97629,276.39615 L 263.97629,278.16781 L 260.43297,281.71113"
-       id="path10789"
-       sodipodi:nodetypes="cccc" />
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 260.43296,285.25444 L 263.97629,288.79773 L 263.97629,290.56938 L 272.83453,290.5694"
-       id="path10791"
-       sodipodi:nodetypes="cccc" />
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 260.43296,278.16783 L 260.43296,288.79775"
-       id="path10793" />
-    <path
-       style="fill:#000000;fill-opacity:1;stroke:none;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 260.43299,287.02607 L 262.20465,285.25442 L 263.9763,288.79773 L 260.43299,287.02607 z"
-       id="path10795" />
-    <path
-       id="path10797"
-       d="M 237.40144,191.35681 L 248.03136,191.35681 L 248.03136,205.53004 L 237.40144,205.53004"
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
-    <path
-       id="path10799"
-       d="M 244.48805,194.90012 L 251.57466,194.90012 L 248.03136,201.98673 L 244.48805,194.90012 z"
-       style="fill:#000000;fill-opacity:1;stroke:none;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
-    <path
-       id="path10801"
-       d="M 244.48805,201.98673 L 251.57466,201.98673"
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
-    <path
-       id="path10803"
-       d="M 253.34632,196.67177 L 256.88963,198.44342"
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;marker-end:url(#Arrow1Send);stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
-    <path
-       id="path10805"
-       d="M 251.57466,200.21508 L 255.11797,201.98673"
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;marker-end:url(#Arrow1Send);stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
-    <path
-       sodipodi:nodetypes="cccc"
-       id="path10807"
-       d="M 272.83452,191.35679 L 263.97628,191.35677 L 263.97628,193.12843 L 260.43296,196.67175"
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
-    <path
-       sodipodi:nodetypes="cccc"
-       id="path10809"
-       d="M 260.43295,200.21506 L 263.97628,203.75835 L 263.97628,205.53 L 272.83452,205.53002"
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
-    <path
-       id="path10811"
-       d="M 260.43295,193.12845 L 260.43295,203.75837"
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
-    <path
-       id="path10813"
-       d="M 260.43298,201.98669 L 262.20464,200.21504 L 263.97629,203.75835 L 260.43298,201.98669 z"
-       style="fill:#000000;fill-opacity:1;stroke:none;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
-    <rect
-       y="63.779503"
-       x="237.40158"
-       height="113.5481"
-       width="35.34045"
-       id="rect10815"
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866142;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
-    <path
-       id="path10817"
-       d="M 237.40155,99.212589 L 248.03147,99.212589 L 248.03147,113.38582 L 237.40155,113.38582"
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
-    <path
-       id="path10819"
-       d="M 244.48816,102.7559 L 251.57477,102.7559 L 248.03147,109.84251 L 244.48816,102.7559 z"
-       style="fill:#000000;fill-opacity:1;stroke:none;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
-    <path
-       id="path10821"
-       d="M 244.48816,109.84251 L 251.57477,109.84251"
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
-    <path
-       id="path10823"
-       d="M 253.34643,104.52755 L 256.88974,106.2992"
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;marker-end:url(#Arrow1Send);stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
-    <path
-       id="path10825"
-       d="M 251.57477,108.07086 L 255.11808,109.84251"
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;marker-end:url(#Arrow1Send);stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
-    <path
-       sodipodi:nodetypes="cccc"
-       id="path10827"
-       d="M 272.83463,99.212569 L 263.97639,99.212549 L 263.97639,100.98421 L 260.43307,104.52753"
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
-    <path
-       sodipodi:nodetypes="cccc"
-       id="path10829"
-       d="M 260.43306,108.07084 L 263.97639,111.61413 L 263.97639,113.38578 L 272.83463,113.3858"
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
-    <path
-       id="path10831"
-       d="M 260.43306,100.98423 L 260.43306,111.61415"
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
-    <path
-       id="path10833"
-       d="M 260.43309,109.84247 L 262.20475,108.07082 L 263.9764,111.61413 L 260.43309,109.84247 z"
-       style="fill:#000000;fill-opacity:1;stroke:none;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 237.40157,127.55905 L 248.03149,127.55905 L 248.03149,141.73228 L 237.40157,141.73228"
-       id="path10835" />
-    <path
-       style="fill:#000000;fill-opacity:1;stroke:none;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 244.48818,131.10236 L 251.57479,131.10236 L 248.03149,138.18897 L 244.48818,131.10236 z"
-       id="path10837" />
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 244.48818,138.18897 L 251.57479,138.18897"
-       id="path10839" />
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;marker-end:url(#Arrow1Send);stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 253.34645,132.87401 L 256.88976,134.64566"
-       id="path10841" />
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;marker-end:url(#Arrow1Send);stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 251.57479,136.41732 L 255.1181,138.18897"
-       id="path10843" />
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 272.83465,127.55903 L 263.97641,127.55901 L 263.97641,129.33067 L 260.43309,132.87399"
-       id="path10845"
-       sodipodi:nodetypes="cccc" />
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 260.43308,136.4173 L 263.97641,139.96059 L 263.97641,141.73224 L 272.83465,141.73226"
-       id="path10847"
-       sodipodi:nodetypes="cccc" />
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 260.43308,129.33069 L 260.43308,139.96061"
-       id="path10849" />
-    <path
-       style="fill:#000000;fill-opacity:1;stroke:none;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 260.43311,138.18893 L 262.20477,136.41728 L 263.97642,139.96059 L 260.43311,138.18893 z"
-       id="path10851" />
-    <path
-       id="path10853"
-       d="M 237.40153,155.90552 L 248.03145,155.90552 L 248.03145,170.07875 L 237.40153,170.07875"
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
-    <path
-       id="path10855"
-       d="M 244.48814,159.44883 L 251.57475,159.44883 L 248.03145,166.53544 L 244.48814,159.44883 z"
-       style="fill:#000000;fill-opacity:1;stroke:none;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
-    <path
-       id="path10857"
-       d="M 244.48814,166.53544 L 251.57475,166.53544"
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
-    <path
-       id="path10859"
-       d="M 253.34641,161.22048 L 256.88972,162.99213"
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;marker-end:url(#Arrow1Send);stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
-    <path
-       id="path10861"
-       d="M 251.57475,164.76379 L 255.11806,166.53544"
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;marker-end:url(#Arrow1Send);stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
-    <path
-       sodipodi:nodetypes="cccc"
-       id="path10863"
-       d="M 272.83461,155.9055 L 263.97637,155.90548 L 263.97637,157.67714 L 260.43305,161.22046"
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
-    <path
-       sodipodi:nodetypes="cccc"
-       id="path10865"
-       d="M 260.43304,164.76377 L 263.97637,168.30706 L 263.97637,170.07871 L 272.83461,170.07873"
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
-    <path
-       id="path10867"
-       d="M 260.43304,157.67716 L 260.43304,168.30708"
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
-    <path
-       id="path10869"
-       d="M 260.43307,166.5354 L 262.20473,164.76375 L 263.97638,168.30706 L 260.43307,166.5354 z"
-       style="fill:#000000;fill-opacity:1;stroke:none;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 237.40153,70.866149 L 248.03145,70.866149 L 248.03145,85.039379 L 237.40153,85.039379"
-       id="path10871" />
-    <path
-       style="fill:#000000;fill-opacity:1;stroke:none;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 244.48814,74.409459 L 251.57475,74.409459 L 248.03145,81.496069 L 244.48814,74.409459 z"
-       id="path10873" />
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 244.48814,81.496069 L 251.57475,81.496069"
-       id="path10875" />
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;marker-end:url(#Arrow1Send);stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 253.34641,76.181109 L 256.88972,77.952759"
-       id="path10877" />
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;marker-end:url(#Arrow1Send);stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 251.57475,79.724419 L 255.11806,81.496069"
-       id="path10879" />
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 272.83461,70.866129 L 263.97637,70.866109 L 263.97637,72.637769 L 260.43305,76.181089"
-       id="path10881"
-       sodipodi:nodetypes="cccc" />
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 260.43304,79.724399 L 263.97637,83.267689 L 263.97637,85.039339 L 272.83461,85.039359"
-       id="path10883"
-       sodipodi:nodetypes="cccc" />
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 260.43304,72.637789 L 260.43304,83.267709"
-       id="path10885" />
-    <path
-       style="fill:#000000;fill-opacity:1;stroke:none;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 260.43307,81.496029 L 262.20473,79.724379 L 263.97638,83.267689 L 260.43307,81.496029 z"
-       id="path10887" />
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 162.99213,198.42511 L 177.16536,198.42511 L 177.16536,70.866049 L 237.40158,70.866049"
-       id="path10889"
-       sodipodi:nodetypes="cccc" />
-    <path
-       id="path10891"
-       d="M 116.92914,212.59834 L 141.73229,212.59834"
-       style="fill:none;fill-rule:evenodd;stroke:#000000;stroke-width:0.70866144;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
-    <path
-       sodipodi:nodetypes="cccccccc"
-       id="path10893"
-       d="M 141.7323,212.59836 L 143.50396,209.05503 L 147.04727,216.14165 L 150.59057,209.05503 L 154.13388,216.14165 L 157.67719,209.05503 L 161.22049,216.14165 L 162.99214,212.59836"
-       style="fill:none;fill-rule:evenodd;stroke:#000000;stroke-width:0.70866144;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
-    <path
-       style="fill:none;fill-rule:evenodd;stroke:#000000;stroke-width:0.70866144;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 116.92913,226.77157 L 141.73228,226.77157"
-       id="path10895" />
-    <path
-       style="fill:none;fill-rule:evenodd;stroke:#000000;stroke-width:0.70866144;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 141.73229,226.77159 L 143.50395,223.22826 L 147.04726,230.31488 L 150.59056,223.22826 L 154.13387,230.31488 L 157.67718,223.22826 L 161.22048,230.31488 L 162.99213,226.77159"
-       id="path10897"
-       sodipodi:nodetypes="cccccccc" />
-    <path
-       id="path10899"
-       d="M 116.92913,240.94477 L 141.73228,240.94477"
-       style="fill:none;fill-rule:evenodd;stroke:#000000;stroke-width:0.70866144;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
-    <path
-       sodipodi:nodetypes="cccccccc"
-       id="path10901"
-       d="M 141.73229,240.94479 L 143.50395,237.40146 L 147.04726,244.48808 L 150.59056,237.40146 L 154.13387,244.48808 L 157.67718,237.40146 L 161.22048,244.48808 L 162.99213,240.94479"
-       style="fill:none;fill-rule:evenodd;stroke:#000000;stroke-width:0.70866144;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
-    <path
-       style="fill:none;fill-rule:evenodd;stroke:#000000;stroke-width:0.70866144;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 116.92914,255.11802 L 141.73229,255.11802"
-       id="path10903" />
-    <path
-       style="fill:none;fill-rule:evenodd;stroke:#000000;stroke-width:0.70866144;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 141.7323,255.11804 L 143.50396,251.57471 L 147.04727,258.66133 L 150.59057,251.57471 L 154.13388,258.66133 L 157.67719,251.57471 L 161.22049,258.66133 L 162.99214,255.11804"
-       id="path10905"
-       sodipodi:nodetypes="cccccccc" />
-    <path
-       id="path10907"
-       d="M 116.92912,269.29125 L 141.73227,269.29125"
-       style="fill:none;fill-rule:evenodd;stroke:#000000;stroke-width:0.70866144;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
-    <path
-       sodipodi:nodetypes="cccccccc"
-       id="path10909"
-       d="M 141.73228,269.29127 L 143.50394,265.74794 L 147.04725,272.83456 L 150.59055,265.74794 L 154.13386,272.83456 L 157.67717,265.74794 L 161.22047,272.83456 L 162.99212,269.29127"
-       style="fill:none;fill-rule:evenodd;stroke:#000000;stroke-width:0.70866144;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
-    <path
-       style="fill:none;fill-rule:evenodd;stroke:#000000;stroke-width:0.70866144;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 116.92913,283.46446 L 141.73228,283.46446"
-       id="path10911" />
-    <path
-       style="fill:none;fill-rule:evenodd;stroke:#000000;stroke-width:0.70866144;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 141.73229,283.46448 L 143.50395,279.92115 L 147.04726,287.00777 L 150.59056,279.92115 L 154.13387,287.00777 L 157.67718,279.92115 L 161.22048,287.00777 L 162.99213,283.46448"
-       id="path10913"
-       sodipodi:nodetypes="cccccccc" />
-    <path
-       id="path10915"
-       d="M 116.92912,297.63771 L 141.73227,297.63771"
-       style="fill:none;fill-rule:evenodd;stroke:#000000;stroke-width:0.70866144;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
-    <path
-       sodipodi:nodetypes="cccccccc"
-       id="path10917"
-       d="M 141.73228,297.63773 L 143.50394,294.0944 L 147.04725,301.18102 L 150.59055,294.0944 L 154.13386,301.18102 L 157.67717,294.0944 L 161.22047,301.18102 L 162.99212,297.63773"
-       style="fill:none;fill-rule:evenodd;stroke:#000000;stroke-width:0.70866144;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 162.99213,212.59834 L 180.70867,212.59834 L 180.70867,99.212509 L 237.40158,99.212509"
-       id="path10919"
-       sodipodi:nodetypes="cccc" />
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 162.99213,226.77157 L 184.25197,226.77157 L 184.25197,127.55897 L 237.40158,127.55897"
-       id="path10921"
-       sodipodi:nodetypes="cccc" />
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 162.99213,240.94479 L 187.79528,240.94479 L 187.79528,155.90542 L 237.40158,155.90542"
-       id="path10923"
-       sodipodi:nodetypes="cccc" />
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 162.99213,255.11802 L 191.33859,255.11802 L 191.33859,191.3385 L 237.40158,191.3385"
-       id="path10925"
-       sodipodi:nodetypes="cccc" />
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 162.99213,269.29125 L 194.8819,269.29125 L 194.8819,219.68495 L 237.40158,219.68495"
-       id="path10927"
-       sodipodi:nodetypes="cccc" />
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 162.99213,283.46448 L 198.4252,283.46448 L 198.4252,248.03141 L 237.40158,248.03141"
-       id="path10929"
-       sodipodi:nodetypes="cccc" />
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 162.99213,297.63771 L 201.96851,297.63771 L 201.96851,276.37787 L 237.40158,276.37787"
-       id="path10931"
-       sodipodi:nodetypes="cccc" />
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 237.40158,85.039279 L 216.14174,85.039279 L 216.14174,297.63771"
-       id="path10933"
-       sodipodi:nodetypes="ccc" />
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 210.82678,297.63771 L 221.4567,297.63771"
-       id="path10935" />
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 212.59843,301.18102 L 219.68504,301.18102"
-       id="path10937" />
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 214.37008,304.72432 L 217.91339,304.72432"
-       id="path10939" />
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;marker-end:url(#DotS);stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 237.40158,113.3858 L 216.14174,113.38574"
-       id="path10941"
-       sodipodi:nodetypes="cc" />
-    <path
-       id="path11485"
-       d="M 237.40158,141.73226 L 216.14174,141.7322"
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;marker-end:url(#DotS);stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       sodipodi:nodetypes="cc" />
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;marker-end:url(#DotS);stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 237.40158,170.07871 L 216.14174,170.07865"
-       id="path11487"
-       sodipodi:nodetypes="cc" />
-    <path
-       id="path11489"
-       d="M 237.40158,205.51178 L 216.14174,205.51172"
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;marker-end:url(#DotS);stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       sodipodi:nodetypes="cc" />
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;marker-end:url(#DotS);stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 237.40158,233.85824 L 216.14174,233.85818"
-       id="path11491"
-       sodipodi:nodetypes="cc" />
-    <path
-       id="path11493"
-       d="M 237.40158,262.2047 L 216.14174,262.20464"
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;marker-end:url(#DotS);stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       sodipodi:nodetypes="cc" />
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;marker-end:url(#DotS);stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 237.40158,290.55115 L 216.14174,290.55109"
-       id="path11495"
-       sodipodi:nodetypes="cc" />
-    <path
-       id="path11497"
-       d="M 272.83465,85.039279 L 294.09449,85.039279 L 294.09449,297.63771"
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       sodipodi:nodetypes="ccc" />
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;marker-end:url(#DotS);stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 272.83465,113.3858 L 294.09449,113.38574"
-       id="path11499"
-       sodipodi:nodetypes="cc" />
-    <path
-       id="path12043"
-       d="M 272.83465,141.73226 L 294.09449,141.7322"
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;marker-end:url(#DotS);stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       sodipodi:nodetypes="cc" />
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;marker-end:url(#DotS);stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 272.83465,170.07871 L 294.09449,170.07865"
-       id="path12045"
-       sodipodi:nodetypes="cc" />
-    <path
-       id="path12047"
-       d="M 272.83465,205.51178 L 294.09449,205.51172"
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;marker-end:url(#DotS);stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       sodipodi:nodetypes="cc" />
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;marker-end:url(#DotS);stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 272.83465,233.85824 L 294.09449,233.85818"
-       id="path12049"
-       sodipodi:nodetypes="cc" />
-    <path
-       id="path12051"
-       d="M 272.83465,262.20469 L 294.09449,262.20464"
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;marker-end:url(#DotS);stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       sodipodi:nodetypes="cc" />
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;marker-end:url(#DotS);stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 272.83465,290.55115 L 294.09449,290.55109"
-       id="path12053"
-       sodipodi:nodetypes="cc" />
-    <path
-       id="path12055"
-       d="M 288.77954,297.63771 L 299.40946,297.63771"
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
-    <path
-       id="path12057"
-       d="M 290.55119,301.18102 L 297.6378,301.18102"
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
-    <path
-       id="path12059"
-       d="M 292.32284,304.72432 L 295.86615,304.72432"
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
-    <text
-       xml:space="preserve"
-       style="font-size:10px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
-       x="159.44882"
-       y="359.6456"
-       id="text12061"
-       sodipodi:linespacing="125%"><tspan
-         sodipodi:role="line"
-         id="tspan12063"
-         x="159.44882"
-         y="359.6456">FR206</tspan></text>
-    <text
-       xml:space="preserve"
-       style="font-size:10px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
-       x="237.40158"
-       y="308.26761"
-       id="text12065"
-       sodipodi:linespacing="125%"><tspan
-         sodipodi:role="line"
-         id="tspan12067"
-         x="237.40158"
-         y="308.26761">LTV847</tspan></text>
-    <rect
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866142;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       id="rect12069"
-       width="88.715057"
-       height="116.98304"
-       x="361.35117"
-       y="155.91777" />
-    <text
-       xml:space="preserve"
-       style="font-size:10px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
-       x="375.59058"
-       y="283.46451"
-       id="text12071"
-       sodipodi:linespacing="125%"><tspan
-         sodipodi:role="line"
-         id="tspan12073"
-         x="375.59058"
-         y="283.46451">Arduino Mini</tspan></text>
-    <rect
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866142;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       id="rect12075"
-       width="53.114006"
-       height="88.751289"
-       x="549.16486"
-       y="155.86205" />
-    <text
-       xml:space="preserve"
-       style="font-size:10px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
-       x="563.3858"
-       y="255.118"
-       id="text12077"
-       sodipodi:linespacing="125%"><tspan
-         sodipodi:role="line"
-         id="tspan12079"
-         x="563.3858"
-         y="255.118">XBee</tspan></text>
-    <text
-       xml:space="preserve"
-       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
-       x="364.96066"
-       y="166.53542"
-       id="text12081"
-       sodipodi:linespacing="125%"><tspan
-         sodipodi:role="line"
-         id="tspan12083"
-         x="364.96066"
-         y="166.53542">IO2 (PD2)</tspan></text>
-    <text
-       sodipodi:linespacing="125%"
-       id="text12085"
-       y="180.70863"
-       x="364.96066"
-       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
-       xml:space="preserve"><tspan
-         y="180.70863"
-         x="364.96066"
-         id="tspan12087"
-         sodipodi:role="line">IO3 (PD3)</tspan></text>
-    <text
-       xml:space="preserve"
-       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
-       x="364.96066"
-       y="194.88185"
-       id="text12089"
-       sodipodi:linespacing="125%"><tspan
-         sodipodi:role="line"
-         id="tspan12091"
-         x="364.96066"
-         y="194.88185">IO4 (PD4)</tspan></text>
-    <text
-       sodipodi:linespacing="125%"
-       id="text12093"
-       y="209.0551"
-       x="364.96066"
-       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
-       xml:space="preserve"><tspan
-         y="209.0551"
-         x="364.96066"
-         id="tspan12095"
-         sodipodi:role="line">IO5 (PD5)</tspan></text>
-    <text
-       xml:space="preserve"
-       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
-       x="364.96066"
-       y="223.22832"
-       id="text12097"
-       sodipodi:linespacing="125%"><tspan
-         sodipodi:role="line"
-         id="tspan12099"
-         x="364.96066"
-         y="223.22832">IO6 (PD6)</tspan></text>
-    <text
-       sodipodi:linespacing="125%"
-       id="text12101"
-       y="237.40157"
-       x="364.96066"
-       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
-       xml:space="preserve"><tspan
-         y="237.40157"
-         x="364.96066"
-         id="tspan12103"
-         sodipodi:role="line">IO7 (PD7)</tspan></text>
-    <text
-       xml:space="preserve"
-       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
-       x="364.96066"
-       y="251.57472"
-       id="text12105"
-       sodipodi:linespacing="125%"><tspan
-         sodipodi:role="line"
-         id="tspan12107"
-         x="364.96066"
-         y="251.57472">IO8 (PB0)</tspan></text>
-    <text
-       sodipodi:linespacing="125%"
-       id="text12109"
-       y="265.74796"
-       x="364.96066"
-       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
-       xml:space="preserve"><tspan
-         y="265.74796"
-         x="364.96066"
-         id="tspan12111"
-         sodipodi:role="line">IO9 (PB1)</tspan></text>
-    <text
-       xml:space="preserve"
-       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
-       x="411.02368"
-       y="180.7086"
-       id="text12113"
-       sodipodi:linespacing="125%"><tspan
-         sodipodi:role="line"
-         id="tspan12115"
-         x="411.02368"
-         y="180.7086">TX (PD0)</tspan></text>
-    <text
-       xml:space="preserve"
-       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
-       x="411.02365"
-       y="166.53542"
-       id="text12117"
-       sodipodi:linespacing="125%"><tspan
-         sodipodi:role="line"
-         id="tspan12119"
-         x="411.02365"
-         y="166.53542">RX (PD1)</tspan></text>
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 272.83465,276.37793 L 322.44095,276.37793 L 322.44095,262.2047 L 361.41732,262.2047"
-       id="path12121"
-       sodipodi:nodetypes="cccc" />
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 272.83465,248.03147 L 361.41732,248.03147"
-       id="path12123"
-       sodipodi:nodetypes="cc" />
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 272.83465,219.68501 L 322.44095,219.68501 L 322.44095,233.85824 L 361.41732,233.85824"
-       id="path12125"
-       sodipodi:nodetypes="cccc" />
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 361.41732,162.9921 L 340.15748,162.9921 L 340.15748,70.866109 L 272.83465,70.866109"
-       id="path12127"
-       sodipodi:nodetypes="cccc" />
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 361.41732,177.16533 L 336.61417,177.16533 L 336.61417,99.212569 L 272.83465,99.212569"
-       id="path12129"
-       sodipodi:nodetypes="cccc" />
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 361.41732,191.33856 L 333.07087,191.33856 L 333.07087,127.55903 L 272.83465,127.55903"
-       id="path12131"
-       sodipodi:nodetypes="cccc" />
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 361.41732,205.51178 L 329.52756,205.51178 L 329.52756,155.90548 L 272.83465,155.90548"
-       id="path12133"
-       sodipodi:nodetypes="cccc" />
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 361.41732,219.68501 L 325.98425,219.68501 L 325.98425,191.33856 L 272.83465,191.33856"
-       id="path12135"
-       sodipodi:nodetypes="cccc" />
-    <text
-       xml:space="preserve"
-       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
-       x="432.28348"
-       y="265.74796"
-       id="text12137"
-       sodipodi:linespacing="125%"><tspan
-         sodipodi:role="line"
-         id="tspan12139"
-         x="432.28348"
-         y="265.74796">Vcc</tspan></text>
-    <text
-       xml:space="preserve"
-       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
-       x="428.74017"
-       y="251.57472"
-       id="text12141"
-       sodipodi:linespacing="125%"><tspan
-         sodipodi:role="line"
-         id="tspan12143"
-         x="428.74017"
-         y="251.57472">GND</tspan></text>
-    <text
-       xml:space="preserve"
-       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
-       x="584.64563"
-       y="237.40147"
-       id="text12145"
-       sodipodi:linespacing="125%"><tspan
-         sodipodi:role="line"
-         id="tspan12147"
-         x="584.64563"
-         y="237.40147">Vcc</tspan></text>
-    <text
-       xml:space="preserve"
-       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
-       x="556.29919"
-       y="166.53539"
-       id="text12149"
-       sodipodi:linespacing="125%"><tspan
-         sodipodi:role="line"
-         id="tspan12151"
-         x="556.29919"
-         y="166.53539">DOUT</tspan></text>
-    <text
-       xml:space="preserve"
-       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
-       x="556.29919"
-       y="180.70854"
-       id="text12153"
-       sodipodi:linespacing="125%"><tspan
-         sodipodi:role="line"
-         id="tspan12155"
-         x="556.29919"
-         y="180.70854">DIN</tspan></text>
-    <text
-       xml:space="preserve"
-       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
-       x="556.29919"
-       y="237.40147"
-       id="text12157"
-       sodipodi:linespacing="125%"><tspan
-         sodipodi:role="line"
-         id="tspan12159"
-         x="556.29919"
-         y="237.40147">GND</tspan></text>
-    <text
-       xml:space="preserve"
-       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
-       x="582.87402"
-       y="209.05504"
-       id="text12161"
-       sodipodi:linespacing="125%"><tspan
-         sodipodi:role="line"
-         id="tspan12163"
-         x="582.87402"
-         y="209.05504">AD5</tspan></text>
-    <rect
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866142;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       id="rect12167"
-       width="53.164974"
-       height="35.41814"
-       x="513.82629"
-       y="333.11758" />
-    <text
-       xml:space="preserve"
-       style="font-size:10px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
-       x="520.86615"
-       y="329.5275"
-       id="text12169"
-       sodipodi:linespacing="125%"><tspan
-         sodipodi:role="line"
-         id="tspan12171"
-         x="520.86615"
-         y="329.5275">EZ1085</tspan></text>
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 379.13386,375.59053 L 485.43308,375.59046 L 485.43308,262.20464 L 450.00001,262.20464"
-       id="path12173"
-       sodipodi:nodetypes="cccc" />
-    <text
-       sodipodi:linespacing="125%"
-       id="text12175"
-       y="175.39366"
-       x="453.54337"
-       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
-       xml:space="preserve"><tspan
-         y="175.39366"
-         x="453.54337"
-         id="tspan12177"
-         sodipodi:role="line">1</tspan></text>
-    <text
-       sodipodi:linespacing="125%"
-       id="text12179"
-       y="189.56691"
-       x="354.33075"
-       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
-       xml:space="preserve"><tspan
-         y="189.56691"
-         x="354.33075"
-         id="tspan12181"
-         sodipodi:role="line">7</tspan></text>
-    <text
-       sodipodi:linespacing="125%"
-       id="text12183"
-       y="161.22044"
-       x="354.33075"
-       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
-       xml:space="preserve"><tspan
-         y="161.22044"
-         x="354.33075"
-         id="tspan12185"
-         sodipodi:role="line">5</tspan></text>
-    <text
-       xml:space="preserve"
-       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
-       x="354.33075"
-       y="175.39366"
-       id="text12187"
-       sodipodi:linespacing="125%"><tspan
-         sodipodi:role="line"
-         id="tspan12189"
-         x="354.33075"
-         y="175.39366">6</tspan></text>
-    <text
-       xml:space="preserve"
-       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
-       x="354.33075"
-       y="203.74013"
-       id="text12191"
-       sodipodi:linespacing="125%"><tspan
-         sodipodi:role="line"
-         id="tspan12193"
-         x="354.33075"
-         y="203.74013">8</tspan></text>
-    <text
-       xml:space="preserve"
-       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
-       x="354.33075"
-       y="217.91335"
-       id="text12195"
-       sodipodi:linespacing="125%"><tspan
-         sodipodi:role="line"
-         id="tspan12197"
-         x="354.33075"
-         y="217.91335">9</tspan></text>
-    <text
-       xml:space="preserve"
-       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
-       x="349.01578"
-       y="232.08659"
-       id="text12199"
-       sodipodi:linespacing="125%"><tspan
-         sodipodi:role="line"
-         id="tspan12201"
-         x="349.01578"
-         y="232.08659">10</tspan></text>
-    <text
-       xml:space="preserve"
-       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
-       x="349.01578"
-       y="246.25972"
-       id="text12203"
-       sodipodi:linespacing="125%"><tspan
-         sodipodi:role="line"
-         id="tspan12205"
-         x="349.01578"
-         y="246.25972">11</tspan></text>
-    <text
-       xml:space="preserve"
-       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
-       x="349.01578"
-       y="260.43301"
-       id="text12207"
-       sodipodi:linespacing="125%"><tspan
-         sodipodi:role="line"
-         id="tspan12209"
-         x="349.01578"
-         y="260.43301">12</tspan></text>
-    <text
-       xml:space="preserve"
-       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
-       x="453.54333"
-       y="161.22044"
-       id="text12211"
-       sodipodi:linespacing="125%"><tspan
-         sodipodi:role="line"
-         id="tspan12213"
-         x="453.54333"
-         y="161.22044">2</tspan></text>
-    <text
-       xml:space="preserve"
-       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
-       x="453.5433"
-       y="260.43301"
-       id="text12215"
-       sodipodi:linespacing="125%"><tspan
-         sodipodi:role="line"
-         id="tspan12217"
-         x="453.5433"
-         y="260.43301">21</tspan></text>
-    <text
-       xml:space="preserve"
-       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
-       x="453.5433"
-       y="246.25978"
-       id="text12219"
-       sodipodi:linespacing="125%"><tspan
-         sodipodi:role="line"
-         id="tspan12221"
-         x="453.5433"
-         y="246.25978">23</tspan></text>
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;marker-end:url(#DotS);stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 449.99998,248.03141 L 527.95276,248.03141"
-       id="path12223"
-       sodipodi:nodetypes="cc" />
-    <text
-       xml:space="preserve"
-       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
-       x="230.31496"
-       y="189.56691"
-       id="text12231"
-       sodipodi:linespacing="125%"><tspan
-         sodipodi:role="line"
-         id="tspan12233"
-         x="230.31496"
-         y="189.56691">1</tspan></text>
-    <text
-       sodipodi:linespacing="125%"
-       id="text12235"
-       y="203.74013"
-       x="230.31496"
-       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
-       xml:space="preserve"><tspan
-         y="203.74013"
-         x="230.31496"
-         id="tspan12237"
-         sodipodi:role="line">2</tspan></text>
-    <text
-       xml:space="preserve"
-       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
-       x="230.31496"
-       y="274.60623"
-       id="text12239"
-       sodipodi:linespacing="125%"><tspan
-         sodipodi:role="line"
-         id="tspan12241"
-         x="230.31496"
-         y="274.60623">7</tspan></text>
-    <text
-       xml:space="preserve"
-       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
-       x="230.31496"
-       y="246.25972"
-       id="text12243"
-       sodipodi:linespacing="125%"><tspan
-         sodipodi:role="line"
-         id="tspan12245"
-         x="230.31496"
-         y="246.25972">5</tspan></text>
-    <text
-       sodipodi:linespacing="125%"
-       id="text12247"
-       y="260.43295"
-       x="230.31496"
-       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
-       xml:space="preserve"><tspan
-         y="260.43295"
-         x="230.31496"
-         id="tspan12249"
-         sodipodi:role="line">6</tspan></text>
-    <text
-       sodipodi:linespacing="125%"
-       id="text12251"
-       y="288.77945"
-       x="230.31496"
-       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
-       xml:space="preserve"><tspan
-         y="288.77945"
-         x="230.31496"
-         id="tspan12253"
-         sodipodi:role="line">8</tspan></text>
-    <text
-       sodipodi:linespacing="125%"
-       id="text12255"
-       y="288.77945"
-       x="276.37799"
-       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
-       xml:space="preserve"><tspan
-         y="288.77945"
-         x="276.37799"
-         id="tspan12257"
-         sodipodi:role="line">9</tspan></text>
-    <text
-       sodipodi:linespacing="125%"
-       id="text12259"
-       y="274.60623"
-       x="276.37799"
-       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
-       xml:space="preserve"><tspan
-         y="274.60623"
-         x="276.37799"
-         id="tspan12261"
-         sodipodi:role="line">10</tspan></text>
-    <text
-       sodipodi:linespacing="125%"
-       id="text12263"
-       y="260.43301"
-       x="276.37799"
-       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
-       xml:space="preserve"><tspan
-         y="260.43301"
-         x="276.37799"
-         id="tspan12265"
-         sodipodi:role="line">11</tspan></text>
-    <text
-       sodipodi:linespacing="125%"
-       id="text12267"
-       y="246.25972"
-       x="276.37799"
-       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
-       xml:space="preserve"><tspan
-         y="246.25972"
-         x="276.37799"
-         id="tspan12269"
-         sodipodi:role="line">12</tspan></text>
-    <text
-       xml:space="preserve"
-       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
-       x="230.31496"
-       y="217.91335"
-       id="text12271"
-       sodipodi:linespacing="125%"><tspan
-         sodipodi:role="line"
-         id="tspan12273"
-         x="230.31496"
-         y="217.91335">3</tspan></text>
-    <text
-       xml:space="preserve"
-       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
-       x="230.31496"
-       y="232.08659"
-       id="text12275"
-       sodipodi:linespacing="125%"><tspan
-         sodipodi:role="line"
-         id="tspan12277"
-         x="230.31496"
-         y="232.08659">4</tspan></text>
-    <text
-       xml:space="preserve"
-       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
-       x="276.37799"
-       y="232.08659"
-       id="text12279"
-       sodipodi:linespacing="125%"><tspan
-         sodipodi:role="line"
-         id="tspan12281"
-         x="276.37799"
-         y="232.08659">13</tspan></text>
-    <text
-       xml:space="preserve"
-       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
-       x="276.37799"
-       y="217.91335"
-       id="text12283"
-       sodipodi:linespacing="125%"><tspan
-         sodipodi:role="line"
-         id="tspan12285"
-         x="276.37799"
-         y="217.91335">14</tspan></text>
-    <text
-       xml:space="preserve"
-       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
-       x="276.37799"
-       y="203.74013"
-       id="text12287"
-       sodipodi:linespacing="125%"><tspan
-         sodipodi:role="line"
-         id="tspan12289"
-         x="276.37799"
-         y="203.74013">15</tspan></text>
-    <text
-       xml:space="preserve"
-       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
-       x="276.37799"
-       y="189.56691"
-       id="text12291"
-       sodipodi:linespacing="125%"><tspan
-         sodipodi:role="line"
-         id="tspan12293"
-         x="276.37799"
-         y="189.56691">16</tspan></text>
-    <text
-       sodipodi:linespacing="125%"
-       id="text12295"
-       y="69.094444"
-       x="230.31496"
-       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
-       xml:space="preserve"><tspan
-         y="69.094444"
-         x="230.31496"
-         id="tspan12297"
-         sodipodi:role="line">1</tspan></text>
-    <text
-       xml:space="preserve"
-       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
-       x="230.31496"
-       y="83.267662"
-       id="text12299"
-       sodipodi:linespacing="125%"><tspan
-         sodipodi:role="line"
-         id="tspan12301"
-         x="230.31496"
-         y="83.267662">2</tspan></text>
-    <text
-       sodipodi:linespacing="125%"
-       id="text12303"
-       y="154.1338"
-       x="230.31496"
-       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
-       xml:space="preserve"><tspan
-         y="154.1338"
-         x="230.31496"
-         id="tspan12305"
-         sodipodi:role="line">7</tspan></text>
-    <text
-       sodipodi:linespacing="125%"
-       id="text12307"
-       y="125.78732"
-       x="230.31496"
-       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
-       xml:space="preserve"><tspan
-         y="125.78732"
-         x="230.31496"
-         id="tspan12309"
-         sodipodi:role="line">5</tspan></text>
-    <text
-       xml:space="preserve"
-       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
-       x="230.31496"
-       y="139.96053"
-       id="text12311"
-       sodipodi:linespacing="125%"><tspan
-         sodipodi:role="line"
-         id="tspan12313"
-         x="230.31496"
-         y="139.96053">6</tspan></text>
-    <text
-       xml:space="preserve"
-       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
-       x="230.31496"
-       y="168.30702"
-       id="text12315"
-       sodipodi:linespacing="125%"><tspan
-         sodipodi:role="line"
-         id="tspan12317"
-         x="230.31496"
-         y="168.30702">8</tspan></text>
-    <text
-       xml:space="preserve"
-       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
-       x="276.37799"
-       y="168.30702"
-       id="text12319"
-       sodipodi:linespacing="125%"><tspan
-         sodipodi:role="line"
-         id="tspan12321"
-         x="276.37799"
-         y="168.30702">9</tspan></text>
-    <text
-       xml:space="preserve"
-       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
-       x="276.37799"
-       y="154.1338"
-       id="text12323"
-       sodipodi:linespacing="125%"><tspan
-         sodipodi:role="line"
-         id="tspan12325"
-         x="276.37799"
-         y="154.1338">10</tspan></text>
-    <text
-       xml:space="preserve"
-       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
-       x="276.37799"
-       y="139.96059"
-       id="text12327"
-       sodipodi:linespacing="125%"><tspan
-         sodipodi:role="line"
-         id="tspan12329"
-         x="276.37799"
-         y="139.96059">11</tspan></text>
-    <text
-       xml:space="preserve"
-       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
-       x="276.37799"
-       y="125.78732"
-       id="text12331"
-       sodipodi:linespacing="125%"><tspan
-         sodipodi:role="line"
-         id="tspan12333"
-         x="276.37799"
-         y="125.78732">12</tspan></text>
-    <text
-       sodipodi:linespacing="125%"
-       id="text12335"
-       y="97.44088"
-       x="230.31496"
-       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
-       xml:space="preserve"><tspan
-         y="97.44088"
-         x="230.31496"
-         id="tspan12337"
-         sodipodi:role="line">3</tspan></text>
-    <text
-       sodipodi:linespacing="125%"
-       id="text12339"
-       y="111.61413"
-       x="230.31496"
-       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
-       xml:space="preserve"><tspan
-         y="111.61413"
-         x="230.31496"
-         id="tspan12341"
-         sodipodi:role="line">4</tspan></text>
-    <text
-       sodipodi:linespacing="125%"
-       id="text12343"
-       y="111.61413"
-       x="276.37799"
-       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
-       xml:space="preserve"><tspan
-         y="111.61413"
-         x="276.37799"
-         id="tspan12345"
-         sodipodi:role="line">13</tspan></text>
-    <text
-       sodipodi:linespacing="125%"
-       id="text12347"
-       y="97.44088"
-       x="276.37799"
-       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
-       xml:space="preserve"><tspan
-         y="97.44088"
-         x="276.37799"
-         id="tspan12349"
-         sodipodi:role="line">14</tspan></text>
-    <text
-       sodipodi:linespacing="125%"
-       id="text12351"
-       y="83.267662"
-       x="276.37799"
-       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
-       xml:space="preserve"><tspan
-         y="83.267662"
-         x="276.37799"
-         id="tspan12353"
-         sodipodi:role="line">15</tspan></text>
-    <text
-       sodipodi:linespacing="125%"
-       id="text12355"
-       y="69.094444"
-       x="276.37799"
-       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
-       xml:space="preserve"><tspan
-         y="69.094444"
-         x="276.37799"
-         id="tspan12357"
-         sodipodi:role="line">16</tspan></text>
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 379.13386,375.5906 C 380.90551,370.27564 380.90551,364.96067 375.59055,364.96062 C 368.50394,364.96055 368.50394,375.59053 372.04724,375.59053 C 375.59054,375.59053 375.59055,364.96062 368.50394,364.96062 C 361.41733,364.96062 361.41732,375.59053 364.96063,375.59053 C 368.50394,375.59053 368.50394,364.96062 361.41733,364.96062 C 354.3307,364.96062 354.33071,375.59053 357.87401,375.59053 C 361.41731,375.59053 361.41733,364.9606 354.33071,364.9606 C 349.01575,364.9606 349.01575,370.27557 350.7874,375.59053"
-       id="path12359"
-       sodipodi:nodetypes="cszzzzzsz" />
-    <text
-       xml:space="preserve"
-       style="font-size:10px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
-       x="349.01578"
-       y="361.41721"
-       id="text12361"
-       sodipodi:linespacing="125%"><tspan
-         sodipodi:role="line"
-         id="tspan12363"
-         x="349.01578"
-         y="361.41721">680µH</tspan></text>
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 311.81104,375.59047 L 350.7874,375.59053"
-       id="path12365"
-       sodipodi:nodetypes="cc" />
-    <path
-       style="fill:#000000;fill-opacity:1;stroke:none;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 329.52758,407.48023 L 333.07089,400.39362 L 336.6142,407.48023 L 329.52758,407.48023 z"
-       id="path12367" />
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 336.61421,403.93693 C 338.38586,403.93693 338.38586,400.39362 336.61421,400.39362 L 329.52759,400.39362 C 327.75594,400.39362 327.75594,396.85031 329.52759,396.85031"
-       id="path12369"
-       sodipodi:nodetypes="cccc" />
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;marker-end:url(#DotS);stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 333.07089,428.74008 L 333.07089,375.59047"
-       id="path12371"
-       sodipodi:nodetypes="cc" />
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 327.75593,428.74007 L 338.38585,428.74007"
-       id="path12375" />
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 336.6142,432.28338 L 329.52758,432.28338"
-       id="path12377" />
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 331.29924,435.82668 L 334.84254,435.82668"
-       id="path12379" />
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;marker-start:url(#DotS);stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 205.51182,347.24401 L 205.51182,364.96054"
-       id="path12381"
-       sodipodi:nodetypes="cc" />
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 200.19685,364.9606 L 210.82677,364.9606"
-       id="path12383"
-       sodipodi:nodetypes="cc" />
-    <path
-       style="fill:#000000;fill-opacity:1;stroke:none;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 200.19686,366.7322 L 200.19686,368.50385 L 210.82678,368.50385 L 210.82678,366.7322 L 200.19686,366.7322 z"
-       id="path12385"
-       sodipodi:nodetypes="ccccc" />
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;marker-end:url(#DotS);stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 205.51182,368.50385 L 205.51182,389.7637"
-       id="path12387"
-       sodipodi:nodetypes="cc" />
-    <text
-       xml:space="preserve"
-       style="font-size:10px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
-       x="210.82677"
-       y="370.27554"
-       id="text12395"
-       sodipodi:linespacing="125%"><tspan
-         sodipodi:role="line"
-         id="tspan12397"
-         x="210.82677"
-         y="370.27554">22µF</tspan></text>
-    <path
-       sodipodi:nodetypes="cc"
-       id="path12399"
-       d="M 393.30709,375.59053 L 393.30709,400.39368"
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;marker-start:url(#DotS);stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
-    <path
-       sodipodi:nodetypes="cc"
-       id="path12401"
-       d="M 387.99213,400.39368 L 398.62205,400.39368"
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
-    <path
-       sodipodi:nodetypes="ccccc"
-       id="path12403"
-       d="M 387.99213,402.16533 L 387.99213,403.93698 L 398.62205,403.93698 L 398.62205,402.16533 L 387.99213,402.16533 z"
-       style="fill:#000000;fill-opacity:1;stroke:none;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
-    <path
-       sodipodi:nodetypes="cc"
-       id="path12405"
-       d="M 393.30709,403.93698 L 393.30709,428.74013"
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 387.99213,428.74013 L 398.62205,428.74013"
-       id="path12407" />
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 396.8504,432.28343 L 389.76378,432.28343"
-       id="path12409" />
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 391.53544,435.82674 L 395.07874,435.82674"
-       id="path12411" />
-    <text
-       sodipodi:linespacing="125%"
-       id="text12413"
-       y="407.48029"
-       x="398.62207"
-       style="font-size:10px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
-       xml:space="preserve"><tspan
-         y="407.48029"
-         x="398.62207"
-         sodipodi:role="line"
-         id="tspan12417">220µF</tspan></text>
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;marker-start:url(#DotS);stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 400.3937,375.59053 L 400.3937,347.24407 L 311.81103,347.24401"
-       id="path13505"
-       sodipodi:nodetypes="ccc" />
-    <path
-       style="fill:#000000;fill-opacity:1;stroke:none;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 442.91339,329.52747 L 442.91339,336.61409 L 435.82678,333.07078 L 442.91339,329.52747 z"
-       id="path14591" />
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 435.82678,329.52747 L 435.82678,336.61409"
-       id="path14593" />
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;marker-end:url(#Arrow1Send);stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 437.59843,329.52747 L 435.82678,325.98416"
-       id="path14595" />
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;marker-end:url(#Arrow1Send);stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 441.14174,327.75582 L 439.37008,324.21251"
-       id="path14597" />
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 457.08662,333.07078 L 418.11024,333.07078 L 418.11024,350.78732"
-       id="path15683"
-       sodipodi:nodetypes="ccc" />
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 412.79528,350.78732 L 423.4252,350.78732"
-       id="path15685" />
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 421.65355,354.33062 L 414.56693,354.33062"
-       id="path15687" />
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 416.33859,357.87393 L 419.8819,357.87393"
-       id="path15689" />
-    <path
-       style="fill:none;fill-rule:evenodd;stroke:#000000;stroke-width:0.70866144;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 457.08662,333.07078 L 458.85828,329.52745 L 462.40159,336.61407 L 465.94489,329.52745 L 469.4882,336.61407 L 473.03151,329.52745 L 476.57481,336.61407 L 478.34646,333.07078"
-       id="path15691"
-       sodipodi:nodetypes="cccccccc" />
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;marker-end:url(#DotS);stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 478.34646,333.07078 L 485.43308,333.07078"
-       id="path15693" />
-    <text
-       xml:space="preserve"
-       style="font-size:10px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
-       x="453.54333"
-       y="327.75583"
-       id="text16237"
-       sodipodi:linespacing="125%"><tspan
-         sodipodi:role="line"
-         id="tspan16239"
-         x="453.54333"
-         y="327.75583">1.8kΩ</tspan></text>
-    <text
-       xml:space="preserve"
-       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
-       x="517.32281"
-       y="354.33066"
-       id="text16241"
-       sodipodi:linespacing="125%"><tspan
-         sodipodi:role="line"
-         id="tspan16243"
-         x="517.32281"
-         y="354.33066">VIN</tspan></text>
-    <text
-       xml:space="preserve"
-       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
-       x="542.12598"
-       y="354.33066"
-       id="text16245"
-       sodipodi:linespacing="125%"><tspan
-         sodipodi:role="line"
-         id="tspan16247"
-         x="542.12598"
-         y="354.33066">VOUT</tspan></text>
-    <text
-       xml:space="preserve"
-       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
-       x="531.49603"
-       y="364.96054"
-       id="text16249"
-       sodipodi:linespacing="125%"><tspan
-         sodipodi:role="line"
-         id="tspan16251"
-         x="531.49603"
-         y="364.96054">GND</tspan></text>
-    <path
-       sodipodi:nodetypes="cccccccc"
-       id="path16253"
-       d="M 481.88979,177.16528 L 483.66145,173.62195 L 487.20476,180.70857 L 490.74806,173.62195 L 494.29137,180.70857 L 497.83468,173.62195 L 501.37798,180.70857 L 503.14963,177.16528"
-       style="fill:none;fill-rule:evenodd;stroke:#000000;stroke-width:0.70866144;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
-    <text
-       sodipodi:linespacing="125%"
-       id="text16255"
-       y="189.56685"
-       x="478.34647"
-       style="font-size:10px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
-       xml:space="preserve"><tspan
-         y="189.56685"
-         x="478.34647"
-         id="tspan16257"
-         sodipodi:role="line">1.8kΩ</tspan></text>
-    <path
-       sodipodi:nodetypes="cccccccc"
-       id="path16259"
-       d="M 527.95276,198.42511 L 531.49609,200.19677 L 524.40947,203.74008 L 531.49609,207.28338 L 524.40947,210.82669 L 531.49609,214.37 L 524.40947,217.9133 L 527.95276,219.68495"
-       style="fill:none;fill-rule:evenodd;stroke:#000000;stroke-width:0.70866144;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
-    <text
-       sodipodi:linespacing="125%"
-       id="text16261"
-       y="212.59834"
-       x="492.51971"
-       style="font-size:10px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
-       xml:space="preserve"><tspan
-         id="tspan16263"
-         y="212.59834"
-         x="492.51971"
-         sodipodi:role="line">3.3kΩ</tspan></text>
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 450.00003,177.16526 L 481.88979,177.16526"
-       id="path16271" />
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 503.14963,177.16526 L 549.2126,177.16527"
-       id="path16273"
-       sodipodi:nodetypes="cc" />
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;marker-start:url(#DotS);stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 527.95278,177.16526 L 527.95276,198.42511"
-       id="path16275"
-       sodipodi:nodetypes="cc" />
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 527.95276,219.68495 L 527.95278,256.88967"
-       id="path16277"
-       sodipodi:nodetypes="cc" />
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 522.63782,256.88967 L 533.26774,256.88967"
-       id="path16279" />
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 531.49609,260.43297 L 524.40947,260.43297"
-       id="path16281" />
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 526.18112,263.97628 L 529.72443,263.97628"
-       id="path16283" />
-    <text
-       xml:space="preserve"
-       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
-       x="542.12598"
-       y="175.3936"
-       id="text16827"
-       sodipodi:linespacing="125%"><tspan
-         sodipodi:role="line"
-         id="tspan16829"
-         x="542.12598"
-         y="175.3936">3</tspan></text>
-    <text
-       xml:space="preserve"
-       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
-       x="542.12598"
-       y="161.22041"
-       id="text16831"
-       sodipodi:linespacing="125%"><tspan
-         sodipodi:role="line"
-         id="tspan16833"
-         x="542.12598"
-         y="161.22041">2</tspan></text>
-    <text
-       xml:space="preserve"
-       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
-       x="605.90546"
-       y="203.74007"
-       id="text16835"
-       sodipodi:linespacing="125%"><tspan
-         sodipodi:role="line"
-         id="tspan16837"
-         x="605.90546"
-         y="203.74007">15</tspan></text>
-    <text
-       xml:space="preserve"
-       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
-       x="605.90552"
-       y="232.08653"
-       id="text16839"
-       sodipodi:linespacing="125%"><tspan
-         sodipodi:role="line"
-         id="tspan16841"
-         x="605.90552"
-         y="232.08653">1</tspan></text>
-    <text
-       xml:space="preserve"
-       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
-       x="536.81104"
-       y="232.08653"
-       id="text16843"
-       sodipodi:linespacing="125%"><tspan
-         sodipodi:role="line"
-         id="tspan16845"
-         x="536.81104"
-         y="232.08653">10</tspan></text>
-    <path
-       style="fill:none;fill-rule:evenodd;stroke:#000000;stroke-width:0.70866144;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 481.88977,162.99206 L 483.66143,159.44873 L 487.20474,166.53535 L 490.74804,159.44873 L 494.29135,166.53535 L 497.83466,159.44873 L 501.37796,166.53535 L 503.14961,162.99206"
-       id="path16847"
-       sodipodi:nodetypes="cccccccc" />
-    <path
-       id="path16849"
-       d="M 450.00001,162.99204 L 481.88977,162.99204"
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
-    <path
-       id="path16851"
-       d="M 503.14961,162.99204 L 549.2126,162.99204"
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       sodipodi:nodetypes="cc" />
-    <text
-       xml:space="preserve"
-       style="font-size:10px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
-       x="478.34647"
-       y="157.67708"
-       id="text16853"
-       sodipodi:linespacing="125%"><tspan
-         sodipodi:role="line"
-         id="tspan16855"
-         x="478.34647"
-         y="157.67708">100Ω</tspan></text>
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866143999999998;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1;marker-start:url(#DotS)"
-       d="M 485.43308,350.78731 L 513.77953,350.78731"
-       id="path16857" />
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 540.35434,368.50385 L 540.35434,386.22039"
-       id="path16859" />
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 535.03938,386.22039 L 545.6693,386.22039"
-       id="path16861" />
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 543.89764,389.76369 L 536.81103,389.76369"
-       id="path16863" />
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 538.58268,393.307 L 542.12599,393.307"
-       id="path16865" />
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 566.92914,350.78731 L 616.53544,350.78731 L 616.53544,233.85818 L 602.36221,233.85818"
-       id="path16867"
-       sodipodi:nodetypes="cccc" />
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;marker-end:url(#DotS);stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 549.2126,233.85818 L 527.95276,233.85818"
-       id="path16877"
-       sodipodi:nodetypes="cc" />
-    <path
-       style="fill:none;fill-rule:evenodd;stroke:#000000;stroke-width:0.70866144;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 616.53544,205.51172 L 618.3071,201.96839 L 621.85041,209.05501 L 625.39371,201.96839 L 628.93702,209.05501 L 632.48033,201.96839 L 636.02363,209.05501 L 637.79528,205.51172"
-       id="path18505"
-       sodipodi:nodetypes="cccccccc" />
-    <text
-       xml:space="preserve"
-       style="font-size:10px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
-       x="616.5354"
-       y="217.91328"
-       id="text18507"
-       sodipodi:linespacing="125%"><tspan
-         sodipodi:role="line"
-         id="tspan18509"
-         x="616.5354"
-         y="217.91328">1kΩ</tspan></text>
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 602.36221,205.51172 L 616.53543,205.51172"
-       id="path18511" />
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 637.79528,205.51172 L 644.88189,205.51172 L 644.88189,265.74794"
-       id="path18513" />
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 639.56693,265.74794 L 650.19685,265.74794"
-       id="path18515" />
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 648.4252,269.29124 L 641.33858,269.29124"
-       id="path18517" />
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 643.11024,272.83455 L 646.65354,272.83455"
-       id="path18519" />
-    <path
-       style="fill:#000000;fill-opacity:1;stroke:none;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 641.33858,226.77156 L 648.4252,226.77156 L 644.88189,233.85817 L 641.33858,226.77156 z"
-       id="path18521" />
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 641.33858,233.85817 L 648.4252,233.85817"
-       id="path18523" />
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;marker-end:url(#Arrow1Send);stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 650.19685,228.54321 L 653.74016,230.31487"
-       id="path18525" />
-    <path
-       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;marker-end:url(#Arrow1Send);stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
-       d="M 648.4252,232.08652 L 651.9685,233.85817"
-       id="path18527" />
-    <text
-       xml:space="preserve"
-       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
-       x="506.6929"
-       y="349.01566"
-       id="text19071"
-       sodipodi:linespacing="125%"><tspan
-         sodipodi:role="line"
-         id="tspan19073"
-         x="506.6929"
-         y="349.01566">3</tspan></text>
-    <text
-       xml:space="preserve"
-       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
-       x="570.47241"
-       y="349.01566"
-       id="text19075"
-       sodipodi:linespacing="125%"><tspan
-         sodipodi:role="line"
-         id="tspan19077"
-         x="570.47241"
-         y="349.01566">2</tspan></text>
-    <text
-       xml:space="preserve"
-       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
-       x="542.12598"
-       y="377.36215"
-       id="text19079"
-       sodipodi:linespacing="125%"><tspan
-         sodipodi:role="line"
-         id="tspan19081"
-         x="542.12598"
-         y="377.36215">1</tspan></text>
-    <text
-       xml:space="preserve"
-       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
-       x="251.57481"
-       y="387.99203"
-       id="text19625"
-       sodipodi:linespacing="125%"><tspan
-         sodipodi:role="line"
-         id="tspan19627"
-         x="251.57481"
-         y="387.99203">2</tspan></text>
-    <text
-       xml:space="preserve"
-       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
-       x="251.57481"
-       y="373.81882"
-       id="text19629"
-       sodipodi:linespacing="125%"><tspan
-         sodipodi:role="line"
-         id="tspan19631"
-         x="251.57481"
-         y="373.81882">3</tspan></text>
-    <text
-       xml:space="preserve"
-       style="font-size:10px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
-       x="340.15747"
-       y="407.48029"
-       id="text20175"
-       sodipodi:linespacing="125%"><tspan
-         sodipodi:role="line"
-         id="tspan20177"
-         x="340.15747"
-         y="407.48029">1N5819</tspan></text>
-  </g>
-</svg>
diff --git a/firmware/serial.c b/firmware/serial.c
deleted file mode 100644 (file)
index 2bf6901..0000000
+++ /dev/null
@@ -1,22 +0,0 @@
-#include <avr/io.h>
-#include "serial.h"
-
-#define BIT(n) (1<<(n))
-
-void serial_init(uint16_t baud)
-{
-       DDRD = (DDRD&~0x03) | 0x02;
-       PORTD &= ~0x03;
-
-       baud = (F_CPU/16+baud/2)/baud-1;
-       UBRR0H = baud>>8;
-       UBRR0L = baud;
-       UCSR0C = BIT(UCSZ00) | BIT(UCSZ01);  // 8N1
-       UCSR0B = BIT(RXEN0) | BIT(TXEN0) | BIT(RXCIE0);
-}
-
-void serial_write(uint8_t c)
-{
-       while(!(UCSR0A&(1<<UDRE0))) ;
-       UDR0 = c;
-}
diff --git a/firmware/serial.h b/firmware/serial.h
deleted file mode 100644 (file)
index 04ea50b..0000000
+++ /dev/null
@@ -1,16 +0,0 @@
-#ifndef SERIAL_H_
-#define SERIAL_H_
-
-#include <avr/interrupt.h>
-
-#define SERIAL_SET_CALLBACK(f) \
-       ISR(USART_RX_vect) \
-       { \
-               char c = UDR0; \
-               f(c); \
-       }
-
-void serial_init(uint16_t);
-void serial_write(uint8_t);
-
-#endif
diff --git a/firmware/timer.c b/firmware/timer.c
deleted file mode 100644 (file)
index 99625f8..0000000
+++ /dev/null
@@ -1,101 +0,0 @@
-#include <avr/io.h>
-#include "timer.h"
-
-#define BIT(n) (1<<(n))
-
-static void timer_start(uint8_t num, uint32_t period)
-{
-       uint8_t cs;
-
-       if(num==0)
-       {
-               if(period<0x100)
-               {
-                       cs = BIT(CS00);
-               }
-               else if(period<0x800)
-               {
-                       cs = BIT(CS01);
-                       period /= 8;
-               }
-               else if(period<0x4000)
-               {
-                       cs = BIT(CS01) | BIT(CS00);
-                       period /= 64;
-               }
-               else if(period<0x10000)
-               {
-                       cs = BIT(CS02);
-                       period /= 256;
-               }
-               else
-               {
-                       cs = BIT(CS02) | BIT(CS00);
-                       period /= 1024;
-                       if(period>0xFF)
-                               period = 0xFF;
-               }
-               TCCR0A = BIT(WGM01);
-               TCCR0B = cs;
-               OCR0A = period;
-               TIMSK0 = BIT(OCIE0A);
-       }
-       if(num==1)
-       {
-               if(period<0x10000)
-               {
-                       cs = BIT(CS10);
-               }
-               else if(period<0x80000)
-               {
-                       cs = BIT(CS11);
-                       period /= 8;
-               }
-               else if(period<0x400000)
-               {
-                       cs = BIT(CS11) | BIT(CS10);
-                       period /= 64;
-               }
-               else if(period<0x1000000)
-               {
-                       cs = BIT(CS12);
-                       period /= 256;
-               }
-               else
-               {
-                       cs = BIT(CS12) | BIT(CS10);
-                       period /= 1024;
-                       if(period>0xFFFF)
-                               period = 0xFFFF;
-               }
-               TCCR1A = 0;
-               TCCR1B = BIT(WGM12) | cs;
-               OCR1AH = period>>8;
-               OCR1AL = period;
-               TIMSK1 = BIT(OCIE1A);
-       }
-}
-
-void timer_start_hz(uint8_t num, uint32_t freq_p, uint8_t freq_q)
-{
-       timer_start(num, F_CPU*freq_q/freq_p);
-}
-
-void timer_start_us(uint8_t num, uint32_t us)
-{
-       timer_start(num, F_CPU/1000000*us);
-}
-
-void timer_stop(uint8_t num)
-{
-       if(num==0)
-       {
-               TCCR0B = 0;
-               TIMSK0 = 0;
-       }
-       else if(num==1)
-       {
-               TCCR1B = 0;
-               TIMSK1 = 0;
-       }
-}
diff --git a/firmware/timer.h b/firmware/timer.h
deleted file mode 100644 (file)
index 2869caa..0000000
+++ /dev/null
@@ -1,16 +0,0 @@
-#ifndef TIMER_H_
-#define TIMER_H_
-
-#include <avr/interrupt.h>
-
-#define TIMER_SET_CALLBACK(n, f) \
-       ISR(TIMER ## n ## _COMPA_vect) \
-       { \
-               f(); \
-       }
-
-void timer_start_hz(uint8_t, uint32_t, uint8_t);
-void timer_start_us(uint8_t, uint32_t);
-void timer_stop(uint8_t);
-
-#endif
diff --git a/misc/Makefile b/misc/Makefile
new file mode 100644 (file)
index 0000000..c7b57b4
--- /dev/null
@@ -0,0 +1 @@
+include ../common/build.mk
diff --git a/misc/ctrl.c b/misc/ctrl.c
new file mode 100644 (file)
index 0000000..0ac212e
--- /dev/null
@@ -0,0 +1,221 @@
+#include <avr/io.h>
+#include <avr/interrupt.h>
+
+#define BIT(n) (1<<(n))
+#define NOP() __asm__("nop");
+
+uint8_t digits[11] =
+{
+       0x3F,
+       0x06,
+       0x5B,
+       0x4F,
+       0x66,
+       0x6D,
+       0x7D,
+       0x07,
+       0x7F,
+       0x6F,
+       0x40
+};
+
+uint16_t read_input(void);
+uint16_t read_input_filtered(void);
+void write_serial(uint8_t);
+void write_7seg(uint8_t);
+
+uint8_t speed = 0;
+uint16_t funcs = 0;
+volatile uint8_t ticks = 0;
+volatile uint8_t rx_buf[3];
+volatile uint8_t rx_fill = 0;
+
+ISR(TIMER1_COMPA_vect)
+{
+       if(ticks<255)
+               ++ticks;
+}
+
+ISR(USART_RX_vect)
+{
+       uint8_t c = UDR0;
+       if(rx_fill==0)
+       {
+               if(c=='A' || c=='S')
+                       rx_buf[rx_fill++] = c;
+       }
+       else
+       {
+               rx_buf[rx_fill++] = c;
+               if(rx_buf[0]=='A' && rx_fill==3)
+               {
+                       uint8_t n = (rx_buf[1]-'0')*10+(rx_buf[2]-'0');
+                       write_7seg(n/10);
+                       write_7seg(n%10);
+                       rx_fill = 0;
+               }
+               else if(rx_buf[0]=='S' && rx_fill==3)
+               {
+                       speed = (rx_buf[1]-'0')*10+(rx_buf[2]-'0');
+                       rx_fill = 0;
+               }
+       }
+}
+
+int main()
+{
+       uint16_t state = 0;
+
+       DDRD = 0x02;   // 00000010
+       PORTD = 0xFC;  // 11111100
+       DDRB = 0x3F;   // 00111111
+       PORTB = 0x0F;  // 00001111
+
+       write_7seg(10);
+       write_7seg(10);
+
+       // 9600 baud, 8N1
+       UBRR0H = 0;
+       UBRR0L = 103;
+       UCSR0C = BIT(UCSZ00) | BIT(UCSZ01);
+       UCSR0B = BIT(RXEN0) | BIT(TXEN0) | BIT(RXCIE0);
+
+       TCCR1A = 0;
+       TCCR1B = BIT(WGM12) | BIT(CS12);
+       OCR1AH = 24;
+       OCR1AL = 106;
+       TIMSK1 = BIT(OCIE1A);
+
+       sei();
+
+       while(1)
+       {
+               uint16_t toggled;
+               uint8_t i;
+               uint16_t input;
+
+               input = read_input_filtered();
+               input ^= 0xFFFC;
+
+               toggled = state^input;
+               state = input;
+
+               if((toggled&3)==2 && (state&1))
+               {
+                       uint8_t action = 0;
+                       if(state&2)
+                       {
+                               if(speed<14)
+                               {
+                                       ++speed;
+                                       action = 1;
+                               }
+                       }
+                       else
+                       {
+                               if(speed>0)
+                               {
+                                       --speed;
+                                       action = 1;
+                               }
+                               else if(ticks>10)
+                                       action = 2;
+                       }
+
+                       if(action==1)
+                       {
+                               write_serial('S');
+                               write_serial('0'+speed/10);
+                               write_serial('0'+speed%10);
+                       }
+                       else if(action==2)
+                               write_serial('R');
+
+                       ticks = 0;
+               }
+
+               for(i=0; i<14; ++i)
+               {
+                       uint16_t bit = 4<<i;
+                       if(toggled&~state&bit)
+                       {
+                               if(i==0)
+                                       write_serial('N');
+                               else if(i==1)
+                                       write_serial('P');
+                               else
+                               {
+                                       uint8_t f = i-2;
+                                       uint16_t fbit = 1<<f;
+                                       funcs ^= fbit;
+                                       write_serial((funcs&fbit) ? 'H' : 'L');
+                                       write_serial('0'+f);
+                               }
+                       }
+               }
+       }
+}
+
+uint16_t read_input(void)
+{
+       uint8_t row;
+       uint16_t input = 0;
+
+       for(row=0; row<4; ++row)
+       {
+               uint8_t pins;
+
+               PORTB = (PORTB|0x0F)&~(1<<row);
+               NOP();
+               NOP();
+               NOP();
+               NOP();
+               NOP();
+               NOP();
+               pins = PIND>>2;
+               input |= pins&3;
+               input |= (pins&0x3C)<<(row*4);
+       }
+
+       return input;
+}
+
+uint16_t read_input_filtered(void)
+{
+       uint16_t valid = 0xFFFF;
+       uint16_t prev;
+       uint16_t input;
+       uint8_t i;
+
+       prev = read_input();
+       for(i=0; i<20; ++i)
+       {
+               input = read_input();
+               valid &= ~(input^prev);
+               prev = input;
+       }
+
+       return input&valid;
+}
+
+void write_serial(uint8_t c)
+{
+       while(!(UCSR0A&(1<<UDRE0))) ;
+       UDR0 = c;
+}
+
+void write_7seg(uint8_t n)
+{
+       uint8_t segs = ~digits[n];
+       uint8_t i;
+       for(i=0; i<8; ++i)
+       {
+               PORTB &= ~0x20;
+               if(segs&0x80)
+                       PORTB |= 0x10;
+               else
+                       PORTB &= ~0x10;
+               PORTB |= 0x20;
+               segs <<= 1;
+       }
+}
diff --git a/s88w/Makefile b/s88w/Makefile
new file mode 100644 (file)
index 0000000..5018b01
--- /dev/null
@@ -0,0 +1,6 @@
+FEATURES := LCD_SHIFTREG LCD_ASYNC
+
+include ../common/build.mk
+
+s88w-t.elf: serial.o timer.o eeprom.o
+s88w-r.elf: serial.o lcd.o timer.o
diff --git a/s88w/s88w-r.c b/s88w/s88w-r.c
new file mode 100644 (file)
index 0000000..0198974
--- /dev/null
@@ -0,0 +1,219 @@
+/*
+Firmware for wireless S88 receiver module
+
+S88 pinout:
+1 - DATA
+2 - GND
+3 - CLOCK
+4 - LOAD
+5 - RESET
+6 - POWER
+
+ATMega pinout:
+D0 - serial RX
+D1 - serial TX
+D2 - S88 DATA
+D3 - S88 CLOCK
+D4 - S88 LOAD
+D5 - S88 RESET
+*/
+
+#include <avr/io.h>
+#include <avr/interrupt.h>
+#include "lcd.h"
+#include "serial.h"
+#include "delay.h"
+
+#define DATA_OUT PORTD2
+#define CLOCK    PIND3
+#define LOAD     PIND4
+#define RESET    PIND5
+
+#define LCD_DISABLE PINB4
+
+#define BIT(n)   (1<<(n))
+
+void receive(uint8_t);
+uint8_t hexdigit(uint8_t);
+uint8_t decode_hex(uint8_t);
+
+volatile uint8_t rx_buf[7];
+volatile uint8_t rx_fill = 0xFF;
+volatile uint8_t input[128] = { 0 };
+volatile uint8_t latch[128] = { 0 };
+volatile uint8_t lcd_enabled = 0;
+uint8_t log_row = 0;
+uint8_t log_col = 0;
+
+int main()
+{
+       uint8_t clock_high = 0;
+       uint8_t bits = 0;
+       uint8_t n_bits = 8;
+       uint8_t offset = 0;
+       uint8_t i;
+
+       DDRD = 0x06;   // 00000110
+       PORTD = 0xC0;  // 11000000
+       DDRB = 0x20;   // 00100000
+       PORTB = 0x1F;  // 00011111
+
+       serial_init(9600);
+       lcd_init();
+
+       sei();
+
+       while(1)
+       {
+               uint8_t b_pins, d_pins;
+
+               b_pins = PINB;
+               d_pins = PIND;
+
+               if(d_pins&BIT(CLOCK))
+               {
+                       if(!clock_high)
+                       {
+                               if(d_pins&BIT(LOAD))
+                               {
+                                       offset = 0;
+                                       bits = latch[0];
+                                       n_bits = 8;
+                               }
+                               else
+                               {
+                                       bits >>= 1;
+                                       if(!--n_bits)
+                                       {
+                                               ++offset;
+                                               bits = latch[offset];
+                                               n_bits = 8;
+                                       }
+                               }
+
+                               if(bits&1)
+                                       PORTD |= BIT(DATA_OUT);
+                               else
+                                       PORTD &= ~BIT(DATA_OUT);
+
+                               clock_high = 1;
+                       }
+               }
+               else if(clock_high)
+                       clock_high = 0;
+
+               if(d_pins&BIT(RESET))
+               {
+                       uint8_t i;
+                       for(i=0; i<128; ++i)
+                               latch[i] = input[i];
+               }
+
+               if(b_pins&BIT(LCD_DISABLE))
+               {
+                       if(lcd_enabled)
+                       {
+                               lcd_enabled = 0;
+
+                               lcd_clear();
+                       }
+               }
+               else if(!lcd_enabled)
+               {
+                       lcd_enabled = 1;
+                       log_row = 0;
+                       log_col = 0;
+
+                       lcd_clear();
+                       for(i=0; i<20; ++i)
+                               lcd_write(hexdigit(input[9-i/2]>>(4-i%2*4)));
+                       lcd_gotoxy(0, 1);
+                       lcd_write(255);
+               }
+       }
+}
+
+void receive(uint8_t c)
+{
+       if(rx_fill==0xFF)
+       {
+               if(c==':')
+                       rx_fill = 0;
+       }
+       else if(c=='.')
+       {
+               if(rx_fill>=4)
+               {
+                       uint16_t offset;
+                       uint8_t nibbles;
+                       uint8_t i;
+
+                       offset = (decode_hex(rx_buf[0])<<8) | (decode_hex(rx_buf[1])<<4) | decode_hex(rx_buf[2]);
+                       nibbles = (offset&3);
+                       offset >>= 2;
+                       if(rx_fill>3+nibbles)
+                       {
+                               for(i=0; i<=nibbles; ++i)
+                               {
+                                       uint16_t j = offset+nibbles-i;
+                                       uint8_t shift = 4*(j&1);
+                                       uint8_t bits = decode_hex(rx_buf[3+i]);
+                                       input[j/2] = (input[j/2]&~(0xF<<shift)) | (bits<<shift);
+                                       latch[j/2] = input[j/2];
+                               }
+
+                               if(lcd_enabled)
+                               {
+                                       lcd_gotoxy(19-offset-nibbles, 0);
+                                       for(i=0; i<=nibbles; ++i)
+                                               lcd_write(rx_buf[3+i]);
+                               }
+                       }
+               }
+               rx_fill = 0xFF;
+       }
+       else
+       {
+               if(rx_fill<sizeof(rx_buf))
+                       rx_buf[rx_fill++] = c;
+               else
+                       rx_fill = 0xFF;
+       }
+
+       if(lcd_enabled)
+       {
+               lcd_gotoxy(log_col, 1+log_row);
+               lcd_write(c);
+               ++log_col;
+               if(log_col>=20)
+               {
+                       log_col = 0;
+                       ++log_row;
+                       if(log_row>=3)
+                               log_row = 0;
+                       lcd_gotoxy(log_col, 1+log_row);
+               }
+               lcd_write(255);
+       }
+}
+
+SERIAL_SET_CALLBACK(receive)
+
+uint8_t hexdigit(uint8_t n)
+{
+       n &= 0xF;
+       if(n<10)
+               return '0'+n;
+       else
+               return 'A'+(n-0xA);
+}
+
+uint8_t decode_hex(uint8_t c)
+{
+       if(c>='0' && c<='9')
+               return c-'0';
+       else if(c>='A' && c<='F')
+               return 0xA+(c-'A');
+       else
+               return 0;
+}
diff --git a/s88w/s88w-t.c b/s88w/s88w-t.c
new file mode 100644 (file)
index 0000000..692eac5
--- /dev/null
@@ -0,0 +1,177 @@
+/*
+Firmware for wireless S88 transmitter module
+
+ATMega pinout:
+D0 - serial RX
+D1 - serial TX
+D2 - input 1
+D3 - input 2
+D4 - input 3
+D5 - input 4
+D6 - input 5
+D7 - input 6
+B0 - input 7
+B1 - input 8
+B2 - input 9
+B3 - input 10
+B4 - input 11
+B5 - input 12
+
+Inputs are pulled high by internal pull-up resistors.  Connect to GND to
+activate.
+
+The module can be configured by sending a string of form ":Shhh." over the
+serial port, where hhh is a hex number.  Lower two bits indicate the number of
+inputs (00=4, 01=8, 10=12, 11=16) and upper ten bits indicate offset of lowest
+input in multiples of 4 bits.  At the moment there are no provisions for
+having 16 physical inputs.
+
+Example: ":S016." would configure the module to have 12 inputs at offset 20.
+*/
+
+#include <avr/io.h>
+#include <avr/interrupt.h>
+#include "eeprom.h"
+#include "serial.h"
+#include "timer.h"
+
+#define BIT(n) (1<<(n))
+
+void receive(uint8_t);
+void send_state(void);
+uint8_t hexdigit(uint8_t);
+uint8_t decode_hex(uint8_t);
+
+uint8_t rx_buf[4];
+uint8_t rx_fill = 0xFF;
+volatile uint8_t nibbles = 2;
+volatile uint8_t offset = 0;
+volatile uint16_t state = 0;
+volatile uint8_t time_since_send = 0;
+
+int main()
+{
+       if(eeprom_read(0)==0xA5)
+       {
+               offset = eeprom_read(1)<<8;
+               offset |= eeprom_read(2);
+               nibbles = eeprom_read(3);
+       }
+
+       DDRD = 0x02;   // 00000010
+       PORTD = 0xFC;  // 11111100
+       DDRB = 0x00;   // 00000000
+       PORTB = 0x3F;  // 00111111
+
+       serial_init(9600);
+       timer_start_hz(1, 100, 1);
+
+       sei();
+
+       while(1)
+       {
+               uint8_t i, j;
+               uint16_t input = 0;
+               uint16_t valid = 0xFFF;
+
+               for(i=0; i<100; ++i)
+               {
+                       uint16_t pins = 0;
+                       for(j=0; j<100; ++j)
+                               pins |= ~((PIND>>2) | ((PINB&0x3F)<<6));
+
+                       if(i==0)
+                               input = pins;
+
+                       valid &= ~(pins^input);
+               }
+
+               input &= valid;
+               input |= state&~valid;
+               input &= (1<<(nibbles*4))-1;
+
+               if(input!=state && time_since_send>5)
+               {
+                       state = input;
+                       send_state();
+               }
+       }
+
+       return 0;
+}
+
+void receive(uint8_t c)
+{
+       if(rx_fill==0xFF)
+       {
+               if(c==':')
+                       rx_fill = 0;
+       }
+       else if(c=='.')
+       {
+               if(rx_buf[0]=='S' && rx_fill==4)
+               {
+                       offset = (decode_hex(rx_buf[1])<<8) | (decode_hex(rx_buf[2])<<4) | decode_hex(rx_buf[3]);
+                       nibbles = (offset&3)+1;
+                       offset &= 0xFFC;
+
+                       eeprom_write(0, 0xA5);
+                       eeprom_write(1, offset>>8);
+                       eeprom_write(2, offset);
+                       eeprom_write(3, nibbles);
+               }
+               rx_fill = 0xFF;
+       }
+       else
+       {
+               if(rx_fill<sizeof(rx_buf))
+                       rx_buf[rx_fill++] = c;
+               else
+                       rx_fill = 0xFF;
+       }
+}
+
+SERIAL_SET_CALLBACK(receive)
+
+void send_state(void)
+{
+       uint8_t i;
+
+       serial_write(':');
+       serial_write(hexdigit(offset>>8));
+       serial_write(hexdigit(offset>>4));
+       serial_write(hexdigit(offset|(nibbles-1)));
+       for(i=nibbles; i--;)
+               serial_write(hexdigit(state>>(i*4)));
+       serial_write('.');
+
+       time_since_send = 0;
+}
+
+void timer(void)
+{
+       ++time_since_send;
+       if(time_since_send>200)
+               send_state();
+}
+
+TIMER_SET_CALLBACK(1, timer)
+
+uint8_t hexdigit(uint8_t n)
+{
+       n &= 0xF;
+       if(n<10)
+               return '0'+n;
+       else
+               return 'A'+(n-0xA);
+}
+
+uint8_t decode_hex(uint8_t c)
+{
+       if(c>='0' && c<='9')
+               return c-'0';
+       else if(c>='A' && c<='F')
+               return 0xA+(c-'A');
+       else
+               return 0;
+}
diff --git a/s88w/s88w-t.svg b/s88w/s88w-t.svg
new file mode 100644 (file)
index 0000000..edd250b
--- /dev/null
@@ -0,0 +1,2365 @@
+<?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="744.09448"
+   height="524.40942"
+   id="svg2"
+   sodipodi:version="0.32"
+   inkscape:version="0.47 r22583"
+   version="1.0"
+   sodipodi:docname="s88w-t.svg"
+   inkscape:output_extension="org.inkscape.output.svg.inkscape"
+   inkscape:export-filename="/home/tdb/prog/r2c2/firmware/s88w-t.png"
+   inkscape:export-xdpi="254.05862"
+   inkscape:export-ydpi="254.05862">
+  <defs
+     id="defs4">
+    <marker
+       style="overflow:visible"
+       inkscape:stockid="InfiniteLineEnd"
+       id="InfiniteLineEnd"
+       refX="0"
+       refY="0"
+       orient="auto">
+      <g
+         id="g3456">
+        <circle
+           id="circle3458"
+           r="0.80000001"
+           cy="0"
+           cx="3"
+           sodipodi:cx="3"
+           sodipodi:cy="0"
+           sodipodi:rx="0.80000001"
+           sodipodi:ry="0.80000001" />
+        <circle
+           id="circle3460"
+           r="0.80000001"
+           cy="0"
+           cx="6.5"
+           sodipodi:cx="6.5"
+           sodipodi:cy="0"
+           sodipodi:rx="0.80000001"
+           sodipodi:ry="0.80000001" />
+        <circle
+           id="circle3462"
+           r="0.80000001"
+           cy="0"
+           cx="10"
+           sodipodi:cx="10"
+           sodipodi:cy="0"
+           sodipodi:rx="0.80000001"
+           sodipodi:ry="0.80000001" />
+      </g>
+    </marker>
+    <marker
+       inkscape:stockid="DotS"
+       orient="auto"
+       refY="0"
+       refX="0"
+       id="DotS"
+       style="overflow:visible">
+      <path
+         id="path3288"
+         d="M -2.5,-1 C -2.5,1.76 -4.74,4 -7.5,4 C -10.26,4 -12.5,1.76 -12.5,-1 C -12.5,-3.76 -10.26,-6 -7.5,-6 C -4.74,-6 -2.5,-3.76 -2.5,-1 z"
+         style="fill-rule:evenodd;stroke:#000000;stroke-width:1pt;marker-start:none;marker-end:none"
+         transform="matrix(0.2,0,0,0.2,1.48,0.2)" />
+    </marker>
+    <marker
+       inkscape:stockid="DotM"
+       orient="auto"
+       refY="0"
+       refX="0"
+       id="DotM"
+       style="overflow:visible">
+      <path
+         id="path3285"
+         d="M -2.5,-1 C -2.5,1.76 -4.74,4 -7.5,4 C -10.26,4 -12.5,1.76 -12.5,-1 C -12.5,-3.76 -10.26,-6 -7.5,-6 C -4.74,-6 -2.5,-3.76 -2.5,-1 z"
+         style="fill-rule:evenodd;stroke:#000000;stroke-width:1pt;marker-start:none;marker-end:none"
+         transform="matrix(0.4,0,0,0.4,2.96,0.4)" />
+    </marker>
+    <marker
+       inkscape:stockid="Arrow1Send"
+       orient="auto"
+       refY="0"
+       refX="0"
+       id="Arrow1Send"
+       style="overflow:visible">
+      <path
+         id="path3235"
+         d="M 0,0 L 5,-5 L -12.5,0 L 5,5 L 0,0 z"
+         style="fill-rule:evenodd;stroke:#000000;stroke-width:1pt;marker-start:none"
+         transform="matrix(-0.2,0,0,-0.2,-1.2,0)" />
+    </marker>
+    <inkscape:perspective
+       sodipodi:type="inkscape:persp3d"
+       inkscape:vp_x="0 : 526.18109 : 1"
+       inkscape:vp_y="0 : 1000 : 0"
+       inkscape:vp_z="744.09448 : 526.18109 : 1"
+       inkscape:persp3d-origin="372.04724 : 350.78739 : 1"
+       id="perspective10" />
+  </defs>
+  <sodipodi:namedview
+     id="base"
+     pagecolor="#ffffff"
+     bordercolor="#666666"
+     borderopacity="1.0"
+     gridtolerance="10000"
+     guidetolerance="10"
+     objecttolerance="10"
+     inkscape:pageopacity="0.0"
+     inkscape:pageshadow="2"
+     inkscape:zoom="2.0926789"
+     inkscape:cx="370.20287"
+     inkscape:cy="272.41936"
+     inkscape:document-units="mm"
+     inkscape:current-layer="layer1"
+     showgrid="true"
+     units="mm"
+     inkscape:window-width="1880"
+     inkscape:window-height="1142"
+     inkscape:window-x="1600"
+     inkscape:window-y="0"
+     inkscape:window-maximized="1">
+    <inkscape:grid
+       type="xygrid"
+       id="grid2383"
+       visible="true"
+       enabled="true"
+       units="mm"
+       spacingx="1mm"
+       spacingy="1mm"
+       dotted="false" />
+    <inkscape:grid
+       type="xygrid"
+       id="grid3205"
+       visible="true"
+       enabled="true"
+       units="mm"
+       spacingx="0.5mm"
+       spacingy="0.5mm"
+       dotted="true"
+       color="#00ff00"
+       opacity="0.1254902"
+       empspacing="10"
+       empcolor="#00ff00"
+       empopacity="0.25098039" />
+  </sodipodi:namedview>
+  <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:label="Layer 1"
+     inkscape:groupmode="layer"
+     id="layer1">
+    <rect
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866142;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       id="rect2385"
+       width="14.173293"
+       height="141.69885"
+       x="106.22831"
+       y="191.22704" />
+    <text
+       xml:space="preserve"
+       style="font-size:10px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
+       x="109.84251"
+       y="187.79518"
+       id="text3157"
+       sodipodi:linespacing="125%"><tspan
+         sodipodi:role="line"
+         id="tspan3159"
+         x="109.84251"
+         y="187.79518">J1</tspan></text>
+    <path
+       sodipodi:type="arc"
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       id="path3161"
+       sodipodi:cx="148.81889"
+       sodipodi:cy="651.96851"
+       sodipodi:rx="3.5433071"
+       sodipodi:ry="3.5433071"
+       d="M 152.3622,651.96851 A 3.5433071,3.5433071 0 1 1 145.27559,651.96851 A 3.5433071,3.5433071 0 1 1 152.3622,651.96851 z"
+       transform="translate(-35.433069,-453.5434)" />
+    <path
+       d="M 152.3622,651.96851 A 3.5433071,3.5433071 0 1 1 145.27559,651.96851 A 3.5433071,3.5433071 0 1 1 152.3622,651.96851 z"
+       sodipodi:ry="3.5433071"
+       sodipodi:rx="3.5433071"
+       sodipodi:cy="651.96851"
+       sodipodi:cx="148.81889"
+       id="path3163"
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       sodipodi:type="arc"
+       transform="translate(-35.433083,-411.02371)" />
+    <path
+       transform="translate(-35.433069,-439.37017)"
+       sodipodi:type="arc"
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       id="path3165"
+       sodipodi:cx="148.81889"
+       sodipodi:cy="651.96851"
+       sodipodi:rx="3.5433071"
+       sodipodi:ry="3.5433071"
+       d="M 152.3622,651.96851 A 3.5433071,3.5433071 0 1 1 145.27559,651.96851 A 3.5433071,3.5433071 0 1 1 152.3622,651.96851 z" />
+    <path
+       d="M 152.3622,651.96851 A 3.5433071,3.5433071 0 1 1 145.27559,651.96851 A 3.5433071,3.5433071 0 1 1 152.3622,651.96851 z"
+       sodipodi:ry="3.5433071"
+       sodipodi:rx="3.5433071"
+       sodipodi:cy="651.96851"
+       sodipodi:cx="148.81889"
+       id="path3167"
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       sodipodi:type="arc"
+       transform="translate(-35.433069,-425.19694)" />
+    <path
+       d="M 152.3622,651.96851 A 3.5433071,3.5433071 0 1 1 145.27559,651.96851 A 3.5433071,3.5433071 0 1 1 152.3622,651.96851 z"
+       sodipodi:ry="3.5433071"
+       sodipodi:rx="3.5433071"
+       sodipodi:cy="651.96851"
+       sodipodi:cx="148.81889"
+       id="path3169"
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       sodipodi:type="arc"
+       transform="translate(-35.433069,-396.85048)" />
+    <path
+       transform="translate(-35.433083,-368.50403)"
+       sodipodi:type="arc"
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       id="path3171"
+       sodipodi:cx="148.81889"
+       sodipodi:cy="651.96851"
+       sodipodi:rx="3.5433071"
+       sodipodi:ry="3.5433071"
+       d="M 152.3622,651.96851 A 3.5433071,3.5433071 0 1 1 145.27559,651.96851 A 3.5433071,3.5433071 0 1 1 152.3622,651.96851 z" />
+    <path
+       d="M 152.3622,651.96851 A 3.5433071,3.5433071 0 1 1 145.27559,651.96851 A 3.5433071,3.5433071 0 1 1 152.3622,651.96851 z"
+       sodipodi:ry="3.5433071"
+       sodipodi:rx="3.5433071"
+       sodipodi:cy="651.96851"
+       sodipodi:cx="148.81889"
+       id="path3173"
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       sodipodi:type="arc"
+       transform="translate(-35.433069,-382.67726)" />
+    <path
+       transform="translate(-35.433069,-354.3308)"
+       sodipodi:type="arc"
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       id="path3175"
+       sodipodi:cx="148.81889"
+       sodipodi:cy="651.96851"
+       sodipodi:rx="3.5433071"
+       sodipodi:ry="3.5433071"
+       d="M 152.3622,651.96851 A 3.5433071,3.5433071 0 1 1 145.27559,651.96851 A 3.5433071,3.5433071 0 1 1 152.3622,651.96851 z" />
+    <path
+       transform="translate(-35.433069,-340.15757)"
+       sodipodi:type="arc"
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       id="path3177"
+       sodipodi:cx="148.81889"
+       sodipodi:cy="651.96851"
+       sodipodi:rx="3.5433071"
+       sodipodi:ry="3.5433071"
+       d="M 152.3622,651.96851 A 3.5433071,3.5433071 0 1 1 145.27559,651.96851 A 3.5433071,3.5433071 0 1 1 152.3622,651.96851 z" />
+    <path
+       d="M 152.3622,651.96851 A 3.5433071,3.5433071 0 1 1 145.27559,651.96851 A 3.5433071,3.5433071 0 1 1 152.3622,651.96851 z"
+       sodipodi:ry="3.5433071"
+       sodipodi:rx="3.5433071"
+       sodipodi:cy="651.96851"
+       sodipodi:cx="148.81889"
+       id="path3179"
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       sodipodi:type="arc"
+       transform="translate(-35.433083,-325.98434)" />
+    <path
+       style="fill:none;fill-rule:evenodd;stroke:#000000;stroke-width:0.70866144;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 116.92914,198.4251 L 141.73229,198.4251"
+       id="path3185" />
+    <path
+       style="fill:none;fill-rule:evenodd;stroke:#000000;stroke-width:0.70866144;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 141.7323,198.42512 L 143.50396,194.88179 L 147.04727,201.96841 L 150.59057,194.88179 L 154.13388,201.96841 L 157.67719,194.88179 L 161.22049,201.96841 L 162.99214,198.42512"
+       id="path3187"
+       sodipodi:nodetypes="cccccccc" />
+    <text
+       xml:space="preserve"
+       style="font-size:10px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
+       x="138.18898"
+       y="191.33849"
+       id="text3189"
+       sodipodi:linespacing="125%"><tspan
+         sodipodi:role="line"
+         x="138.18898"
+         y="191.33849"
+         id="tspan3193">3.3kΩ</tspan></text>
+    <rect
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866142;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       id="rect3197"
+       width="35.34045"
+       height="113.5481"
+       x="237.40158"
+       y="184.25194" />
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 237.40148,219.70325 L 248.0314,219.70325 L 248.0314,233.87648 L 237.40148,233.87648"
+       id="path3207" />
+    <path
+       style="fill:#000000;fill-opacity:1;stroke:none;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 244.48809,223.24656 L 251.5747,223.24656 L 248.0314,230.33317 L 244.48809,223.24656 z"
+       id="path3209" />
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 244.48809,230.33317 L 251.5747,230.33317"
+       id="path3211" />
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;marker-end:url(#Arrow1Send);stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 253.34636,225.01821 L 256.88967,226.78986"
+       id="path3213" />
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;marker-end:url(#Arrow1Send);stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 251.5747,228.56152 L 255.11801,230.33317"
+       id="path3215" />
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 272.83456,219.70323 L 263.97632,219.70321 L 263.97632,221.47487 L 260.433,225.01819"
+       id="path4510"
+       sodipodi:nodetypes="cccc" />
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 260.43299,228.5615 L 263.97632,232.10479 L 263.97632,233.87644 L 272.83456,233.87646"
+       id="path4512"
+       sodipodi:nodetypes="cccc" />
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 260.43299,221.47489 L 260.43299,232.10481"
+       id="path4514" />
+    <path
+       style="fill:#000000;fill-opacity:1;stroke:none;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 260.43302,230.33313 L 262.20468,228.56148 L 263.97633,232.10479 L 260.43302,230.33313 z"
+       id="path4516" />
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 166.53543,325.98416 L 166.53543,347.24401"
+       id="path4520"
+       sodipodi:nodetypes="cc" />
+    <path
+       id="path4524"
+       d="M 162.99213,333.07078 L 170.07874,333.07078 L 166.53544,340.15739 L 162.99213,333.07078 z"
+       style="fill:#000000;fill-opacity:1;stroke:none;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
+    <path
+       id="path4526"
+       d="M 162.99213,340.15739 L 170.07874,340.15739"
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
+    <path
+       sodipodi:nodetypes="cc"
+       id="path4528"
+       d="M 187.79527,325.98416 L 187.79527,347.24401"
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
+    <path
+       style="fill:#000000;fill-opacity:1;stroke:none;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 184.25197,333.07078 L 191.33858,333.07078 L 187.79528,340.15739 L 184.25197,333.07078 z"
+       id="path4530" />
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 184.25196,340.15739 L 191.33857,340.15739"
+       id="path4532" />
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 166.53543,325.98416 L 187.79528,325.98416"
+       id="path4534"
+       sodipodi:nodetypes="cc" />
+    <path
+       id="path4536"
+       d="M 173.62205,329.52747 L 173.62205,322.44086 L 180.70866,325.98416 L 173.62205,329.52747 z"
+       style="fill:#000000;fill-opacity:1;stroke:none;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
+    <path
+       id="path4538"
+       d="M 180.70866,329.52747 L 180.70866,322.44086"
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
+    <path
+       sodipodi:nodetypes="cc"
+       id="path4540"
+       d="M 166.53543,347.24401 L 187.79528,347.24401"
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
+    <path
+       style="fill:#000000;fill-opacity:1;stroke:none;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 173.62205,350.78732 L 173.62205,343.70071 L 180.70866,347.24401 L 173.62205,350.78732 z"
+       id="path4542" />
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 180.70866,350.78732 L 180.70866,343.70071"
+       id="path4544" />
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;marker-end:url(#DotS);stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 116.92914,325.98416 L 141.73229,325.98416 L 141.73229,347.24401 L 166.53544,347.24401"
+       id="path4546"
+       sodipodi:nodetypes="cccc" />
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;marker-end:url(#DotS);stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 116.92914,311.81094 L 187.79528,311.81094 L 187.79528,325.98416"
+       id="path5600"
+       sodipodi:nodetypes="ccc" />
+    <rect
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866142;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       id="rect6691"
+       width="53.287567"
+       height="60.217022"
+       x="258.66144"
+       y="340.17661" />
+    <text
+       xml:space="preserve"
+       style="font-size:10px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
+       x="265.74808"
+       y="409.25186"
+       id="text6697"
+       sodipodi:linespacing="125%"><tspan
+         sodipodi:role="line"
+         id="tspan6699"
+         x="265.74808"
+         y="409.25186">LM2574</tspan></text>
+    <text
+       xml:space="preserve"
+       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
+       x="262.20474"
+       y="350.78732"
+       id="text6701"
+       sodipodi:linespacing="125%"><tspan
+         sodipodi:role="line"
+         id="tspan6703"
+         x="262.20474"
+         y="350.78732">VIN</tspan></text>
+    <text
+       xml:space="preserve"
+       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
+       x="262.20477"
+       y="364.9606"
+       id="text6705"
+       sodipodi:linespacing="125%"><tspan
+         sodipodi:role="line"
+         id="tspan6707"
+         x="262.20477"
+         y="364.9606">GND</tspan></text>
+    <text
+       xml:space="preserve"
+       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
+       x="262.20477"
+       y="379.13376"
+       id="text6709"
+       sodipodi:linespacing="125%"><tspan
+         sodipodi:role="line"
+         id="tspan6711"
+         x="262.20477"
+         y="379.13376">OFF</tspan></text>
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;marker-start:url(#DotS);stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 187.79528,347.24401 L 258.66142,347.24401"
+       id="path7799"
+       sodipodi:nodetypes="cc" />
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;marker-start:url(#DotS);marker-end:none;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 166.53544,325.98416 L 155.90552,325.98416 L 155.90552,400.39361"
+       id="path8343"
+       sodipodi:nodetypes="ccc" />
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 150.59056,400.39361 L 161.22048,400.39361"
+       id="path8345"
+       sodipodi:nodetypes="cc" />
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 152.36221,403.93691 L 159.44882,403.93691"
+       id="path8347"
+       sodipodi:nodetypes="cc" />
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 154.13386,407.48022 C 155.90551,407.48022 157.67717,407.48022 157.67717,407.48022"
+       id="path8349"
+       sodipodi:nodetypes="cc" />
+    <text
+       xml:space="preserve"
+       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
+       x="287.00787"
+       y="350.78738"
+       id="text9095"
+       sodipodi:linespacing="125%"><tspan
+         sodipodi:role="line"
+         id="tspan9097"
+         x="287.00787"
+         y="350.78738">VOUT</tspan></text>
+    <text
+       xml:space="preserve"
+       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
+       x="299.40945"
+       y="379.13382"
+       id="text9099"
+       sodipodi:linespacing="125%"><tspan
+         sodipodi:role="line"
+         id="tspan9101"
+         x="299.40945"
+         y="379.13382">FB</tspan></text>
+    <text
+       xml:space="preserve"
+       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
+       x="251.57478"
+       y="345.47238"
+       id="text9103"
+       sodipodi:linespacing="125%"><tspan
+         sodipodi:role="line"
+         id="tspan9105"
+         x="251.57478"
+         y="345.47238">5</tspan></text>
+    <text
+       xml:space="preserve"
+       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
+       x="251.57481"
+       y="359.6456"
+       id="text9107"
+       sodipodi:linespacing="125%"><tspan
+         sodipodi:role="line"
+         id="tspan9109"
+         x="251.57481"
+         y="359.6456">4</tspan></text>
+    <text
+       xml:space="preserve"
+       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
+       x="315.35434"
+       y="345.47241"
+       id="text9111"
+       sodipodi:linespacing="125%"><tspan
+         sodipodi:role="line"
+         id="tspan9113"
+         x="315.35434"
+         y="345.47241">1</tspan></text>
+    <text
+       xml:space="preserve"
+       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
+       x="315.35434"
+       y="373.81888"
+       id="text9115"
+       sodipodi:linespacing="125%"><tspan
+         sodipodi:role="line"
+         id="tspan9117"
+         x="315.35434"
+         y="373.81888">7</tspan></text>
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;marker-end:url(#DotS);stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 258.66142,361.41724 L 240.94488,361.41724 L 240.94489,389.76369"
+       id="path9119"
+       sodipodi:nodetypes="ccc" />
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;marker-end:url(#DotS);stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 258.66144,375.59048 L 240.9449,375.59048"
+       id="path9127" />
+    <text
+       xml:space="preserve"
+       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
+       x="262.20477"
+       y="393.30698"
+       id="text9671"
+       sodipodi:linespacing="125%"><tspan
+         sodipodi:role="line"
+         id="tspan9673"
+         x="262.20477"
+         y="393.30698">SIG GND</tspan></text>
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;marker-end:url(#DotS);stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 258.66144,389.7637 L 155.90552,389.76369"
+       id="path9675"
+       sodipodi:nodetypes="cc" />
+    <path
+       id="path10761"
+       d="M 237.4015,248.04969 L 248.03142,248.04969 L 248.03142,262.22292 L 237.4015,262.22292"
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
+    <path
+       id="path10763"
+       d="M 244.48811,251.593 L 251.57472,251.593 L 248.03142,258.67961 L 244.48811,251.593 z"
+       style="fill:#000000;fill-opacity:1;stroke:none;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
+    <path
+       id="path10765"
+       d="M 244.48811,258.67961 L 251.57472,258.67961"
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
+    <path
+       id="path10767"
+       d="M 253.34638,253.36465 L 256.88969,255.1363"
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;marker-end:url(#Arrow1Send);stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
+    <path
+       id="path10769"
+       d="M 251.57472,256.90796 L 255.11803,258.67961"
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;marker-end:url(#Arrow1Send);stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
+    <path
+       sodipodi:nodetypes="cccc"
+       id="path10771"
+       d="M 272.83458,248.04967 L 263.97634,248.04965 L 263.97634,249.82131 L 260.43302,253.36463"
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
+    <path
+       sodipodi:nodetypes="cccc"
+       id="path10773"
+       d="M 260.43301,256.90794 L 263.97634,260.45123 L 263.97634,262.22288 L 272.83458,262.2229"
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
+    <path
+       id="path10775"
+       d="M 260.43301,249.82133 L 260.43301,260.45125"
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
+    <path
+       id="path10777"
+       d="M 260.43304,258.67957 L 262.2047,256.90792 L 263.97635,260.45123 L 260.43304,258.67957 z"
+       style="fill:#000000;fill-opacity:1;stroke:none;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 237.40145,276.39619 L 248.03137,276.39619 L 248.03137,290.56942 L 237.40145,290.56942"
+       id="path10779" />
+    <path
+       style="fill:#000000;fill-opacity:1;stroke:none;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 244.48806,279.9395 L 251.57467,279.9395 L 248.03137,287.02611 L 244.48806,279.9395 z"
+       id="path10781" />
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 244.48806,287.02611 L 251.57467,287.02611"
+       id="path10783" />
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;marker-end:url(#Arrow1Send);stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 253.34633,281.71115 L 256.88964,283.4828"
+       id="path10785" />
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;marker-end:url(#Arrow1Send);stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 251.57467,285.25446 L 255.11798,287.02611"
+       id="path10787" />
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 272.83453,276.39617 L 263.97629,276.39615 L 263.97629,278.16781 L 260.43297,281.71113"
+       id="path10789"
+       sodipodi:nodetypes="cccc" />
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 260.43296,285.25444 L 263.97629,288.79773 L 263.97629,290.56938 L 272.83453,290.5694"
+       id="path10791"
+       sodipodi:nodetypes="cccc" />
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 260.43296,278.16783 L 260.43296,288.79775"
+       id="path10793" />
+    <path
+       style="fill:#000000;fill-opacity:1;stroke:none;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 260.43299,287.02607 L 262.20465,285.25442 L 263.9763,288.79773 L 260.43299,287.02607 z"
+       id="path10795" />
+    <path
+       id="path10797"
+       d="M 237.40144,191.35681 L 248.03136,191.35681 L 248.03136,205.53004 L 237.40144,205.53004"
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
+    <path
+       id="path10799"
+       d="M 244.48805,194.90012 L 251.57466,194.90012 L 248.03136,201.98673 L 244.48805,194.90012 z"
+       style="fill:#000000;fill-opacity:1;stroke:none;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
+    <path
+       id="path10801"
+       d="M 244.48805,201.98673 L 251.57466,201.98673"
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
+    <path
+       id="path10803"
+       d="M 253.34632,196.67177 L 256.88963,198.44342"
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;marker-end:url(#Arrow1Send);stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
+    <path
+       id="path10805"
+       d="M 251.57466,200.21508 L 255.11797,201.98673"
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;marker-end:url(#Arrow1Send);stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
+    <path
+       sodipodi:nodetypes="cccc"
+       id="path10807"
+       d="M 272.83452,191.35679 L 263.97628,191.35677 L 263.97628,193.12843 L 260.43296,196.67175"
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
+    <path
+       sodipodi:nodetypes="cccc"
+       id="path10809"
+       d="M 260.43295,200.21506 L 263.97628,203.75835 L 263.97628,205.53 L 272.83452,205.53002"
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
+    <path
+       id="path10811"
+       d="M 260.43295,193.12845 L 260.43295,203.75837"
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
+    <path
+       id="path10813"
+       d="M 260.43298,201.98669 L 262.20464,200.21504 L 263.97629,203.75835 L 260.43298,201.98669 z"
+       style="fill:#000000;fill-opacity:1;stroke:none;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
+    <rect
+       y="63.779503"
+       x="237.40158"
+       height="113.5481"
+       width="35.34045"
+       id="rect10815"
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866142;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
+    <path
+       id="path10817"
+       d="M 237.40155,99.212589 L 248.03147,99.212589 L 248.03147,113.38582 L 237.40155,113.38582"
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
+    <path
+       id="path10819"
+       d="M 244.48816,102.7559 L 251.57477,102.7559 L 248.03147,109.84251 L 244.48816,102.7559 z"
+       style="fill:#000000;fill-opacity:1;stroke:none;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
+    <path
+       id="path10821"
+       d="M 244.48816,109.84251 L 251.57477,109.84251"
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
+    <path
+       id="path10823"
+       d="M 253.34643,104.52755 L 256.88974,106.2992"
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;marker-end:url(#Arrow1Send);stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
+    <path
+       id="path10825"
+       d="M 251.57477,108.07086 L 255.11808,109.84251"
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;marker-end:url(#Arrow1Send);stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
+    <path
+       sodipodi:nodetypes="cccc"
+       id="path10827"
+       d="M 272.83463,99.212569 L 263.97639,99.212549 L 263.97639,100.98421 L 260.43307,104.52753"
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
+    <path
+       sodipodi:nodetypes="cccc"
+       id="path10829"
+       d="M 260.43306,108.07084 L 263.97639,111.61413 L 263.97639,113.38578 L 272.83463,113.3858"
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
+    <path
+       id="path10831"
+       d="M 260.43306,100.98423 L 260.43306,111.61415"
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
+    <path
+       id="path10833"
+       d="M 260.43309,109.84247 L 262.20475,108.07082 L 263.9764,111.61413 L 260.43309,109.84247 z"
+       style="fill:#000000;fill-opacity:1;stroke:none;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 237.40157,127.55905 L 248.03149,127.55905 L 248.03149,141.73228 L 237.40157,141.73228"
+       id="path10835" />
+    <path
+       style="fill:#000000;fill-opacity:1;stroke:none;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 244.48818,131.10236 L 251.57479,131.10236 L 248.03149,138.18897 L 244.48818,131.10236 z"
+       id="path10837" />
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 244.48818,138.18897 L 251.57479,138.18897"
+       id="path10839" />
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;marker-end:url(#Arrow1Send);stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 253.34645,132.87401 L 256.88976,134.64566"
+       id="path10841" />
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;marker-end:url(#Arrow1Send);stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 251.57479,136.41732 L 255.1181,138.18897"
+       id="path10843" />
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 272.83465,127.55903 L 263.97641,127.55901 L 263.97641,129.33067 L 260.43309,132.87399"
+       id="path10845"
+       sodipodi:nodetypes="cccc" />
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 260.43308,136.4173 L 263.97641,139.96059 L 263.97641,141.73224 L 272.83465,141.73226"
+       id="path10847"
+       sodipodi:nodetypes="cccc" />
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 260.43308,129.33069 L 260.43308,139.96061"
+       id="path10849" />
+    <path
+       style="fill:#000000;fill-opacity:1;stroke:none;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 260.43311,138.18893 L 262.20477,136.41728 L 263.97642,139.96059 L 260.43311,138.18893 z"
+       id="path10851" />
+    <path
+       id="path10853"
+       d="M 237.40153,155.90552 L 248.03145,155.90552 L 248.03145,170.07875 L 237.40153,170.07875"
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
+    <path
+       id="path10855"
+       d="M 244.48814,159.44883 L 251.57475,159.44883 L 248.03145,166.53544 L 244.48814,159.44883 z"
+       style="fill:#000000;fill-opacity:1;stroke:none;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
+    <path
+       id="path10857"
+       d="M 244.48814,166.53544 L 251.57475,166.53544"
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
+    <path
+       id="path10859"
+       d="M 253.34641,161.22048 L 256.88972,162.99213"
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;marker-end:url(#Arrow1Send);stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
+    <path
+       id="path10861"
+       d="M 251.57475,164.76379 L 255.11806,166.53544"
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;marker-end:url(#Arrow1Send);stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
+    <path
+       sodipodi:nodetypes="cccc"
+       id="path10863"
+       d="M 272.83461,155.9055 L 263.97637,155.90548 L 263.97637,157.67714 L 260.43305,161.22046"
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
+    <path
+       sodipodi:nodetypes="cccc"
+       id="path10865"
+       d="M 260.43304,164.76377 L 263.97637,168.30706 L 263.97637,170.07871 L 272.83461,170.07873"
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
+    <path
+       id="path10867"
+       d="M 260.43304,157.67716 L 260.43304,168.30708"
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
+    <path
+       id="path10869"
+       d="M 260.43307,166.5354 L 262.20473,164.76375 L 263.97638,168.30706 L 260.43307,166.5354 z"
+       style="fill:#000000;fill-opacity:1;stroke:none;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 237.40153,70.866149 L 248.03145,70.866149 L 248.03145,85.039379 L 237.40153,85.039379"
+       id="path10871" />
+    <path
+       style="fill:#000000;fill-opacity:1;stroke:none;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 244.48814,74.409459 L 251.57475,74.409459 L 248.03145,81.496069 L 244.48814,74.409459 z"
+       id="path10873" />
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 244.48814,81.496069 L 251.57475,81.496069"
+       id="path10875" />
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;marker-end:url(#Arrow1Send);stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 253.34641,76.181109 L 256.88972,77.952759"
+       id="path10877" />
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;marker-end:url(#Arrow1Send);stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 251.57475,79.724419 L 255.11806,81.496069"
+       id="path10879" />
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 272.83461,70.866129 L 263.97637,70.866109 L 263.97637,72.637769 L 260.43305,76.181089"
+       id="path10881"
+       sodipodi:nodetypes="cccc" />
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 260.43304,79.724399 L 263.97637,83.267689 L 263.97637,85.039339 L 272.83461,85.039359"
+       id="path10883"
+       sodipodi:nodetypes="cccc" />
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 260.43304,72.637789 L 260.43304,83.267709"
+       id="path10885" />
+    <path
+       style="fill:#000000;fill-opacity:1;stroke:none;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 260.43307,81.496029 L 262.20473,79.724379 L 263.97638,83.267689 L 260.43307,81.496029 z"
+       id="path10887" />
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 162.99213,198.42511 L 177.16536,198.42511 L 177.16536,70.866049 L 237.40158,70.866049"
+       id="path10889"
+       sodipodi:nodetypes="cccc" />
+    <path
+       id="path10891"
+       d="M 116.92914,212.59834 L 141.73229,212.59834"
+       style="fill:none;fill-rule:evenodd;stroke:#000000;stroke-width:0.70866144;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
+    <path
+       sodipodi:nodetypes="cccccccc"
+       id="path10893"
+       d="M 141.7323,212.59836 L 143.50396,209.05503 L 147.04727,216.14165 L 150.59057,209.05503 L 154.13388,216.14165 L 157.67719,209.05503 L 161.22049,216.14165 L 162.99214,212.59836"
+       style="fill:none;fill-rule:evenodd;stroke:#000000;stroke-width:0.70866144;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
+    <path
+       style="fill:none;fill-rule:evenodd;stroke:#000000;stroke-width:0.70866144;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 116.92913,226.77157 L 141.73228,226.77157"
+       id="path10895" />
+    <path
+       style="fill:none;fill-rule:evenodd;stroke:#000000;stroke-width:0.70866144;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 141.73229,226.77159 L 143.50395,223.22826 L 147.04726,230.31488 L 150.59056,223.22826 L 154.13387,230.31488 L 157.67718,223.22826 L 161.22048,230.31488 L 162.99213,226.77159"
+       id="path10897"
+       sodipodi:nodetypes="cccccccc" />
+    <path
+       id="path10899"
+       d="M 116.92913,240.94477 L 141.73228,240.94477"
+       style="fill:none;fill-rule:evenodd;stroke:#000000;stroke-width:0.70866144;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
+    <path
+       sodipodi:nodetypes="cccccccc"
+       id="path10901"
+       d="M 141.73229,240.94479 L 143.50395,237.40146 L 147.04726,244.48808 L 150.59056,237.40146 L 154.13387,244.48808 L 157.67718,237.40146 L 161.22048,244.48808 L 162.99213,240.94479"
+       style="fill:none;fill-rule:evenodd;stroke:#000000;stroke-width:0.70866144;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
+    <path
+       style="fill:none;fill-rule:evenodd;stroke:#000000;stroke-width:0.70866144;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 116.92914,255.11802 L 141.73229,255.11802"
+       id="path10903" />
+    <path
+       style="fill:none;fill-rule:evenodd;stroke:#000000;stroke-width:0.70866144;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 141.7323,255.11804 L 143.50396,251.57471 L 147.04727,258.66133 L 150.59057,251.57471 L 154.13388,258.66133 L 157.67719,251.57471 L 161.22049,258.66133 L 162.99214,255.11804"
+       id="path10905"
+       sodipodi:nodetypes="cccccccc" />
+    <path
+       id="path10907"
+       d="M 116.92912,269.29125 L 141.73227,269.29125"
+       style="fill:none;fill-rule:evenodd;stroke:#000000;stroke-width:0.70866144;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
+    <path
+       sodipodi:nodetypes="cccccccc"
+       id="path10909"
+       d="M 141.73228,269.29127 L 143.50394,265.74794 L 147.04725,272.83456 L 150.59055,265.74794 L 154.13386,272.83456 L 157.67717,265.74794 L 161.22047,272.83456 L 162.99212,269.29127"
+       style="fill:none;fill-rule:evenodd;stroke:#000000;stroke-width:0.70866144;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
+    <path
+       style="fill:none;fill-rule:evenodd;stroke:#000000;stroke-width:0.70866144;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 116.92913,283.46446 L 141.73228,283.46446"
+       id="path10911" />
+    <path
+       style="fill:none;fill-rule:evenodd;stroke:#000000;stroke-width:0.70866144;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 141.73229,283.46448 L 143.50395,279.92115 L 147.04726,287.00777 L 150.59056,279.92115 L 154.13387,287.00777 L 157.67718,279.92115 L 161.22048,287.00777 L 162.99213,283.46448"
+       id="path10913"
+       sodipodi:nodetypes="cccccccc" />
+    <path
+       id="path10915"
+       d="M 116.92912,297.63771 L 141.73227,297.63771"
+       style="fill:none;fill-rule:evenodd;stroke:#000000;stroke-width:0.70866144;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
+    <path
+       sodipodi:nodetypes="cccccccc"
+       id="path10917"
+       d="M 141.73228,297.63773 L 143.50394,294.0944 L 147.04725,301.18102 L 150.59055,294.0944 L 154.13386,301.18102 L 157.67717,294.0944 L 161.22047,301.18102 L 162.99212,297.63773"
+       style="fill:none;fill-rule:evenodd;stroke:#000000;stroke-width:0.70866144;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 162.99213,212.59834 L 180.70867,212.59834 L 180.70867,99.212509 L 237.40158,99.212509"
+       id="path10919"
+       sodipodi:nodetypes="cccc" />
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 162.99213,226.77157 L 184.25197,226.77157 L 184.25197,127.55897 L 237.40158,127.55897"
+       id="path10921"
+       sodipodi:nodetypes="cccc" />
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 162.99213,240.94479 L 187.79528,240.94479 L 187.79528,155.90542 L 237.40158,155.90542"
+       id="path10923"
+       sodipodi:nodetypes="cccc" />
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 162.99213,255.11802 L 191.33859,255.11802 L 191.33859,191.3385 L 237.40158,191.3385"
+       id="path10925"
+       sodipodi:nodetypes="cccc" />
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 162.99213,269.29125 L 194.8819,269.29125 L 194.8819,219.68495 L 237.40158,219.68495"
+       id="path10927"
+       sodipodi:nodetypes="cccc" />
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 162.99213,283.46448 L 198.4252,283.46448 L 198.4252,248.03141 L 237.40158,248.03141"
+       id="path10929"
+       sodipodi:nodetypes="cccc" />
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 162.99213,297.63771 L 201.96851,297.63771 L 201.96851,276.37787 L 237.40158,276.37787"
+       id="path10931"
+       sodipodi:nodetypes="cccc" />
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 237.40158,85.039279 L 216.14174,85.039279 L 216.14174,297.63771"
+       id="path10933"
+       sodipodi:nodetypes="ccc" />
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 210.82678,297.63771 L 221.4567,297.63771"
+       id="path10935" />
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 212.59843,301.18102 L 219.68504,301.18102"
+       id="path10937" />
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 214.37008,304.72432 L 217.91339,304.72432"
+       id="path10939" />
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;marker-end:url(#DotS);stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 237.40158,113.3858 L 216.14174,113.38574"
+       id="path10941"
+       sodipodi:nodetypes="cc" />
+    <path
+       id="path11485"
+       d="M 237.40158,141.73226 L 216.14174,141.7322"
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;marker-end:url(#DotS);stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       sodipodi:nodetypes="cc" />
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;marker-end:url(#DotS);stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 237.40158,170.07871 L 216.14174,170.07865"
+       id="path11487"
+       sodipodi:nodetypes="cc" />
+    <path
+       id="path11489"
+       d="M 237.40158,205.51178 L 216.14174,205.51172"
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;marker-end:url(#DotS);stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       sodipodi:nodetypes="cc" />
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;marker-end:url(#DotS);stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 237.40158,233.85824 L 216.14174,233.85818"
+       id="path11491"
+       sodipodi:nodetypes="cc" />
+    <path
+       id="path11493"
+       d="M 237.40158,262.2047 L 216.14174,262.20464"
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;marker-end:url(#DotS);stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       sodipodi:nodetypes="cc" />
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;marker-end:url(#DotS);stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 237.40158,290.55115 L 216.14174,290.55109"
+       id="path11495"
+       sodipodi:nodetypes="cc" />
+    <path
+       id="path11497"
+       d="M 272.83465,85.039279 L 294.09449,85.039279 L 294.09449,297.63771"
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       sodipodi:nodetypes="ccc" />
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;marker-end:url(#DotS);stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 272.83465,113.3858 L 294.09449,113.38574"
+       id="path11499"
+       sodipodi:nodetypes="cc" />
+    <path
+       id="path12043"
+       d="M 272.83465,141.73226 L 294.09449,141.7322"
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;marker-end:url(#DotS);stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       sodipodi:nodetypes="cc" />
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;marker-end:url(#DotS);stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 272.83465,170.07871 L 294.09449,170.07865"
+       id="path12045"
+       sodipodi:nodetypes="cc" />
+    <path
+       id="path12047"
+       d="M 272.83465,205.51178 L 294.09449,205.51172"
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;marker-end:url(#DotS);stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       sodipodi:nodetypes="cc" />
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;marker-end:url(#DotS);stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 272.83465,233.85824 L 294.09449,233.85818"
+       id="path12049"
+       sodipodi:nodetypes="cc" />
+    <path
+       id="path12051"
+       d="M 272.83465,262.20469 L 294.09449,262.20464"
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;marker-end:url(#DotS);stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       sodipodi:nodetypes="cc" />
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;marker-end:url(#DotS);stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 272.83465,290.55115 L 294.09449,290.55109"
+       id="path12053"
+       sodipodi:nodetypes="cc" />
+    <path
+       id="path12055"
+       d="M 288.77954,297.63771 L 299.40946,297.63771"
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
+    <path
+       id="path12057"
+       d="M 290.55119,301.18102 L 297.6378,301.18102"
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
+    <path
+       id="path12059"
+       d="M 292.32284,304.72432 L 295.86615,304.72432"
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
+    <text
+       xml:space="preserve"
+       style="font-size:10px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
+       x="159.44882"
+       y="359.6456"
+       id="text12061"
+       sodipodi:linespacing="125%"><tspan
+         sodipodi:role="line"
+         id="tspan12063"
+         x="159.44882"
+         y="359.6456">FR206</tspan></text>
+    <text
+       xml:space="preserve"
+       style="font-size:10px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
+       x="237.40158"
+       y="308.26761"
+       id="text12065"
+       sodipodi:linespacing="125%"><tspan
+         sodipodi:role="line"
+         id="tspan12067"
+         x="237.40158"
+         y="308.26761">LTV847</tspan></text>
+    <rect
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866142;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       id="rect12069"
+       width="88.715057"
+       height="116.98304"
+       x="361.35117"
+       y="155.91777" />
+    <text
+       xml:space="preserve"
+       style="font-size:10px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
+       x="375.59058"
+       y="283.46451"
+       id="text12071"
+       sodipodi:linespacing="125%"><tspan
+         sodipodi:role="line"
+         id="tspan12073"
+         x="375.59058"
+         y="283.46451">Arduino Mini</tspan></text>
+    <rect
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866142;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       id="rect12075"
+       width="53.114006"
+       height="88.751289"
+       x="549.16486"
+       y="155.86205" />
+    <text
+       xml:space="preserve"
+       style="font-size:10px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
+       x="563.3858"
+       y="255.118"
+       id="text12077"
+       sodipodi:linespacing="125%"><tspan
+         sodipodi:role="line"
+         id="tspan12079"
+         x="563.3858"
+         y="255.118">XBee</tspan></text>
+    <text
+       xml:space="preserve"
+       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
+       x="364.96066"
+       y="166.53542"
+       id="text12081"
+       sodipodi:linespacing="125%"><tspan
+         sodipodi:role="line"
+         id="tspan12083"
+         x="364.96066"
+         y="166.53542">IO2 (PD2)</tspan></text>
+    <text
+       sodipodi:linespacing="125%"
+       id="text12085"
+       y="180.70863"
+       x="364.96066"
+       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
+       xml:space="preserve"><tspan
+         y="180.70863"
+         x="364.96066"
+         id="tspan12087"
+         sodipodi:role="line">IO3 (PD3)</tspan></text>
+    <text
+       xml:space="preserve"
+       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
+       x="364.96066"
+       y="194.88185"
+       id="text12089"
+       sodipodi:linespacing="125%"><tspan
+         sodipodi:role="line"
+         id="tspan12091"
+         x="364.96066"
+         y="194.88185">IO4 (PD4)</tspan></text>
+    <text
+       sodipodi:linespacing="125%"
+       id="text12093"
+       y="209.0551"
+       x="364.96066"
+       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
+       xml:space="preserve"><tspan
+         y="209.0551"
+         x="364.96066"
+         id="tspan12095"
+         sodipodi:role="line">IO5 (PD5)</tspan></text>
+    <text
+       xml:space="preserve"
+       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
+       x="364.96066"
+       y="223.22832"
+       id="text12097"
+       sodipodi:linespacing="125%"><tspan
+         sodipodi:role="line"
+         id="tspan12099"
+         x="364.96066"
+         y="223.22832">IO6 (PD6)</tspan></text>
+    <text
+       sodipodi:linespacing="125%"
+       id="text12101"
+       y="237.40157"
+       x="364.96066"
+       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
+       xml:space="preserve"><tspan
+         y="237.40157"
+         x="364.96066"
+         id="tspan12103"
+         sodipodi:role="line">IO7 (PD7)</tspan></text>
+    <text
+       xml:space="preserve"
+       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
+       x="364.96066"
+       y="251.57472"
+       id="text12105"
+       sodipodi:linespacing="125%"><tspan
+         sodipodi:role="line"
+         id="tspan12107"
+         x="364.96066"
+         y="251.57472">IO8 (PB0)</tspan></text>
+    <text
+       sodipodi:linespacing="125%"
+       id="text12109"
+       y="265.74796"
+       x="364.96066"
+       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
+       xml:space="preserve"><tspan
+         y="265.74796"
+         x="364.96066"
+         id="tspan12111"
+         sodipodi:role="line">IO9 (PB1)</tspan></text>
+    <text
+       xml:space="preserve"
+       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
+       x="411.02368"
+       y="180.7086"
+       id="text12113"
+       sodipodi:linespacing="125%"><tspan
+         sodipodi:role="line"
+         id="tspan12115"
+         x="411.02368"
+         y="180.7086">TX (PD0)</tspan></text>
+    <text
+       xml:space="preserve"
+       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
+       x="411.02365"
+       y="166.53542"
+       id="text12117"
+       sodipodi:linespacing="125%"><tspan
+         sodipodi:role="line"
+         id="tspan12119"
+         x="411.02365"
+         y="166.53542">RX (PD1)</tspan></text>
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 272.83465,276.37793 L 322.44095,276.37793 L 322.44095,262.2047 L 361.41732,262.2047"
+       id="path12121"
+       sodipodi:nodetypes="cccc" />
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 272.83465,248.03147 L 361.41732,248.03147"
+       id="path12123"
+       sodipodi:nodetypes="cc" />
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 272.83465,219.68501 L 322.44095,219.68501 L 322.44095,233.85824 L 361.41732,233.85824"
+       id="path12125"
+       sodipodi:nodetypes="cccc" />
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 361.41732,162.9921 L 340.15748,162.9921 L 340.15748,70.866109 L 272.83465,70.866109"
+       id="path12127"
+       sodipodi:nodetypes="cccc" />
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 361.41732,177.16533 L 336.61417,177.16533 L 336.61417,99.212569 L 272.83465,99.212569"
+       id="path12129"
+       sodipodi:nodetypes="cccc" />
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 361.41732,191.33856 L 333.07087,191.33856 L 333.07087,127.55903 L 272.83465,127.55903"
+       id="path12131"
+       sodipodi:nodetypes="cccc" />
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 361.41732,205.51178 L 329.52756,205.51178 L 329.52756,155.90548 L 272.83465,155.90548"
+       id="path12133"
+       sodipodi:nodetypes="cccc" />
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 361.41732,219.68501 L 325.98425,219.68501 L 325.98425,191.33856 L 272.83465,191.33856"
+       id="path12135"
+       sodipodi:nodetypes="cccc" />
+    <text
+       xml:space="preserve"
+       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
+       x="432.28348"
+       y="265.74796"
+       id="text12137"
+       sodipodi:linespacing="125%"><tspan
+         sodipodi:role="line"
+         id="tspan12139"
+         x="432.28348"
+         y="265.74796">Vcc</tspan></text>
+    <text
+       xml:space="preserve"
+       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
+       x="428.74017"
+       y="251.57472"
+       id="text12141"
+       sodipodi:linespacing="125%"><tspan
+         sodipodi:role="line"
+         id="tspan12143"
+         x="428.74017"
+         y="251.57472">GND</tspan></text>
+    <text
+       xml:space="preserve"
+       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
+       x="584.64563"
+       y="237.40147"
+       id="text12145"
+       sodipodi:linespacing="125%"><tspan
+         sodipodi:role="line"
+         id="tspan12147"
+         x="584.64563"
+         y="237.40147">Vcc</tspan></text>
+    <text
+       xml:space="preserve"
+       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
+       x="556.29919"
+       y="166.53539"
+       id="text12149"
+       sodipodi:linespacing="125%"><tspan
+         sodipodi:role="line"
+         id="tspan12151"
+         x="556.29919"
+         y="166.53539">DOUT</tspan></text>
+    <text
+       xml:space="preserve"
+       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
+       x="556.29919"
+       y="180.70854"
+       id="text12153"
+       sodipodi:linespacing="125%"><tspan
+         sodipodi:role="line"
+         id="tspan12155"
+         x="556.29919"
+         y="180.70854">DIN</tspan></text>
+    <text
+       xml:space="preserve"
+       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
+       x="556.29919"
+       y="237.40147"
+       id="text12157"
+       sodipodi:linespacing="125%"><tspan
+         sodipodi:role="line"
+         id="tspan12159"
+         x="556.29919"
+         y="237.40147">GND</tspan></text>
+    <text
+       xml:space="preserve"
+       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
+       x="582.87402"
+       y="209.05504"
+       id="text12161"
+       sodipodi:linespacing="125%"><tspan
+         sodipodi:role="line"
+         id="tspan12163"
+         x="582.87402"
+         y="209.05504">AD5</tspan></text>
+    <rect
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866142;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       id="rect12167"
+       width="53.164974"
+       height="35.41814"
+       x="513.82629"
+       y="333.11758" />
+    <text
+       xml:space="preserve"
+       style="font-size:10px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
+       x="520.86615"
+       y="329.5275"
+       id="text12169"
+       sodipodi:linespacing="125%"><tspan
+         sodipodi:role="line"
+         id="tspan12171"
+         x="520.86615"
+         y="329.5275">EZ1085</tspan></text>
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 379.13386,375.59053 L 485.43308,375.59046 L 485.43308,262.20464 L 450.00001,262.20464"
+       id="path12173"
+       sodipodi:nodetypes="cccc" />
+    <text
+       sodipodi:linespacing="125%"
+       id="text12175"
+       y="175.39366"
+       x="453.54337"
+       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
+       xml:space="preserve"><tspan
+         y="175.39366"
+         x="453.54337"
+         id="tspan12177"
+         sodipodi:role="line">1</tspan></text>
+    <text
+       sodipodi:linespacing="125%"
+       id="text12179"
+       y="189.56691"
+       x="354.33075"
+       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
+       xml:space="preserve"><tspan
+         y="189.56691"
+         x="354.33075"
+         id="tspan12181"
+         sodipodi:role="line">7</tspan></text>
+    <text
+       sodipodi:linespacing="125%"
+       id="text12183"
+       y="161.22044"
+       x="354.33075"
+       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
+       xml:space="preserve"><tspan
+         y="161.22044"
+         x="354.33075"
+         id="tspan12185"
+         sodipodi:role="line">5</tspan></text>
+    <text
+       xml:space="preserve"
+       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
+       x="354.33075"
+       y="175.39366"
+       id="text12187"
+       sodipodi:linespacing="125%"><tspan
+         sodipodi:role="line"
+         id="tspan12189"
+         x="354.33075"
+         y="175.39366">6</tspan></text>
+    <text
+       xml:space="preserve"
+       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
+       x="354.33075"
+       y="203.74013"
+       id="text12191"
+       sodipodi:linespacing="125%"><tspan
+         sodipodi:role="line"
+         id="tspan12193"
+         x="354.33075"
+         y="203.74013">8</tspan></text>
+    <text
+       xml:space="preserve"
+       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
+       x="354.33075"
+       y="217.91335"
+       id="text12195"
+       sodipodi:linespacing="125%"><tspan
+         sodipodi:role="line"
+         id="tspan12197"
+         x="354.33075"
+         y="217.91335">9</tspan></text>
+    <text
+       xml:space="preserve"
+       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
+       x="349.01578"
+       y="232.08659"
+       id="text12199"
+       sodipodi:linespacing="125%"><tspan
+         sodipodi:role="line"
+         id="tspan12201"
+         x="349.01578"
+         y="232.08659">10</tspan></text>
+    <text
+       xml:space="preserve"
+       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
+       x="349.01578"
+       y="246.25972"
+       id="text12203"
+       sodipodi:linespacing="125%"><tspan
+         sodipodi:role="line"
+         id="tspan12205"
+         x="349.01578"
+         y="246.25972">11</tspan></text>
+    <text
+       xml:space="preserve"
+       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
+       x="349.01578"
+       y="260.43301"
+       id="text12207"
+       sodipodi:linespacing="125%"><tspan
+         sodipodi:role="line"
+         id="tspan12209"
+         x="349.01578"
+         y="260.43301">12</tspan></text>
+    <text
+       xml:space="preserve"
+       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
+       x="453.54333"
+       y="161.22044"
+       id="text12211"
+       sodipodi:linespacing="125%"><tspan
+         sodipodi:role="line"
+         id="tspan12213"
+         x="453.54333"
+         y="161.22044">2</tspan></text>
+    <text
+       xml:space="preserve"
+       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
+       x="453.5433"
+       y="260.43301"
+       id="text12215"
+       sodipodi:linespacing="125%"><tspan
+         sodipodi:role="line"
+         id="tspan12217"
+         x="453.5433"
+         y="260.43301">21</tspan></text>
+    <text
+       xml:space="preserve"
+       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
+       x="453.5433"
+       y="246.25978"
+       id="text12219"
+       sodipodi:linespacing="125%"><tspan
+         sodipodi:role="line"
+         id="tspan12221"
+         x="453.5433"
+         y="246.25978">23</tspan></text>
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;marker-end:url(#DotS);stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 449.99998,248.03141 L 527.95276,248.03141"
+       id="path12223"
+       sodipodi:nodetypes="cc" />
+    <text
+       xml:space="preserve"
+       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
+       x="230.31496"
+       y="189.56691"
+       id="text12231"
+       sodipodi:linespacing="125%"><tspan
+         sodipodi:role="line"
+         id="tspan12233"
+         x="230.31496"
+         y="189.56691">1</tspan></text>
+    <text
+       sodipodi:linespacing="125%"
+       id="text12235"
+       y="203.74013"
+       x="230.31496"
+       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
+       xml:space="preserve"><tspan
+         y="203.74013"
+         x="230.31496"
+         id="tspan12237"
+         sodipodi:role="line">2</tspan></text>
+    <text
+       xml:space="preserve"
+       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
+       x="230.31496"
+       y="274.60623"
+       id="text12239"
+       sodipodi:linespacing="125%"><tspan
+         sodipodi:role="line"
+         id="tspan12241"
+         x="230.31496"
+         y="274.60623">7</tspan></text>
+    <text
+       xml:space="preserve"
+       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
+       x="230.31496"
+       y="246.25972"
+       id="text12243"
+       sodipodi:linespacing="125%"><tspan
+         sodipodi:role="line"
+         id="tspan12245"
+         x="230.31496"
+         y="246.25972">5</tspan></text>
+    <text
+       sodipodi:linespacing="125%"
+       id="text12247"
+       y="260.43295"
+       x="230.31496"
+       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
+       xml:space="preserve"><tspan
+         y="260.43295"
+         x="230.31496"
+         id="tspan12249"
+         sodipodi:role="line">6</tspan></text>
+    <text
+       sodipodi:linespacing="125%"
+       id="text12251"
+       y="288.77945"
+       x="230.31496"
+       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
+       xml:space="preserve"><tspan
+         y="288.77945"
+         x="230.31496"
+         id="tspan12253"
+         sodipodi:role="line">8</tspan></text>
+    <text
+       sodipodi:linespacing="125%"
+       id="text12255"
+       y="288.77945"
+       x="276.37799"
+       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
+       xml:space="preserve"><tspan
+         y="288.77945"
+         x="276.37799"
+         id="tspan12257"
+         sodipodi:role="line">9</tspan></text>
+    <text
+       sodipodi:linespacing="125%"
+       id="text12259"
+       y="274.60623"
+       x="276.37799"
+       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
+       xml:space="preserve"><tspan
+         y="274.60623"
+         x="276.37799"
+         id="tspan12261"
+         sodipodi:role="line">10</tspan></text>
+    <text
+       sodipodi:linespacing="125%"
+       id="text12263"
+       y="260.43301"
+       x="276.37799"
+       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
+       xml:space="preserve"><tspan
+         y="260.43301"
+         x="276.37799"
+         id="tspan12265"
+         sodipodi:role="line">11</tspan></text>
+    <text
+       sodipodi:linespacing="125%"
+       id="text12267"
+       y="246.25972"
+       x="276.37799"
+       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
+       xml:space="preserve"><tspan
+         y="246.25972"
+         x="276.37799"
+         id="tspan12269"
+         sodipodi:role="line">12</tspan></text>
+    <text
+       xml:space="preserve"
+       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
+       x="230.31496"
+       y="217.91335"
+       id="text12271"
+       sodipodi:linespacing="125%"><tspan
+         sodipodi:role="line"
+         id="tspan12273"
+         x="230.31496"
+         y="217.91335">3</tspan></text>
+    <text
+       xml:space="preserve"
+       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
+       x="230.31496"
+       y="232.08659"
+       id="text12275"
+       sodipodi:linespacing="125%"><tspan
+         sodipodi:role="line"
+         id="tspan12277"
+         x="230.31496"
+         y="232.08659">4</tspan></text>
+    <text
+       xml:space="preserve"
+       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
+       x="276.37799"
+       y="232.08659"
+       id="text12279"
+       sodipodi:linespacing="125%"><tspan
+         sodipodi:role="line"
+         id="tspan12281"
+         x="276.37799"
+         y="232.08659">13</tspan></text>
+    <text
+       xml:space="preserve"
+       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
+       x="276.37799"
+       y="217.91335"
+       id="text12283"
+       sodipodi:linespacing="125%"><tspan
+         sodipodi:role="line"
+         id="tspan12285"
+         x="276.37799"
+         y="217.91335">14</tspan></text>
+    <text
+       xml:space="preserve"
+       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
+       x="276.37799"
+       y="203.74013"
+       id="text12287"
+       sodipodi:linespacing="125%"><tspan
+         sodipodi:role="line"
+         id="tspan12289"
+         x="276.37799"
+         y="203.74013">15</tspan></text>
+    <text
+       xml:space="preserve"
+       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
+       x="276.37799"
+       y="189.56691"
+       id="text12291"
+       sodipodi:linespacing="125%"><tspan
+         sodipodi:role="line"
+         id="tspan12293"
+         x="276.37799"
+         y="189.56691">16</tspan></text>
+    <text
+       sodipodi:linespacing="125%"
+       id="text12295"
+       y="69.094444"
+       x="230.31496"
+       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
+       xml:space="preserve"><tspan
+         y="69.094444"
+         x="230.31496"
+         id="tspan12297"
+         sodipodi:role="line">1</tspan></text>
+    <text
+       xml:space="preserve"
+       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
+       x="230.31496"
+       y="83.267662"
+       id="text12299"
+       sodipodi:linespacing="125%"><tspan
+         sodipodi:role="line"
+         id="tspan12301"
+         x="230.31496"
+         y="83.267662">2</tspan></text>
+    <text
+       sodipodi:linespacing="125%"
+       id="text12303"
+       y="154.1338"
+       x="230.31496"
+       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
+       xml:space="preserve"><tspan
+         y="154.1338"
+         x="230.31496"
+         id="tspan12305"
+         sodipodi:role="line">7</tspan></text>
+    <text
+       sodipodi:linespacing="125%"
+       id="text12307"
+       y="125.78732"
+       x="230.31496"
+       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
+       xml:space="preserve"><tspan
+         y="125.78732"
+         x="230.31496"
+         id="tspan12309"
+         sodipodi:role="line">5</tspan></text>
+    <text
+       xml:space="preserve"
+       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
+       x="230.31496"
+       y="139.96053"
+       id="text12311"
+       sodipodi:linespacing="125%"><tspan
+         sodipodi:role="line"
+         id="tspan12313"
+         x="230.31496"
+         y="139.96053">6</tspan></text>
+    <text
+       xml:space="preserve"
+       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
+       x="230.31496"
+       y="168.30702"
+       id="text12315"
+       sodipodi:linespacing="125%"><tspan
+         sodipodi:role="line"
+         id="tspan12317"
+         x="230.31496"
+         y="168.30702">8</tspan></text>
+    <text
+       xml:space="preserve"
+       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
+       x="276.37799"
+       y="168.30702"
+       id="text12319"
+       sodipodi:linespacing="125%"><tspan
+         sodipodi:role="line"
+         id="tspan12321"
+         x="276.37799"
+         y="168.30702">9</tspan></text>
+    <text
+       xml:space="preserve"
+       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
+       x="276.37799"
+       y="154.1338"
+       id="text12323"
+       sodipodi:linespacing="125%"><tspan
+         sodipodi:role="line"
+         id="tspan12325"
+         x="276.37799"
+         y="154.1338">10</tspan></text>
+    <text
+       xml:space="preserve"
+       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
+       x="276.37799"
+       y="139.96059"
+       id="text12327"
+       sodipodi:linespacing="125%"><tspan
+         sodipodi:role="line"
+         id="tspan12329"
+         x="276.37799"
+         y="139.96059">11</tspan></text>
+    <text
+       xml:space="preserve"
+       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
+       x="276.37799"
+       y="125.78732"
+       id="text12331"
+       sodipodi:linespacing="125%"><tspan
+         sodipodi:role="line"
+         id="tspan12333"
+         x="276.37799"
+         y="125.78732">12</tspan></text>
+    <text
+       sodipodi:linespacing="125%"
+       id="text12335"
+       y="97.44088"
+       x="230.31496"
+       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
+       xml:space="preserve"><tspan
+         y="97.44088"
+         x="230.31496"
+         id="tspan12337"
+         sodipodi:role="line">3</tspan></text>
+    <text
+       sodipodi:linespacing="125%"
+       id="text12339"
+       y="111.61413"
+       x="230.31496"
+       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
+       xml:space="preserve"><tspan
+         y="111.61413"
+         x="230.31496"
+         id="tspan12341"
+         sodipodi:role="line">4</tspan></text>
+    <text
+       sodipodi:linespacing="125%"
+       id="text12343"
+       y="111.61413"
+       x="276.37799"
+       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
+       xml:space="preserve"><tspan
+         y="111.61413"
+         x="276.37799"
+         id="tspan12345"
+         sodipodi:role="line">13</tspan></text>
+    <text
+       sodipodi:linespacing="125%"
+       id="text12347"
+       y="97.44088"
+       x="276.37799"
+       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
+       xml:space="preserve"><tspan
+         y="97.44088"
+         x="276.37799"
+         id="tspan12349"
+         sodipodi:role="line">14</tspan></text>
+    <text
+       sodipodi:linespacing="125%"
+       id="text12351"
+       y="83.267662"
+       x="276.37799"
+       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
+       xml:space="preserve"><tspan
+         y="83.267662"
+         x="276.37799"
+         id="tspan12353"
+         sodipodi:role="line">15</tspan></text>
+    <text
+       sodipodi:linespacing="125%"
+       id="text12355"
+       y="69.094444"
+       x="276.37799"
+       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
+       xml:space="preserve"><tspan
+         y="69.094444"
+         x="276.37799"
+         id="tspan12357"
+         sodipodi:role="line">16</tspan></text>
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 379.13386,375.5906 C 380.90551,370.27564 380.90551,364.96067 375.59055,364.96062 C 368.50394,364.96055 368.50394,375.59053 372.04724,375.59053 C 375.59054,375.59053 375.59055,364.96062 368.50394,364.96062 C 361.41733,364.96062 361.41732,375.59053 364.96063,375.59053 C 368.50394,375.59053 368.50394,364.96062 361.41733,364.96062 C 354.3307,364.96062 354.33071,375.59053 357.87401,375.59053 C 361.41731,375.59053 361.41733,364.9606 354.33071,364.9606 C 349.01575,364.9606 349.01575,370.27557 350.7874,375.59053"
+       id="path12359"
+       sodipodi:nodetypes="cszzzzzsz" />
+    <text
+       xml:space="preserve"
+       style="font-size:10px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
+       x="349.01578"
+       y="361.41721"
+       id="text12361"
+       sodipodi:linespacing="125%"><tspan
+         sodipodi:role="line"
+         id="tspan12363"
+         x="349.01578"
+         y="361.41721">680µH</tspan></text>
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 311.81104,375.59047 L 350.7874,375.59053"
+       id="path12365"
+       sodipodi:nodetypes="cc" />
+    <path
+       style="fill:#000000;fill-opacity:1;stroke:none;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 329.52758,407.48023 L 333.07089,400.39362 L 336.6142,407.48023 L 329.52758,407.48023 z"
+       id="path12367" />
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 336.61421,403.93693 C 338.38586,403.93693 338.38586,400.39362 336.61421,400.39362 L 329.52759,400.39362 C 327.75594,400.39362 327.75594,396.85031 329.52759,396.85031"
+       id="path12369"
+       sodipodi:nodetypes="cccc" />
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;marker-end:url(#DotS);stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 333.07089,428.74008 L 333.07089,375.59047"
+       id="path12371"
+       sodipodi:nodetypes="cc" />
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 327.75593,428.74007 L 338.38585,428.74007"
+       id="path12375" />
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 336.6142,432.28338 L 329.52758,432.28338"
+       id="path12377" />
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 331.29924,435.82668 L 334.84254,435.82668"
+       id="path12379" />
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;marker-start:url(#DotS);stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 205.51182,347.24401 L 205.51182,364.96054"
+       id="path12381"
+       sodipodi:nodetypes="cc" />
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 200.19685,364.9606 L 210.82677,364.9606"
+       id="path12383"
+       sodipodi:nodetypes="cc" />
+    <path
+       style="fill:#000000;fill-opacity:1;stroke:none;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 200.19686,366.7322 L 200.19686,368.50385 L 210.82678,368.50385 L 210.82678,366.7322 L 200.19686,366.7322 z"
+       id="path12385"
+       sodipodi:nodetypes="ccccc" />
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;marker-end:url(#DotS);stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 205.51182,368.50385 L 205.51182,389.7637"
+       id="path12387"
+       sodipodi:nodetypes="cc" />
+    <text
+       xml:space="preserve"
+       style="font-size:10px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
+       x="210.82677"
+       y="370.27554"
+       id="text12395"
+       sodipodi:linespacing="125%"><tspan
+         sodipodi:role="line"
+         id="tspan12397"
+         x="210.82677"
+         y="370.27554">22µF</tspan></text>
+    <path
+       sodipodi:nodetypes="cc"
+       id="path12399"
+       d="M 393.30709,375.59053 L 393.30709,400.39368"
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;marker-start:url(#DotS);stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
+    <path
+       sodipodi:nodetypes="cc"
+       id="path12401"
+       d="M 387.99213,400.39368 L 398.62205,400.39368"
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
+    <path
+       sodipodi:nodetypes="ccccc"
+       id="path12403"
+       d="M 387.99213,402.16533 L 387.99213,403.93698 L 398.62205,403.93698 L 398.62205,402.16533 L 387.99213,402.16533 z"
+       style="fill:#000000;fill-opacity:1;stroke:none;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
+    <path
+       sodipodi:nodetypes="cc"
+       id="path12405"
+       d="M 393.30709,403.93698 L 393.30709,428.74013"
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 387.99213,428.74013 L 398.62205,428.74013"
+       id="path12407" />
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 396.8504,432.28343 L 389.76378,432.28343"
+       id="path12409" />
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 391.53544,435.82674 L 395.07874,435.82674"
+       id="path12411" />
+    <text
+       sodipodi:linespacing="125%"
+       id="text12413"
+       y="407.48029"
+       x="398.62207"
+       style="font-size:10px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
+       xml:space="preserve"><tspan
+         y="407.48029"
+         x="398.62207"
+         sodipodi:role="line"
+         id="tspan12417">220µF</tspan></text>
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;marker-start:url(#DotS);stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 400.3937,375.59053 L 400.3937,347.24407 L 311.81103,347.24401"
+       id="path13505"
+       sodipodi:nodetypes="ccc" />
+    <path
+       style="fill:#000000;fill-opacity:1;stroke:none;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 442.91339,329.52747 L 442.91339,336.61409 L 435.82678,333.07078 L 442.91339,329.52747 z"
+       id="path14591" />
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 435.82678,329.52747 L 435.82678,336.61409"
+       id="path14593" />
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;marker-end:url(#Arrow1Send);stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 437.59843,329.52747 L 435.82678,325.98416"
+       id="path14595" />
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;marker-end:url(#Arrow1Send);stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 441.14174,327.75582 L 439.37008,324.21251"
+       id="path14597" />
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 457.08662,333.07078 L 418.11024,333.07078 L 418.11024,350.78732"
+       id="path15683"
+       sodipodi:nodetypes="ccc" />
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 412.79528,350.78732 L 423.4252,350.78732"
+       id="path15685" />
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 421.65355,354.33062 L 414.56693,354.33062"
+       id="path15687" />
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 416.33859,357.87393 L 419.8819,357.87393"
+       id="path15689" />
+    <path
+       style="fill:none;fill-rule:evenodd;stroke:#000000;stroke-width:0.70866144;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 457.08662,333.07078 L 458.85828,329.52745 L 462.40159,336.61407 L 465.94489,329.52745 L 469.4882,336.61407 L 473.03151,329.52745 L 476.57481,336.61407 L 478.34646,333.07078"
+       id="path15691"
+       sodipodi:nodetypes="cccccccc" />
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;marker-end:url(#DotS);stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 478.34646,333.07078 L 485.43308,333.07078"
+       id="path15693" />
+    <text
+       xml:space="preserve"
+       style="font-size:10px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
+       x="453.54333"
+       y="327.75583"
+       id="text16237"
+       sodipodi:linespacing="125%"><tspan
+         sodipodi:role="line"
+         id="tspan16239"
+         x="453.54333"
+         y="327.75583">1.8kΩ</tspan></text>
+    <text
+       xml:space="preserve"
+       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
+       x="517.32281"
+       y="354.33066"
+       id="text16241"
+       sodipodi:linespacing="125%"><tspan
+         sodipodi:role="line"
+         id="tspan16243"
+         x="517.32281"
+         y="354.33066">VIN</tspan></text>
+    <text
+       xml:space="preserve"
+       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
+       x="542.12598"
+       y="354.33066"
+       id="text16245"
+       sodipodi:linespacing="125%"><tspan
+         sodipodi:role="line"
+         id="tspan16247"
+         x="542.12598"
+         y="354.33066">VOUT</tspan></text>
+    <text
+       xml:space="preserve"
+       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
+       x="531.49603"
+       y="364.96054"
+       id="text16249"
+       sodipodi:linespacing="125%"><tspan
+         sodipodi:role="line"
+         id="tspan16251"
+         x="531.49603"
+         y="364.96054">GND</tspan></text>
+    <path
+       sodipodi:nodetypes="cccccccc"
+       id="path16253"
+       d="M 481.88979,177.16528 L 483.66145,173.62195 L 487.20476,180.70857 L 490.74806,173.62195 L 494.29137,180.70857 L 497.83468,173.62195 L 501.37798,180.70857 L 503.14963,177.16528"
+       style="fill:none;fill-rule:evenodd;stroke:#000000;stroke-width:0.70866144;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
+    <text
+       sodipodi:linespacing="125%"
+       id="text16255"
+       y="189.56685"
+       x="478.34647"
+       style="font-size:10px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
+       xml:space="preserve"><tspan
+         y="189.56685"
+         x="478.34647"
+         id="tspan16257"
+         sodipodi:role="line">1.8kΩ</tspan></text>
+    <path
+       sodipodi:nodetypes="cccccccc"
+       id="path16259"
+       d="M 527.95276,198.42511 L 531.49609,200.19677 L 524.40947,203.74008 L 531.49609,207.28338 L 524.40947,210.82669 L 531.49609,214.37 L 524.40947,217.9133 L 527.95276,219.68495"
+       style="fill:none;fill-rule:evenodd;stroke:#000000;stroke-width:0.70866144;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
+    <text
+       sodipodi:linespacing="125%"
+       id="text16261"
+       y="212.59834"
+       x="492.51971"
+       style="font-size:10px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
+       xml:space="preserve"><tspan
+         id="tspan16263"
+         y="212.59834"
+         x="492.51971"
+         sodipodi:role="line">3.3kΩ</tspan></text>
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 450.00003,177.16526 L 481.88979,177.16526"
+       id="path16271" />
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 503.14963,177.16526 L 549.2126,177.16527"
+       id="path16273"
+       sodipodi:nodetypes="cc" />
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;marker-start:url(#DotS);stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 527.95278,177.16526 L 527.95276,198.42511"
+       id="path16275"
+       sodipodi:nodetypes="cc" />
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 527.95276,219.68495 L 527.95278,256.88967"
+       id="path16277"
+       sodipodi:nodetypes="cc" />
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 522.63782,256.88967 L 533.26774,256.88967"
+       id="path16279" />
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 531.49609,260.43297 L 524.40947,260.43297"
+       id="path16281" />
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 526.18112,263.97628 L 529.72443,263.97628"
+       id="path16283" />
+    <text
+       xml:space="preserve"
+       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
+       x="542.12598"
+       y="175.3936"
+       id="text16827"
+       sodipodi:linespacing="125%"><tspan
+         sodipodi:role="line"
+         id="tspan16829"
+         x="542.12598"
+         y="175.3936">3</tspan></text>
+    <text
+       xml:space="preserve"
+       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
+       x="542.12598"
+       y="161.22041"
+       id="text16831"
+       sodipodi:linespacing="125%"><tspan
+         sodipodi:role="line"
+         id="tspan16833"
+         x="542.12598"
+         y="161.22041">2</tspan></text>
+    <text
+       xml:space="preserve"
+       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
+       x="605.90546"
+       y="203.74007"
+       id="text16835"
+       sodipodi:linespacing="125%"><tspan
+         sodipodi:role="line"
+         id="tspan16837"
+         x="605.90546"
+         y="203.74007">15</tspan></text>
+    <text
+       xml:space="preserve"
+       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
+       x="605.90552"
+       y="232.08653"
+       id="text16839"
+       sodipodi:linespacing="125%"><tspan
+         sodipodi:role="line"
+         id="tspan16841"
+         x="605.90552"
+         y="232.08653">1</tspan></text>
+    <text
+       xml:space="preserve"
+       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
+       x="536.81104"
+       y="232.08653"
+       id="text16843"
+       sodipodi:linespacing="125%"><tspan
+         sodipodi:role="line"
+         id="tspan16845"
+         x="536.81104"
+         y="232.08653">10</tspan></text>
+    <path
+       style="fill:none;fill-rule:evenodd;stroke:#000000;stroke-width:0.70866144;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 481.88977,162.99206 L 483.66143,159.44873 L 487.20474,166.53535 L 490.74804,159.44873 L 494.29135,166.53535 L 497.83466,159.44873 L 501.37796,166.53535 L 503.14961,162.99206"
+       id="path16847"
+       sodipodi:nodetypes="cccccccc" />
+    <path
+       id="path16849"
+       d="M 450.00001,162.99204 L 481.88977,162.99204"
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
+    <path
+       id="path16851"
+       d="M 503.14961,162.99204 L 549.2126,162.99204"
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       sodipodi:nodetypes="cc" />
+    <text
+       xml:space="preserve"
+       style="font-size:10px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
+       x="478.34647"
+       y="157.67708"
+       id="text16853"
+       sodipodi:linespacing="125%"><tspan
+         sodipodi:role="line"
+         id="tspan16855"
+         x="478.34647"
+         y="157.67708">100Ω</tspan></text>
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866143999999998;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1;marker-start:url(#DotS)"
+       d="M 485.43308,350.78731 L 513.77953,350.78731"
+       id="path16857" />
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 540.35434,368.50385 L 540.35434,386.22039"
+       id="path16859" />
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 535.03938,386.22039 L 545.6693,386.22039"
+       id="path16861" />
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 543.89764,389.76369 L 536.81103,389.76369"
+       id="path16863" />
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 538.58268,393.307 L 542.12599,393.307"
+       id="path16865" />
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 566.92914,350.78731 L 616.53544,350.78731 L 616.53544,233.85818 L 602.36221,233.85818"
+       id="path16867"
+       sodipodi:nodetypes="cccc" />
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;marker-end:url(#DotS);stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 549.2126,233.85818 L 527.95276,233.85818"
+       id="path16877"
+       sodipodi:nodetypes="cc" />
+    <path
+       style="fill:none;fill-rule:evenodd;stroke:#000000;stroke-width:0.70866144;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 616.53544,205.51172 L 618.3071,201.96839 L 621.85041,209.05501 L 625.39371,201.96839 L 628.93702,209.05501 L 632.48033,201.96839 L 636.02363,209.05501 L 637.79528,205.51172"
+       id="path18505"
+       sodipodi:nodetypes="cccccccc" />
+    <text
+       xml:space="preserve"
+       style="font-size:10px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
+       x="616.5354"
+       y="217.91328"
+       id="text18507"
+       sodipodi:linespacing="125%"><tspan
+         sodipodi:role="line"
+         id="tspan18509"
+         x="616.5354"
+         y="217.91328">1kΩ</tspan></text>
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 602.36221,205.51172 L 616.53543,205.51172"
+       id="path18511" />
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 637.79528,205.51172 L 644.88189,205.51172 L 644.88189,265.74794"
+       id="path18513" />
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 639.56693,265.74794 L 650.19685,265.74794"
+       id="path18515" />
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 648.4252,269.29124 L 641.33858,269.29124"
+       id="path18517" />
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 643.11024,272.83455 L 646.65354,272.83455"
+       id="path18519" />
+    <path
+       style="fill:#000000;fill-opacity:1;stroke:none;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 641.33858,226.77156 L 648.4252,226.77156 L 644.88189,233.85817 L 641.33858,226.77156 z"
+       id="path18521" />
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 641.33858,233.85817 L 648.4252,233.85817"
+       id="path18523" />
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;marker-end:url(#Arrow1Send);stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 650.19685,228.54321 L 653.74016,230.31487"
+       id="path18525" />
+    <path
+       style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.70866144;marker-end:url(#Arrow1Send);stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
+       d="M 648.4252,232.08652 L 651.9685,233.85817"
+       id="path18527" />
+    <text
+       xml:space="preserve"
+       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
+       x="506.6929"
+       y="349.01566"
+       id="text19071"
+       sodipodi:linespacing="125%"><tspan
+         sodipodi:role="line"
+         id="tspan19073"
+         x="506.6929"
+         y="349.01566">3</tspan></text>
+    <text
+       xml:space="preserve"
+       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
+       x="570.47241"
+       y="349.01566"
+       id="text19075"
+       sodipodi:linespacing="125%"><tspan
+         sodipodi:role="line"
+         id="tspan19077"
+         x="570.47241"
+         y="349.01566">2</tspan></text>
+    <text
+       xml:space="preserve"
+       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
+       x="542.12598"
+       y="377.36215"
+       id="text19079"
+       sodipodi:linespacing="125%"><tspan
+         sodipodi:role="line"
+         id="tspan19081"
+         x="542.12598"
+         y="377.36215">1</tspan></text>
+    <text
+       xml:space="preserve"
+       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
+       x="251.57481"
+       y="387.99203"
+       id="text19625"
+       sodipodi:linespacing="125%"><tspan
+         sodipodi:role="line"
+         id="tspan19627"
+         x="251.57481"
+         y="387.99203">2</tspan></text>
+    <text
+       xml:space="preserve"
+       style="font-size:8px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
+       x="251.57481"
+       y="373.81882"
+       id="text19629"
+       sodipodi:linespacing="125%"><tspan
+         sodipodi:role="line"
+         id="tspan19631"
+         x="251.57481"
+         y="373.81882">3</tspan></text>
+    <text
+       xml:space="preserve"
+       style="font-size:10px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
+       x="340.15747"
+       y="407.48029"
+       id="text20175"
+       sodipodi:linespacing="125%"><tspan
+         sodipodi:role="line"
+         id="tspan20177"
+         x="340.15747"
+         y="407.48029">1N5819</tspan></text>
+  </g>
+</svg>