diff --git a/.gitignore b/.gitignore index 3843d7f..a08af4e 100644 --- a/.gitignore +++ b/.gitignore @@ -8,6 +8,7 @@ *.drl *.pdf *.svg +*.ods *.xml */mk/* .hg* diff --git a/F0-nolib/pl2303/pl2303.bin b/F0-nolib/pl2303/pl2303.bin index a0ff3ac..60a4697 100755 Binary files a/F0-nolib/pl2303/pl2303.bin and b/F0-nolib/pl2303/pl2303.bin differ diff --git a/F0-nolib/pl2303/usb.c b/F0-nolib/pl2303/usb.c index 13a06e1..fce5ed6 100644 --- a/F0-nolib/pl2303/usb.c +++ b/F0-nolib/pl2303/usb.c @@ -144,7 +144,7 @@ void USB_send(char *buf){ * @param buf (i) - buffer for received data * @param bufsize - its size * @return amount of received bytes - */ + * int USB_receive(char *buf, int bufsize){ if(!bufsize || !idatalen) return 0; USB->CNTR = 0; @@ -163,6 +163,36 @@ int USB_receive(char *buf, int bufsize){ } USB->CNTR = USB_CNTR_RESETM | USB_CNTR_CTRM; return sz; +}*/ + +int USB_receive(char *buf, int bufsize){ + if(bufsize<1 || !idatalen) return 0; + IWDG->KR = IWDG_REFRESH; + int stlen = 0; + for(int i = 0; i < idatalen; ++i){ + if(incoming_data[i] == '\n'){ + stlen = i+1; + incoming_data[i] = 0; + break; + } + } + if(stlen == 0) return 0; + USB->CNTR = 0; + int sz = (stlen > bufsize) ? bufsize : stlen, rest = idatalen - sz; + memcpy(buf, incoming_data, sz); + if(rest > 0){ + memmove(incoming_data, &incoming_data[sz], rest); + idatalen = rest; + }else idatalen = 0; + if(ovfl){ + EP23_Handler(endpoints[2]); + uint16_t epstatus = USB->EPnR[2]; + epstatus = CLEAR_DTOG_RX(epstatus); + epstatus = SET_VALID_RX(epstatus); + USB->EPnR[2] = epstatus; + } + USB->CNTR = USB_CNTR_RESETM | USB_CNTR_CTRM; + return sz; } /** diff --git a/F1-nolib/chronometer/GPS.c b/F1-nolib/chronometer/GPS.c new file mode 100644 index 0000000..0a0454c --- /dev/null +++ b/F1-nolib/chronometer/GPS.c @@ -0,0 +1,175 @@ +/* + * GPS.c + * + * Copyright 2015 Edward V. Emelianov + * + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program; if not, write to the Free Software + * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, + * MA 02110-1301, USA. + */ + +#include "GPS.h" +#include "hardware.h" +#include "time.h" +#include "usart.h" +#include "str.h" +#include // memcpy + +#define GPS_endline() do{usart_send(GPS_USART, "\r\n"); transmit_tbuf(GPS_USART); }while(0) +#define GPS_send_string(str) do{usart_send(GPS_USART, str);}while(0) + +gps_status GPS_status = GPS_WAIT; +int need2startseq = 1; + +static uint8_t hex(uint8_t n){ + return ((n < 10) ? (n+'0') : (n+'A'-10)); +} + +/** + * Check checksum + */ +static int checksum_true(const char *buf){ + char *eol; + uint8_t checksum = 0, cs[3]; + if(*buf != '$' || !(eol = getchr(buf, '*'))){ + return 0; + } + while(++buf != eol) + checksum ^= (uint8_t)*buf; + ++buf; + cs[0] = hex(checksum >> 4); + cs[1] = hex(checksum & 0x0f); + if(buf[0] == cs[0] && buf[1] == cs[1]) + return 1; + return 0; +} + +static void send_chksum(uint8_t chs){ + usart_putchar(GPS_USART, hex(chs >> 4)); + usart_putchar(1, hex(chs >> 4)); + usart_putchar(GPS_USART, hex(chs & 0x0f)); + usart_putchar(1, hex(chs & 0x0f)); +} +/** + * Calculate checksum & write message to port + * @param buf - command to write (without leading $ and trailing *) + * return 0 if fails + */ +static void write_with_checksum(const char *buf){ + char *txt = NULL; + // clear old buffer data + for(int i = 0; i < 10000; ++i){ + if(usartrx(GPS_USART)){ + usart_getline(GPS_USART, &txt); + DBG("Old data"); + GPS_parse_answer(txt); + break; + } + } + DBG("Send:"); + uint8_t checksum = 0; + usart_putchar(GPS_USART, '$'); + usart_putchar(1, '$'); + GPS_send_string(buf); + SEND(buf); + do{ + checksum ^= *buf++; + }while(*buf); + usart_putchar(GPS_USART, '*'); + usart_putchar(1, '*'); + send_chksum(checksum); + newline(); + GPS_endline(); +} + + +/* + * MTK fields format: + * $PMTKxxx,yyy,zzz*2E + * P - proprietary, MTK - always this, xxx - packet type, yyy,zzz - packet data + * Packet types: + * 220 - PMTK_SET_POS_FIX, data - position fix interval (msec, > 200) + * 255 - PMTK_SET_SYNC_PPS_NMEA - turn on/off (def - off) PPS, data = 0/1 -> "$PMTK255,1" turn ON + * 285 - PMTK_SET_PPS_CONFIG - set PPS configuration, data fields: + * 1st - 0-disable, 1-after 1st fix, 2-3D only, 3-2D/3D only, 4-always + * 2nd - 2..998 - pulse width + * 314 - PMTK_API_SET_NMEA_OUTPUT - set output messages, N== N fixes per output, + * order of messages: GLL,RMC,VTG,GGA,GSA,GSV,GRS,GST, only RMC per every pos fix: + * $PMTK314,0,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0 + * 386 - PMTK_API_SET_STATIC_NAV_THD speed threshold (m/s) for static navigation + * $PMTK386,1.5 + * ; + */ + +/** + * Send starting sequences (get only RMC messages) + */ +void GPS_send_start_seq(){ + DBG("Send start seq"); + // turn ON PPS: + write_with_checksum("PMTK255,1"); + // set pulse width to 10ms with working after 1st fix + write_with_checksum("PMTK285,1,10"); + // set only RMC: + write_with_checksum("PMTK314,0,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0"); + // set static speed threshold + write_with_checksum("PMTK386,1.5"); + need2startseq = 0; +} + +/** + * Parse answer from GPS module + * + * Recommended minimum specific GPS/Transit data + * $GPRMC,hhmmss.sss,status,latitude,N,longitude,E,spd,cog,ddmmyy,mv,mvE,mode*cs + * 1 = UTC of position fix + * 2 = Data status (V=valid, A=invalid) + * 3 = Latitude (ddmm.mmmm) + * 4 = N or S + * 5 = Longitude (dddmm.mmmm) + * 6 = E or W + * 7 = Speed over ground in knots + * 8 = Cource over ground in degrees + * 9 = UT date (ddmmyy) + * 10 = Magnetic variation degrees (Easterly var. subtracts from true course) + * 11 = E or W + * 12 = Mode: N(bad), E(approx), A(auto), D(diff) + * 213457.00,A,4340.59415,N,04127.47560,E,2.494,,290615,,,A*7B + */ +void GPS_parse_answer(const char *buf){ + char *ptr; + DBG(buf); + if(buf[1] == 'P') return; // answers to proprietary messages + if(cmpstr(buf+3, "RMC", 3)){ // not RMC message + need2startseq = 1; + return; + } + if(!checksum_true(buf)){ + return; // wrong checksum + } + buf += 7; // skip header + if(*buf == ','){ // time unknown + GPS_status = GPS_WAIT; + return; + } + ptr = getchr(buf, ','); + if(!ptr ) return; + *ptr++ = 0; + if(*ptr == 'A'){ + GPS_status = GPS_VALID; + set_time(buf); + }else{ + GPS_status = GPS_NOT_VALID; + } +} diff --git a/F1-nolib/chronometer/GPS.h b/F1-nolib/chronometer/GPS.h new file mode 100644 index 0000000..2feeef2 --- /dev/null +++ b/F1-nolib/chronometer/GPS.h @@ -0,0 +1,41 @@ +/* + * GPS.h + * + * Copyright 2015 Edward V. Emelianov + * + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program; if not, write to the Free Software + * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, + * MA 02110-1301, USA. + */ + +#pragma once +#ifndef __GPS_H__ +#define __GPS_H__ + +#include "stm32f1.h" + +extern int need2startseq; + +typedef enum{ + GPS_WAIT // wait for satellites + ,GPS_NOT_VALID // time known, but not valid + ,GPS_VALID +} gps_status; + +extern gps_status GPS_status; + +void GPS_parse_answer(const char *string); +void GPS_send_start_seq(); + +#endif // __GPS_H__ diff --git a/F1-nolib/chronometer/Makefile b/F1-nolib/chronometer/Makefile new file mode 100644 index 0000000..76dd294 --- /dev/null +++ b/F1-nolib/chronometer/Makefile @@ -0,0 +1,140 @@ +BINARY = chrono +BOOTPORT ?= /dev/ttyUSB0 +BOOTSPEED ?= 115200 +# MCU FAMILY +FAMILY ?= F1 +# MCU code +MCU ?= F103x8 +# density (stm32f10x.h, lines 70-84) +DENSITY ?= MD +# change this linking script depending on particular MCU model, +LDSCRIPT ?= stm32f103x8.ld +DEFS = -DVERSION=\"0.0.1\" +# debug +DEFS += -DEBUG + +INDEPENDENT_HEADERS= + +FP_FLAGS ?= -msoft-float -mfloat-abi=soft +ASM_FLAGS ?= -mthumb -mcpu=cortex-m3 -mfix-cortex-m3-ldrd +ARCH_FLAGS = $(ASM_FLAGS) $(FP_FLAGS) + +############################################################################### +# Executables +#PREFIX ?= arm-none-eabi +# gcc from arm web site +PREFIX ?= /opt/bin/arm-none-eabi +TOOLCHLIB ?= /opt/arm-none-eabi/lib +RM := rm -f +RMDIR := rmdir +CC := $(PREFIX)-gcc +# don't replace ld with gcc: the binary size would be much greater!! +LD := $(PREFIX)-ld +AR := $(PREFIX)-ar +AS := $(PREFIX)-as +SIZE := $(PREFIX)-size +OBJCOPY := $(PREFIX)-objcopy +OBJDUMP := $(PREFIX)-objdump +GDB := $(PREFIX)-gdb +STFLASH := $(shell which st-flash) +STBOOT := $(shell which stm32flash) +DFUUTIL := $(shell which dfu-util) + +############################################################################### +# Source files +OBJDIR = mk +SRC := $(wildcard *.c) +OBJS := $(addprefix $(OBJDIR)/, $(SRC:%.c=%.o)) +STARTUP = $(OBJDIR)/startup.o +OBJS += $(STARTUP) +# dependencies: we need them to recompile files if their headers-dependencies changed +DEPS := $(OBJS:.o=.d) + +INC_DIR ?= ../inc + +INCLUDE := -I$(INC_DIR)/Fx -I$(INC_DIR)/cm +LIB_DIR := $(INC_DIR)/ld + +############################################################################### +# C flags +CFLAGS += -O2 -g -D__thumb2__=1 -MD +CFLAGS += -Wall -Werror -Wextra -Wshadow +CFLAGS += -fno-common -ffunction-sections -fdata-sections -fno-stack-protector +CFLAGS += $(ARCH_FLAGS) + +############################################################################### +# Linker flags +LDFLAGS += -nostartfiles --static -nostdlibs +LDFLAGS += -L$(LIB_DIR) -L$(TOOLCHLIB) +LDFLAGS += -T$(LDSCRIPT) + +############################################################################### +# Used libraries +LDLIBS += -lc $(shell $(CC) $(CFLAGS) -print-libgcc-file-name) + +DEFS += -DSTM32$(FAMILY) -DSTM32$(MCU) -DSTM32F10X_$(DENSITY) + +ELF := $(OBJDIR)/$(BINARY).elf +LIST := $(OBJDIR)/$(BINARY).list +BIN := $(BINARY).bin +HEX := $(BINARY).hex + +all: bin list size + +elf: $(ELF) +bin: $(BIN) +hex: $(HEX) +list: $(LIST) + +ifneq ($(MAKECMDGOALS),clean) +-include $(DEPS) +endif + +$(OBJDIR): + mkdir $(OBJDIR) + +$(STARTUP): $(INC_DIR)/startup/vector.c + $(CC) $(CFLAGS) $(DEFS) $(INCLUDE) -o $@ -c $< + +$(OBJDIR)/%.o: %.c + @echo " CC $<" + $(CC) $(CFLAGS) $(DEFS) $(INCLUDE) -o $@ -c $< + +$(BIN): $(ELF) + @echo " OBJCOPY $(BIN)" + $(OBJCOPY) -Obinary $(ELF) $(BIN) + +$(HEX): $(ELF) + @echo " OBJCOPY $(HEX)" + $(OBJCOPY) -Oihex $(ELF) $(HEX) + +$(LIST): $(ELF) + @echo " OBJDUMP $(LIST)" + $(OBJDUMP) -S $(ELF) > $(LIST) + +$(ELF): $(OBJDIR) $(OBJS) + @echo " LD $(ELF)" + $(LD) $(LDFLAGS) $(OBJS) $(LDLIBS) -o $(ELF) + +size: $(ELF) + $(SIZE) $(ELF) + +clean: + @echo " CLEAN" + $(RM) $(OBJS) $(DEPS) $(ELF) $(HEX) $(LIST) + @rmdir $(OBJDIR) 2>/dev/null || true + + +flash: $(BIN) + @echo " FLASH $(BIN)" + $(STFLASH) write $(BIN) 0x8000000 + +boot: $(BIN) + @echo " LOAD $(BIN) through bootloader" + $(STBOOT) -b$(BOOTSPEED) $(BOOTPORT) -w $(BIN) + +dfuboot: $(BIN) + @echo " LOAD $(BIN) THROUGH DFU" + $(DFUUTIL) -a0 -D $(BIN) -s 0x08000000 + +.PHONY: clean flash boot diff --git a/F1-nolib/chronometer/Readme.md b/F1-nolib/chronometer/Readme.md new file mode 100644 index 0000000..c37bb0b --- /dev/null +++ b/F1-nolib/chronometer/Readme.md @@ -0,0 +1,18 @@ +Chronometer for downhill competitions +===================================== + +## Pinout + +- PA9(Tx),PA10 (debug mode) - USART1 - debug console +- PA2(Tx), PA3 - USART2 - GPS +- PB10(Tx), PB11 - USART3 - LIDAR + +- PA1 - PPS signal from GPS (EXTI) + +- PB8, PB9 - onboard LEDs + +- PA4 - TRIG2 - 12V trigger (EXTI) +- PA13 - TRIG0 - button0 (EXTI) +- PA14 - TRIG1 - button1/laser/etc (EXTI) +- PA15 - USB pullup + diff --git a/F1-nolib/chronometer/adc.c b/F1-nolib/chronometer/adc.c new file mode 100644 index 0000000..9887722 --- /dev/null +++ b/F1-nolib/chronometer/adc.c @@ -0,0 +1,70 @@ +/* + * This file is part of the chronometer project. + * Copyright 2018 Edward V. Emelianov . + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + */ + +#include "adc.h" + +/** + * @brief ADC_array - array for ADC channels with median filtering: + * 0 - Rvar + * 1 - internal Tsens + * 2 - Vref + */ +uint16_t ADC_array[NUMBER_OF_ADC_CHANNELS*9]; + +/** + * @brief getADCval - calculate median value for `nch` channel + * @param nch - number of channel + * @return + */ +uint16_t getADCval(int nch){ + int i, addr = nch; + register uint16_t temp; +#define PIX_SORT(a,b) { if ((a)>(b)) PIX_SWAP((a),(b)); } +#define PIX_SWAP(a,b) { temp=(a);(a)=(b);(b)=temp; } + uint16_t p[9]; + for(i = 0; i < 9; ++i, addr += NUMBER_OF_ADC_CHANNELS) // first we should prepare array for optmed + p[i] = ADC_array[addr]; + PIX_SORT(p[1], p[2]) ; PIX_SORT(p[4], p[5]) ; PIX_SORT(p[7], p[8]) ; + PIX_SORT(p[0], p[1]) ; PIX_SORT(p[3], p[4]) ; PIX_SORT(p[6], p[7]) ; + PIX_SORT(p[1], p[2]) ; PIX_SORT(p[4], p[5]) ; PIX_SORT(p[7], p[8]) ; + PIX_SORT(p[0], p[3]) ; PIX_SORT(p[5], p[8]) ; PIX_SORT(p[4], p[7]) ; + PIX_SORT(p[3], p[6]) ; PIX_SORT(p[1], p[4]) ; PIX_SORT(p[2], p[5]) ; + PIX_SORT(p[4], p[7]) ; PIX_SORT(p[4], p[2]) ; PIX_SORT(p[6], p[4]) ; + PIX_SORT(p[4], p[2]) ; + return p[4]; +#undef PIX_SORT +#undef PIX_SWAP +} + +// return MCU temperature (degrees of celsius * 10) +int32_t getMCUtemp(){ + // Temp = (V25 - Vsense)/Avg_Slope + 25 + // V_25 = 1.45V, Slope = 4.3e-3 + int32_t Vsense = getVdd() * getADCval(1); + int32_t temperature = 593920 - Vsense; // 593920 == 145*4096 + temperature /= 172; // == /(4096*10*4.3e-3), 10 - to convert from *100 to *10 + temperature += 250; + return(temperature); +} + +// return Vdd * 100 (V) +uint32_t getVdd(){ + uint32_t vdd = 120 * 4096; // 1.2V + vdd /= getADCval(2); + return vdd; +} diff --git a/F1-nolib/chronometer/adc.h b/F1-nolib/chronometer/adc.h new file mode 100644 index 0000000..de20e01 --- /dev/null +++ b/F1-nolib/chronometer/adc.h @@ -0,0 +1,29 @@ +/* + * This file is part of the chronometer project. + * Copyright 2018 Edward V. Emelianov . + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + */ +#ifndef ADC_H +#define ADC_H +#include "stm32f1.h" + +#define NUMBER_OF_ADC_CHANNELS (3) + +extern uint16_t ADC_array[]; +int32_t getMCUtemp(); +uint32_t getVdd(); +uint16_t getADCval(int nch); + +#endif // ADC_H diff --git a/F1-nolib/chronometer/chrono.bin b/F1-nolib/chronometer/chrono.bin new file mode 100755 index 0000000..9d8617c Binary files /dev/null and b/F1-nolib/chronometer/chrono.bin differ diff --git a/F1-nolib/chronometer/hardware.c b/F1-nolib/chronometer/hardware.c new file mode 100644 index 0000000..57d32ca --- /dev/null +++ b/F1-nolib/chronometer/hardware.c @@ -0,0 +1,122 @@ +/* + * geany_encoding=koi8-r + * hardware.c - hardware-dependent macros & functions + * + * Copyright 2018 Edward V. Emelianov + * + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program; if not, write to the Free Software + * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, + * MA 02110-1301, USA. + * + */ + +#include "adc.h" +#include "hardware.h" +#include "usart.h" + +static inline void gpio_setup(){ + // Enable clocks to the GPIO subsystems (PB for ADC), turn on AFIO clocking to disable SWD/JTAG + RCC->APB2ENR |= RCC_APB2ENR_IOPAEN | RCC_APB2ENR_IOPBEN | RCC_APB2ENR_IOPCEN | RCC_APB2ENR_AFIOEN; + // turn off SWJ/JTAG + AFIO->MAPR = AFIO_MAPR_SWJ_CFG_DISABLE; + // pullups + GPIOA->ODR = (1<<12)|(1<<13)|(1<<14); + // Set led (PB8) as opendrain output + GPIOB->CRH = CRH(8, CNF_ODOUTPUT|MODE_SLOW); + // PPS pin (PA1) - input with weak pullup + GPIOA->CRL = CRL(1, CNF_PUDINPUT|MODE_INPUT); + // Set buttons (PA13/14) as inputs with weak pullups, USB pullup (PA15) - opendrain output + GPIOA->CRH = CRH(13, CNF_PUDINPUT|MODE_INPUT) | CRH(14, CNF_PUDINPUT|MODE_INPUT) | + CRH(15, CNF_ODOUTPUT|MODE_SLOW); + // EXTI: all three EXTI are on PA -> AFIO_EXTICRx = 0 + // interrupt on pulse front: buttons - 1->0, PPS - 0->1 + EXTI->IMR = EXTI_IMR_MR1 | EXTI_IMR_MR13 | EXTI_IMR_MR14; // unmask + EXTI->RTSR = EXTI_RTSR_TR1; // rising trigger + EXTI->FTSR = EXTI_FTSR_TR13 | EXTI_FTSR_TR14; // falling trigger + NVIC_EnableIRQ(EXTI15_10_IRQn); + NVIC_EnableIRQ(EXTI1_IRQn); +} + +static inline void adc_setup(){ + GPIOB->CRL |= CRL(0, CNF_ANALOG|MODE_INPUT); + uint32_t ctr = 0; + // Enable clocking + RCC->APB2ENR |= RCC_APB2ENR_ADC1EN; + RCC->CFGR &= ~(RCC_CFGR_ADCPRE); + RCC->CFGR |= RCC_CFGR_ADCPRE_DIV8; // ADC clock = RCC / 8 + // sampling time - 239.5 cycles for channels 8, 16 and 17 + ADC1->SMPR2 = ADC_SMPR2_SMP8; + ADC1->SMPR1 = ADC_SMPR1_SMP16 | ADC_SMPR1_SMP17; + // we have three conversions in group -> ADC1->SQR1[L] = 2, order: 8->16->17 + ADC1->SQR3 = 8 | (16<<5) | (17<<10); + ADC1->SQR1 = ADC_SQR1_L_1; + ADC1->CR1 |= ADC_CR1_SCAN; // scan mode + // DMA configuration + RCC->AHBENR |= RCC_AHBENR_DMA1EN; + DMA1_Channel1->CPAR = (uint32_t) (&(ADC1->DR)); + DMA1_Channel1->CMAR = (uint32_t)(ADC_array); + DMA1_Channel1->CNDTR = NUMBER_OF_ADC_CHANNELS * 9; + DMA1_Channel1->CCR |= DMA_CCR_MINC | DMA_CCR_MSIZE_0 | DMA_CCR_PSIZE_0 + | DMA_CCR_CIRC | DMA_CCR_PL | DMA_CCR_EN; + // continuous mode & DMA; enable vref & Tsens; wake up ADC + ADC1->CR2 |= ADC_CR2_DMA | ADC_CR2_TSVREFE | ADC_CR2_CONT | ADC_CR2_ADON; + // wait for Tstab - at least 1us + while(++ctr < 0xff) nop(); + // calibration + ADC1->CR2 |= ADC_CR2_RSTCAL; + ctr = 0; while((ADC1->CR2 & ADC_CR2_RSTCAL) && ++ctr < 0xfffff); + ADC1->CR2 |= ADC_CR2_CAL; + ctr = 0; while((ADC1->CR2 & ADC_CR2_CAL) && ++ctr < 0xfffff); + // turn ON ADC + ADC1->CR2 |= ADC_CR2_ADON; +} + +void hw_setup(){ + gpio_setup(); + //adc_setup(); +} + +void exti1_isr(){ // PPS - PA1 + /* + if(trigger_ms[2] == DIDNT_TRIGGERED){ // prevent bounce + trigger_ms[2] = Timer; + memcpy(&trigger_time[2], ¤t_time, sizeof(curtime)); + } + */ + DBG("exti1"); + EXTI->PR = EXTI_PR_PR1; +} + +void exti15_10_isr(){ // PA13 - button0, PA14 - button1 + if(EXTI->PR & EXTI_PR_PR13){ + /* + if(trigger_ms[0] == DIDNT_TRIGGERED){ // prevent bounce + trigger_ms[0] = Timer; + memcpy(&trigger_time[0], ¤t_time, sizeof(curtime)); + } + */ + DBG("exti13"); + EXTI->PR = EXTI_PR_PR13; + } + if(EXTI->PR & EXTI_PR_PR14){ + /* + if(trigger_ms[3] == DIDNT_TRIGGERED){ // prevent bounce + trigger_ms[3] = Timer; + memcpy(&trigger_time[3], ¤t_time, sizeof(curtime)); + } + */ + DBG("exti14"); + EXTI->PR = EXTI_PR_PR14; + } +} diff --git a/F1-nolib/chronometer/hardware.h b/F1-nolib/chronometer/hardware.h new file mode 100644 index 0000000..0c9017e --- /dev/null +++ b/F1-nolib/chronometer/hardware.h @@ -0,0 +1,68 @@ +/* + * geany_encoding=koi8-r + * hardware.h + * + * Copyright 2018 Edward V. Emelianov + * + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program; if not, write to the Free Software + * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, + * MA 02110-1301, USA. + * + */ +#pragma once +#ifndef __HARDWARE_H__ +#define __HARDWARE_H__ + +#include "stm32f1.h" + +// usb commands +// lower and upper limits to capture +#define CMD_DISTMIN "distmin" +#define CMD_DISTMAX "distmax" +#define CMD_ADC1MIN "adc1min" +#define CMD_ADC2MIN "adc2min" +#define CMD_ADC1MAX "adc1max" +#define CMD_ADC2MAX "adc2max" +#define CMD_PRINTTIME "time" + +// onboard LED - PB8 +#define LED_port GPIOB +#define LED_pin (1<<8) + +// PPS pin - PA1 +#define PPS_port GPIOA +#define PPS_pin (1<<1) + +// Buttons' state: PA13 (0)/PA14 (1) +#define GET_BTN0() ((GPIOA->IDR & (1<<13)) ? 0 : 1) +#define GET_BTN1() ((GPIOA->IDR & (1<<14)) ? 0 : 1) +#define GET_PPS() ((GPIOA->IDR & (1<<1)) ? 1 : 0) + +// USB pullup - PA15 +#define USBPU_port GPIOA +#define USBPU_pin (1<<15) +#define USBPU_ON() pin_clear(USBPU_port, USBPU_pin) +#define USBPU_OFF() pin_set(USBPU_port, USBPU_pin) + +#define LED_blink() pin_toggle(LED_port, LED_pin) +#define LED_on() pin_clear(LED_port, LED_pin) +#define LED_off() pin_set(LED_port, LED_pin) + +// GPS USART == USART2, LIDAR USART == USART3 +#define GPS_USART (2) +#define LIDAR_USART (3) + +void hw_setup(); + +#endif // __HARDWARE_H__ diff --git a/F1-nolib/chronometer/kicad/chrono/BOM_chrono.csv b/F1-nolib/chronometer/kicad/chrono/BOM_chrono.csv new file mode 100644 index 0000000..54816d6 --- /dev/null +++ b/F1-nolib/chronometer/kicad/chrono/BOM_chrono.csv @@ -0,0 +1,115 @@ +"Source:","/home/eddy/Docs/SAO/ELECTRONICS/STM32/F1-srcs/chronometer/kicad/chrono/chrono.sch" +"Date:","þÔ 27 ÉÀÎ 2019 18:58:30" +"Tool:","Eeschema (6.0.0-rc1-dev-1613-ga55d9819b)" +"Generator:","/usr/local/share/kicad/plugins/bom_csv_grouped_by_value.py" +"Component Count:","62" + +"Individual Components:" + +"Item","Qty","Reference(s)","Value","LibPart","Footprint","Datasheet","Manufacturer" +"","","C1","0.1","stm32-rescue:C","Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder","","" +"","","C2","0.1","stm32-rescue:C","Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder","","" +"","","C3","0.1","stm32-rescue:C","Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder","","" +"","","C4","47u","stm32-rescue:CP","Capacitor_Tantalum_SMD:CP_EIA-3216-18_Kemet-A_Pad1.58x1.35mm_HandSolder","","" +"","","C5","10u","Device:C","Capacitor_SMD:C_1206_3216Metric_Pad1.42x1.75mm_HandSolder","~","" +"","","C6","100u","stm32-rescue:CP","Capacitor_THT:CP_Radial_D8.0mm_P3.50mm","","" +"","","C7","0.1","stm32-rescue:C","Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder","","" +"","","C8","0.1","stm32-rescue:C","Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder","","" +"","","C9","47u","stm32-rescue:CP","Capacitor_Tantalum_SMD:CP_EIA-3216-18_Kemet-A_Pad1.58x1.35mm_HandSolder","","" +"","","C10","12","stm32-rescue:C","Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder","","" +"","","C11","12","stm32-rescue:C","Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder","","" +"","","C12","0.1","stm32-rescue:C","Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder","","" +"","","C13","0.1","stm32-rescue:C","Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder","","" +"","","C14","0.1","stm32-rescue:C","Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder","","" +"","","C15","0.1","stm32-rescue:C","Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder","","" +"","","D1","MM3Z7V5","Device:D_Zener","Diode_SMD:D_0805_2012Metric_Pad1.15x1.40mm_HandSolder","~","" +"","","D2","SS14","Device:D_Schottky","Diode_SMD:D_SMA_Handsoldering","~","" +"","","D3","1n5822","stm32-rescue:D","Diode_THT:D_DO-201_P12.70mm_Horizontal","","" +"","","D4","LED0","stm32-rescue:LED-RESCUE-stm32","LED_THT:LED_D5.0mm","","" +"","","D5","LED1","stm32-rescue:LED-RESCUE-stm32","LED_THT:LED_D5.0mm","","" +"","","J1","Power 12V","Connector_Generic:Conn_01x02","TerminalBlock_Phoenix:TerminalBlock_Phoenix_MKDS-1,5-2-5.08_1x02_P5.08mm_Horizontal","~","" +"","","J2","+5Vout","Connector_Generic:Conn_01x02","TerminalBlock_Phoenix:TerminalBlock_Phoenix_MKDS-1,5-2-5.08_1x02_P5.08mm_Horizontal","~","" +"","","J3","Ext_trig0","Connector_Generic:Conn_01x02","TerminalBlock_Phoenix:TerminalBlock_Phoenix_MKDS-1,5-2-5.08_1x02_P5.08mm_Horizontal","~","" +"","","J4","LIDAR","Connector:Conn_01x04_Female","Connector_PinSocket_2.54mm:PinSocket_1x04_P2.54mm_Vertical","~","" +"","","J5","Ext_trig1","Connector_Generic:Conn_01x02","TerminalBlock_Phoenix:TerminalBlock_Phoenix_MKDS-1,5-2-5.08_1x02_P5.08mm_Horizontal","~","" +"","","J6","Ext_trig2","Connector_Generic:Conn_01x02","TerminalBlock_Phoenix:TerminalBlock_Phoenix_MKDS-1,5-2-5.08_1x02_P5.08mm_Horizontal","~","" +"","","J7","USART1","Connector:Conn_01x03_Female","Connector_PinSocket_2.54mm:PinSocket_1x03_P2.54mm_Vertical","~","" +"","","L1","100u","stm32-rescue:L","Inductor_SMD:L_12x12mm_H4.5mm","","" +"","","P1","USB_B","stm32-rescue:USB_A-RESCUE-stm32","Connectors_USB:USB_B_OST_USB-B1HSxx_Horizontal","","" +"","","Q1","AO3407","stm32-rescue:Q_PMOS_GSD","TO_SOT_Packages_SMD:SOT-23_Handsoldering","","" +"","","Q2","DTA114Y","Transistor_BJT:DTA114Y","TO_SOT_Packages_SMD:SOT-323_SC-70_Handsoldering","","" +"","","R1","10k","stm32-rescue:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder","","" +"","","R2","10k","stm32-rescue:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder","","" +"","","R3","22","stm32-rescue:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder","","" +"","","R4","22","stm32-rescue:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder","","" +"","","R5","10k","stm32-rescue:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder","","" +"","","R6","1k5","stm32-rescue:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder","","" +"","","R7","22","Device:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder","~","" +"","","R8","330","stm32-rescue:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder","","" +"","","R9","330","stm32-rescue:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder","","" +"","","R10","330","Device:R","Resistor_SMD:R_0805_2012Metric_Pad1.15x1.40mm_HandSolder","~","" +"","","R11","4k7","Device:R","Resistor_SMD:R_0805_2012Metric_Pad1.15x1.40mm_HandSolder","~","" +"","","R12","4k7","Device:R","Resistor_SMD:R_0805_2012Metric_Pad1.15x1.40mm_HandSolder","~","" +"","","R13","100k","stm32-rescue:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder","","" +"","","R14","330","Device:R","Resistor_SMD:R_0805_2012Metric_Pad1.15x1.40mm_HandSolder","~","" +"","","R15","4k7","Device:R","Resistor_SMD:R_0805_2012Metric_Pad1.15x1.40mm_HandSolder","~","" +"","","R16","4k7","Device:R","Resistor_SMD:R_0805_2012Metric_Pad1.15x1.40mm_HandSolder","~","" +"","","R17","2k2","Device:R","Resistor_SMD:R_0805_2012Metric_Pad1.15x1.40mm_HandSolder","~","" +"","","R18","100k","stm32-rescue:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder","","" +"","","R19","4k7","Device:R","Resistor_SMD:R_0805_2012Metric_Pad1.15x1.40mm_HandSolder","~","" +"","","R20","4k7","Device:R","Resistor_SMD:R_0805_2012Metric_Pad1.15x1.40mm_HandSolder","~","" +"","","SW1","Reset","Switch:SW_Push","Buttons_Switches_SMD:SW_SPST_FSMSM","","" +"","","SW2","Boot","Switch:SW_Push","Buttons_Switches_SMD:SW_SPST_FSMSM","","" +"","","U1","USBLC6-2SC6","Power_Protection:USBLC6-2SC6","TO_SOT_Packages_SMD:SOT-23-6_Handsoldering","http://www2.st.com/resource/en/datasheet/CD00050750.pdf","" +"","","U2","LM2576HV","stm32-rescue:LM2576HV","TO_SOT_Packages_THT:TO-220-5_P3.4x3.7mm_StaggerEven_Lead3.8mm_Vertical","","Texas Instruments" +"","","U3","L80-R","Chrono:L80-R","chrono:L80-R","","" +"","","U4","LM1117-3.3","stm32-rescue:LM1117-3.3-RESCUE-stm32","TO_SOT_Packages_SMD:SOT-223","","" +"","","U5","PC817","Isolator:PC817","Package_DIP:DIP-4_W7.62mm","http://www.soselectronic.cz/a_info/resource/d/pc817.pdf","" +"","","U6","PC817","Isolator:PC817","Package_DIP:DIP-4_W7.62mm","http://www.soselectronic.cz/a_info/resource/d/pc817.pdf","" +"","","U7","STM32F103C6Tx","MCU_ST_STM32F1:STM32F103C6Tx","Package_QFP:LQFP-48_7x7mm_P0.5mm","http://www.st.com/st-web-ui/static/active/en/resource/technical/document/datasheet/CD00210843.pdf","" +"","","U8","PC817","Isolator:PC817","Package_DIP:DIP-4_W7.62mm","http://www.soselectronic.cz/a_info/resource/d/pc817.pdf","" +"","","Y1","8MHz","Device:Crystal","Crystal:Crystal_HC49-U_Vertical","~","" + + + +"Collated Components:" + +"Item","Qty","Reference(s)","Value","LibPart","Footprint","Datasheet","Manufacturer" +"1","9","C1, C2, C3, C7, C8, C12, C13, C14, C15","0.1","stm32-rescue:C","Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder","","" +"2","2","C4, C9","47u","stm32-rescue:CP","Capacitor_Tantalum_SMD:CP_EIA-3216-18_Kemet-A_Pad1.58x1.35mm_HandSolder","","" +"3","1","C5","10u","Device:C","Capacitor_SMD:C_1206_3216Metric_Pad1.42x1.75mm_HandSolder","~","" +"4","1","C6","100u","stm32-rescue:CP","Capacitor_THT:CP_Radial_D8.0mm_P3.50mm","","" +"5","2","C10, C11","12","stm32-rescue:C","Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder","","" +"6","1","D1","MM3Z7V5","Device:D_Zener","Diode_SMD:D_0805_2012Metric_Pad1.15x1.40mm_HandSolder","~","" +"7","1","D2","SS14","Device:D_Schottky","Diode_SMD:D_SMA_Handsoldering","~","" +"8","1","D3","1n5822","stm32-rescue:D","Diode_THT:D_DO-201_P12.70mm_Horizontal","","" +"9","1","D4","LED0","stm32-rescue:LED-RESCUE-stm32","LED_THT:LED_D5.0mm","","" +"10","1","D5","LED1","stm32-rescue:LED-RESCUE-stm32","LED_THT:LED_D5.0mm","","" +"11","1","J1","Power 12V","Connector_Generic:Conn_01x02","TerminalBlock_Phoenix:TerminalBlock_Phoenix_MKDS-1,5-2-5.08_1x02_P5.08mm_Horizontal","~","" +"12","1","J2","+5Vout","Connector_Generic:Conn_01x02","TerminalBlock_Phoenix:TerminalBlock_Phoenix_MKDS-1,5-2-5.08_1x02_P5.08mm_Horizontal","~","" +"13","1","J3","Ext_trig0","Connector_Generic:Conn_01x02","TerminalBlock_Phoenix:TerminalBlock_Phoenix_MKDS-1,5-2-5.08_1x02_P5.08mm_Horizontal","~","" +"14","1","J4","LIDAR","Connector:Conn_01x04_Female","Connector_PinSocket_2.54mm:PinSocket_1x04_P2.54mm_Vertical","~","" +"15","1","J5","Ext_trig1","Connector_Generic:Conn_01x02","TerminalBlock_Phoenix:TerminalBlock_Phoenix_MKDS-1,5-2-5.08_1x02_P5.08mm_Horizontal","~","" +"16","1","J6","Ext_trig2","Connector_Generic:Conn_01x02","TerminalBlock_Phoenix:TerminalBlock_Phoenix_MKDS-1,5-2-5.08_1x02_P5.08mm_Horizontal","~","" +"17","1","J7","USART1","Connector:Conn_01x03_Female","Connector_PinSocket_2.54mm:PinSocket_1x03_P2.54mm_Vertical","~","" +"18","1","L1","100u","stm32-rescue:L","Inductor_SMD:L_12x12mm_H4.5mm","","" +"19","1","P1","USB_B","stm32-rescue:USB_A-RESCUE-stm32","Connectors_USB:USB_B_OST_USB-B1HSxx_Horizontal","","" +"20","1","Q1","AO3407","stm32-rescue:Q_PMOS_GSD","TO_SOT_Packages_SMD:SOT-23_Handsoldering","","" +"21","1","Q2","DTA114Y","Transistor_BJT:DTA114Y","TO_SOT_Packages_SMD:SOT-323_SC-70_Handsoldering","","" +"22","3","R1, R2, R5","10k","stm32-rescue:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder","","" +"23","3","R3, R4, R7","22","Device:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder","~","" +"24","1","R6","1k5","stm32-rescue:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder","","" +"25","2","R8, R9","330","stm32-rescue:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder","","" +"26","2","R10, R14","330","Device:R","Resistor_SMD:R_0805_2012Metric_Pad1.15x1.40mm_HandSolder","~","" +"27","6","R11, R12, R15, R16, R19, R20","4k7","Device:R","Resistor_SMD:R_0805_2012Metric_Pad1.15x1.40mm_HandSolder","~","" +"28","2","R13, R18","100k","stm32-rescue:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder","","" +"29","1","R17","2k2","Device:R","Resistor_SMD:R_0805_2012Metric_Pad1.15x1.40mm_HandSolder","~","" +"30","1","SW1","Reset","Switch:SW_Push","Buttons_Switches_SMD:SW_SPST_FSMSM","","" +"31","1","SW2","Boot","Switch:SW_Push","Buttons_Switches_SMD:SW_SPST_FSMSM","","" +"32","1","U1","USBLC6-2SC6","Power_Protection:USBLC6-2SC6","TO_SOT_Packages_SMD:SOT-23-6_Handsoldering","http://www2.st.com/resource/en/datasheet/CD00050750.pdf","" +"33","1","U2","LM2576HV","stm32-rescue:LM2576HV","TO_SOT_Packages_THT:TO-220-5_P3.4x3.7mm_StaggerEven_Lead3.8mm_Vertical","","Texas Instruments" +"34","1","U3","L80-R","Chrono:L80-R","chrono:L80-R","","" +"35","1","U4","LM1117-3.3","stm32-rescue:LM1117-3.3-RESCUE-stm32","TO_SOT_Packages_SMD:SOT-223","","" +"36","3","U5, U6, U8","PC817","Isolator:PC817","Package_DIP:DIP-4_W7.62mm","http://www.soselectronic.cz/a_info/resource/d/pc817.pdf","" +"37","1","U7","STM32F103C6Tx","MCU_ST_STM32F1:STM32F103C6Tx","Package_QFP:LQFP-48_7x7mm_P0.5mm","http://www.st.com/st-web-ui/static/active/en/resource/technical/document/datasheet/CD00210843.pdf","" +"38","1","Y1","8MHz","Device:Crystal","Crystal:Crystal_HC49-U_Vertical","~","" diff --git a/F1-nolib/chronometer/kicad/chrono/Chrono.lib b/F1-nolib/chronometer/kicad/chrono/Chrono.lib new file mode 100644 index 0000000..27c643c --- /dev/null +++ b/F1-nolib/chronometer/kicad/chrono/Chrono.lib @@ -0,0 +1,31 @@ +EESchema-LIBRARY Version 2.4 +#encoding utf-8 +# +# L80-R +# +DEF L80-R U 0 40 Y Y 1 F N +F0 "U" 0 -375 50 H V C CNN +F1 "L80-R" 0 425 50 H V C CNN +F2 "chrono:L80-R" 0 0 50 H I C CNN +F3 "" -550 -50 50 H I C CNN +$FPLIST + L80-R +$ENDFPLIST +DRAW +S -250 350 250 -325 0 1 0 N +X RXD 1 -450 250 200 R 50 50 1 1 P +X RESET 10 450 50 200 L 50 50 1 1 P +X Res 11 450 150 200 L 50 50 1 1 P +X Gnd 12 450 250 200 L 50 50 1 1 P +X TXD 2 -450 150 200 R 50 50 1 1 P +X Gnd 3 -450 50 200 R 50 50 1 1 P +X Vcc 4 -450 -50 200 R 50 50 1 1 P +X V_BKP 5 -450 -150 200 R 50 50 1 1 P +X PPS 6 -450 -250 200 R 50 50 1 1 P +X Res 7 450 -250 200 L 50 50 1 1 P +X Res 8 450 -150 200 L 50 50 1 1 P +X NC 9 450 -50 200 L 50 50 1 1 P +ENDDRAW +ENDDEF +# +#End Library diff --git a/F1-nolib/chronometer/kicad/chrono/chrono.kicad_pcb b/F1-nolib/chronometer/kicad/chrono/chrono.kicad_pcb new file mode 100644 index 0000000..a9821c5 --- /dev/null +++ b/F1-nolib/chronometer/kicad/chrono/chrono.kicad_pcb @@ -0,0 +1,5276 @@ +(kicad_pcb (version 20171130) (host pcbnew "(6.0.0-rc1-dev-1613-ga55d9819b)") + + (general + (thickness 1.6) + (drawings 15) + (tracks 562) + (zones 0) + (modules 66) + (nets 44) + ) + + (page A4) + (layers + (0 F.Cu signal) + (31 B.Cu signal) + (32 B.Adhes user) + (33 F.Adhes user) + (34 B.Paste user) + (35 F.Paste user) + (36 B.SilkS user) + (37 F.SilkS user) + (38 B.Mask user) + (39 F.Mask user) + (40 Dwgs.User user) + (41 Cmts.User user) + (42 Eco1.User user) + (43 Eco2.User user) + (44 Edge.Cuts user) + (45 Margin user) + (46 B.CrtYd user) + (47 F.CrtYd user) + (48 B.Fab user) + (49 F.Fab user) + ) + + (setup + (last_trace_width 1) + (user_trace_width 0.5) + (user_trace_width 1) + (user_trace_width 2) + (trace_clearance 0.2) + (zone_clearance 0.508) + (zone_45_only no) + (trace_min 0.2) + (via_size 1.5) + (via_drill 0.6) + (via_min_size 0.4) + (via_min_drill 0.3) + (user_via 2.5 0.8) + (uvia_size 0.3) + (uvia_drill 0.1) + (uvias_allowed no) + (uvia_min_size 0.2) + (uvia_min_drill 0.1) + (edge_width 0.05) + (segment_width 0.2) + (pcb_text_width 0.3) + (pcb_text_size 1.5 1.5) + (mod_edge_width 0.12) + (mod_text_size 1 1) + (mod_text_width 0.15) + (pad_size 1.524 1.524) + (pad_drill 0.762) + (pad_to_mask_clearance 0.051) + (solder_mask_min_width 0.25) + (aux_axis_origin 0 0) + (visible_elements FFFFFF7F) + (pcbplotparams + (layerselection 0x00000_7ffffffe) + (usegerberextensions false) + (usegerberattributes false) + (usegerberadvancedattributes false) + (creategerberjobfile false) + (excludeedgelayer false) + (linewidth 0.100000) + (plotframeref false) + (viasonmask false) + (mode 1) + (useauxorigin false) + (hpglpennumber 1) + (hpglpenspeed 20) + (hpglpendiameter 15.000000) + (psnegative false) + (psa4output false) + (plotreference true) + (plotvalue false) + (plotinvisibletext false) + (padsonsilk false) + (subtractmaskfromsilk false) + (outputformat 5) + (mirror false) + (drillshape 2) + (scaleselection 1) + (outputdirectory "")) + ) + + (net 0 "") + (net 1 GND) + (net 2 +3V3) + (net 3 +5V) + (net 4 /OSC_IN) + (net 5 /OSC_OUT) + (net 6 "Net-(C3-Pad1)") + (net 7 "Net-(D2-Pad2)") + (net 8 "Net-(D3-Pad1)") + (net 9 /LED0) + (net 10 "Net-(D4-Pad2)") + (net 11 "Net-(D5-Pad2)") + (net 12 /LED1) + (net 13 "Net-(J1-Pad2)") + (net 14 "Net-(J2-Pad1)") + (net 15 "Net-(J3-Pad2)") + (net 16 /U2Tx) + (net 17 /U2Rx) + (net 18 "Net-(J5-Pad2)") + (net 19 "Net-(J6-Pad1)") + (net 20 "Net-(J6-Pad2)") + (net 21 /U1Tx) + (net 22 /U1Rx) + (net 23 "Net-(P1-Pad2)") + (net 24 "Net-(P1-Pad3)") + (net 25 /USB_PU) + (net 26 "Net-(Q2-Pad3)") + (net 27 /USBDM) + (net 28 "Net-(R3-Pad1)") + (net 29 "Net-(R4-Pad1)") + (net 30 /USBDP) + (net 31 "Net-(R10-Pad1)") + (net 32 /TRIG0) + (net 33 "Net-(R13-Pad1)") + (net 34 "Net-(R14-Pad1)") + (net 35 /TRIG1) + (net 36 "Net-(R17-Pad2)") + (net 37 /PPS) + (net 38 /TRIG2) + (net 39 /NRST) + (net 40 /BOOT0) + (net 41 /U3Tx) + (net 42 /U3Rx) + (net 43 "Net-(D1-Pad2)") + + (net_class Default "This is the default net class." + (clearance 0.2) + (trace_width 0.25) + (via_dia 1.5) + (via_drill 0.6) + (uvia_dia 0.3) + (uvia_drill 0.1) + (add_net +3V3) + (add_net +5V) + (add_net /BOOT0) + (add_net /LED0) + (add_net /LED1) + (add_net /NRST) + (add_net /OSC_IN) + (add_net /OSC_OUT) + (add_net /PPS) + (add_net /TRIG0) + (add_net /TRIG1) + (add_net /TRIG2) + (add_net /U1Rx) + (add_net /U1Tx) + (add_net /U2Rx) + (add_net /U2Tx) + (add_net /U3Rx) + (add_net /U3Tx) + (add_net /USBDM) + (add_net /USBDP) + (add_net /USB_PU) + (add_net GND) + (add_net "Net-(C3-Pad1)") + (add_net "Net-(D1-Pad2)") + (add_net "Net-(D2-Pad2)") + (add_net "Net-(D3-Pad1)") + (add_net "Net-(D4-Pad2)") + (add_net "Net-(D5-Pad2)") + (add_net "Net-(J1-Pad2)") + (add_net "Net-(J2-Pad1)") + (add_net "Net-(J3-Pad2)") + (add_net "Net-(J5-Pad2)") + (add_net "Net-(J6-Pad1)") + (add_net "Net-(J6-Pad2)") + (add_net "Net-(P1-Pad2)") + (add_net "Net-(P1-Pad3)") + (add_net "Net-(Q2-Pad3)") + (add_net "Net-(R10-Pad1)") + (add_net "Net-(R13-Pad1)") + (add_net "Net-(R14-Pad1)") + (add_net "Net-(R17-Pad2)") + (add_net "Net-(R3-Pad1)") + (add_net "Net-(R4-Pad1)") + ) + + (module MountingHole:MountingHole_3.2mm_M3 (layer F.Cu) (tedit 56D1B4CB) (tstamp 5D168BE7) + (at 97 82) + (descr "Mounting Hole 3.2mm, no annular, M3") + (tags "mounting hole 3.2mm no annular m3") + (attr virtual) + (fp_text reference REF** (at 0 -4.2) (layer F.SilkS) hide + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text value MountingHole_3.2mm_M3 (at 0 4.2) (layer F.Fab) hide + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_circle (center 0 0) (end 3.45 0) (layer F.CrtYd) (width 0.05)) + (fp_circle (center 0 0) (end 3.2 0) (layer Cmts.User) (width 0.15)) + (fp_text user %R (at 0.3 0) (layer F.Fab) hide + (effects (font (size 1 1) (thickness 0.15))) + ) + (pad 1 np_thru_hole circle (at 0 0) (size 3.2 3.2) (drill 3.2) (layers *.Cu *.Mask)) + ) + + (module MountingHole:MountingHole_3.2mm_M3 (layer F.Cu) (tedit 56D1B4CB) (tstamp 5D168BD9) + (at 51.5 93.5) + (descr "Mounting Hole 3.2mm, no annular, M3") + (tags "mounting hole 3.2mm no annular m3") + (attr virtual) + (fp_text reference REF** (at 0 -4.2) (layer F.SilkS) hide + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text value MountingHole_3.2mm_M3 (at 0 4.2) (layer F.Fab) hide + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text user %R (at 0.3 0) (layer F.Fab) hide + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_circle (center 0 0) (end 3.2 0) (layer Cmts.User) (width 0.15)) + (fp_circle (center 0 0) (end 3.45 0) (layer F.CrtYd) (width 0.05)) + (pad 1 np_thru_hole circle (at 0 0) (size 3.2 3.2) (drill 3.2) (layers *.Cu *.Mask)) + ) + + (module MountingHole:MountingHole_3.2mm_M3 (layer F.Cu) (tedit 56D1B4CB) (tstamp 5D168BB4) + (at 138.5 47) + (descr "Mounting Hole 3.2mm, no annular, M3") + (tags "mounting hole 3.2mm no annular m3") + (attr virtual) + (fp_text reference REF** (at 0 -4.2) (layer F.SilkS) hide + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text value MountingHole_3.2mm_M3 (at 0 4.2) (layer F.Fab) hide + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text user %R (at 0.3 0) (layer F.Fab) hide + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_circle (center 0 0) (end 3.2 0) (layer Cmts.User) (width 0.15)) + (fp_circle (center 0 0) (end 3.45 0) (layer F.CrtYd) (width 0.05)) + (pad 1 np_thru_hole circle (at 0 0) (size 3.2 3.2) (drill 3.2) (layers *.Cu *.Mask)) + ) + + (module MountingHole:MountingHole_3.2mm_M3 (layer F.Cu) (tedit 56D1B4CB) (tstamp 5D168B69) + (at 51.5 47) + (descr "Mounting Hole 3.2mm, no annular, M3") + (tags "mounting hole 3.2mm no annular m3") + (attr virtual) + (fp_text reference REF** (at 0 -4.2) (layer F.SilkS) hide + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text value MountingHole_3.2mm_M3 (at 0 4.2) (layer F.Fab) hide + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_circle (center 0 0) (end 3.45 0) (layer F.CrtYd) (width 0.05)) + (fp_circle (center 0 0) (end 3.2 0) (layer Cmts.User) (width 0.15)) + (fp_text user %R (at 0.3 0) (layer F.Fab) hide + (effects (font (size 1 1) (thickness 0.15))) + ) + (pad 1 np_thru_hole circle (at 0 0) (size 3.2 3.2) (drill 3.2) (layers *.Cu *.Mask)) + ) + + (module chrono:L80-R (layer F.Cu) (tedit 5D14811E) (tstamp 5D165190) + (at 65.8162 67.1943) + (path /5D13B322) + (fp_text reference U3 (at 0 4) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text value L80-R (at 0 -8) (layer F.Fab) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_line (start -8 -14) (end -8 3) (layer F.SilkS) (width 0.15)) + (fp_line (start -8 3) (end 8 3) (layer F.SilkS) (width 0.15)) + (fp_line (start 8 3) (end 8 -14) (layer F.SilkS) (width 0.15)) + (fp_line (start 8 -14) (end -8 -14) (layer F.SilkS) (width 0.15)) + (fp_text user 1 (at 10 3) (layer F.SilkS) + (effects (font (size 2.5 2.5) (thickness 0.15))) + ) + (fp_line (start -4 3) (end -4 1) (layer F.SilkS) (width 0.15)) + (fp_line (start -4 1) (end -8 1) (layer F.SilkS) (width 0.15)) + (fp_line (start 8 2) (end 7 3) (layer F.SilkS) (width 0.15)) + (fp_text user Keepout (at -0.05 -8.65) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text user area (at 0 -4.5) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_line (start -18 -24) (end -18 13) (layer F.SilkS) (width 0.15)) + (fp_line (start -18 13) (end 18 13) (layer F.SilkS) (width 0.15)) + (fp_line (start 18 13) (end 18 -24) (layer F.SilkS) (width 0.15)) + (fp_line (start 18 -24) (end -18 -24) (layer F.SilkS) (width 0.15)) + (fp_text user "Clear area" (at 0 -22) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text user "Clear area" (at 0 -22) (layer B.SilkS) + (effects (font (size 1 1) (thickness 0.15)) (justify mirror)) + ) + (fp_line (start -18 -24) (end -18 13) (layer B.SilkS) (width 0.15)) + (fp_line (start -18 13) (end 18 13) (layer B.SilkS) (width 0.15)) + (fp_line (start 18 13) (end 18 -24) (layer B.SilkS) (width 0.15)) + (fp_line (start 18 -24) (end -18 -24) (layer B.SilkS) (width 0.15)) + (pad 1 smd rect (at 8 0) (size 4 2) (layers F.Cu F.Paste F.Mask) + (net 41 /U3Tx)) + (pad 2 smd rect (at 8 -2.54) (size 4 2) (layers F.Cu F.Paste F.Mask) + (net 42 /U3Rx)) + (pad 3 smd rect (at 8 -5.08) (size 4 2) (layers F.Cu F.Paste F.Mask) + (net 1 GND)) + (pad 4 smd rect (at 8 -7.62) (size 4 2) (layers F.Cu F.Paste F.Mask) + (net 2 +3V3)) + (pad 5 smd rect (at 8 -10.16) (size 4 2) (layers F.Cu F.Paste F.Mask) + (net 2 +3V3)) + (pad 6 smd rect (at 8 -12.7) (size 4 2) (layers F.Cu F.Paste F.Mask) + (net 37 /PPS)) + (pad 12 smd rect (at -8 0) (size 4 2) (layers F.Cu F.Paste F.Mask) + (net 1 GND)) + (pad 11 smd rect (at -8 -2.54) (size 4 2) (layers F.Cu F.Paste F.Mask)) + (pad 10 smd rect (at -8 -5.08) (size 4 2) (layers F.Cu F.Paste F.Mask)) + (pad 9 smd rect (at -8 -7.62) (size 4 2) (layers F.Cu F.Paste F.Mask)) + (pad 8 smd rect (at -8 -10.16) (size 4 2) (layers F.Cu F.Paste F.Mask)) + (pad 7 smd rect (at -8 -12.7) (size 4 2) (layers F.Cu F.Paste F.Mask)) + (pad ~ smd circle (at 0 -6.35) (size 0.1 0.1) (layers B.Cu) + (solder_mask_margin 1.5) (solder_paste_margin 1.5) (clearance 1.3) (zone_connect 0)) + (pad ~ smd circle (at 0 -6.35) (size 0.1 0.1) (layers F.Cu) + (solder_mask_margin 1.5) (solder_paste_margin 1.5) (clearance 1.3) (zone_connect 0)) + ) + + (module Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder (layer F.Cu) (tedit 5B301BBE) (tstamp 5D152086) + (at 89.8065 61.5695 90) + (descr "Capacitor SMD 0603 (1608 Metric), square (rectangular) end terminal, IPC_7351 nominal with elongated pad for handsoldering. (Body size source: http://www.tortai-tech.com/upload/download/2011102023233369053.pdf), generated with kicad-footprint-generator") + (tags "capacitor handsolder") + (path /5D4AE2B9) + (attr smd) + (fp_text reference C1 (at -2.4625 -0.0635 180) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text value 0.1 (at 0 1.43 90) (layer F.Fab) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text user %R (at 0 0 90) (layer F.Fab) + (effects (font (size 0.4 0.4) (thickness 0.06))) + ) + (fp_line (start 1.65 0.73) (end -1.65 0.73) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.65 -0.73) (end 1.65 0.73) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.65 -0.73) (end 1.65 -0.73) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.65 0.73) (end -1.65 -0.73) (layer F.CrtYd) (width 0.05)) + (fp_line (start -0.171267 0.51) (end 0.171267 0.51) (layer F.SilkS) (width 0.12)) + (fp_line (start -0.171267 -0.51) (end 0.171267 -0.51) (layer F.SilkS) (width 0.12)) + (fp_line (start 0.8 0.4) (end -0.8 0.4) (layer F.Fab) (width 0.1)) + (fp_line (start 0.8 -0.4) (end 0.8 0.4) (layer F.Fab) (width 0.1)) + (fp_line (start -0.8 -0.4) (end 0.8 -0.4) (layer F.Fab) (width 0.1)) + (fp_line (start -0.8 0.4) (end -0.8 -0.4) (layer F.Fab) (width 0.1)) + (pad 2 smd roundrect (at 0.875 0 90) (size 1.05 0.95) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.25) + (net 1 GND)) + (pad 1 smd roundrect (at -0.875 0 90) (size 1.05 0.95) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.25) + (net 39 /NRST)) + (model ${KISYS3DMOD}/Capacitor_SMD.3dshapes/C_0603_1608Metric.wrl + (at (xyz 0 0 0)) + (scale (xyz 1 1 1)) + (rotate (xyz 0 0 0)) + ) + ) + + (module Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder (layer F.Cu) (tedit 5B301BBE) (tstamp 5D152097) + (at 107.029 50.3795 180) + (descr "Capacitor SMD 0603 (1608 Metric), square (rectangular) end terminal, IPC_7351 nominal with elongated pad for handsoldering. (Body size source: http://www.tortai-tech.com/upload/download/2011102023233369053.pdf), generated with kicad-footprint-generator") + (tags "capacitor handsolder") + (path /590D4150) + (attr smd) + (fp_text reference C2 (at -0.0775 1.4605 180) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text value 0.1 (at 0 1.43 180) (layer F.Fab) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_line (start -0.8 0.4) (end -0.8 -0.4) (layer F.Fab) (width 0.1)) + (fp_line (start -0.8 -0.4) (end 0.8 -0.4) (layer F.Fab) (width 0.1)) + (fp_line (start 0.8 -0.4) (end 0.8 0.4) (layer F.Fab) (width 0.1)) + (fp_line (start 0.8 0.4) (end -0.8 0.4) (layer F.Fab) (width 0.1)) + (fp_line (start -0.171267 -0.51) (end 0.171267 -0.51) (layer F.SilkS) (width 0.12)) + (fp_line (start -0.171267 0.51) (end 0.171267 0.51) (layer F.SilkS) (width 0.12)) + (fp_line (start -1.65 0.73) (end -1.65 -0.73) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.65 -0.73) (end 1.65 -0.73) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.65 -0.73) (end 1.65 0.73) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.65 0.73) (end -1.65 0.73) (layer F.CrtYd) (width 0.05)) + (fp_text user %R (at 0 0 180) (layer F.Fab) + (effects (font (size 0.4 0.4) (thickness 0.06))) + ) + (pad 1 smd roundrect (at -0.875 0 180) (size 1.05 0.95) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.25) + (net 40 /BOOT0)) + (pad 2 smd roundrect (at 0.875 0 180) (size 1.05 0.95) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.25) + (net 2 +3V3)) + (model ${KISYS3DMOD}/Capacitor_SMD.3dshapes/C_0603_1608Metric.wrl + (at (xyz 0 0 0)) + (scale (xyz 1 1 1)) + (rotate (xyz 0 0 0)) + ) + ) + + (module Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder (layer F.Cu) (tedit 5B301BBE) (tstamp 5D1520A8) + (at 117.048 81.29 90) + (descr "Capacitor SMD 0603 (1608 Metric), square (rectangular) end terminal, IPC_7351 nominal with elongated pad for handsoldering. (Body size source: http://www.tortai-tech.com/upload/download/2011102023233369053.pdf), generated with kicad-footprint-generator") + (tags "capacitor handsolder") + (path /596772D4) + (attr smd) + (fp_text reference C3 (at 2.526 0 180) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text value 0.1 (at 0 1.43 90) (layer F.Fab) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_line (start -0.8 0.4) (end -0.8 -0.4) (layer F.Fab) (width 0.1)) + (fp_line (start -0.8 -0.4) (end 0.8 -0.4) (layer F.Fab) (width 0.1)) + (fp_line (start 0.8 -0.4) (end 0.8 0.4) (layer F.Fab) (width 0.1)) + (fp_line (start 0.8 0.4) (end -0.8 0.4) (layer F.Fab) (width 0.1)) + (fp_line (start -0.171267 -0.51) (end 0.171267 -0.51) (layer F.SilkS) (width 0.12)) + (fp_line (start -0.171267 0.51) (end 0.171267 0.51) (layer F.SilkS) (width 0.12)) + (fp_line (start -1.65 0.73) (end -1.65 -0.73) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.65 -0.73) (end 1.65 -0.73) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.65 -0.73) (end 1.65 0.73) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.65 0.73) (end -1.65 0.73) (layer F.CrtYd) (width 0.05)) + (fp_text user %R (at 0 0 90) (layer F.Fab) + (effects (font (size 0.4 0.4) (thickness 0.06))) + ) + (pad 1 smd roundrect (at -0.875 0 90) (size 1.05 0.95) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.25) + (net 6 "Net-(C3-Pad1)")) + (pad 2 smd roundrect (at 0.875 0 90) (size 1.05 0.95) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.25) + (net 1 GND)) + (model ${KISYS3DMOD}/Capacitor_SMD.3dshapes/C_0603_1608Metric.wrl + (at (xyz 0 0 0)) + (scale (xyz 1 1 1)) + (rotate (xyz 0 0 0)) + ) + ) + + (module Capacitor_Tantalum_SMD:CP_EIA-3216-18_Kemet-A_Pad1.58x1.35mm_HandSolder (layer F.Cu) (tedit 5B301BBE) (tstamp 5D1520BB) + (at 113.0475 83.186 90) + (descr "Tantalum Capacitor SMD Kemet-A (3216-18 Metric), IPC_7351 nominal, (Body size from: http://www.kemet.com/Lists/ProductCatalog/Attachments/253/KEM_TC101_STD.pdf), generated with kicad-footprint-generator") + (tags "capacitor tantalum") + (path /58C43A3B) + (attr smd) + (fp_text reference C4 (at -0.0865 -2.032 180) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text value 47u (at 0 1.75 90) (layer F.Fab) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text user %R (at 0 0 90) (layer F.Fab) + (effects (font (size 0.8 0.8) (thickness 0.12))) + ) + (fp_line (start 2.48 1.05) (end -2.48 1.05) (layer F.CrtYd) (width 0.05)) + (fp_line (start 2.48 -1.05) (end 2.48 1.05) (layer F.CrtYd) (width 0.05)) + (fp_line (start -2.48 -1.05) (end 2.48 -1.05) (layer F.CrtYd) (width 0.05)) + (fp_line (start -2.48 1.05) (end -2.48 -1.05) (layer F.CrtYd) (width 0.05)) + (fp_line (start -2.485 0.935) (end 1.6 0.935) (layer F.SilkS) (width 0.12)) + (fp_line (start -2.485 -0.935) (end -2.485 0.935) (layer F.SilkS) (width 0.12)) + (fp_line (start 1.6 -0.935) (end -2.485 -0.935) (layer F.SilkS) (width 0.12)) + (fp_line (start 1.6 0.8) (end 1.6 -0.8) (layer F.Fab) (width 0.1)) + (fp_line (start -1.6 0.8) (end 1.6 0.8) (layer F.Fab) (width 0.1)) + (fp_line (start -1.6 -0.4) (end -1.6 0.8) (layer F.Fab) (width 0.1)) + (fp_line (start -1.2 -0.8) (end -1.6 -0.4) (layer F.Fab) (width 0.1)) + (fp_line (start 1.6 -0.8) (end -1.2 -0.8) (layer F.Fab) (width 0.1)) + (pad 2 smd roundrect (at 1.4375 0 90) (size 1.575 1.35) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.185185) + (net 1 GND)) + (pad 1 smd roundrect (at -1.4375 0 90) (size 1.575 1.35) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.185185) + (net 6 "Net-(C3-Pad1)")) + (model ${KISYS3DMOD}/Capacitor_Tantalum_SMD.3dshapes/CP_EIA-3216-18_Kemet-A.wrl + (at (xyz 0 0 0)) + (scale (xyz 1 1 1)) + (rotate (xyz 0 0 0)) + ) + ) + + (module Capacitor_SMD:C_1206_3216Metric_Pad1.42x1.75mm_HandSolder (layer F.Cu) (tedit 5B301BBE) (tstamp 5D1520CC) + (at 81.5134 61.1634 90) + (descr "Capacitor SMD 1206 (3216 Metric), square (rectangular) end terminal, IPC_7351 nominal with elongated pad for handsoldering. (Body size source: http://www.tortai-tech.com/upload/download/2011102023233369053.pdf), generated with kicad-footprint-generator") + (tags "capacitor handsolder") + (path /5DB80168) + (attr smd) + (fp_text reference C5 (at 3.2274 0.1651 180) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text value 10u (at 0 1.82 90) (layer F.Fab) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_line (start -1.6 0.8) (end -1.6 -0.8) (layer F.Fab) (width 0.1)) + (fp_line (start -1.6 -0.8) (end 1.6 -0.8) (layer F.Fab) (width 0.1)) + (fp_line (start 1.6 -0.8) (end 1.6 0.8) (layer F.Fab) (width 0.1)) + (fp_line (start 1.6 0.8) (end -1.6 0.8) (layer F.Fab) (width 0.1)) + (fp_line (start -0.602064 -0.91) (end 0.602064 -0.91) (layer F.SilkS) (width 0.12)) + (fp_line (start -0.602064 0.91) (end 0.602064 0.91) (layer F.SilkS) (width 0.12)) + (fp_line (start -2.45 1.12) (end -2.45 -1.12) (layer F.CrtYd) (width 0.05)) + (fp_line (start -2.45 -1.12) (end 2.45 -1.12) (layer F.CrtYd) (width 0.05)) + (fp_line (start 2.45 -1.12) (end 2.45 1.12) (layer F.CrtYd) (width 0.05)) + (fp_line (start 2.45 1.12) (end -2.45 1.12) (layer F.CrtYd) (width 0.05)) + (fp_text user %R (at 0 0 90) (layer F.Fab) + (effects (font (size 0.8 0.8) (thickness 0.12))) + ) + (pad 1 smd roundrect (at -1.4875 0 90) (size 1.425 1.75) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.175439) + (net 1 GND)) + (pad 2 smd roundrect (at 1.4875 0 90) (size 1.425 1.75) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.175439) + (net 2 +3V3)) + (model ${KISYS3DMOD}/Capacitor_SMD.3dshapes/C_1206_3216Metric.wrl + (at (xyz 0 0 0)) + (scale (xyz 1 1 1)) + (rotate (xyz 0 0 0)) + ) + ) + + (module Capacitor_THT:CP_Radial_D8.0mm_P3.50mm (layer B.Cu) (tedit 5AE50EF0) (tstamp 5D152175) + (at 133.939 81.3675 90) + (descr "CP, Radial series, Radial, pin pitch=3.50mm, , diameter=8mm, Electrolytic Capacitor") + (tags "CP Radial series Radial pin pitch 3.50mm diameter 8mm Electrolytic Capacitor") + (path /58C4396A) + (fp_text reference C6 (at 6.858 -0.0635 180) (layer B.SilkS) + (effects (font (size 1 1) (thickness 0.15)) (justify mirror)) + ) + (fp_text value 100u (at 1.75 -5.25 90) (layer B.Fab) + (effects (font (size 1 1) (thickness 0.15)) (justify mirror)) + ) + (fp_circle (center 1.75 0) (end 5.75 0) (layer B.Fab) (width 0.1)) + (fp_circle (center 1.75 0) (end 5.87 0) (layer B.SilkS) (width 0.12)) + (fp_circle (center 1.75 0) (end 6 0) (layer B.CrtYd) (width 0.05)) + (fp_line (start -1.676759 1.7475) (end -0.876759 1.7475) (layer B.Fab) (width 0.1)) + (fp_line (start -1.276759 2.1475) (end -1.276759 1.3475) (layer B.Fab) (width 0.1)) + (fp_line (start 1.75 4.08) (end 1.75 -4.08) (layer B.SilkS) (width 0.12)) + (fp_line (start 1.79 4.08) (end 1.79 -4.08) (layer B.SilkS) (width 0.12)) + (fp_line (start 1.83 4.08) (end 1.83 -4.08) (layer B.SilkS) (width 0.12)) + (fp_line (start 1.87 4.079) (end 1.87 -4.079) (layer B.SilkS) (width 0.12)) + (fp_line (start 1.91 4.077) (end 1.91 -4.077) (layer B.SilkS) (width 0.12)) + (fp_line (start 1.95 4.076) (end 1.95 -4.076) (layer B.SilkS) (width 0.12)) + (fp_line (start 1.99 4.074) (end 1.99 -4.074) (layer B.SilkS) (width 0.12)) + (fp_line (start 2.03 4.071) (end 2.03 -4.071) (layer B.SilkS) (width 0.12)) + (fp_line (start 2.07 4.068) (end 2.07 -4.068) (layer B.SilkS) (width 0.12)) + (fp_line (start 2.11 4.065) (end 2.11 -4.065) (layer B.SilkS) (width 0.12)) + (fp_line (start 2.15 4.061) (end 2.15 -4.061) (layer B.SilkS) (width 0.12)) + (fp_line (start 2.19 4.057) (end 2.19 -4.057) (layer B.SilkS) (width 0.12)) + (fp_line (start 2.23 4.052) (end 2.23 -4.052) (layer B.SilkS) (width 0.12)) + (fp_line (start 2.27 4.048) (end 2.27 -4.048) (layer B.SilkS) (width 0.12)) + (fp_line (start 2.31 4.042) (end 2.31 -4.042) (layer B.SilkS) (width 0.12)) + (fp_line (start 2.35 4.037) (end 2.35 -4.037) (layer B.SilkS) (width 0.12)) + (fp_line (start 2.39 4.03) (end 2.39 -4.03) (layer B.SilkS) (width 0.12)) + (fp_line (start 2.43 4.024) (end 2.43 -4.024) (layer B.SilkS) (width 0.12)) + (fp_line (start 2.471 4.017) (end 2.471 1.04) (layer B.SilkS) (width 0.12)) + (fp_line (start 2.471 -1.04) (end 2.471 -4.017) (layer B.SilkS) (width 0.12)) + (fp_line (start 2.511 4.01) (end 2.511 1.04) (layer B.SilkS) (width 0.12)) + (fp_line (start 2.511 -1.04) (end 2.511 -4.01) (layer B.SilkS) (width 0.12)) + (fp_line (start 2.551 4.002) (end 2.551 1.04) (layer B.SilkS) (width 0.12)) + (fp_line (start 2.551 -1.04) (end 2.551 -4.002) (layer B.SilkS) (width 0.12)) + (fp_line (start 2.591 3.994) (end 2.591 1.04) (layer B.SilkS) (width 0.12)) + (fp_line (start 2.591 -1.04) (end 2.591 -3.994) (layer B.SilkS) (width 0.12)) + (fp_line (start 2.631 3.985) (end 2.631 1.04) (layer B.SilkS) (width 0.12)) + (fp_line (start 2.631 -1.04) (end 2.631 -3.985) (layer B.SilkS) (width 0.12)) + (fp_line (start 2.671 3.976) (end 2.671 1.04) (layer B.SilkS) (width 0.12)) + (fp_line (start 2.671 -1.04) (end 2.671 -3.976) (layer B.SilkS) (width 0.12)) + (fp_line (start 2.711 3.967) (end 2.711 1.04) (layer B.SilkS) (width 0.12)) + (fp_line (start 2.711 -1.04) (end 2.711 -3.967) (layer B.SilkS) (width 0.12)) + (fp_line (start 2.751 3.957) (end 2.751 1.04) (layer B.SilkS) (width 0.12)) + (fp_line (start 2.751 -1.04) (end 2.751 -3.957) (layer B.SilkS) (width 0.12)) + (fp_line (start 2.791 3.947) (end 2.791 1.04) (layer B.SilkS) (width 0.12)) + (fp_line (start 2.791 -1.04) (end 2.791 -3.947) (layer B.SilkS) (width 0.12)) + (fp_line (start 2.831 3.936) (end 2.831 1.04) (layer B.SilkS) (width 0.12)) + (fp_line (start 2.831 -1.04) (end 2.831 -3.936) (layer B.SilkS) (width 0.12)) + (fp_line (start 2.871 3.925) (end 2.871 1.04) (layer B.SilkS) (width 0.12)) + (fp_line (start 2.871 -1.04) (end 2.871 -3.925) (layer B.SilkS) (width 0.12)) + (fp_line (start 2.911 3.914) (end 2.911 1.04) (layer B.SilkS) (width 0.12)) + (fp_line (start 2.911 -1.04) (end 2.911 -3.914) (layer B.SilkS) (width 0.12)) + (fp_line (start 2.951 3.902) (end 2.951 1.04) (layer B.SilkS) (width 0.12)) + (fp_line (start 2.951 -1.04) (end 2.951 -3.902) (layer B.SilkS) (width 0.12)) + (fp_line (start 2.991 3.889) (end 2.991 1.04) (layer B.SilkS) (width 0.12)) + (fp_line (start 2.991 -1.04) (end 2.991 -3.889) (layer B.SilkS) (width 0.12)) + (fp_line (start 3.031 3.877) (end 3.031 1.04) (layer B.SilkS) (width 0.12)) + (fp_line (start 3.031 -1.04) (end 3.031 -3.877) (layer B.SilkS) (width 0.12)) + (fp_line (start 3.071 3.863) (end 3.071 1.04) (layer B.SilkS) (width 0.12)) + (fp_line (start 3.071 -1.04) (end 3.071 -3.863) (layer B.SilkS) (width 0.12)) + (fp_line (start 3.111 3.85) (end 3.111 1.04) (layer B.SilkS) (width 0.12)) + (fp_line (start 3.111 -1.04) (end 3.111 -3.85) (layer B.SilkS) (width 0.12)) + (fp_line (start 3.151 3.835) (end 3.151 1.04) (layer B.SilkS) (width 0.12)) + (fp_line (start 3.151 -1.04) (end 3.151 -3.835) (layer B.SilkS) (width 0.12)) + (fp_line (start 3.191 3.821) (end 3.191 1.04) (layer B.SilkS) (width 0.12)) + (fp_line (start 3.191 -1.04) (end 3.191 -3.821) (layer B.SilkS) (width 0.12)) + (fp_line (start 3.231 3.805) (end 3.231 1.04) (layer B.SilkS) (width 0.12)) + (fp_line (start 3.231 -1.04) (end 3.231 -3.805) (layer B.SilkS) (width 0.12)) + (fp_line (start 3.271 3.79) (end 3.271 1.04) (layer B.SilkS) (width 0.12)) + (fp_line (start 3.271 -1.04) (end 3.271 -3.79) (layer B.SilkS) (width 0.12)) + (fp_line (start 3.311 3.774) (end 3.311 1.04) (layer B.SilkS) (width 0.12)) + (fp_line (start 3.311 -1.04) (end 3.311 -3.774) (layer B.SilkS) (width 0.12)) + (fp_line (start 3.351 3.757) (end 3.351 1.04) (layer B.SilkS) (width 0.12)) + (fp_line (start 3.351 -1.04) (end 3.351 -3.757) (layer B.SilkS) (width 0.12)) + (fp_line (start 3.391 3.74) (end 3.391 1.04) (layer B.SilkS) (width 0.12)) + (fp_line (start 3.391 -1.04) (end 3.391 -3.74) (layer B.SilkS) (width 0.12)) + (fp_line (start 3.431 3.722) (end 3.431 1.04) (layer B.SilkS) (width 0.12)) + (fp_line (start 3.431 -1.04) (end 3.431 -3.722) (layer B.SilkS) (width 0.12)) + (fp_line (start 3.471 3.704) (end 3.471 1.04) (layer B.SilkS) (width 0.12)) + (fp_line (start 3.471 -1.04) (end 3.471 -3.704) (layer B.SilkS) (width 0.12)) + (fp_line (start 3.511 3.686) (end 3.511 1.04) (layer B.SilkS) (width 0.12)) + (fp_line (start 3.511 -1.04) (end 3.511 -3.686) (layer B.SilkS) (width 0.12)) + (fp_line (start 3.551 3.666) (end 3.551 1.04) (layer B.SilkS) (width 0.12)) + (fp_line (start 3.551 -1.04) (end 3.551 -3.666) (layer B.SilkS) (width 0.12)) + (fp_line (start 3.591 3.647) (end 3.591 1.04) (layer B.SilkS) (width 0.12)) + (fp_line (start 3.591 -1.04) (end 3.591 -3.647) (layer B.SilkS) (width 0.12)) + (fp_line (start 3.631 3.627) (end 3.631 1.04) (layer B.SilkS) (width 0.12)) + (fp_line (start 3.631 -1.04) (end 3.631 -3.627) (layer B.SilkS) (width 0.12)) + (fp_line (start 3.671 3.606) (end 3.671 1.04) (layer B.SilkS) (width 0.12)) + (fp_line (start 3.671 -1.04) (end 3.671 -3.606) (layer B.SilkS) (width 0.12)) + (fp_line (start 3.711 3.584) (end 3.711 1.04) (layer B.SilkS) (width 0.12)) + (fp_line (start 3.711 -1.04) (end 3.711 -3.584) (layer B.SilkS) (width 0.12)) + (fp_line (start 3.751 3.562) (end 3.751 1.04) (layer B.SilkS) (width 0.12)) + (fp_line (start 3.751 -1.04) (end 3.751 -3.562) (layer B.SilkS) (width 0.12)) + (fp_line (start 3.791 3.54) (end 3.791 1.04) (layer B.SilkS) (width 0.12)) + (fp_line (start 3.791 -1.04) (end 3.791 -3.54) (layer B.SilkS) (width 0.12)) + (fp_line (start 3.831 3.517) (end 3.831 1.04) (layer B.SilkS) (width 0.12)) + (fp_line (start 3.831 -1.04) (end 3.831 -3.517) (layer B.SilkS) (width 0.12)) + (fp_line (start 3.871 3.493) (end 3.871 1.04) (layer B.SilkS) (width 0.12)) + (fp_line (start 3.871 -1.04) (end 3.871 -3.493) (layer B.SilkS) (width 0.12)) + (fp_line (start 3.911 3.469) (end 3.911 1.04) (layer B.SilkS) (width 0.12)) + (fp_line (start 3.911 -1.04) (end 3.911 -3.469) (layer B.SilkS) (width 0.12)) + (fp_line (start 3.951 3.444) (end 3.951 1.04) (layer B.SilkS) (width 0.12)) + (fp_line (start 3.951 -1.04) (end 3.951 -3.444) (layer B.SilkS) (width 0.12)) + (fp_line (start 3.991 3.418) (end 3.991 1.04) (layer B.SilkS) (width 0.12)) + (fp_line (start 3.991 -1.04) (end 3.991 -3.418) (layer B.SilkS) (width 0.12)) + (fp_line (start 4.031 3.392) (end 4.031 1.04) (layer B.SilkS) (width 0.12)) + (fp_line (start 4.031 -1.04) (end 4.031 -3.392) (layer B.SilkS) (width 0.12)) + (fp_line (start 4.071 3.365) (end 4.071 1.04) (layer B.SilkS) (width 0.12)) + (fp_line (start 4.071 -1.04) (end 4.071 -3.365) (layer B.SilkS) (width 0.12)) + (fp_line (start 4.111 3.338) (end 4.111 1.04) (layer B.SilkS) (width 0.12)) + (fp_line (start 4.111 -1.04) (end 4.111 -3.338) (layer B.SilkS) (width 0.12)) + (fp_line (start 4.151 3.309) (end 4.151 1.04) (layer B.SilkS) (width 0.12)) + (fp_line (start 4.151 -1.04) (end 4.151 -3.309) (layer B.SilkS) (width 0.12)) + (fp_line (start 4.191 3.28) (end 4.191 1.04) (layer B.SilkS) (width 0.12)) + (fp_line (start 4.191 -1.04) (end 4.191 -3.28) (layer B.SilkS) (width 0.12)) + (fp_line (start 4.231 3.25) (end 4.231 1.04) (layer B.SilkS) (width 0.12)) + (fp_line (start 4.231 -1.04) (end 4.231 -3.25) (layer B.SilkS) (width 0.12)) + (fp_line (start 4.271 3.22) (end 4.271 1.04) (layer B.SilkS) (width 0.12)) + (fp_line (start 4.271 -1.04) (end 4.271 -3.22) (layer B.SilkS) (width 0.12)) + (fp_line (start 4.311 3.189) (end 4.311 1.04) (layer B.SilkS) (width 0.12)) + (fp_line (start 4.311 -1.04) (end 4.311 -3.189) (layer B.SilkS) (width 0.12)) + (fp_line (start 4.351 3.156) (end 4.351 1.04) (layer B.SilkS) (width 0.12)) + (fp_line (start 4.351 -1.04) (end 4.351 -3.156) (layer B.SilkS) (width 0.12)) + (fp_line (start 4.391 3.124) (end 4.391 1.04) (layer B.SilkS) (width 0.12)) + (fp_line (start 4.391 -1.04) (end 4.391 -3.124) (layer B.SilkS) (width 0.12)) + (fp_line (start 4.431 3.09) (end 4.431 1.04) (layer B.SilkS) (width 0.12)) + (fp_line (start 4.431 -1.04) (end 4.431 -3.09) (layer B.SilkS) (width 0.12)) + (fp_line (start 4.471 3.055) (end 4.471 1.04) (layer B.SilkS) (width 0.12)) + (fp_line (start 4.471 -1.04) (end 4.471 -3.055) (layer B.SilkS) (width 0.12)) + (fp_line (start 4.511 3.019) (end 4.511 1.04) (layer B.SilkS) (width 0.12)) + (fp_line (start 4.511 -1.04) (end 4.511 -3.019) (layer B.SilkS) (width 0.12)) + (fp_line (start 4.551 2.983) (end 4.551 -2.983) (layer B.SilkS) (width 0.12)) + (fp_line (start 4.591 2.945) (end 4.591 -2.945) (layer B.SilkS) (width 0.12)) + (fp_line (start 4.631 2.907) (end 4.631 -2.907) (layer B.SilkS) (width 0.12)) + (fp_line (start 4.671 2.867) (end 4.671 -2.867) (layer B.SilkS) (width 0.12)) + (fp_line (start 4.711 2.826) (end 4.711 -2.826) (layer B.SilkS) (width 0.12)) + (fp_line (start 4.751 2.784) (end 4.751 -2.784) (layer B.SilkS) (width 0.12)) + (fp_line (start 4.791 2.741) (end 4.791 -2.741) (layer B.SilkS) (width 0.12)) + (fp_line (start 4.831 2.697) (end 4.831 -2.697) (layer B.SilkS) (width 0.12)) + (fp_line (start 4.871 2.651) (end 4.871 -2.651) (layer B.SilkS) (width 0.12)) + (fp_line (start 4.911 2.604) (end 4.911 -2.604) (layer B.SilkS) (width 0.12)) + (fp_line (start 4.951 2.556) (end 4.951 -2.556) (layer B.SilkS) (width 0.12)) + (fp_line (start 4.991 2.505) (end 4.991 -2.505) (layer B.SilkS) (width 0.12)) + (fp_line (start 5.031 2.454) (end 5.031 -2.454) (layer B.SilkS) (width 0.12)) + (fp_line (start 5.071 2.4) (end 5.071 -2.4) (layer B.SilkS) (width 0.12)) + (fp_line (start 5.111 2.345) (end 5.111 -2.345) (layer B.SilkS) (width 0.12)) + (fp_line (start 5.151 2.287) (end 5.151 -2.287) (layer B.SilkS) (width 0.12)) + (fp_line (start 5.191 2.228) (end 5.191 -2.228) (layer B.SilkS) (width 0.12)) + (fp_line (start 5.231 2.166) (end 5.231 -2.166) (layer B.SilkS) (width 0.12)) + (fp_line (start 5.271 2.102) (end 5.271 -2.102) (layer B.SilkS) (width 0.12)) + (fp_line (start 5.311 2.034) (end 5.311 -2.034) (layer B.SilkS) (width 0.12)) + (fp_line (start 5.351 1.964) (end 5.351 -1.964) (layer B.SilkS) (width 0.12)) + (fp_line (start 5.391 1.89) (end 5.391 -1.89) (layer B.SilkS) (width 0.12)) + (fp_line (start 5.431 1.813) (end 5.431 -1.813) (layer B.SilkS) (width 0.12)) + (fp_line (start 5.471 1.731) (end 5.471 -1.731) (layer B.SilkS) (width 0.12)) + (fp_line (start 5.511 1.645) (end 5.511 -1.645) (layer B.SilkS) (width 0.12)) + (fp_line (start 5.551 1.552) (end 5.551 -1.552) (layer B.SilkS) (width 0.12)) + (fp_line (start 5.591 1.453) (end 5.591 -1.453) (layer B.SilkS) (width 0.12)) + (fp_line (start 5.631 1.346) (end 5.631 -1.346) (layer B.SilkS) (width 0.12)) + (fp_line (start 5.671 1.229) (end 5.671 -1.229) (layer B.SilkS) (width 0.12)) + (fp_line (start 5.711 1.098) (end 5.711 -1.098) (layer B.SilkS) (width 0.12)) + (fp_line (start 5.751 0.948) (end 5.751 -0.948) (layer B.SilkS) (width 0.12)) + (fp_line (start 5.791 0.768) (end 5.791 -0.768) (layer B.SilkS) (width 0.12)) + (fp_line (start 5.831 0.533) (end 5.831 -0.533) (layer B.SilkS) (width 0.12)) + (fp_line (start -2.659698 2.315) (end -1.859698 2.315) (layer B.SilkS) (width 0.12)) + (fp_line (start -2.259698 2.715) (end -2.259698 1.915) (layer B.SilkS) (width 0.12)) + (fp_text user %R (at 1.75 0 90) (layer B.Fab) + (effects (font (size 1 1) (thickness 0.15)) (justify mirror)) + ) + (pad 1 thru_hole rect (at 0 0 90) (size 1.6 1.6) (drill 0.8) (layers *.Cu *.Mask) + (net 3 +5V)) + (pad 2 thru_hole circle (at 3.5 0 90) (size 1.6 1.6) (drill 0.8) (layers *.Cu *.Mask) + (net 1 GND)) + (model ${KISYS3DMOD}/Capacitor_THT.3dshapes/CP_Radial_D8.0mm_P3.50mm.wrl + (at (xyz 0 0 0)) + (scale (xyz 1 1 1)) + (rotate (xyz 0 0 0)) + ) + ) + + (module Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder (layer F.Cu) (tedit 5B301BBE) (tstamp 5D154D36) + (at 78.1098 60.9573 90) + (descr "Capacitor SMD 0603 (1608 Metric), square (rectangular) end terminal, IPC_7351 nominal with elongated pad for handsoldering. (Body size source: http://www.tortai-tech.com/upload/download/2011102023233369053.pdf), generated with kicad-footprint-generator") + (tags "capacitor handsolder") + (path /5DB8A65B) + (attr smd) + (fp_text reference C7 (at 2.4625 0.0254 180) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text value 0.1 (at 0 1.43 90) (layer F.Fab) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_line (start -0.8 0.4) (end -0.8 -0.4) (layer F.Fab) (width 0.1)) + (fp_line (start -0.8 -0.4) (end 0.8 -0.4) (layer F.Fab) (width 0.1)) + (fp_line (start 0.8 -0.4) (end 0.8 0.4) (layer F.Fab) (width 0.1)) + (fp_line (start 0.8 0.4) (end -0.8 0.4) (layer F.Fab) (width 0.1)) + (fp_line (start -0.171267 -0.51) (end 0.171267 -0.51) (layer F.SilkS) (width 0.12)) + (fp_line (start -0.171267 0.51) (end 0.171267 0.51) (layer F.SilkS) (width 0.12)) + (fp_line (start -1.65 0.73) (end -1.65 -0.73) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.65 -0.73) (end 1.65 -0.73) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.65 -0.73) (end 1.65 0.73) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.65 0.73) (end -1.65 0.73) (layer F.CrtYd) (width 0.05)) + (fp_text user %R (at 0 0 90) (layer F.Fab) + (effects (font (size 0.4 0.4) (thickness 0.06))) + ) + (pad 1 smd roundrect (at -0.875 0 90) (size 1.05 0.95) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.25) + (net 1 GND)) + (pad 2 smd roundrect (at 0.875 0 90) (size 1.05 0.95) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.25) + (net 2 +3V3)) + (model ${KISYS3DMOD}/Capacitor_SMD.3dshapes/C_0603_1608Metric.wrl + (at (xyz 0 0 0)) + (scale (xyz 1 1 1)) + (rotate (xyz 0 0 0)) + ) + ) + + (module Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder (layer F.Cu) (tedit 5B301BBE) (tstamp 5D152197) + (at 131.78 79.286 90) + (descr "Capacitor SMD 0603 (1608 Metric), square (rectangular) end terminal, IPC_7351 nominal with elongated pad for handsoldering. (Body size source: http://www.tortai-tech.com/upload/download/2011102023233369053.pdf), generated with kicad-footprint-generator") + (tags "capacitor handsolder") + (path /5A4FA4E4) + (attr smd) + (fp_text reference C8 (at 0.8395 -1.778 180) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text value 0.1 (at 0 1.43 90) (layer F.Fab) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text user %R (at 0 0 90) (layer F.Fab) + (effects (font (size 0.4 0.4) (thickness 0.06))) + ) + (fp_line (start 1.65 0.73) (end -1.65 0.73) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.65 -0.73) (end 1.65 0.73) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.65 -0.73) (end 1.65 -0.73) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.65 0.73) (end -1.65 -0.73) (layer F.CrtYd) (width 0.05)) + (fp_line (start -0.171267 0.51) (end 0.171267 0.51) (layer F.SilkS) (width 0.12)) + (fp_line (start -0.171267 -0.51) (end 0.171267 -0.51) (layer F.SilkS) (width 0.12)) + (fp_line (start 0.8 0.4) (end -0.8 0.4) (layer F.Fab) (width 0.1)) + (fp_line (start 0.8 -0.4) (end 0.8 0.4) (layer F.Fab) (width 0.1)) + (fp_line (start -0.8 -0.4) (end 0.8 -0.4) (layer F.Fab) (width 0.1)) + (fp_line (start -0.8 0.4) (end -0.8 -0.4) (layer F.Fab) (width 0.1)) + (pad 2 smd roundrect (at 0.875 0 90) (size 1.05 0.95) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.25) + (net 1 GND)) + (pad 1 smd roundrect (at -0.875 0 90) (size 1.05 0.95) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.25) + (net 3 +5V)) + (model ${KISYS3DMOD}/Capacitor_SMD.3dshapes/C_0603_1608Metric.wrl + (at (xyz 0 0 0)) + (scale (xyz 1 1 1)) + (rotate (xyz 0 0 0)) + ) + ) + + (module Capacitor_Tantalum_SMD:CP_EIA-3216-18_Kemet-A_Pad1.58x1.35mm_HandSolder (layer F.Cu) (tedit 5B301BBE) (tstamp 5D1521AA) + (at 133.558 50.674 270) + (descr "Tantalum Capacitor SMD Kemet-A (3216-18 Metric), IPC_7351 nominal, (Body size from: http://www.kemet.com/Lists/ProductCatalog/Attachments/253/KEM_TC101_STD.pdf), generated with kicad-footprint-generator") + (tags "capacitor tantalum") + (path /5D4AE2B5) + (attr smd) + (fp_text reference C9 (at 0.023 -1.9685) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text value 47u (at 0 1.75 270) (layer F.Fab) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_line (start 1.6 -0.8) (end -1.2 -0.8) (layer F.Fab) (width 0.1)) + (fp_line (start -1.2 -0.8) (end -1.6 -0.4) (layer F.Fab) (width 0.1)) + (fp_line (start -1.6 -0.4) (end -1.6 0.8) (layer F.Fab) (width 0.1)) + (fp_line (start -1.6 0.8) (end 1.6 0.8) (layer F.Fab) (width 0.1)) + (fp_line (start 1.6 0.8) (end 1.6 -0.8) (layer F.Fab) (width 0.1)) + (fp_line (start 1.6 -0.935) (end -2.485 -0.935) (layer F.SilkS) (width 0.12)) + (fp_line (start -2.485 -0.935) (end -2.485 0.935) (layer F.SilkS) (width 0.12)) + (fp_line (start -2.485 0.935) (end 1.6 0.935) (layer F.SilkS) (width 0.12)) + (fp_line (start -2.48 1.05) (end -2.48 -1.05) (layer F.CrtYd) (width 0.05)) + (fp_line (start -2.48 -1.05) (end 2.48 -1.05) (layer F.CrtYd) (width 0.05)) + (fp_line (start 2.48 -1.05) (end 2.48 1.05) (layer F.CrtYd) (width 0.05)) + (fp_line (start 2.48 1.05) (end -2.48 1.05) (layer F.CrtYd) (width 0.05)) + (fp_text user %R (at 0 0 270) (layer F.Fab) + (effects (font (size 0.8 0.8) (thickness 0.12))) + ) + (pad 1 smd roundrect (at -1.4375 0 270) (size 1.575 1.35) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.185185) + (net 2 +3V3)) + (pad 2 smd roundrect (at 1.4375 0 270) (size 1.575 1.35) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.185185) + (net 1 GND)) + (model ${KISYS3DMOD}/Capacitor_Tantalum_SMD.3dshapes/CP_EIA-3216-18_Kemet-A.wrl + (at (xyz 0 0 0)) + (scale (xyz 1 1 1)) + (rotate (xyz 0 0 0)) + ) + ) + + (module Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder (layer F.Cu) (tedit 5B301BBE) (tstamp 5D1521BB) + (at 96.4105 55.3465 270) + (descr "Capacitor SMD 0603 (1608 Metric), square (rectangular) end terminal, IPC_7351 nominal with elongated pad for handsoldering. (Body size source: http://www.tortai-tech.com/upload/download/2011102023233369053.pdf), generated with kicad-footprint-generator") + (tags "capacitor handsolder") + (path /5D1F7471) + (attr smd) + (fp_text reference C10 (at 0.8115 -2.159) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text value 12 (at 0 1.43 270) (layer F.Fab) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text user %R (at 0 0 270) (layer F.Fab) + (effects (font (size 0.4 0.4) (thickness 0.06))) + ) + (fp_line (start 1.65 0.73) (end -1.65 0.73) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.65 -0.73) (end 1.65 0.73) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.65 -0.73) (end 1.65 -0.73) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.65 0.73) (end -1.65 -0.73) (layer F.CrtYd) (width 0.05)) + (fp_line (start -0.171267 0.51) (end 0.171267 0.51) (layer F.SilkS) (width 0.12)) + (fp_line (start -0.171267 -0.51) (end 0.171267 -0.51) (layer F.SilkS) (width 0.12)) + (fp_line (start 0.8 0.4) (end -0.8 0.4) (layer F.Fab) (width 0.1)) + (fp_line (start 0.8 -0.4) (end 0.8 0.4) (layer F.Fab) (width 0.1)) + (fp_line (start -0.8 -0.4) (end 0.8 -0.4) (layer F.Fab) (width 0.1)) + (fp_line (start -0.8 0.4) (end -0.8 -0.4) (layer F.Fab) (width 0.1)) + (pad 2 smd roundrect (at 0.875 0 270) (size 1.05 0.95) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.25) + (net 1 GND)) + (pad 1 smd roundrect (at -0.875 0 270) (size 1.05 0.95) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.25) + (net 4 /OSC_IN)) + (model ${KISYS3DMOD}/Capacitor_SMD.3dshapes/C_0603_1608Metric.wrl + (at (xyz 0 0 0)) + (scale (xyz 1 1 1)) + (rotate (xyz 0 0 0)) + ) + ) + + (module Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder (layer F.Cu) (tedit 5B301BBE) (tstamp 5D1521CC) + (at 96.4105 58.811 90) + (descr "Capacitor SMD 0603 (1608 Metric), square (rectangular) end terminal, IPC_7351 nominal with elongated pad for handsoldering. (Body size source: http://www.tortai-tech.com/upload/download/2011102023233369053.pdf), generated with kicad-footprint-generator") + (tags "capacitor handsolder") + (path /5D1F64B1) + (attr smd) + (fp_text reference C11 (at 0.9385 2.159 180) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text value 12 (at 0 1.43 90) (layer F.Fab) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_line (start -0.8 0.4) (end -0.8 -0.4) (layer F.Fab) (width 0.1)) + (fp_line (start -0.8 -0.4) (end 0.8 -0.4) (layer F.Fab) (width 0.1)) + (fp_line (start 0.8 -0.4) (end 0.8 0.4) (layer F.Fab) (width 0.1)) + (fp_line (start 0.8 0.4) (end -0.8 0.4) (layer F.Fab) (width 0.1)) + (fp_line (start -0.171267 -0.51) (end 0.171267 -0.51) (layer F.SilkS) (width 0.12)) + (fp_line (start -0.171267 0.51) (end 0.171267 0.51) (layer F.SilkS) (width 0.12)) + (fp_line (start -1.65 0.73) (end -1.65 -0.73) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.65 -0.73) (end 1.65 -0.73) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.65 -0.73) (end 1.65 0.73) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.65 0.73) (end -1.65 0.73) (layer F.CrtYd) (width 0.05)) + (fp_text user %R (at 0 0 90) (layer F.Fab) + (effects (font (size 0.4 0.4) (thickness 0.06))) + ) + (pad 1 smd roundrect (at -0.875 0 90) (size 1.05 0.95) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.25) + (net 5 /OSC_OUT)) + (pad 2 smd roundrect (at 0.875 0 90) (size 1.05 0.95) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.25) + (net 1 GND)) + (model ${KISYS3DMOD}/Capacitor_SMD.3dshapes/C_0603_1608Metric.wrl + (at (xyz 0 0 0)) + (scale (xyz 1 1 1)) + (rotate (xyz 0 0 0)) + ) + ) + + (module Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder (layer F.Cu) (tedit 5B301BBE) (tstamp 5D1521DD) + (at 101.6175 61.4425 270) + (descr "Capacitor SMD 0603 (1608 Metric), square (rectangular) end terminal, IPC_7351 nominal with elongated pad for handsoldering. (Body size source: http://www.tortai-tech.com/upload/download/2011102023233369053.pdf), generated with kicad-footprint-generator") + (tags "capacitor handsolder") + (path /58C42D39) + (attr smd) + (fp_text reference C12 (at -0.0775 2.2225) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text value 0.1 (at 0 1.43 270) (layer F.Fab) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_line (start -0.8 0.4) (end -0.8 -0.4) (layer F.Fab) (width 0.1)) + (fp_line (start -0.8 -0.4) (end 0.8 -0.4) (layer F.Fab) (width 0.1)) + (fp_line (start 0.8 -0.4) (end 0.8 0.4) (layer F.Fab) (width 0.1)) + (fp_line (start 0.8 0.4) (end -0.8 0.4) (layer F.Fab) (width 0.1)) + (fp_line (start -0.171267 -0.51) (end 0.171267 -0.51) (layer F.SilkS) (width 0.12)) + (fp_line (start -0.171267 0.51) (end 0.171267 0.51) (layer F.SilkS) (width 0.12)) + (fp_line (start -1.65 0.73) (end -1.65 -0.73) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.65 -0.73) (end 1.65 -0.73) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.65 -0.73) (end 1.65 0.73) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.65 0.73) (end -1.65 0.73) (layer F.CrtYd) (width 0.05)) + (fp_text user %R (at 0 0 270) (layer F.Fab) + (effects (font (size 0.4 0.4) (thickness 0.06))) + ) + (pad 1 smd roundrect (at -0.875 0 270) (size 1.05 0.95) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.25) + (net 1 GND)) + (pad 2 smd roundrect (at 0.875 0 270) (size 1.05 0.95) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.25) + (net 2 +3V3)) + (model ${KISYS3DMOD}/Capacitor_SMD.3dshapes/C_0603_1608Metric.wrl + (at (xyz 0 0 0)) + (scale (xyz 1 1 1)) + (rotate (xyz 0 0 0)) + ) + ) + + (module Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder (layer F.Cu) (tedit 5B301BBE) (tstamp 5D1521EE) + (at 106.126 55.029 270) + (descr "Capacitor SMD 0603 (1608 Metric), square (rectangular) end terminal, IPC_7351 nominal with elongated pad for handsoldering. (Body size source: http://www.tortai-tech.com/upload/download/2011102023233369053.pdf), generated with kicad-footprint-generator") + (tags "capacitor handsolder") + (path /590935EA) + (attr smd) + (fp_text reference C13 (at 0.113 2.2225) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text value 0.1 (at 0 1.43 270) (layer F.Fab) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text user %R (at 0 0 270) (layer F.Fab) + (effects (font (size 0.4 0.4) (thickness 0.06))) + ) + (fp_line (start 1.65 0.73) (end -1.65 0.73) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.65 -0.73) (end 1.65 0.73) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.65 -0.73) (end 1.65 -0.73) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.65 0.73) (end -1.65 -0.73) (layer F.CrtYd) (width 0.05)) + (fp_line (start -0.171267 0.51) (end 0.171267 0.51) (layer F.SilkS) (width 0.12)) + (fp_line (start -0.171267 -0.51) (end 0.171267 -0.51) (layer F.SilkS) (width 0.12)) + (fp_line (start 0.8 0.4) (end -0.8 0.4) (layer F.Fab) (width 0.1)) + (fp_line (start 0.8 -0.4) (end 0.8 0.4) (layer F.Fab) (width 0.1)) + (fp_line (start -0.8 -0.4) (end 0.8 -0.4) (layer F.Fab) (width 0.1)) + (fp_line (start -0.8 0.4) (end -0.8 -0.4) (layer F.Fab) (width 0.1)) + (pad 2 smd roundrect (at 0.875 0 270) (size 1.05 0.95) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.25) + (net 2 +3V3)) + (pad 1 smd roundrect (at -0.875 0 270) (size 1.05 0.95) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.25) + (net 1 GND)) + (model ${KISYS3DMOD}/Capacitor_SMD.3dshapes/C_0603_1608Metric.wrl + (at (xyz 0 0 0)) + (scale (xyz 1 1 1)) + (rotate (xyz 0 0 0)) + ) + ) + + (module Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder (layer F.Cu) (tedit 5B301BBE) (tstamp 5D15894F) + (at 114.5715 65.9865 90) + (descr "Capacitor SMD 0603 (1608 Metric), square (rectangular) end terminal, IPC_7351 nominal with elongated pad for handsoldering. (Body size source: http://www.tortai-tech.com/upload/download/2011102023233369053.pdf), generated with kicad-footprint-generator") + (tags "capacitor handsolder") + (path /59093675) + (attr smd) + (fp_text reference C14 (at -2.3635 -0.1905 180) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text value 0.1 (at 0 1.43 90) (layer F.Fab) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_line (start -0.8 0.4) (end -0.8 -0.4) (layer F.Fab) (width 0.1)) + (fp_line (start -0.8 -0.4) (end 0.8 -0.4) (layer F.Fab) (width 0.1)) + (fp_line (start 0.8 -0.4) (end 0.8 0.4) (layer F.Fab) (width 0.1)) + (fp_line (start 0.8 0.4) (end -0.8 0.4) (layer F.Fab) (width 0.1)) + (fp_line (start -0.171267 -0.51) (end 0.171267 -0.51) (layer F.SilkS) (width 0.12)) + (fp_line (start -0.171267 0.51) (end 0.171267 0.51) (layer F.SilkS) (width 0.12)) + (fp_line (start -1.65 0.73) (end -1.65 -0.73) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.65 -0.73) (end 1.65 -0.73) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.65 -0.73) (end 1.65 0.73) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.65 0.73) (end -1.65 0.73) (layer F.CrtYd) (width 0.05)) + (fp_text user %R (at 0 0 90) (layer F.Fab) + (effects (font (size 0.4 0.4) (thickness 0.06))) + ) + (pad 1 smd roundrect (at -0.875 0 90) (size 1.05 0.95) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.25) + (net 1 GND)) + (pad 2 smd roundrect (at 0.875 0 90) (size 1.05 0.95) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.25) + (net 2 +3V3)) + (model ${KISYS3DMOD}/Capacitor_SMD.3dshapes/C_0603_1608Metric.wrl + (at (xyz 0 0 0)) + (scale (xyz 1 1 1)) + (rotate (xyz 0 0 0)) + ) + ) + + (module Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder (layer F.Cu) (tedit 5B301BBE) (tstamp 5D157C72) + (at 116.2365 56.0945 180) + (descr "Capacitor SMD 0603 (1608 Metric), square (rectangular) end terminal, IPC_7351 nominal with elongated pad for handsoldering. (Body size source: http://www.tortai-tech.com/upload/download/2011102023233369053.pdf), generated with kicad-footprint-generator") + (tags "capacitor handsolder") + (path /590A8102) + (attr smd) + (fp_text reference C15 (at -3.0975 0.381 180) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text value 0.1 (at 0 1.43 180) (layer F.Fab) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text user %R (at 0 0 180) (layer F.Fab) + (effects (font (size 0.4 0.4) (thickness 0.06))) + ) + (fp_line (start 1.65 0.73) (end -1.65 0.73) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.65 -0.73) (end 1.65 0.73) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.65 -0.73) (end 1.65 -0.73) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.65 0.73) (end -1.65 -0.73) (layer F.CrtYd) (width 0.05)) + (fp_line (start -0.171267 0.51) (end 0.171267 0.51) (layer F.SilkS) (width 0.12)) + (fp_line (start -0.171267 -0.51) (end 0.171267 -0.51) (layer F.SilkS) (width 0.12)) + (fp_line (start 0.8 0.4) (end -0.8 0.4) (layer F.Fab) (width 0.1)) + (fp_line (start 0.8 -0.4) (end 0.8 0.4) (layer F.Fab) (width 0.1)) + (fp_line (start -0.8 -0.4) (end 0.8 -0.4) (layer F.Fab) (width 0.1)) + (fp_line (start -0.8 0.4) (end -0.8 -0.4) (layer F.Fab) (width 0.1)) + (pad 2 smd roundrect (at 0.875 0 180) (size 1.05 0.95) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.25) + (net 2 +3V3)) + (pad 1 smd roundrect (at -0.875 0 180) (size 1.05 0.95) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.25) + (net 1 GND)) + (model ${KISYS3DMOD}/Capacitor_SMD.3dshapes/C_0603_1608Metric.wrl + (at (xyz 0 0 0)) + (scale (xyz 1 1 1)) + (rotate (xyz 0 0 0)) + ) + ) + + (module Diode_SMD:D_0805_2012Metric_Pad1.15x1.40mm_HandSolder (layer F.Cu) (tedit 5B4B45C8) (tstamp 5D155695) + (at 107.7135 78.773 270) + (descr "Diode SMD 0805 (2012 Metric), square (rectangular) end terminal, IPC_7351 nominal, (Body size source: https://docs.google.com/spreadsheets/d/1BsfQQcO9C6DZCsRaXUlFlo91Tg2WpOkGARC1WS5S8t0/edit?usp=sharing), generated with kicad-footprint-generator") + (tags "diode handsolder") + (path /5D1735CA) + (attr smd) + (fp_text reference D1 (at -0.009 -2.032) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text value MM3Z7V5 (at 0 1.65 270) (layer F.Fab) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_line (start 1 -0.6) (end -0.7 -0.6) (layer F.Fab) (width 0.1)) + (fp_line (start -0.7 -0.6) (end -1 -0.3) (layer F.Fab) (width 0.1)) + (fp_line (start -1 -0.3) (end -1 0.6) (layer F.Fab) (width 0.1)) + (fp_line (start -1 0.6) (end 1 0.6) (layer F.Fab) (width 0.1)) + (fp_line (start 1 0.6) (end 1 -0.6) (layer F.Fab) (width 0.1)) + (fp_line (start 1 -0.96) (end -1.86 -0.96) (layer F.SilkS) (width 0.12)) + (fp_line (start -1.86 -0.96) (end -1.86 0.96) (layer F.SilkS) (width 0.12)) + (fp_line (start -1.86 0.96) (end 1 0.96) (layer F.SilkS) (width 0.12)) + (fp_line (start -1.85 0.95) (end -1.85 -0.95) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.85 -0.95) (end 1.85 -0.95) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.85 -0.95) (end 1.85 0.95) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.85 0.95) (end -1.85 0.95) (layer F.CrtYd) (width 0.05)) + (fp_text user %R (at 0 0 270) (layer F.Fab) + (effects (font (size 0.5 0.5) (thickness 0.08))) + ) + (pad 1 smd roundrect (at -1.025 0 270) (size 1.15 1.4) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.217391) + (net 6 "Net-(C3-Pad1)")) + (pad 2 smd roundrect (at 1.025 0 270) (size 1.15 1.4) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.217391) + (net 43 "Net-(D1-Pad2)")) + (model ${KISYS3DMOD}/Diode_SMD.3dshapes/D_0805_2012Metric.wrl + (at (xyz 0 0 0)) + (scale (xyz 1 1 1)) + (rotate (xyz 0 0 0)) + ) + ) + + (module Diode_SMD:D_SMA_Handsoldering (layer F.Cu) (tedit 58643398) (tstamp 5D15223B) + (at 127.5655 71.7663) + (descr "Diode SMA (DO-214AC) Handsoldering") + (tags "Diode SMA (DO-214AC) Handsoldering") + (path /5D89B9B8) + (attr smd) + (fp_text reference D2 (at 0 -2.5) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text value SS14 (at 0 2.6) (layer F.Fab) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text user %R (at 0 -2.5) (layer F.Fab) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_line (start -4.4 -1.65) (end -4.4 1.65) (layer F.SilkS) (width 0.12)) + (fp_line (start 2.3 1.5) (end -2.3 1.5) (layer F.Fab) (width 0.1)) + (fp_line (start -2.3 1.5) (end -2.3 -1.5) (layer F.Fab) (width 0.1)) + (fp_line (start 2.3 -1.5) (end 2.3 1.5) (layer F.Fab) (width 0.1)) + (fp_line (start 2.3 -1.5) (end -2.3 -1.5) (layer F.Fab) (width 0.1)) + (fp_line (start -4.5 -1.75) (end 4.5 -1.75) (layer F.CrtYd) (width 0.05)) + (fp_line (start 4.5 -1.75) (end 4.5 1.75) (layer F.CrtYd) (width 0.05)) + (fp_line (start 4.5 1.75) (end -4.5 1.75) (layer F.CrtYd) (width 0.05)) + (fp_line (start -4.5 1.75) (end -4.5 -1.75) (layer F.CrtYd) (width 0.05)) + (fp_line (start -0.64944 0.00102) (end -1.55114 0.00102) (layer F.Fab) (width 0.1)) + (fp_line (start 0.50118 0.00102) (end 1.4994 0.00102) (layer F.Fab) (width 0.1)) + (fp_line (start -0.64944 -0.79908) (end -0.64944 0.80112) (layer F.Fab) (width 0.1)) + (fp_line (start 0.50118 0.75032) (end 0.50118 -0.79908) (layer F.Fab) (width 0.1)) + (fp_line (start -0.64944 0.00102) (end 0.50118 0.75032) (layer F.Fab) (width 0.1)) + (fp_line (start -0.64944 0.00102) (end 0.50118 -0.79908) (layer F.Fab) (width 0.1)) + (fp_line (start -4.4 1.65) (end 2.5 1.65) (layer F.SilkS) (width 0.12)) + (fp_line (start -4.4 -1.65) (end 2.5 -1.65) (layer F.SilkS) (width 0.12)) + (pad 1 smd rect (at -2.5 0) (size 3.5 1.8) (layers F.Cu F.Paste F.Mask) + (net 3 +5V)) + (pad 2 smd rect (at 2.5 0) (size 3.5 1.8) (layers F.Cu F.Paste F.Mask) + (net 7 "Net-(D2-Pad2)")) + (model ${KISYS3DMOD}/Diode_SMD.3dshapes/D_SMA.wrl + (at (xyz 0 0 0)) + (scale (xyz 1 1 1)) + (rotate (xyz 0 0 0)) + ) + ) + + (module Diode_THT:D_DO-201_P12.70mm_Horizontal (layer B.Cu) (tedit 5AE50CD5) (tstamp 5D15EB7B) + (at 113.0475 91.0195 90) + (descr "Diode, DO-201 series, Axial, Horizontal, pin pitch=12.7mm, , length*diameter=9.53*5.21mm^2, , http://www.diodes.com/_files/packages/DO-201.pdf") + (tags "Diode DO-201 series Axial Horizontal pin pitch 12.7mm length 9.53mm diameter 5.21mm") + (path /58C43816) + (fp_text reference D3 (at -2.794 0.0635 180) (layer B.SilkS) + (effects (font (size 1 1) (thickness 0.15)) (justify mirror)) + ) + (fp_text value 1n5822 (at 6.35 -3.725 90) (layer B.Fab) + (effects (font (size 1 1) (thickness 0.15)) (justify mirror)) + ) + (fp_line (start 1.585 2.605) (end 1.585 -2.605) (layer B.Fab) (width 0.1)) + (fp_line (start 1.585 -2.605) (end 11.115 -2.605) (layer B.Fab) (width 0.1)) + (fp_line (start 11.115 -2.605) (end 11.115 2.605) (layer B.Fab) (width 0.1)) + (fp_line (start 11.115 2.605) (end 1.585 2.605) (layer B.Fab) (width 0.1)) + (fp_line (start 0 0) (end 1.585 0) (layer B.Fab) (width 0.1)) + (fp_line (start 12.7 0) (end 11.115 0) (layer B.Fab) (width 0.1)) + (fp_line (start 3.0145 2.605) (end 3.0145 -2.605) (layer B.Fab) (width 0.1)) + (fp_line (start 3.1145 2.605) (end 3.1145 -2.605) (layer B.Fab) (width 0.1)) + (fp_line (start 2.9145 2.605) (end 2.9145 -2.605) (layer B.Fab) (width 0.1)) + (fp_line (start 1.465 1.54) (end 1.465 2.725) (layer B.SilkS) (width 0.12)) + (fp_line (start 1.465 2.725) (end 11.235 2.725) (layer B.SilkS) (width 0.12)) + (fp_line (start 11.235 2.725) (end 11.235 1.54) (layer B.SilkS) (width 0.12)) + (fp_line (start 1.465 -1.54) (end 1.465 -2.725) (layer B.SilkS) (width 0.12)) + (fp_line (start 1.465 -2.725) (end 11.235 -2.725) (layer B.SilkS) (width 0.12)) + (fp_line (start 11.235 -2.725) (end 11.235 -1.54) (layer B.SilkS) (width 0.12)) + (fp_line (start 3.0145 2.725) (end 3.0145 -2.725) (layer B.SilkS) (width 0.12)) + (fp_line (start 3.1345 2.725) (end 3.1345 -2.725) (layer B.SilkS) (width 0.12)) + (fp_line (start 2.8945 2.725) (end 2.8945 -2.725) (layer B.SilkS) (width 0.12)) + (fp_line (start -1.55 2.86) (end -1.55 -2.86) (layer B.CrtYd) (width 0.05)) + (fp_line (start -1.55 -2.86) (end 14.25 -2.86) (layer B.CrtYd) (width 0.05)) + (fp_line (start 14.25 -2.86) (end 14.25 2.86) (layer B.CrtYd) (width 0.05)) + (fp_line (start 14.25 2.86) (end -1.55 2.86) (layer B.CrtYd) (width 0.05)) + (fp_text user %R (at 7.06475 0 90) (layer B.Fab) + (effects (font (size 1 1) (thickness 0.15)) (justify mirror)) + ) + (fp_text user K (at 0 2.3 90) (layer B.Fab) + (effects (font (size 1 1) (thickness 0.15)) (justify mirror)) + ) + (fp_text user K (at 0 2.3 90) (layer B.SilkS) + (effects (font (size 1 1) (thickness 0.15)) (justify mirror)) + ) + (pad 1 thru_hole rect (at 0 0 90) (size 2.6 2.6) (drill 1.3) (layers *.Cu *.Mask) + (net 8 "Net-(D3-Pad1)")) + (pad 2 thru_hole oval (at 12.7 0 90) (size 2.6 2.6) (drill 1.3) (layers *.Cu *.Mask) + (net 1 GND)) + (model ${KISYS3DMOD}/Diode_THT.3dshapes/D_DO-201_P12.70mm_Horizontal.wrl + (at (xyz 0 0 0)) + (scale (xyz 1 1 1)) + (rotate (xyz 0 0 0)) + ) + ) + + (module LED_THT:LED_D5.0mm (layer F.Cu) (tedit 5995936A) (tstamp 5D162528) + (at 97.871 45.8075 180) + (descr "LED, diameter 5.0mm, 2 pins, http://cdn-reichelt.de/documents/datenblatt/A500/LL-504BC2E-009.pdf") + (tags "LED diameter 5.0mm 2 pins") + (path /5908EA64) + (fp_text reference D4 (at 1.27 -3.96 180) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text value LED0 (at 1.27 3.96 180) (layer F.Fab) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text user %R (at 1.25 0 180) (layer F.Fab) + (effects (font (size 0.8 0.8) (thickness 0.2))) + ) + (fp_line (start 4.5 -3.25) (end -1.95 -3.25) (layer F.CrtYd) (width 0.05)) + (fp_line (start 4.5 3.25) (end 4.5 -3.25) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.95 3.25) (end 4.5 3.25) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.95 -3.25) (end -1.95 3.25) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.29 -1.545) (end -1.29 1.545) (layer F.SilkS) (width 0.12)) + (fp_line (start -1.23 -1.469694) (end -1.23 1.469694) (layer F.Fab) (width 0.1)) + (fp_circle (center 1.27 0) (end 3.77 0) (layer F.SilkS) (width 0.12)) + (fp_circle (center 1.27 0) (end 3.77 0) (layer F.Fab) (width 0.1)) + (fp_arc (start 1.27 0) (end -1.29 1.54483) (angle -148.9) (layer F.SilkS) (width 0.12)) + (fp_arc (start 1.27 0) (end -1.29 -1.54483) (angle 148.9) (layer F.SilkS) (width 0.12)) + (fp_arc (start 1.27 0) (end -1.23 -1.469694) (angle 299.1) (layer F.Fab) (width 0.1)) + (pad 2 thru_hole circle (at 2.54 0 180) (size 1.8 1.8) (drill 0.9) (layers *.Cu *.Mask) + (net 10 "Net-(D4-Pad2)")) + (pad 1 thru_hole rect (at 0 0 180) (size 1.8 1.8) (drill 0.9) (layers *.Cu *.Mask) + (net 9 /LED0)) + (model ${KISYS3DMOD}/LED_THT.3dshapes/LED_D5.0mm.wrl + (at (xyz 0 0 0)) + (scale (xyz 1 1 1)) + (rotate (xyz 0 0 0)) + ) + ) + + (module LED_THT:LED_D5.0mm (layer F.Cu) (tedit 5995936A) (tstamp 5D15227E) + (at 104.475 45.8075 180) + (descr "LED, diameter 5.0mm, 2 pins, http://cdn-reichelt.de/documents/datenblatt/A500/LL-504BC2E-009.pdf") + (tags "LED diameter 5.0mm 2 pins") + (path /5909AF9A) + (fp_text reference D5 (at 1.27 -3.96 180) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text value LED1 (at 1.27 3.96 180) (layer F.Fab) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_arc (start 1.27 0) (end -1.23 -1.469694) (angle 299.1) (layer F.Fab) (width 0.1)) + (fp_arc (start 1.27 0) (end -1.29 -1.54483) (angle 148.9) (layer F.SilkS) (width 0.12)) + (fp_arc (start 1.27 0) (end -1.29 1.54483) (angle -148.9) (layer F.SilkS) (width 0.12)) + (fp_circle (center 1.27 0) (end 3.77 0) (layer F.Fab) (width 0.1)) + (fp_circle (center 1.27 0) (end 3.77 0) (layer F.SilkS) (width 0.12)) + (fp_line (start -1.23 -1.469694) (end -1.23 1.469694) (layer F.Fab) (width 0.1)) + (fp_line (start -1.29 -1.545) (end -1.29 1.545) (layer F.SilkS) (width 0.12)) + (fp_line (start -1.95 -3.25) (end -1.95 3.25) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.95 3.25) (end 4.5 3.25) (layer F.CrtYd) (width 0.05)) + (fp_line (start 4.5 3.25) (end 4.5 -3.25) (layer F.CrtYd) (width 0.05)) + (fp_line (start 4.5 -3.25) (end -1.95 -3.25) (layer F.CrtYd) (width 0.05)) + (fp_text user %R (at 1.25 0 180) (layer F.Fab) + (effects (font (size 0.8 0.8) (thickness 0.2))) + ) + (pad 1 thru_hole rect (at 0 0 180) (size 1.8 1.8) (drill 0.9) (layers *.Cu *.Mask) + (net 12 /LED1)) + (pad 2 thru_hole circle (at 2.54 0 180) (size 1.8 1.8) (drill 0.9) (layers *.Cu *.Mask) + (net 11 "Net-(D5-Pad2)")) + (model ${KISYS3DMOD}/LED_THT.3dshapes/LED_D5.0mm.wrl + (at (xyz 0 0 0)) + (scale (xyz 1 1 1)) + (rotate (xyz 0 0 0)) + ) + ) + + (module TerminalBlock_Phoenix:TerminalBlock_Phoenix_MKDS-1,5-2-5.08_1x02_P5.08mm_Horizontal (layer B.Cu) (tedit 5B294EBC) (tstamp 5D15E636) + (at 100.5 92) + (descr "Terminal Block Phoenix MKDS-1,5-2-5.08, 2 pins, pitch 5.08mm, size 10.2x9.8mm^2, drill diamater 1.3mm, pad diameter 2.6mm, see http://www.farnell.com/datasheets/100425.pdf, script-generated using https://github.com/pointhi/kicad-footprint-generator/scripts/TerminalBlock_Phoenix") + (tags "THT Terminal Block Phoenix MKDS-1,5-2-5.08 pitch 5.08mm size 10.2x9.8mm^2 drill 1.3mm pad 2.6mm") + (path /5D79C13C) + (fp_text reference J1 (at 2.54 6.26) (layer B.SilkS) + (effects (font (size 1 1) (thickness 0.15)) (justify mirror)) + ) + (fp_text value "Power 12V" (at 2.54 -5.66) (layer B.Fab) + (effects (font (size 1 1) (thickness 0.15)) (justify mirror)) + ) + (fp_text user %R (at 2.54 -3.2) (layer B.Fab) + (effects (font (size 1 1) (thickness 0.15)) (justify mirror)) + ) + (fp_line (start 8.13 5.71) (end -3.04 5.71) (layer B.CrtYd) (width 0.05)) + (fp_line (start 8.13 -5.1) (end 8.13 5.71) (layer B.CrtYd) (width 0.05)) + (fp_line (start -3.04 -5.1) (end 8.13 -5.1) (layer B.CrtYd) (width 0.05)) + (fp_line (start -3.04 5.71) (end -3.04 -5.1) (layer B.CrtYd) (width 0.05)) + (fp_line (start -2.84 -4.9) (end -2.34 -4.9) (layer B.SilkS) (width 0.12)) + (fp_line (start -2.84 -4.16) (end -2.84 -4.9) (layer B.SilkS) (width 0.12)) + (fp_line (start 3.853 -1.023) (end 3.806 -1.069) (layer B.SilkS) (width 0.12)) + (fp_line (start 6.15 1.275) (end 6.115 1.239) (layer B.SilkS) (width 0.12)) + (fp_line (start 4.046 -1.239) (end 4.011 -1.274) (layer B.SilkS) (width 0.12)) + (fp_line (start 6.355 1.069) (end 6.308 1.023) (layer B.SilkS) (width 0.12)) + (fp_line (start 6.035 1.138) (end 3.943 -0.955) (layer B.Fab) (width 0.1)) + (fp_line (start 6.218 0.955) (end 4.126 -1.138) (layer B.Fab) (width 0.1)) + (fp_line (start 0.955 1.138) (end -1.138 -0.955) (layer B.Fab) (width 0.1)) + (fp_line (start 1.138 0.955) (end -0.955 -1.138) (layer B.Fab) (width 0.1)) + (fp_line (start 7.68 5.261) (end 7.68 -4.66) (layer B.SilkS) (width 0.12)) + (fp_line (start -2.6 5.261) (end -2.6 -4.66) (layer B.SilkS) (width 0.12)) + (fp_line (start -2.6 -4.66) (end 7.68 -4.66) (layer B.SilkS) (width 0.12)) + (fp_line (start -2.6 5.261) (end 7.68 5.261) (layer B.SilkS) (width 0.12)) + (fp_line (start -2.6 2.301) (end 7.68 2.301) (layer B.SilkS) (width 0.12)) + (fp_line (start -2.54 2.3) (end 7.62 2.3) (layer B.Fab) (width 0.1)) + (fp_line (start -2.6 -2.6) (end 7.68 -2.6) (layer B.SilkS) (width 0.12)) + (fp_line (start -2.54 -2.6) (end 7.62 -2.6) (layer B.Fab) (width 0.1)) + (fp_line (start -2.6 -4.1) (end 7.68 -4.1) (layer B.SilkS) (width 0.12)) + (fp_line (start -2.54 -4.1) (end 7.62 -4.1) (layer B.Fab) (width 0.1)) + (fp_line (start -2.54 -4.1) (end -2.54 5.2) (layer B.Fab) (width 0.1)) + (fp_line (start -2.04 -4.6) (end -2.54 -4.1) (layer B.Fab) (width 0.1)) + (fp_line (start 7.62 -4.6) (end -2.04 -4.6) (layer B.Fab) (width 0.1)) + (fp_line (start 7.62 5.2) (end 7.62 -4.6) (layer B.Fab) (width 0.1)) + (fp_line (start -2.54 5.2) (end 7.62 5.2) (layer B.Fab) (width 0.1)) + (fp_circle (center 5.08 0) (end 6.76 0) (layer B.SilkS) (width 0.12)) + (fp_circle (center 5.08 0) (end 6.58 0) (layer B.Fab) (width 0.1)) + (fp_circle (center 0 0) (end 1.5 0) (layer B.Fab) (width 0.1)) + (fp_arc (start 0 0) (end -0.684 -1.535) (angle 25) (layer B.SilkS) (width 0.12)) + (fp_arc (start 0 0) (end -1.535 0.684) (angle 48) (layer B.SilkS) (width 0.12)) + (fp_arc (start 0 0) (end 0.684 1.535) (angle 48) (layer B.SilkS) (width 0.12)) + (fp_arc (start 0 0) (end 1.535 -0.684) (angle 48) (layer B.SilkS) (width 0.12)) + (fp_arc (start 0 0) (end 0 -1.68) (angle 24) (layer B.SilkS) (width 0.12)) + (pad 2 thru_hole circle (at 5.08 0) (size 2.6 2.6) (drill 1.3) (layers *.Cu *.Mask) + (net 13 "Net-(J1-Pad2)")) + (pad 1 thru_hole rect (at 0 0) (size 2.6 2.6) (drill 1.3) (layers *.Cu *.Mask) + (net 1 GND)) + (model ${KISYS3DMOD}/TerminalBlock_Phoenix.3dshapes/TerminalBlock_Phoenix_MKDS-1,5-2-5.08_1x02_P5.08mm_Horizontal.wrl + (at (xyz 0 0 0)) + (scale (xyz 1 1 1)) + (rotate (xyz 0 0 0)) + ) + ) + + (module TerminalBlock_Phoenix:TerminalBlock_Phoenix_MKDS-1,5-2-5.08_1x02_P5.08mm_Horizontal (layer B.Cu) (tedit 5B294EBC) (tstamp 5D15D899) + (at 134 92) + (descr "Terminal Block Phoenix MKDS-1,5-2-5.08, 2 pins, pitch 5.08mm, size 10.2x9.8mm^2, drill diamater 1.3mm, pad diameter 2.6mm, see http://www.farnell.com/datasheets/100425.pdf, script-generated using https://github.com/pointhi/kicad-footprint-generator/scripts/TerminalBlock_Phoenix") + (tags "THT Terminal Block Phoenix MKDS-1,5-2-5.08 pitch 5.08mm size 10.2x9.8mm^2 drill 1.3mm pad 2.6mm") + (path /5D93AD09) + (fp_text reference J2 (at 2.54 6.26) (layer B.SilkS) + (effects (font (size 1 1) (thickness 0.15)) (justify mirror)) + ) + (fp_text value +5Vout (at 2.54 -5.66) (layer B.Fab) + (effects (font (size 1 1) (thickness 0.15)) (justify mirror)) + ) + (fp_arc (start 0 0) (end 0 -1.68) (angle 24) (layer B.SilkS) (width 0.12)) + (fp_arc (start 0 0) (end 1.535 -0.684) (angle 48) (layer B.SilkS) (width 0.12)) + (fp_arc (start 0 0) (end 0.684 1.535) (angle 48) (layer B.SilkS) (width 0.12)) + (fp_arc (start 0 0) (end -1.535 0.684) (angle 48) (layer B.SilkS) (width 0.12)) + (fp_arc (start 0 0) (end -0.684 -1.535) (angle 25) (layer B.SilkS) (width 0.12)) + (fp_circle (center 0 0) (end 1.5 0) (layer B.Fab) (width 0.1)) + (fp_circle (center 5.08 0) (end 6.58 0) (layer B.Fab) (width 0.1)) + (fp_circle (center 5.08 0) (end 6.76 0) (layer B.SilkS) (width 0.12)) + (fp_line (start -2.54 5.2) (end 7.62 5.2) (layer B.Fab) (width 0.1)) + (fp_line (start 7.62 5.2) (end 7.62 -4.6) (layer B.Fab) (width 0.1)) + (fp_line (start 7.62 -4.6) (end -2.04 -4.6) (layer B.Fab) (width 0.1)) + (fp_line (start -2.04 -4.6) (end -2.54 -4.1) (layer B.Fab) (width 0.1)) + (fp_line (start -2.54 -4.1) (end -2.54 5.2) (layer B.Fab) (width 0.1)) + (fp_line (start -2.54 -4.1) (end 7.62 -4.1) (layer B.Fab) (width 0.1)) + (fp_line (start -2.6 -4.1) (end 7.68 -4.1) (layer B.SilkS) (width 0.12)) + (fp_line (start -2.54 -2.6) (end 7.62 -2.6) (layer B.Fab) (width 0.1)) + (fp_line (start -2.6 -2.6) (end 7.68 -2.6) (layer B.SilkS) (width 0.12)) + (fp_line (start -2.54 2.3) (end 7.62 2.3) (layer B.Fab) (width 0.1)) + (fp_line (start -2.6 2.301) (end 7.68 2.301) (layer B.SilkS) (width 0.12)) + (fp_line (start -2.6 5.261) (end 7.68 5.261) (layer B.SilkS) (width 0.12)) + (fp_line (start -2.6 -4.66) (end 7.68 -4.66) (layer B.SilkS) (width 0.12)) + (fp_line (start -2.6 5.261) (end -2.6 -4.66) (layer B.SilkS) (width 0.12)) + (fp_line (start 7.68 5.261) (end 7.68 -4.66) (layer B.SilkS) (width 0.12)) + (fp_line (start 1.138 0.955) (end -0.955 -1.138) (layer B.Fab) (width 0.1)) + (fp_line (start 0.955 1.138) (end -1.138 -0.955) (layer B.Fab) (width 0.1)) + (fp_line (start 6.218 0.955) (end 4.126 -1.138) (layer B.Fab) (width 0.1)) + (fp_line (start 6.035 1.138) (end 3.943 -0.955) (layer B.Fab) (width 0.1)) + (fp_line (start 6.355 1.069) (end 6.308 1.023) (layer B.SilkS) (width 0.12)) + (fp_line (start 4.046 -1.239) (end 4.011 -1.274) (layer B.SilkS) (width 0.12)) + (fp_line (start 6.15 1.275) (end 6.115 1.239) (layer B.SilkS) (width 0.12)) + (fp_line (start 3.853 -1.023) (end 3.806 -1.069) (layer B.SilkS) (width 0.12)) + (fp_line (start -2.84 -4.16) (end -2.84 -4.9) (layer B.SilkS) (width 0.12)) + (fp_line (start -2.84 -4.9) (end -2.34 -4.9) (layer B.SilkS) (width 0.12)) + (fp_line (start -3.04 5.71) (end -3.04 -5.1) (layer B.CrtYd) (width 0.05)) + (fp_line (start -3.04 -5.1) (end 8.13 -5.1) (layer B.CrtYd) (width 0.05)) + (fp_line (start 8.13 -5.1) (end 8.13 5.71) (layer B.CrtYd) (width 0.05)) + (fp_line (start 8.13 5.71) (end -3.04 5.71) (layer B.CrtYd) (width 0.05)) + (fp_text user %R (at 2.54 -3.2) (layer B.Fab) + (effects (font (size 1 1) (thickness 0.15)) (justify mirror)) + ) + (pad 1 thru_hole rect (at 0 0) (size 2.6 2.6) (drill 1.3) (layers *.Cu *.Mask) + (net 14 "Net-(J2-Pad1)")) + (pad 2 thru_hole circle (at 5.08 0) (size 2.6 2.6) (drill 1.3) (layers *.Cu *.Mask) + (net 1 GND)) + (model ${KISYS3DMOD}/TerminalBlock_Phoenix.3dshapes/TerminalBlock_Phoenix_MKDS-1,5-2-5.08_1x02_P5.08mm_Horizontal.wrl + (at (xyz 0 0 0)) + (scale (xyz 1 1 1)) + (rotate (xyz 0 0 0)) + ) + ) + + (module TerminalBlock_Phoenix:TerminalBlock_Phoenix_MKDS-1,5-2-5.08_1x02_P5.08mm_Horizontal (layer B.Cu) (tedit 5B294EBC) (tstamp 5D152302) + (at 59.5 92) + (descr "Terminal Block Phoenix MKDS-1,5-2-5.08, 2 pins, pitch 5.08mm, size 10.2x9.8mm^2, drill diamater 1.3mm, pad diameter 2.6mm, see http://www.farnell.com/datasheets/100425.pdf, script-generated using https://github.com/pointhi/kicad-footprint-generator/scripts/TerminalBlock_Phoenix") + (tags "THT Terminal Block Phoenix MKDS-1,5-2-5.08 pitch 5.08mm size 10.2x9.8mm^2 drill 1.3mm pad 2.6mm") + (path /5D1444DC) + (fp_text reference J3 (at 2.54 6.26) (layer B.SilkS) + (effects (font (size 1 1) (thickness 0.15)) (justify mirror)) + ) + (fp_text value Ext_trig0 (at 2.54 -5.66) (layer B.Fab) + (effects (font (size 1 1) (thickness 0.15)) (justify mirror)) + ) + (fp_arc (start 0 0) (end 0 -1.68) (angle 24) (layer B.SilkS) (width 0.12)) + (fp_arc (start 0 0) (end 1.535 -0.684) (angle 48) (layer B.SilkS) (width 0.12)) + (fp_arc (start 0 0) (end 0.684 1.535) (angle 48) (layer B.SilkS) (width 0.12)) + (fp_arc (start 0 0) (end -1.535 0.684) (angle 48) (layer B.SilkS) (width 0.12)) + (fp_arc (start 0 0) (end -0.684 -1.535) (angle 25) (layer B.SilkS) (width 0.12)) + (fp_circle (center 0 0) (end 1.5 0) (layer B.Fab) (width 0.1)) + (fp_circle (center 5.08 0) (end 6.58 0) (layer B.Fab) (width 0.1)) + (fp_circle (center 5.08 0) (end 6.76 0) (layer B.SilkS) (width 0.12)) + (fp_line (start -2.54 5.2) (end 7.62 5.2) (layer B.Fab) (width 0.1)) + (fp_line (start 7.62 5.2) (end 7.62 -4.6) (layer B.Fab) (width 0.1)) + (fp_line (start 7.62 -4.6) (end -2.04 -4.6) (layer B.Fab) (width 0.1)) + (fp_line (start -2.04 -4.6) (end -2.54 -4.1) (layer B.Fab) (width 0.1)) + (fp_line (start -2.54 -4.1) (end -2.54 5.2) (layer B.Fab) (width 0.1)) + (fp_line (start -2.54 -4.1) (end 7.62 -4.1) (layer B.Fab) (width 0.1)) + (fp_line (start -2.6 -4.1) (end 7.68 -4.1) (layer B.SilkS) (width 0.12)) + (fp_line (start -2.54 -2.6) (end 7.62 -2.6) (layer B.Fab) (width 0.1)) + (fp_line (start -2.6 -2.6) (end 7.68 -2.6) (layer B.SilkS) (width 0.12)) + (fp_line (start -2.54 2.3) (end 7.62 2.3) (layer B.Fab) (width 0.1)) + (fp_line (start -2.6 2.301) (end 7.68 2.301) (layer B.SilkS) (width 0.12)) + (fp_line (start -2.6 5.261) (end 7.68 5.261) (layer B.SilkS) (width 0.12)) + (fp_line (start -2.6 -4.66) (end 7.68 -4.66) (layer B.SilkS) (width 0.12)) + (fp_line (start -2.6 5.261) (end -2.6 -4.66) (layer B.SilkS) (width 0.12)) + (fp_line (start 7.68 5.261) (end 7.68 -4.66) (layer B.SilkS) (width 0.12)) + (fp_line (start 1.138 0.955) (end -0.955 -1.138) (layer B.Fab) (width 0.1)) + (fp_line (start 0.955 1.138) (end -1.138 -0.955) (layer B.Fab) (width 0.1)) + (fp_line (start 6.218 0.955) (end 4.126 -1.138) (layer B.Fab) (width 0.1)) + (fp_line (start 6.035 1.138) (end 3.943 -0.955) (layer B.Fab) (width 0.1)) + (fp_line (start 6.355 1.069) (end 6.308 1.023) (layer B.SilkS) (width 0.12)) + (fp_line (start 4.046 -1.239) (end 4.011 -1.274) (layer B.SilkS) (width 0.12)) + (fp_line (start 6.15 1.275) (end 6.115 1.239) (layer B.SilkS) (width 0.12)) + (fp_line (start 3.853 -1.023) (end 3.806 -1.069) (layer B.SilkS) (width 0.12)) + (fp_line (start -2.84 -4.16) (end -2.84 -4.9) (layer B.SilkS) (width 0.12)) + (fp_line (start -2.84 -4.9) (end -2.34 -4.9) (layer B.SilkS) (width 0.12)) + (fp_line (start -3.04 5.71) (end -3.04 -5.1) (layer B.CrtYd) (width 0.05)) + (fp_line (start -3.04 -5.1) (end 8.13 -5.1) (layer B.CrtYd) (width 0.05)) + (fp_line (start 8.13 -5.1) (end 8.13 5.71) (layer B.CrtYd) (width 0.05)) + (fp_line (start 8.13 5.71) (end -3.04 5.71) (layer B.CrtYd) (width 0.05)) + (fp_text user %R (at 2.54 -3.2) (layer B.Fab) + (effects (font (size 1 1) (thickness 0.15)) (justify mirror)) + ) + (pad 1 thru_hole rect (at 0 0) (size 2.6 2.6) (drill 1.3) (layers *.Cu *.Mask) + (net 1 GND)) + (pad 2 thru_hole circle (at 5.08 0) (size 2.6 2.6) (drill 1.3) (layers *.Cu *.Mask) + (net 15 "Net-(J3-Pad2)")) + (model ${KISYS3DMOD}/TerminalBlock_Phoenix.3dshapes/TerminalBlock_Phoenix_MKDS-1,5-2-5.08_1x02_P5.08mm_Horizontal.wrl + (at (xyz 0 0 0)) + (scale (xyz 1 1 1)) + (rotate (xyz 0 0 0)) + ) + ) + + (module Connector_PinSocket_2.54mm:PinSocket_1x04_P2.54mm_Vertical (layer B.Cu) (tedit 5A19A429) (tstamp 5D15231A) + (at 110.444 71.779 270) + (descr "Through hole straight socket strip, 1x04, 2.54mm pitch, single row (from Kicad 4.0.7), script generated") + (tags "Through hole socket strip THT 1x04 2.54mm single row") + (path /5D927958) + (fp_text reference J4 (at 2.667 -3.937) (layer B.SilkS) + (effects (font (size 1 1) (thickness 0.15)) (justify mirror)) + ) + (fp_text value LIDAR (at 0 -10.39 270) (layer B.Fab) + (effects (font (size 1 1) (thickness 0.15)) (justify mirror)) + ) + (fp_line (start -1.27 1.27) (end 0.635 1.27) (layer B.Fab) (width 0.1)) + (fp_line (start 0.635 1.27) (end 1.27 0.635) (layer B.Fab) (width 0.1)) + (fp_line (start 1.27 0.635) (end 1.27 -8.89) (layer B.Fab) (width 0.1)) + (fp_line (start 1.27 -8.89) (end -1.27 -8.89) (layer B.Fab) (width 0.1)) + (fp_line (start -1.27 -8.89) (end -1.27 1.27) (layer B.Fab) (width 0.1)) + (fp_line (start -1.33 -1.27) (end 1.33 -1.27) (layer B.SilkS) (width 0.12)) + (fp_line (start -1.33 -1.27) (end -1.33 -8.95) (layer B.SilkS) (width 0.12)) + (fp_line (start -1.33 -8.95) (end 1.33 -8.95) (layer B.SilkS) (width 0.12)) + (fp_line (start 1.33 -1.27) (end 1.33 -8.95) (layer B.SilkS) (width 0.12)) + (fp_line (start 1.33 1.33) (end 1.33 0) (layer B.SilkS) (width 0.12)) + (fp_line (start 0 1.33) (end 1.33 1.33) (layer B.SilkS) (width 0.12)) + (fp_line (start -1.8 1.8) (end 1.75 1.8) (layer B.CrtYd) (width 0.05)) + (fp_line (start 1.75 1.8) (end 1.75 -9.4) (layer B.CrtYd) (width 0.05)) + (fp_line (start 1.75 -9.4) (end -1.8 -9.4) (layer B.CrtYd) (width 0.05)) + (fp_line (start -1.8 -9.4) (end -1.8 1.8) (layer B.CrtYd) (width 0.05)) + (fp_text user %R (at 0 -3.81) (layer F.Fab) + (effects (font (size 1 1) (thickness 0.15))) + ) + (pad 1 thru_hole rect (at 0 0 270) (size 1.7 1.7) (drill 1) (layers *.Cu *.Mask) + (net 16 /U2Tx)) + (pad 2 thru_hole oval (at 0 -2.54 270) (size 1.7 1.7) (drill 1) (layers *.Cu *.Mask) + (net 17 /U2Rx)) + (pad 3 thru_hole oval (at 0 -5.08 270) (size 1.7 1.7) (drill 1) (layers *.Cu *.Mask) + (net 1 GND)) + (pad 4 thru_hole oval (at 0 -7.62 270) (size 1.7 1.7) (drill 1) (layers *.Cu *.Mask) + (net 3 +5V)) + (model ${KISYS3DMOD}/Connector_PinSocket_2.54mm.3dshapes/PinSocket_1x04_P2.54mm_Vertical.wrl + (at (xyz 0 0 0)) + (scale (xyz 1 1 1)) + (rotate (xyz 0 0 0)) + ) + ) + + (module TerminalBlock_Phoenix:TerminalBlock_Phoenix_MKDS-1,5-2-5.08_1x02_P5.08mm_Horizontal (layer B.Cu) (tedit 5B294EBC) (tstamp 5D152346) + (at 72 92) + (descr "Terminal Block Phoenix MKDS-1,5-2-5.08, 2 pins, pitch 5.08mm, size 10.2x9.8mm^2, drill diamater 1.3mm, pad diameter 2.6mm, see http://www.farnell.com/datasheets/100425.pdf, script-generated using https://github.com/pointhi/kicad-footprint-generator/scripts/TerminalBlock_Phoenix") + (tags "THT Terminal Block Phoenix MKDS-1,5-2-5.08 pitch 5.08mm size 10.2x9.8mm^2 drill 1.3mm pad 2.6mm") + (path /5D145441) + (fp_text reference J5 (at 2.54 6.26) (layer B.SilkS) + (effects (font (size 1 1) (thickness 0.15)) (justify mirror)) + ) + (fp_text value Ext_trig1 (at 2.54 -5.66) (layer B.Fab) + (effects (font (size 1 1) (thickness 0.15)) (justify mirror)) + ) + (fp_arc (start 0 0) (end 0 -1.68) (angle 24) (layer B.SilkS) (width 0.12)) + (fp_arc (start 0 0) (end 1.535 -0.684) (angle 48) (layer B.SilkS) (width 0.12)) + (fp_arc (start 0 0) (end 0.684 1.535) (angle 48) (layer B.SilkS) (width 0.12)) + (fp_arc (start 0 0) (end -1.535 0.684) (angle 48) (layer B.SilkS) (width 0.12)) + (fp_arc (start 0 0) (end -0.684 -1.535) (angle 25) (layer B.SilkS) (width 0.12)) + (fp_circle (center 0 0) (end 1.5 0) (layer B.Fab) (width 0.1)) + (fp_circle (center 5.08 0) (end 6.58 0) (layer B.Fab) (width 0.1)) + (fp_circle (center 5.08 0) (end 6.76 0) (layer B.SilkS) (width 0.12)) + (fp_line (start -2.54 5.2) (end 7.62 5.2) (layer B.Fab) (width 0.1)) + (fp_line (start 7.62 5.2) (end 7.62 -4.6) (layer B.Fab) (width 0.1)) + (fp_line (start 7.62 -4.6) (end -2.04 -4.6) (layer B.Fab) (width 0.1)) + (fp_line (start -2.04 -4.6) (end -2.54 -4.1) (layer B.Fab) (width 0.1)) + (fp_line (start -2.54 -4.1) (end -2.54 5.2) (layer B.Fab) (width 0.1)) + (fp_line (start -2.54 -4.1) (end 7.62 -4.1) (layer B.Fab) (width 0.1)) + (fp_line (start -2.6 -4.1) (end 7.68 -4.1) (layer B.SilkS) (width 0.12)) + (fp_line (start -2.54 -2.6) (end 7.62 -2.6) (layer B.Fab) (width 0.1)) + (fp_line (start -2.6 -2.6) (end 7.68 -2.6) (layer B.SilkS) (width 0.12)) + (fp_line (start -2.54 2.3) (end 7.62 2.3) (layer B.Fab) (width 0.1)) + (fp_line (start -2.6 2.301) (end 7.68 2.301) (layer B.SilkS) (width 0.12)) + (fp_line (start -2.6 5.261) (end 7.68 5.261) (layer B.SilkS) (width 0.12)) + (fp_line (start -2.6 -4.66) (end 7.68 -4.66) (layer B.SilkS) (width 0.12)) + (fp_line (start -2.6 5.261) (end -2.6 -4.66) (layer B.SilkS) (width 0.12)) + (fp_line (start 7.68 5.261) (end 7.68 -4.66) (layer B.SilkS) (width 0.12)) + (fp_line (start 1.138 0.955) (end -0.955 -1.138) (layer B.Fab) (width 0.1)) + (fp_line (start 0.955 1.138) (end -1.138 -0.955) (layer B.Fab) (width 0.1)) + (fp_line (start 6.218 0.955) (end 4.126 -1.138) (layer B.Fab) (width 0.1)) + (fp_line (start 6.035 1.138) (end 3.943 -0.955) (layer B.Fab) (width 0.1)) + (fp_line (start 6.355 1.069) (end 6.308 1.023) (layer B.SilkS) (width 0.12)) + (fp_line (start 4.046 -1.239) (end 4.011 -1.274) (layer B.SilkS) (width 0.12)) + (fp_line (start 6.15 1.275) (end 6.115 1.239) (layer B.SilkS) (width 0.12)) + (fp_line (start 3.853 -1.023) (end 3.806 -1.069) (layer B.SilkS) (width 0.12)) + (fp_line (start -2.84 -4.16) (end -2.84 -4.9) (layer B.SilkS) (width 0.12)) + (fp_line (start -2.84 -4.9) (end -2.34 -4.9) (layer B.SilkS) (width 0.12)) + (fp_line (start -3.04 5.71) (end -3.04 -5.1) (layer B.CrtYd) (width 0.05)) + (fp_line (start -3.04 -5.1) (end 8.13 -5.1) (layer B.CrtYd) (width 0.05)) + (fp_line (start 8.13 -5.1) (end 8.13 5.71) (layer B.CrtYd) (width 0.05)) + (fp_line (start 8.13 5.71) (end -3.04 5.71) (layer B.CrtYd) (width 0.05)) + (fp_text user %R (at 2.54 -3.2) (layer B.Fab) + (effects (font (size 1 1) (thickness 0.15)) (justify mirror)) + ) + (pad 1 thru_hole rect (at 0 0) (size 2.6 2.6) (drill 1.3) (layers *.Cu *.Mask) + (net 1 GND)) + (pad 2 thru_hole circle (at 5.08 0) (size 2.6 2.6) (drill 1.3) (layers *.Cu *.Mask) + (net 18 "Net-(J5-Pad2)")) + (model ${KISYS3DMOD}/TerminalBlock_Phoenix.3dshapes/TerminalBlock_Phoenix_MKDS-1,5-2-5.08_1x02_P5.08mm_Horizontal.wrl + (at (xyz 0 0 0)) + (scale (xyz 1 1 1)) + (rotate (xyz 0 0 0)) + ) + ) + + (module TerminalBlock_Phoenix:TerminalBlock_Phoenix_MKDS-1,5-2-5.08_1x02_P5.08mm_Horizontal (layer B.Cu) (tedit 5B294EBC) (tstamp 5D152372) + (at 84.42 92) + (descr "Terminal Block Phoenix MKDS-1,5-2-5.08, 2 pins, pitch 5.08mm, size 10.2x9.8mm^2, drill diamater 1.3mm, pad diameter 2.6mm, see http://www.farnell.com/datasheets/100425.pdf, script-generated using https://github.com/pointhi/kicad-footprint-generator/scripts/TerminalBlock_Phoenix") + (tags "THT Terminal Block Phoenix MKDS-1,5-2-5.08 pitch 5.08mm size 10.2x9.8mm^2 drill 1.3mm pad 2.6mm") + (path /5D1457FF) + (fp_text reference J6 (at 2.54 6.26) (layer B.SilkS) + (effects (font (size 1 1) (thickness 0.15)) (justify mirror)) + ) + (fp_text value Ext_trig2 (at 2.54 -5.66) (layer B.Fab) + (effects (font (size 1 1) (thickness 0.15)) (justify mirror)) + ) + (fp_arc (start 0 0) (end 0 -1.68) (angle 24) (layer B.SilkS) (width 0.12)) + (fp_arc (start 0 0) (end 1.535 -0.684) (angle 48) (layer B.SilkS) (width 0.12)) + (fp_arc (start 0 0) (end 0.684 1.535) (angle 48) (layer B.SilkS) (width 0.12)) + (fp_arc (start 0 0) (end -1.535 0.684) (angle 48) (layer B.SilkS) (width 0.12)) + (fp_arc (start 0 0) (end -0.684 -1.535) (angle 25) (layer B.SilkS) (width 0.12)) + (fp_circle (center 0 0) (end 1.5 0) (layer B.Fab) (width 0.1)) + (fp_circle (center 5.08 0) (end 6.58 0) (layer B.Fab) (width 0.1)) + (fp_circle (center 5.08 0) (end 6.76 0) (layer B.SilkS) (width 0.12)) + (fp_line (start -2.54 5.2) (end 7.62 5.2) (layer B.Fab) (width 0.1)) + (fp_line (start 7.62 5.2) (end 7.62 -4.6) (layer B.Fab) (width 0.1)) + (fp_line (start 7.62 -4.6) (end -2.04 -4.6) (layer B.Fab) (width 0.1)) + (fp_line (start -2.04 -4.6) (end -2.54 -4.1) (layer B.Fab) (width 0.1)) + (fp_line (start -2.54 -4.1) (end -2.54 5.2) (layer B.Fab) (width 0.1)) + (fp_line (start -2.54 -4.1) (end 7.62 -4.1) (layer B.Fab) (width 0.1)) + (fp_line (start -2.6 -4.1) (end 7.68 -4.1) (layer B.SilkS) (width 0.12)) + (fp_line (start -2.54 -2.6) (end 7.62 -2.6) (layer B.Fab) (width 0.1)) + (fp_line (start -2.6 -2.6) (end 7.68 -2.6) (layer B.SilkS) (width 0.12)) + (fp_line (start -2.54 2.3) (end 7.62 2.3) (layer B.Fab) (width 0.1)) + (fp_line (start -2.6 2.301) (end 7.68 2.301) (layer B.SilkS) (width 0.12)) + (fp_line (start -2.6 5.261) (end 7.68 5.261) (layer B.SilkS) (width 0.12)) + (fp_line (start -2.6 -4.66) (end 7.68 -4.66) (layer B.SilkS) (width 0.12)) + (fp_line (start -2.6 5.261) (end -2.6 -4.66) (layer B.SilkS) (width 0.12)) + (fp_line (start 7.68 5.261) (end 7.68 -4.66) (layer B.SilkS) (width 0.12)) + (fp_line (start 1.138 0.955) (end -0.955 -1.138) (layer B.Fab) (width 0.1)) + (fp_line (start 0.955 1.138) (end -1.138 -0.955) (layer B.Fab) (width 0.1)) + (fp_line (start 6.218 0.955) (end 4.126 -1.138) (layer B.Fab) (width 0.1)) + (fp_line (start 6.035 1.138) (end 3.943 -0.955) (layer B.Fab) (width 0.1)) + (fp_line (start 6.355 1.069) (end 6.308 1.023) (layer B.SilkS) (width 0.12)) + (fp_line (start 4.046 -1.239) (end 4.011 -1.274) (layer B.SilkS) (width 0.12)) + (fp_line (start 6.15 1.275) (end 6.115 1.239) (layer B.SilkS) (width 0.12)) + (fp_line (start 3.853 -1.023) (end 3.806 -1.069) (layer B.SilkS) (width 0.12)) + (fp_line (start -2.84 -4.16) (end -2.84 -4.9) (layer B.SilkS) (width 0.12)) + (fp_line (start -2.84 -4.9) (end -2.34 -4.9) (layer B.SilkS) (width 0.12)) + (fp_line (start -3.04 5.71) (end -3.04 -5.1) (layer B.CrtYd) (width 0.05)) + (fp_line (start -3.04 -5.1) (end 8.13 -5.1) (layer B.CrtYd) (width 0.05)) + (fp_line (start 8.13 -5.1) (end 8.13 5.71) (layer B.CrtYd) (width 0.05)) + (fp_line (start 8.13 5.71) (end -3.04 5.71) (layer B.CrtYd) (width 0.05)) + (fp_text user %R (at 2.54 -3.2) (layer B.Fab) + (effects (font (size 1 1) (thickness 0.15)) (justify mirror)) + ) + (pad 1 thru_hole rect (at 0 0) (size 2.6 2.6) (drill 1.3) (layers *.Cu *.Mask) + (net 19 "Net-(J6-Pad1)")) + (pad 2 thru_hole circle (at 5.08 0) (size 2.6 2.6) (drill 1.3) (layers *.Cu *.Mask) + (net 20 "Net-(J6-Pad2)")) + (model ${KISYS3DMOD}/TerminalBlock_Phoenix.3dshapes/TerminalBlock_Phoenix_MKDS-1,5-2-5.08_1x02_P5.08mm_Horizontal.wrl + (at (xyz 0 0 0)) + (scale (xyz 1 1 1)) + (rotate (xyz 0 0 0)) + ) + ) + + (module Connector_PinSocket_2.54mm:PinSocket_1x03_P2.54mm_Vertical (layer B.Cu) (tedit 5A19A429) (tstamp 5D152389) + (at 118.5212 65.4036 270) + (descr "Through hole straight socket strip, 1x03, 2.54mm pitch, single row (from Kicad 4.0.7), script generated") + (tags "Through hole socket strip THT 1x03 2.54mm single row") + (path /5D14396C) + (fp_text reference J7 (at 2.6289 -2.6543) (layer B.SilkS) + (effects (font (size 1 1) (thickness 0.15)) (justify mirror)) + ) + (fp_text value USART1 (at 0 -7.85 270) (layer B.Fab) + (effects (font (size 1 1) (thickness 0.15)) (justify mirror)) + ) + (fp_line (start -1.27 1.27) (end 0.635 1.27) (layer B.Fab) (width 0.1)) + (fp_line (start 0.635 1.27) (end 1.27 0.635) (layer B.Fab) (width 0.1)) + (fp_line (start 1.27 0.635) (end 1.27 -6.35) (layer B.Fab) (width 0.1)) + (fp_line (start 1.27 -6.35) (end -1.27 -6.35) (layer B.Fab) (width 0.1)) + (fp_line (start -1.27 -6.35) (end -1.27 1.27) (layer B.Fab) (width 0.1)) + (fp_line (start -1.33 -1.27) (end 1.33 -1.27) (layer B.SilkS) (width 0.12)) + (fp_line (start -1.33 -1.27) (end -1.33 -6.41) (layer B.SilkS) (width 0.12)) + (fp_line (start -1.33 -6.41) (end 1.33 -6.41) (layer B.SilkS) (width 0.12)) + (fp_line (start 1.33 -1.27) (end 1.33 -6.41) (layer B.SilkS) (width 0.12)) + (fp_line (start 1.33 1.33) (end 1.33 0) (layer B.SilkS) (width 0.12)) + (fp_line (start 0 1.33) (end 1.33 1.33) (layer B.SilkS) (width 0.12)) + (fp_line (start -1.8 1.8) (end 1.75 1.8) (layer B.CrtYd) (width 0.05)) + (fp_line (start 1.75 1.8) (end 1.75 -6.85) (layer B.CrtYd) (width 0.05)) + (fp_line (start 1.75 -6.85) (end -1.8 -6.85) (layer B.CrtYd) (width 0.05)) + (fp_line (start -1.8 -6.85) (end -1.8 1.8) (layer B.CrtYd) (width 0.05)) + (fp_text user %R (at 0 -2.54 180) (layer B.Fab) + (effects (font (size 1 1) (thickness 0.15)) (justify mirror)) + ) + (pad 1 thru_hole rect (at 0 0 270) (size 1.7 1.7) (drill 1) (layers *.Cu *.Mask) + (net 1 GND)) + (pad 2 thru_hole oval (at 0 -2.54 270) (size 1.7 1.7) (drill 1) (layers *.Cu *.Mask) + (net 21 /U1Tx)) + (pad 3 thru_hole oval (at 0 -5.08 270) (size 1.7 1.7) (drill 1) (layers *.Cu *.Mask) + (net 22 /U1Rx)) + (model ${KISYS3DMOD}/Connector_PinSocket_2.54mm.3dshapes/PinSocket_1x03_P2.54mm_Vertical.wrl + (at (xyz 0 0 0)) + (scale (xyz 1 1 1)) + (rotate (xyz 0 0 0)) + ) + ) + + (module Inductor_SMD:L_12x12mm_H4.5mm (layer F.Cu) (tedit 5990349B) (tstamp 5D1523D8) + (at 123.0835 91.0195 180) + (descr "Choke, SMD, 12x12mm 4.5mm height") + (tags "Choke SMD") + (path /58C43929) + (attr smd) + (fp_text reference L1 (at 0 -8.89 180) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text value 100u (at 0 8.89 180) (layer F.Fab) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text user %R (at 0 0 180) (layer F.Fab) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_line (start 6.3 3.3) (end 6.3 6.3) (layer F.SilkS) (width 0.12)) + (fp_line (start 6.3 6.3) (end -6.3 6.3) (layer F.SilkS) (width 0.12)) + (fp_line (start -6.3 6.3) (end -6.3 3.3) (layer F.SilkS) (width 0.12)) + (fp_line (start -6.3 -3.3) (end -6.3 -6.3) (layer F.SilkS) (width 0.12)) + (fp_line (start -6.3 -6.3) (end 6.3 -6.3) (layer F.SilkS) (width 0.12)) + (fp_line (start 6.3 -6.3) (end 6.3 -3.3) (layer F.SilkS) (width 0.12)) + (fp_line (start -6.86 -6.6) (end 6.86 -6.6) (layer F.CrtYd) (width 0.05)) + (fp_line (start 6.86 -6.6) (end 6.86 6.6) (layer F.CrtYd) (width 0.05)) + (fp_line (start 6.86 6.6) (end -6.86 6.6) (layer F.CrtYd) (width 0.05)) + (fp_line (start -6.86 6.6) (end -6.86 -6.6) (layer F.CrtYd) (width 0.05)) + (fp_line (start 4.9 3.3) (end 5 3.4) (layer F.Fab) (width 0.1)) + (fp_line (start 5 3.4) (end 5.1 3.8) (layer F.Fab) (width 0.1)) + (fp_line (start 5.1 3.8) (end 5 4.3) (layer F.Fab) (width 0.1)) + (fp_line (start 5 4.3) (end 4.8 4.6) (layer F.Fab) (width 0.1)) + (fp_line (start 4.8 4.6) (end 4.5 5) (layer F.Fab) (width 0.1)) + (fp_line (start 4.5 5) (end 4 5.1) (layer F.Fab) (width 0.1)) + (fp_line (start 4 5.1) (end 3.5 5) (layer F.Fab) (width 0.1)) + (fp_line (start 3.5 5) (end 3.1 4.7) (layer F.Fab) (width 0.1)) + (fp_line (start 3.1 4.7) (end 3 4.6) (layer F.Fab) (width 0.1)) + (fp_line (start 3 4.6) (end 2.4 5) (layer F.Fab) (width 0.1)) + (fp_line (start 2.4 5) (end 1.6 5.3) (layer F.Fab) (width 0.1)) + (fp_line (start 1.6 5.3) (end 0.6 5.5) (layer F.Fab) (width 0.1)) + (fp_line (start 0.6 5.5) (end -0.6 5.5) (layer F.Fab) (width 0.1)) + (fp_line (start -0.6 5.5) (end -1.5 5.3) (layer F.Fab) (width 0.1)) + (fp_line (start -1.5 5.3) (end -2.1 5.1) (layer F.Fab) (width 0.1)) + (fp_line (start -2.1 5.1) (end -2.6 4.9) (layer F.Fab) (width 0.1)) + (fp_line (start -2.6 4.9) (end -3 4.7) (layer F.Fab) (width 0.1)) + (fp_line (start -3 4.7) (end -3.3 4.9) (layer F.Fab) (width 0.1)) + (fp_line (start -3.3 4.9) (end -3.9 5.1) (layer F.Fab) (width 0.1)) + (fp_line (start -3.9 5.1) (end -4.3 5) (layer F.Fab) (width 0.1)) + (fp_line (start -4.3 5) (end -4.6 4.8) (layer F.Fab) (width 0.1)) + (fp_line (start -4.6 4.8) (end -4.9 4.6) (layer F.Fab) (width 0.1)) + (fp_line (start -4.9 4.6) (end -5.1 4.1) (layer F.Fab) (width 0.1)) + (fp_line (start -5.1 4.1) (end -5 3.6) (layer F.Fab) (width 0.1)) + (fp_line (start -5 3.6) (end -4.8 3.2) (layer F.Fab) (width 0.1)) + (fp_line (start 4.9 -3.3) (end 5 -3.6) (layer F.Fab) (width 0.1)) + (fp_line (start 5 -3.6) (end 5.1 -4) (layer F.Fab) (width 0.1)) + (fp_line (start 5.1 -4) (end 5 -4.3) (layer F.Fab) (width 0.1)) + (fp_line (start 5 -4.3) (end 4.8 -4.7) (layer F.Fab) (width 0.1)) + (fp_line (start 4.8 -4.7) (end 4.5 -4.9) (layer F.Fab) (width 0.1)) + (fp_line (start 4.5 -4.9) (end 4.2 -5.1) (layer F.Fab) (width 0.1)) + (fp_line (start 4.2 -5.1) (end 3.9 -5.1) (layer F.Fab) (width 0.1)) + (fp_line (start 3.9 -5.1) (end 3.6 -5) (layer F.Fab) (width 0.1)) + (fp_line (start 3.6 -5) (end 3.3 -4.9) (layer F.Fab) (width 0.1)) + (fp_line (start 3.3 -4.9) (end 3 -4.6) (layer F.Fab) (width 0.1)) + (fp_line (start 3 -4.6) (end 2.6 -4.9) (layer F.Fab) (width 0.1)) + (fp_line (start 2.6 -4.9) (end 2.2 -5.1) (layer F.Fab) (width 0.1)) + (fp_line (start 2.2 -5.1) (end 1.7 -5.3) (layer F.Fab) (width 0.1)) + (fp_line (start 1.7 -5.3) (end 0.9 -5.5) (layer F.Fab) (width 0.1)) + (fp_line (start 0.9 -5.5) (end 0 -5.6) (layer F.Fab) (width 0.1)) + (fp_line (start 0 -5.6) (end -0.8 -5.5) (layer F.Fab) (width 0.1)) + (fp_line (start -0.8 -5.5) (end -1.7 -5.3) (layer F.Fab) (width 0.1)) + (fp_line (start -1.7 -5.3) (end -2.6 -4.9) (layer F.Fab) (width 0.1)) + (fp_line (start -2.6 -4.9) (end -3 -4.7) (layer F.Fab) (width 0.1)) + (fp_line (start -3 -4.7) (end -3.3 -4.9) (layer F.Fab) (width 0.1)) + (fp_line (start -3.3 -4.9) (end -3.7 -5.1) (layer F.Fab) (width 0.1)) + (fp_line (start -3.7 -5.1) (end -4.2 -5) (layer F.Fab) (width 0.1)) + (fp_line (start -4.2 -5) (end -4.6 -4.8) (layer F.Fab) (width 0.1)) + (fp_line (start -4.6 -4.8) (end -4.9 -4.5) (layer F.Fab) (width 0.1)) + (fp_line (start -4.9 -4.5) (end -5.1 -4) (layer F.Fab) (width 0.1)) + (fp_line (start -5.1 -4) (end -5 -3.5) (layer F.Fab) (width 0.1)) + (fp_line (start -5 -3.5) (end -4.8 -3.2) (layer F.Fab) (width 0.1)) + (fp_line (start -6.2 3.3) (end -6.2 6.2) (layer F.Fab) (width 0.1)) + (fp_line (start -6.2 6.2) (end 6.2 6.2) (layer F.Fab) (width 0.1)) + (fp_line (start 6.2 6.2) (end 6.2 3.3) (layer F.Fab) (width 0.1)) + (fp_line (start 6.2 -6.2) (end -6.2 -6.2) (layer F.Fab) (width 0.1)) + (fp_line (start -6.2 -6.2) (end -6.2 -3.3) (layer F.Fab) (width 0.1)) + (fp_line (start 6.2 -6.2) (end 6.2 -3.3) (layer F.Fab) (width 0.1)) + (fp_circle (center 0 0) (end 0.9 0) (layer F.Adhes) (width 0.38)) + (fp_circle (center 0 0) (end 0.55 0) (layer F.Adhes) (width 0.38)) + (fp_circle (center 0 0) (end 0.15 0.15) (layer F.Adhes) (width 0.38)) + (fp_circle (center -2.1 3) (end -1.8 3.25) (layer F.Fab) (width 0.1)) + (pad 1 smd rect (at -4.95 0 180) (size 2.9 5.4) (layers F.Cu F.Paste F.Mask) + (net 3 +5V)) + (pad 2 smd rect (at 4.95 0 180) (size 2.9 5.4) (layers F.Cu F.Paste F.Mask) + (net 8 "Net-(D3-Pad1)")) + (model ${KISYS3DMOD}/Inductor_SMD.3dshapes/L_12x12mm_H4.5mm.wrl + (at (xyz 0 0 0)) + (scale (xyz 1 1 1)) + (rotate (xyz 0 0 0)) + ) + ) + + (module Connectors_USB:USB_B_OST_USB-B1HSxx_Horizontal (layer B.Cu) (tedit 5AFE01FF) (tstamp 5D154E88) + (at 130.8402 64.032) + (descr "USB B receptacle, Horizontal, through-hole, http://www.on-shore.com/wp-content/uploads/2015/09/usb-b1hsxx.pdf") + (tags "USB-B receptacle horizontal through-hole") + (path /5CEABE76) + (fp_text reference P1 (at 6.76 7.77) (layer B.SilkS) + (effects (font (size 1 1) (thickness 0.15)) (justify mirror)) + ) + (fp_text value USB_B (at 6.76 -10.27) (layer B.Fab) + (effects (font (size 1 1) (thickness 0.15)) (justify mirror)) + ) + (fp_line (start -0.49 4.8) (end 15.01 4.8) (layer B.Fab) (width 0.1)) + (fp_line (start 15.01 4.8) (end 15.01 -7.3) (layer B.Fab) (width 0.1)) + (fp_line (start 15.01 -7.3) (end -1.49 -7.3) (layer B.Fab) (width 0.1)) + (fp_line (start -1.49 -7.3) (end -1.49 3.8) (layer B.Fab) (width 0.1)) + (fp_line (start -1.49 3.8) (end -0.49 4.8) (layer B.Fab) (width 0.1)) + (fp_line (start 2.66 4.91) (end -1.6 4.91) (layer B.SilkS) (width 0.12)) + (fp_line (start -1.6 4.91) (end -1.6 -7.41) (layer B.SilkS) (width 0.12)) + (fp_line (start -1.6 -7.41) (end 2.66 -7.41) (layer B.SilkS) (width 0.12)) + (fp_line (start 6.76 4.91) (end 15.12 4.91) (layer B.SilkS) (width 0.12)) + (fp_line (start 15.12 4.91) (end 15.12 -7.41) (layer B.SilkS) (width 0.12)) + (fp_line (start 15.12 -7.41) (end 6.76 -7.41) (layer B.SilkS) (width 0.12)) + (fp_line (start -1.82 0) (end -2.32 0.5) (layer B.SilkS) (width 0.12)) + (fp_line (start -2.32 0.5) (end -2.32 -0.5) (layer B.SilkS) (width 0.12)) + (fp_line (start -2.32 -0.5) (end -1.82 0) (layer B.SilkS) (width 0.12)) + (fp_line (start -1.99 7.02) (end -1.99 -9.52) (layer B.CrtYd) (width 0.05)) + (fp_line (start -1.99 -9.52) (end 15.51 -9.52) (layer B.CrtYd) (width 0.05)) + (fp_line (start 15.51 -9.52) (end 15.51 7.02) (layer B.CrtYd) (width 0.05)) + (fp_line (start 15.51 7.02) (end -1.99 7.02) (layer B.CrtYd) (width 0.05)) + (fp_text user %R (at 6.76 -1.25) (layer B.Fab) + (effects (font (size 1 1) (thickness 0.15)) (justify mirror)) + ) + (pad 1 thru_hole rect (at 0 0) (size 1.7 1.7) (drill 0.92) (layers *.Cu *.Mask) + (net 7 "Net-(D2-Pad2)")) + (pad 2 thru_hole circle (at 0 -2.5) (size 1.7 1.7) (drill 0.92) (layers *.Cu *.Mask) + (net 23 "Net-(P1-Pad2)")) + (pad 3 thru_hole circle (at 2 -2.5) (size 1.7 1.7) (drill 0.92) (layers *.Cu *.Mask) + (net 24 "Net-(P1-Pad3)")) + (pad 4 thru_hole circle (at 2 0) (size 1.7 1.7) (drill 0.92) (layers *.Cu *.Mask) + (net 1 GND)) + (pad 5 thru_hole circle (at 4.71 4.77) (size 3.5 3.5) (drill 2.33) (layers *.Cu *.Mask) + (net 1 GND)) + (pad 5 thru_hole circle (at 4.71 -7.27) (size 3.5 3.5) (drill 2.33) (layers *.Cu *.Mask) + (net 1 GND)) + (model ${KISYS3DMOD}/Connector_USB.3dshapes/USB_B_OST_USB-B1HSxx_Horizontal.wrl + (at (xyz 0 0 0)) + (scale (xyz 1 1 1)) + (rotate (xyz 0 0 0)) + ) + ) + + (module TO_SOT_Packages_SMD:SOT-23_Handsoldering (layer F.Cu) (tedit 5A0AB76C) (tstamp 5D160066) + (at 103.3715 78.7005 180) + (descr "SOT-23, Handsoldering") + (tags SOT-23) + (path /5910E2F2) + (attr smd) + (fp_text reference Q1 (at 0 -2.5 180) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text value AO3407 (at 0 2.5 180) (layer F.Fab) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text user %R (at 0 0 270) (layer F.Fab) + (effects (font (size 0.5 0.5) (thickness 0.075))) + ) + (fp_line (start 0.76 1.58) (end 0.76 0.65) (layer F.SilkS) (width 0.12)) + (fp_line (start 0.76 -1.58) (end 0.76 -0.65) (layer F.SilkS) (width 0.12)) + (fp_line (start -2.7 -1.75) (end 2.7 -1.75) (layer F.CrtYd) (width 0.05)) + (fp_line (start 2.7 -1.75) (end 2.7 1.75) (layer F.CrtYd) (width 0.05)) + (fp_line (start 2.7 1.75) (end -2.7 1.75) (layer F.CrtYd) (width 0.05)) + (fp_line (start -2.7 1.75) (end -2.7 -1.75) (layer F.CrtYd) (width 0.05)) + (fp_line (start 0.76 -1.58) (end -2.4 -1.58) (layer F.SilkS) (width 0.12)) + (fp_line (start -0.7 -0.95) (end -0.7 1.5) (layer F.Fab) (width 0.1)) + (fp_line (start -0.15 -1.52) (end 0.7 -1.52) (layer F.Fab) (width 0.1)) + (fp_line (start -0.7 -0.95) (end -0.15 -1.52) (layer F.Fab) (width 0.1)) + (fp_line (start 0.7 -1.52) (end 0.7 1.52) (layer F.Fab) (width 0.1)) + (fp_line (start -0.7 1.52) (end 0.7 1.52) (layer F.Fab) (width 0.1)) + (fp_line (start 0.76 1.58) (end -0.7 1.58) (layer F.SilkS) (width 0.12)) + (pad 1 smd rect (at -1.5 -0.95 180) (size 1.9 0.8) (layers F.Cu F.Paste F.Mask) + (net 43 "Net-(D1-Pad2)")) + (pad 2 smd rect (at -1.5 0.95 180) (size 1.9 0.8) (layers F.Cu F.Paste F.Mask) + (net 6 "Net-(C3-Pad1)")) + (pad 3 smd rect (at 1.5 0 180) (size 1.9 0.8) (layers F.Cu F.Paste F.Mask) + (net 13 "Net-(J1-Pad2)")) + (model ${KISYS3DMOD}/Package_TO_SOT_SMD.3dshapes/SOT-23.wrl + (at (xyz 0 0 0)) + (scale (xyz 1 1 1)) + (rotate (xyz 0 0 0)) + ) + ) + + (module TO_SOT_Packages_SMD:SOT-323_SC-70_Handsoldering (layer F.Cu) (tedit 5A02FF57) (tstamp 5D15241F) + (at 124.22 56.046) + (descr "SOT-323, SC-70 Handsoldering") + (tags "SOT-323 SC-70 Handsoldering") + (path /5D5EB488) + (attr smd) + (fp_text reference Q2 (at -0.822 -2.047) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text value DTA114Y (at 0 2.05) (layer F.Fab) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text user %R (at 0 0 90) (layer F.Fab) + (effects (font (size 0.5 0.5) (thickness 0.075))) + ) + (fp_line (start 0.735 0.5) (end 0.735 1.16) (layer F.SilkS) (width 0.12)) + (fp_line (start 0.735 -1.17) (end 0.735 -0.5) (layer F.SilkS) (width 0.12)) + (fp_line (start 2.4 1.3) (end -2.4 1.3) (layer F.CrtYd) (width 0.05)) + (fp_line (start 2.4 -1.3) (end 2.4 1.3) (layer F.CrtYd) (width 0.05)) + (fp_line (start -2.4 -1.3) (end 2.4 -1.3) (layer F.CrtYd) (width 0.05)) + (fp_line (start -2.4 1.3) (end -2.4 -1.3) (layer F.CrtYd) (width 0.05)) + (fp_line (start 0.735 -1.16) (end -2 -1.16) (layer F.SilkS) (width 0.12)) + (fp_line (start -0.675 1.16) (end 0.735 1.16) (layer F.SilkS) (width 0.12)) + (fp_line (start 0.675 -1.1) (end -0.175 -1.1) (layer F.Fab) (width 0.1)) + (fp_line (start -0.675 -0.6) (end -0.675 1.1) (layer F.Fab) (width 0.1)) + (fp_line (start 0.675 -1.1) (end 0.675 1.1) (layer F.Fab) (width 0.1)) + (fp_line (start 0.675 1.1) (end -0.675 1.1) (layer F.Fab) (width 0.1)) + (fp_line (start -0.175 -1.1) (end -0.675 -0.6) (layer F.Fab) (width 0.1)) + (pad 1 smd rect (at -1.33 -0.65 270) (size 0.45 1.5) (layers F.Cu F.Paste F.Mask) + (net 25 /USB_PU)) + (pad 2 smd rect (at -1.33 0.65 270) (size 0.45 1.5) (layers F.Cu F.Paste F.Mask) + (net 2 +3V3)) + (pad 3 smd rect (at 1.33 0 270) (size 0.45 1.5) (layers F.Cu F.Paste F.Mask) + (net 26 "Net-(Q2-Pad3)")) + (model ${KISYS3DMOD}/Package_TO_SOT_SMD.3dshapes/SOT-323_SC-70.wrl + (at (xyz 0 0 0)) + (scale (xyz 1 1 1)) + (rotate (xyz 0 0 0)) + ) + ) + + (module Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder (layer F.Cu) (tedit 5B301BBD) (tstamp 5D15B7F1) + (at 107.001 52.2845 180) + (descr "Resistor SMD 0603 (1608 Metric), square (rectangular) end terminal, IPC_7351 nominal with elongated pad for handsoldering. (Body size source: http://www.tortai-tech.com/upload/download/2011102023233369053.pdf), generated with kicad-footprint-generator") + (tags "resistor handsolder") + (path /5D347863) + (attr smd) + (fp_text reference R1 (at 2.653 0 180) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text value 10k (at 0 1.43 180) (layer F.Fab) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text user %R (at 0 0 180) (layer F.Fab) + (effects (font (size 0.4 0.4) (thickness 0.06))) + ) + (fp_line (start 1.65 0.73) (end -1.65 0.73) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.65 -0.73) (end 1.65 0.73) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.65 -0.73) (end 1.65 -0.73) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.65 0.73) (end -1.65 -0.73) (layer F.CrtYd) (width 0.05)) + (fp_line (start -0.171267 0.51) (end 0.171267 0.51) (layer F.SilkS) (width 0.12)) + (fp_line (start -0.171267 -0.51) (end 0.171267 -0.51) (layer F.SilkS) (width 0.12)) + (fp_line (start 0.8 0.4) (end -0.8 0.4) (layer F.Fab) (width 0.1)) + (fp_line (start 0.8 -0.4) (end 0.8 0.4) (layer F.Fab) (width 0.1)) + (fp_line (start -0.8 -0.4) (end 0.8 -0.4) (layer F.Fab) (width 0.1)) + (fp_line (start -0.8 0.4) (end -0.8 -0.4) (layer F.Fab) (width 0.1)) + (pad 2 smd roundrect (at 0.875 0 180) (size 1.05 0.95) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.25) + (net 1 GND)) + (pad 1 smd roundrect (at -0.875 0 180) (size 1.05 0.95) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.25) + (net 40 /BOOT0)) + (model ${KISYS3DMOD}/Resistor_SMD.3dshapes/R_0603_1608Metric.wrl + (at (xyz 0 0 0)) + (scale (xyz 1 1 1)) + (rotate (xyz 0 0 0)) + ) + ) + + (module Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder (layer F.Cu) (tedit 5B301BBD) (tstamp 5D152441) + (at 103.205 60.617 270) + (descr "Resistor SMD 0603 (1608 Metric), square (rectangular) end terminal, IPC_7351 nominal with elongated pad for handsoldering. (Body size source: http://www.tortai-tech.com/upload/download/2011102023233369053.pdf), generated with kicad-footprint-generator") + (tags "resistor handsolder") + (path /590D3334) + (attr smd) + (fp_text reference R2 (at -2.427 -0.127) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text value 10k (at 0 1.43 270) (layer F.Fab) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_line (start -0.8 0.4) (end -0.8 -0.4) (layer F.Fab) (width 0.1)) + (fp_line (start -0.8 -0.4) (end 0.8 -0.4) (layer F.Fab) (width 0.1)) + (fp_line (start 0.8 -0.4) (end 0.8 0.4) (layer F.Fab) (width 0.1)) + (fp_line (start 0.8 0.4) (end -0.8 0.4) (layer F.Fab) (width 0.1)) + (fp_line (start -0.171267 -0.51) (end 0.171267 -0.51) (layer F.SilkS) (width 0.12)) + (fp_line (start -0.171267 0.51) (end 0.171267 0.51) (layer F.SilkS) (width 0.12)) + (fp_line (start -1.65 0.73) (end -1.65 -0.73) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.65 -0.73) (end 1.65 -0.73) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.65 -0.73) (end 1.65 0.73) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.65 0.73) (end -1.65 0.73) (layer F.CrtYd) (width 0.05)) + (fp_text user %R (at 0 0 270) (layer F.Fab) + (effects (font (size 0.4 0.4) (thickness 0.06))) + ) + (pad 1 smd roundrect (at -0.875 0 270) (size 1.05 0.95) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.25) + (net 39 /NRST)) + (pad 2 smd roundrect (at 0.875 0 270) (size 1.05 0.95) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.25) + (net 2 +3V3)) + (model ${KISYS3DMOD}/Resistor_SMD.3dshapes/R_0603_1608Metric.wrl + (at (xyz 0 0 0)) + (scale (xyz 1 1 1)) + (rotate (xyz 0 0 0)) + ) + ) + + (module Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder (layer F.Cu) (tedit 5B301BBD) (tstamp 5D152452) + (at 121.507 58.2535 180) + (descr "Resistor SMD 0603 (1608 Metric), square (rectangular) end terminal, IPC_7351 nominal with elongated pad for handsoldering. (Body size source: http://www.tortai-tech.com/upload/download/2011102023233369053.pdf), generated with kicad-footprint-generator") + (tags "resistor handsolder") + (path /5CEABEA6) + (attr smd) + (fp_text reference R3 (at 0 -1.43 180) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text value 22 (at 0 1.43 180) (layer F.Fab) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_line (start -0.8 0.4) (end -0.8 -0.4) (layer F.Fab) (width 0.1)) + (fp_line (start -0.8 -0.4) (end 0.8 -0.4) (layer F.Fab) (width 0.1)) + (fp_line (start 0.8 -0.4) (end 0.8 0.4) (layer F.Fab) (width 0.1)) + (fp_line (start 0.8 0.4) (end -0.8 0.4) (layer F.Fab) (width 0.1)) + (fp_line (start -0.171267 -0.51) (end 0.171267 -0.51) (layer F.SilkS) (width 0.12)) + (fp_line (start -0.171267 0.51) (end 0.171267 0.51) (layer F.SilkS) (width 0.12)) + (fp_line (start -1.65 0.73) (end -1.65 -0.73) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.65 -0.73) (end 1.65 -0.73) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.65 -0.73) (end 1.65 0.73) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.65 0.73) (end -1.65 0.73) (layer F.CrtYd) (width 0.05)) + (fp_text user %R (at 0 0 180) (layer F.Fab) + (effects (font (size 0.4 0.4) (thickness 0.06))) + ) + (pad 1 smd roundrect (at -0.875 0 180) (size 1.05 0.95) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.25) + (net 28 "Net-(R3-Pad1)")) + (pad 2 smd roundrect (at 0.875 0 180) (size 1.05 0.95) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.25) + (net 30 /USBDP)) + (model ${KISYS3DMOD}/Resistor_SMD.3dshapes/R_0603_1608Metric.wrl + (at (xyz 0 0 0)) + (scale (xyz 1 1 1)) + (rotate (xyz 0 0 0)) + ) + ) + + (module Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder (layer F.Cu) (tedit 5B301BBD) (tstamp 5D152463) + (at 121.507 61.1745 180) + (descr "Resistor SMD 0603 (1608 Metric), square (rectangular) end terminal, IPC_7351 nominal with elongated pad for handsoldering. (Body size source: http://www.tortai-tech.com/upload/download/2011102023233369053.pdf), generated with kicad-footprint-generator") + (tags "resistor handsolder") + (path /5CEABEAC) + (attr smd) + (fp_text reference R4 (at 0 -1.43 180) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text value 22 (at 0 1.43 180) (layer F.Fab) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text user %R (at 0 0 180) (layer F.Fab) + (effects (font (size 0.4 0.4) (thickness 0.06))) + ) + (fp_line (start 1.65 0.73) (end -1.65 0.73) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.65 -0.73) (end 1.65 0.73) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.65 -0.73) (end 1.65 -0.73) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.65 0.73) (end -1.65 -0.73) (layer F.CrtYd) (width 0.05)) + (fp_line (start -0.171267 0.51) (end 0.171267 0.51) (layer F.SilkS) (width 0.12)) + (fp_line (start -0.171267 -0.51) (end 0.171267 -0.51) (layer F.SilkS) (width 0.12)) + (fp_line (start 0.8 0.4) (end -0.8 0.4) (layer F.Fab) (width 0.1)) + (fp_line (start 0.8 -0.4) (end 0.8 0.4) (layer F.Fab) (width 0.1)) + (fp_line (start -0.8 -0.4) (end 0.8 -0.4) (layer F.Fab) (width 0.1)) + (fp_line (start -0.8 0.4) (end -0.8 -0.4) (layer F.Fab) (width 0.1)) + (pad 2 smd roundrect (at 0.875 0 180) (size 1.05 0.95) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.25) + (net 27 /USBDM)) + (pad 1 smd roundrect (at -0.875 0 180) (size 1.05 0.95) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.25) + (net 29 "Net-(R4-Pad1)")) + (model ${KISYS3DMOD}/Resistor_SMD.3dshapes/R_0603_1608Metric.wrl + (at (xyz 0 0 0)) + (scale (xyz 1 1 1)) + (rotate (xyz 0 0 0)) + ) + ) + + (module Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder (layer F.Cu) (tedit 5B301BBD) (tstamp 5D15FC25) + (at 107.7135 82.941 90) + (descr "Resistor SMD 0603 (1608 Metric), square (rectangular) end terminal, IPC_7351 nominal with elongated pad for handsoldering. (Body size source: http://www.tortai-tech.com/upload/download/2011102023233369053.pdf), generated with kicad-footprint-generator") + (tags "resistor handsolder") + (path /5D16EDDD) + (attr smd) + (fp_text reference R5 (at -2.4905 -0.127 180) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text value 10k (at 0 1.43 90) (layer F.Fab) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text user %R (at 0 0 90) (layer F.Fab) + (effects (font (size 0.4 0.4) (thickness 0.06))) + ) + (fp_line (start 1.65 0.73) (end -1.65 0.73) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.65 -0.73) (end 1.65 0.73) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.65 -0.73) (end 1.65 -0.73) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.65 0.73) (end -1.65 -0.73) (layer F.CrtYd) (width 0.05)) + (fp_line (start -0.171267 0.51) (end 0.171267 0.51) (layer F.SilkS) (width 0.12)) + (fp_line (start -0.171267 -0.51) (end 0.171267 -0.51) (layer F.SilkS) (width 0.12)) + (fp_line (start 0.8 0.4) (end -0.8 0.4) (layer F.Fab) (width 0.1)) + (fp_line (start 0.8 -0.4) (end 0.8 0.4) (layer F.Fab) (width 0.1)) + (fp_line (start -0.8 -0.4) (end 0.8 -0.4) (layer F.Fab) (width 0.1)) + (fp_line (start -0.8 0.4) (end -0.8 -0.4) (layer F.Fab) (width 0.1)) + (pad 2 smd roundrect (at 0.875 0 90) (size 1.05 0.95) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.25) + (net 43 "Net-(D1-Pad2)")) + (pad 1 smd roundrect (at -0.875 0 90) (size 1.05 0.95) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.25) + (net 1 GND)) + (model ${KISYS3DMOD}/Resistor_SMD.3dshapes/R_0603_1608Metric.wrl + (at (xyz 0 0 0)) + (scale (xyz 1 1 1)) + (rotate (xyz 0 0 0)) + ) + ) + + (module Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder (layer F.Cu) (tedit 5B301BBD) (tstamp 5D152485) + (at 126.5235 53.872) + (descr "Resistor SMD 0603 (1608 Metric), square (rectangular) end terminal, IPC_7351 nominal with elongated pad for handsoldering. (Body size source: http://www.tortai-tech.com/upload/download/2011102023233369053.pdf), generated with kicad-footprint-generator") + (tags "resistor handsolder") + (path /5D5EA0B2) + (attr smd) + (fp_text reference R6 (at 2.7165 0) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text value 1k5 (at 0 1.43) (layer F.Fab) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_line (start -0.8 0.4) (end -0.8 -0.4) (layer F.Fab) (width 0.1)) + (fp_line (start -0.8 -0.4) (end 0.8 -0.4) (layer F.Fab) (width 0.1)) + (fp_line (start 0.8 -0.4) (end 0.8 0.4) (layer F.Fab) (width 0.1)) + (fp_line (start 0.8 0.4) (end -0.8 0.4) (layer F.Fab) (width 0.1)) + (fp_line (start -0.171267 -0.51) (end 0.171267 -0.51) (layer F.SilkS) (width 0.12)) + (fp_line (start -0.171267 0.51) (end 0.171267 0.51) (layer F.SilkS) (width 0.12)) + (fp_line (start -1.65 0.73) (end -1.65 -0.73) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.65 -0.73) (end 1.65 -0.73) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.65 -0.73) (end 1.65 0.73) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.65 0.73) (end -1.65 0.73) (layer F.CrtYd) (width 0.05)) + (fp_text user %R (at 0 0) (layer F.Fab) + (effects (font (size 0.4 0.4) (thickness 0.06))) + ) + (pad 1 smd roundrect (at -0.875 0) (size 1.05 0.95) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.25) + (net 26 "Net-(Q2-Pad3)")) + (pad 2 smd roundrect (at 0.875 0) (size 1.05 0.95) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.25) + (net 23 "Net-(P1-Pad2)")) + (model ${KISYS3DMOD}/Resistor_SMD.3dshapes/R_0603_1608Metric.wrl + (at (xyz 0 0 0)) + (scale (xyz 1 1 1)) + (rotate (xyz 0 0 0)) + ) + ) + + (module Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder (layer F.Cu) (tedit 5B301BBD) (tstamp 5D160271) + (at 133.939 85.5445 90) + (descr "Resistor SMD 0603 (1608 Metric), square (rectangular) end terminal, IPC_7351 nominal with elongated pad for handsoldering. (Body size source: http://www.tortai-tech.com/upload/download/2011102023233369053.pdf), generated with kicad-footprint-generator") + (tags "resistor handsolder") + (path /5D93EDCC) + (attr smd) + (fp_text reference R7 (at 0.8115 -1.8415 180) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text value 22 (at 0 1.43 90) (layer F.Fab) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_line (start -0.8 0.4) (end -0.8 -0.4) (layer F.Fab) (width 0.1)) + (fp_line (start -0.8 -0.4) (end 0.8 -0.4) (layer F.Fab) (width 0.1)) + (fp_line (start 0.8 -0.4) (end 0.8 0.4) (layer F.Fab) (width 0.1)) + (fp_line (start 0.8 0.4) (end -0.8 0.4) (layer F.Fab) (width 0.1)) + (fp_line (start -0.171267 -0.51) (end 0.171267 -0.51) (layer F.SilkS) (width 0.12)) + (fp_line (start -0.171267 0.51) (end 0.171267 0.51) (layer F.SilkS) (width 0.12)) + (fp_line (start -1.65 0.73) (end -1.65 -0.73) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.65 -0.73) (end 1.65 -0.73) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.65 -0.73) (end 1.65 0.73) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.65 0.73) (end -1.65 0.73) (layer F.CrtYd) (width 0.05)) + (fp_text user %R (at 0 0 90) (layer F.Fab) + (effects (font (size 0.4 0.4) (thickness 0.06))) + ) + (pad 1 smd roundrect (at -0.875 0 90) (size 1.05 0.95) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.25) + (net 14 "Net-(J2-Pad1)")) + (pad 2 smd roundrect (at 0.875 0 90) (size 1.05 0.95) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.25) + (net 3 +5V)) + (model ${KISYS3DMOD}/Resistor_SMD.3dshapes/R_0603_1608Metric.wrl + (at (xyz 0 0 0)) + (scale (xyz 1 1 1)) + (rotate (xyz 0 0 0)) + ) + ) + + (module Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder (layer B.Cu) (tedit 5B301BBD) (tstamp 5D1524A7) + (at 95.2675 48.4605 270) + (descr "Resistor SMD 0603 (1608 Metric), square (rectangular) end terminal, IPC_7351 nominal with elongated pad for handsoldering. (Body size source: http://www.tortai-tech.com/upload/download/2011102023233369053.pdf), generated with kicad-footprint-generator") + (tags "resistor handsolder") + (path /5908EB17) + (attr smd) + (fp_text reference R8 (at -0.0495 1.778) (layer B.SilkS) + (effects (font (size 1 1) (thickness 0.15)) (justify mirror)) + ) + (fp_text value 330 (at 0 -1.43 270) (layer B.Fab) + (effects (font (size 1 1) (thickness 0.15)) (justify mirror)) + ) + (fp_line (start -0.8 -0.4) (end -0.8 0.4) (layer B.Fab) (width 0.1)) + (fp_line (start -0.8 0.4) (end 0.8 0.4) (layer B.Fab) (width 0.1)) + (fp_line (start 0.8 0.4) (end 0.8 -0.4) (layer B.Fab) (width 0.1)) + (fp_line (start 0.8 -0.4) (end -0.8 -0.4) (layer B.Fab) (width 0.1)) + (fp_line (start -0.171267 0.51) (end 0.171267 0.51) (layer B.SilkS) (width 0.12)) + (fp_line (start -0.171267 -0.51) (end 0.171267 -0.51) (layer B.SilkS) (width 0.12)) + (fp_line (start -1.65 -0.73) (end -1.65 0.73) (layer B.CrtYd) (width 0.05)) + (fp_line (start -1.65 0.73) (end 1.65 0.73) (layer B.CrtYd) (width 0.05)) + (fp_line (start 1.65 0.73) (end 1.65 -0.73) (layer B.CrtYd) (width 0.05)) + (fp_line (start 1.65 -0.73) (end -1.65 -0.73) (layer B.CrtYd) (width 0.05)) + (fp_text user %R (at 0 0 270) (layer B.Fab) + (effects (font (size 0.4 0.4) (thickness 0.06)) (justify mirror)) + ) + (pad 1 smd roundrect (at -0.875 0 270) (size 1.05 0.95) (layers B.Cu B.Paste B.Mask) (roundrect_rratio 0.25) + (net 10 "Net-(D4-Pad2)")) + (pad 2 smd roundrect (at 0.875 0 270) (size 1.05 0.95) (layers B.Cu B.Paste B.Mask) (roundrect_rratio 0.25) + (net 2 +3V3)) + (model ${KISYS3DMOD}/Resistor_SMD.3dshapes/R_0603_1608Metric.wrl + (at (xyz 0 0 0)) + (scale (xyz 1 1 1)) + (rotate (xyz 0 0 0)) + ) + ) + + (module Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder (layer B.Cu) (tedit 5B301BBD) (tstamp 5D1524B8) + (at 101.935 48.4885 270) + (descr "Resistor SMD 0603 (1608 Metric), square (rectangular) end terminal, IPC_7351 nominal with elongated pad for handsoldering. (Body size source: http://www.tortai-tech.com/upload/download/2011102023233369053.pdf), generated with kicad-footprint-generator") + (tags "resistor handsolder") + (path /5909AFA0) + (attr smd) + (fp_text reference R9 (at -0.014 1.651) (layer B.SilkS) + (effects (font (size 1 1) (thickness 0.15)) (justify mirror)) + ) + (fp_text value 330 (at 0 -1.43 270) (layer B.Fab) + (effects (font (size 1 1) (thickness 0.15)) (justify mirror)) + ) + (fp_line (start -0.8 -0.4) (end -0.8 0.4) (layer B.Fab) (width 0.1)) + (fp_line (start -0.8 0.4) (end 0.8 0.4) (layer B.Fab) (width 0.1)) + (fp_line (start 0.8 0.4) (end 0.8 -0.4) (layer B.Fab) (width 0.1)) + (fp_line (start 0.8 -0.4) (end -0.8 -0.4) (layer B.Fab) (width 0.1)) + (fp_line (start -0.171267 0.51) (end 0.171267 0.51) (layer B.SilkS) (width 0.12)) + (fp_line (start -0.171267 -0.51) (end 0.171267 -0.51) (layer B.SilkS) (width 0.12)) + (fp_line (start -1.65 -0.73) (end -1.65 0.73) (layer B.CrtYd) (width 0.05)) + (fp_line (start -1.65 0.73) (end 1.65 0.73) (layer B.CrtYd) (width 0.05)) + (fp_line (start 1.65 0.73) (end 1.65 -0.73) (layer B.CrtYd) (width 0.05)) + (fp_line (start 1.65 -0.73) (end -1.65 -0.73) (layer B.CrtYd) (width 0.05)) + (fp_text user %R (at 0 0 270) (layer B.Fab) + (effects (font (size 0.4 0.4) (thickness 0.06)) (justify mirror)) + ) + (pad 1 smd roundrect (at -0.875 0 270) (size 1.05 0.95) (layers B.Cu B.Paste B.Mask) (roundrect_rratio 0.25) + (net 11 "Net-(D5-Pad2)")) + (pad 2 smd roundrect (at 0.875 0 270) (size 1.05 0.95) (layers B.Cu B.Paste B.Mask) (roundrect_rratio 0.25) + (net 2 +3V3)) + (model ${KISYS3DMOD}/Resistor_SMD.3dshapes/R_0603_1608Metric.wrl + (at (xyz 0 0 0)) + (scale (xyz 1 1 1)) + (rotate (xyz 0 0 0)) + ) + ) + + (module Resistor_SMD:R_0805_2012Metric_Pad1.15x1.40mm_HandSolder (layer F.Cu) (tedit 5B36C52B) (tstamp 5D163E3E) + (at 67.4 85.1775) + (descr "Resistor SMD 0805 (2012 Metric), square (rectangular) end terminal, IPC_7351 nominal with elongated pad for handsoldering. (Body size source: https://docs.google.com/spreadsheets/d/1BsfQQcO9C6DZCsRaXUlFlo91Tg2WpOkGARC1WS5S8t0/edit?usp=sharing), generated with kicad-footprint-generator") + (tags "resistor handsolder") + (path /5D6BDDB4) + (attr smd) + (fp_text reference R10 (at 0.0545 1.778) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text value 330 (at 0 1.65) (layer F.Fab) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_line (start -1 0.6) (end -1 -0.6) (layer F.Fab) (width 0.1)) + (fp_line (start -1 -0.6) (end 1 -0.6) (layer F.Fab) (width 0.1)) + (fp_line (start 1 -0.6) (end 1 0.6) (layer F.Fab) (width 0.1)) + (fp_line (start 1 0.6) (end -1 0.6) (layer F.Fab) (width 0.1)) + (fp_line (start -0.261252 -0.71) (end 0.261252 -0.71) (layer F.SilkS) (width 0.12)) + (fp_line (start -0.261252 0.71) (end 0.261252 0.71) (layer F.SilkS) (width 0.12)) + (fp_line (start -1.85 0.95) (end -1.85 -0.95) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.85 -0.95) (end 1.85 -0.95) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.85 -0.95) (end 1.85 0.95) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.85 0.95) (end -1.85 0.95) (layer F.CrtYd) (width 0.05)) + (fp_text user %R (at 0 0) (layer F.Fab) + (effects (font (size 0.5 0.5) (thickness 0.08))) + ) + (pad 1 smd roundrect (at -1.025 0) (size 1.15 1.4) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.217391) + (net 31 "Net-(R10-Pad1)")) + (pad 2 smd roundrect (at 1.025 0) (size 1.15 1.4) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.217391) + (net 2 +3V3)) + (model ${KISYS3DMOD}/Resistor_SMD.3dshapes/R_0805_2012Metric.wrl + (at (xyz 0 0 0)) + (scale (xyz 1 1 1)) + (rotate (xyz 0 0 0)) + ) + ) + + (module Resistor_SMD:R_0805_2012Metric_Pad1.15x1.40mm_HandSolder (layer F.Cu) (tedit 5B36C52B) (tstamp 5D1524DA) + (at 61.295 83.599 90) + (descr "Resistor SMD 0805 (2012 Metric), square (rectangular) end terminal, IPC_7351 nominal with elongated pad for handsoldering. (Body size source: https://docs.google.com/spreadsheets/d/1BsfQQcO9C6DZCsRaXUlFlo91Tg2WpOkGARC1WS5S8t0/edit?usp=sharing), generated with kicad-footprint-generator") + (tags "resistor handsolder") + (path /5D6D432A) + (attr smd) + (fp_text reference R11 (at -0.118 -2.413 180) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text value 4k7 (at 0 1.65 90) (layer F.Fab) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text user %R (at 0 0 90) (layer F.Fab) + (effects (font (size 0.5 0.5) (thickness 0.08))) + ) + (fp_line (start 1.85 0.95) (end -1.85 0.95) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.85 -0.95) (end 1.85 0.95) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.85 -0.95) (end 1.85 -0.95) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.85 0.95) (end -1.85 -0.95) (layer F.CrtYd) (width 0.05)) + (fp_line (start -0.261252 0.71) (end 0.261252 0.71) (layer F.SilkS) (width 0.12)) + (fp_line (start -0.261252 -0.71) (end 0.261252 -0.71) (layer F.SilkS) (width 0.12)) + (fp_line (start 1 0.6) (end -1 0.6) (layer F.Fab) (width 0.1)) + (fp_line (start 1 -0.6) (end 1 0.6) (layer F.Fab) (width 0.1)) + (fp_line (start -1 -0.6) (end 1 -0.6) (layer F.Fab) (width 0.1)) + (fp_line (start -1 0.6) (end -1 -0.6) (layer F.Fab) (width 0.1)) + (pad 2 smd roundrect (at 1.025 0 90) (size 1.15 1.4) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.217391) + (net 31 "Net-(R10-Pad1)")) + (pad 1 smd roundrect (at -1.025 0 90) (size 1.15 1.4) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.217391) + (net 15 "Net-(J3-Pad2)")) + (model ${KISYS3DMOD}/Resistor_SMD.3dshapes/R_0805_2012Metric.wrl + (at (xyz 0 0 0)) + (scale (xyz 1 1 1)) + (rotate (xyz 0 0 0)) + ) + ) + + (module Resistor_SMD:R_0805_2012Metric_Pad1.15x1.40mm_HandSolder (layer F.Cu) (tedit 5B36C52B) (tstamp 5D1524EB) + (at 68.026 81.694 90) + (descr "Resistor SMD 0805 (2012 Metric), square (rectangular) end terminal, IPC_7351 nominal with elongated pad for handsoldering. (Body size source: https://docs.google.com/spreadsheets/d/1BsfQQcO9C6DZCsRaXUlFlo91Tg2WpOkGARC1WS5S8t0/edit?usp=sharing), generated with kicad-footprint-generator") + (tags "resistor handsolder") + (path /5D6934BF) + (attr smd) + (fp_text reference R12 (at 2.803 -0.0635 180) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text value 4k7 (at 0 1.65 90) (layer F.Fab) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text user %R (at 0 0 90) (layer F.Fab) + (effects (font (size 0.5 0.5) (thickness 0.08))) + ) + (fp_line (start 1.85 0.95) (end -1.85 0.95) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.85 -0.95) (end 1.85 0.95) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.85 -0.95) (end 1.85 -0.95) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.85 0.95) (end -1.85 -0.95) (layer F.CrtYd) (width 0.05)) + (fp_line (start -0.261252 0.71) (end 0.261252 0.71) (layer F.SilkS) (width 0.12)) + (fp_line (start -0.261252 -0.71) (end 0.261252 -0.71) (layer F.SilkS) (width 0.12)) + (fp_line (start 1 0.6) (end -1 0.6) (layer F.Fab) (width 0.1)) + (fp_line (start 1 -0.6) (end 1 0.6) (layer F.Fab) (width 0.1)) + (fp_line (start -1 -0.6) (end 1 -0.6) (layer F.Fab) (width 0.1)) + (fp_line (start -1 0.6) (end -1 -0.6) (layer F.Fab) (width 0.1)) + (pad 2 smd roundrect (at 1.025 0 90) (size 1.15 1.4) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.217391) + (net 32 /TRIG0)) + (pad 1 smd roundrect (at -1.025 0 90) (size 1.15 1.4) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.217391) + (net 2 +3V3)) + (model ${KISYS3DMOD}/Resistor_SMD.3dshapes/R_0805_2012Metric.wrl + (at (xyz 0 0 0)) + (scale (xyz 1 1 1)) + (rotate (xyz 0 0 0)) + ) + ) + + (module Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder (layer F.Cu) (tedit 5B301BBD) (tstamp 5D1524FC) + (at 109.0965 67.461 180) + (descr "Resistor SMD 0603 (1608 Metric), square (rectangular) end terminal, IPC_7351 nominal with elongated pad for handsoldering. (Body size source: http://www.tortai-tech.com/upload/download/2011102023233369053.pdf), generated with kicad-footprint-generator") + (tags "resistor handsolder") + (path /5D1076F1) + (attr smd) + (fp_text reference R13 (at 0 -1.43 180) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text value 100k (at 0 1.43 180) (layer F.Fab) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text user %R (at 0 0 180) (layer F.Fab) + (effects (font (size 0.4 0.4) (thickness 0.06))) + ) + (fp_line (start 1.65 0.73) (end -1.65 0.73) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.65 -0.73) (end 1.65 0.73) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.65 -0.73) (end 1.65 -0.73) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.65 0.73) (end -1.65 -0.73) (layer F.CrtYd) (width 0.05)) + (fp_line (start -0.171267 0.51) (end 0.171267 0.51) (layer F.SilkS) (width 0.12)) + (fp_line (start -0.171267 -0.51) (end 0.171267 -0.51) (layer F.SilkS) (width 0.12)) + (fp_line (start 0.8 0.4) (end -0.8 0.4) (layer F.Fab) (width 0.1)) + (fp_line (start 0.8 -0.4) (end 0.8 0.4) (layer F.Fab) (width 0.1)) + (fp_line (start -0.8 -0.4) (end 0.8 -0.4) (layer F.Fab) (width 0.1)) + (fp_line (start -0.8 0.4) (end -0.8 -0.4) (layer F.Fab) (width 0.1)) + (pad 2 smd roundrect (at 0.875 0 180) (size 1.05 0.95) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.25) + (net 1 GND)) + (pad 1 smd roundrect (at -0.875 0 180) (size 1.05 0.95) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.25) + (net 33 "Net-(R13-Pad1)")) + (model ${KISYS3DMOD}/Resistor_SMD.3dshapes/R_0603_1608Metric.wrl + (at (xyz 0 0 0)) + (scale (xyz 1 1 1)) + (rotate (xyz 0 0 0)) + ) + ) + + (module Resistor_SMD:R_0805_2012Metric_Pad1.15x1.40mm_HandSolder (layer F.Cu) (tedit 5B36C52B) (tstamp 5D15250D) + (at 81.334 81.453 90) + (descr "Resistor SMD 0805 (2012 Metric), square (rectangular) end terminal, IPC_7351 nominal with elongated pad for handsoldering. (Body size source: https://docs.google.com/spreadsheets/d/1BsfQQcO9C6DZCsRaXUlFlo91Tg2WpOkGARC1WS5S8t0/edit?usp=sharing), generated with kicad-footprint-generator") + (tags "resistor handsolder") + (path /5D710D44) + (attr smd) + (fp_text reference R14 (at -2.7085 0.027 180) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text value 330 (at 0 1.65 90) (layer F.Fab) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_line (start -1 0.6) (end -1 -0.6) (layer F.Fab) (width 0.1)) + (fp_line (start -1 -0.6) (end 1 -0.6) (layer F.Fab) (width 0.1)) + (fp_line (start 1 -0.6) (end 1 0.6) (layer F.Fab) (width 0.1)) + (fp_line (start 1 0.6) (end -1 0.6) (layer F.Fab) (width 0.1)) + (fp_line (start -0.261252 -0.71) (end 0.261252 -0.71) (layer F.SilkS) (width 0.12)) + (fp_line (start -0.261252 0.71) (end 0.261252 0.71) (layer F.SilkS) (width 0.12)) + (fp_line (start -1.85 0.95) (end -1.85 -0.95) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.85 -0.95) (end 1.85 -0.95) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.85 -0.95) (end 1.85 0.95) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.85 0.95) (end -1.85 0.95) (layer F.CrtYd) (width 0.05)) + (fp_text user %R (at 0 0 90) (layer F.Fab) + (effects (font (size 0.5 0.5) (thickness 0.08))) + ) + (pad 1 smd roundrect (at -1.025 0 90) (size 1.15 1.4) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.217391) + (net 34 "Net-(R14-Pad1)")) + (pad 2 smd roundrect (at 1.025 0 90) (size 1.15 1.4) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.217391) + (net 2 +3V3)) + (model ${KISYS3DMOD}/Resistor_SMD.3dshapes/R_0805_2012Metric.wrl + (at (xyz 0 0 0)) + (scale (xyz 1 1 1)) + (rotate (xyz 0 0 0)) + ) + ) + + (module Resistor_SMD:R_0805_2012Metric_Pad1.15x1.40mm_HandSolder (layer F.Cu) (tedit 5B36C52B) (tstamp 5D15DC2F) + (at 75.619 83.612 90) + (descr "Resistor SMD 0805 (2012 Metric), square (rectangular) end terminal, IPC_7351 nominal with elongated pad for handsoldering. (Body size source: https://docs.google.com/spreadsheets/d/1BsfQQcO9C6DZCsRaXUlFlo91Tg2WpOkGARC1WS5S8t0/edit?usp=sharing), generated with kicad-footprint-generator") + (tags "resistor handsolder") + (path /5D710D50) + (attr smd) + (fp_text reference R15 (at -0.105 -2.4495 180) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text value 4k7 (at 0 1.65 90) (layer F.Fab) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text user %R (at 0 0 90) (layer F.Fab) + (effects (font (size 0.5 0.5) (thickness 0.08))) + ) + (fp_line (start 1.85 0.95) (end -1.85 0.95) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.85 -0.95) (end 1.85 0.95) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.85 -0.95) (end 1.85 -0.95) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.85 0.95) (end -1.85 -0.95) (layer F.CrtYd) (width 0.05)) + (fp_line (start -0.261252 0.71) (end 0.261252 0.71) (layer F.SilkS) (width 0.12)) + (fp_line (start -0.261252 -0.71) (end 0.261252 -0.71) (layer F.SilkS) (width 0.12)) + (fp_line (start 1 0.6) (end -1 0.6) (layer F.Fab) (width 0.1)) + (fp_line (start 1 -0.6) (end 1 0.6) (layer F.Fab) (width 0.1)) + (fp_line (start -1 -0.6) (end 1 -0.6) (layer F.Fab) (width 0.1)) + (fp_line (start -1 0.6) (end -1 -0.6) (layer F.Fab) (width 0.1)) + (pad 2 smd roundrect (at 1.025 0 90) (size 1.15 1.4) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.217391) + (net 34 "Net-(R14-Pad1)")) + (pad 1 smd roundrect (at -1.025 0 90) (size 1.15 1.4) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.217391) + (net 18 "Net-(J5-Pad2)")) + (model ${KISYS3DMOD}/Resistor_SMD.3dshapes/R_0805_2012Metric.wrl + (at (xyz 0 0 0)) + (scale (xyz 1 1 1)) + (rotate (xyz 0 0 0)) + ) + ) + + (module Resistor_SMD:R_0805_2012Metric_Pad1.15x1.40mm_HandSolder (layer F.Cu) (tedit 5B36C52B) (tstamp 5D15252F) + (at 84.4815 80.4785) + (descr "Resistor SMD 0805 (2012 Metric), square (rectangular) end terminal, IPC_7351 nominal with elongated pad for handsoldering. (Body size source: https://docs.google.com/spreadsheets/d/1BsfQQcO9C6DZCsRaXUlFlo91Tg2WpOkGARC1WS5S8t0/edit?usp=sharing), generated with kicad-footprint-generator") + (tags "resistor handsolder") + (path /5D710D30) + (attr smd) + (fp_text reference R16 (at 0.8165 -1.905) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text value 4k7 (at 0 1.65) (layer F.Fab) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text user %R (at 0 0) (layer F.Fab) + (effects (font (size 0.5 0.5) (thickness 0.08))) + ) + (fp_line (start 1.85 0.95) (end -1.85 0.95) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.85 -0.95) (end 1.85 0.95) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.85 -0.95) (end 1.85 -0.95) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.85 0.95) (end -1.85 -0.95) (layer F.CrtYd) (width 0.05)) + (fp_line (start -0.261252 0.71) (end 0.261252 0.71) (layer F.SilkS) (width 0.12)) + (fp_line (start -0.261252 -0.71) (end 0.261252 -0.71) (layer F.SilkS) (width 0.12)) + (fp_line (start 1 0.6) (end -1 0.6) (layer F.Fab) (width 0.1)) + (fp_line (start 1 -0.6) (end 1 0.6) (layer F.Fab) (width 0.1)) + (fp_line (start -1 -0.6) (end 1 -0.6) (layer F.Fab) (width 0.1)) + (fp_line (start -1 0.6) (end -1 -0.6) (layer F.Fab) (width 0.1)) + (pad 2 smd roundrect (at 1.025 0) (size 1.15 1.4) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.217391) + (net 35 /TRIG1)) + (pad 1 smd roundrect (at -1.025 0) (size 1.15 1.4) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.217391) + (net 2 +3V3)) + (model ${KISYS3DMOD}/Resistor_SMD.3dshapes/R_0805_2012Metric.wrl + (at (xyz 0 0 0)) + (scale (xyz 1 1 1)) + (rotate (xyz 0 0 0)) + ) + ) + + (module Resistor_SMD:R_0805_2012Metric_Pad1.15x1.40mm_HandSolder (layer F.Cu) (tedit 5B36C52B) (tstamp 5D152540) + (at 90.378 87.79 90) + (descr "Resistor SMD 0805 (2012 Metric), square (rectangular) end terminal, IPC_7351 nominal with elongated pad for handsoldering. (Body size source: https://docs.google.com/spreadsheets/d/1BsfQQcO9C6DZCsRaXUlFlo91Tg2WpOkGARC1WS5S8t0/edit?usp=sharing), generated with kicad-footprint-generator") + (tags "resistor handsolder") + (path /5D74F6B4) + (attr smd) + (fp_text reference R17 (at 0 2.6035 180) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text value 2k2 (at 0 1.65 90) (layer F.Fab) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_line (start -1 0.6) (end -1 -0.6) (layer F.Fab) (width 0.1)) + (fp_line (start -1 -0.6) (end 1 -0.6) (layer F.Fab) (width 0.1)) + (fp_line (start 1 -0.6) (end 1 0.6) (layer F.Fab) (width 0.1)) + (fp_line (start 1 0.6) (end -1 0.6) (layer F.Fab) (width 0.1)) + (fp_line (start -0.261252 -0.71) (end 0.261252 -0.71) (layer F.SilkS) (width 0.12)) + (fp_line (start -0.261252 0.71) (end 0.261252 0.71) (layer F.SilkS) (width 0.12)) + (fp_line (start -1.85 0.95) (end -1.85 -0.95) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.85 -0.95) (end 1.85 -0.95) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.85 -0.95) (end 1.85 0.95) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.85 0.95) (end -1.85 0.95) (layer F.CrtYd) (width 0.05)) + (fp_text user %R (at 0 0 90) (layer F.Fab) + (effects (font (size 0.5 0.5) (thickness 0.08))) + ) + (pad 1 smd roundrect (at -1.025 0 90) (size 1.15 1.4) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.217391) + (net 20 "Net-(J6-Pad2)")) + (pad 2 smd roundrect (at 1.025 0 90) (size 1.15 1.4) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.217391) + (net 36 "Net-(R17-Pad2)")) + (model ${KISYS3DMOD}/Resistor_SMD.3dshapes/R_0805_2012Metric.wrl + (at (xyz 0 0 0)) + (scale (xyz 1 1 1)) + (rotate (xyz 0 0 0)) + ) + ) + + (module Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder (layer F.Cu) (tedit 5B301BBD) (tstamp 5D152551) + (at 100.03 64.173 270) + (descr "Resistor SMD 0603 (1608 Metric), square (rectangular) end terminal, IPC_7351 nominal with elongated pad for handsoldering. (Body size source: http://www.tortai-tech.com/upload/download/2011102023233369053.pdf), generated with kicad-footprint-generator") + (tags "resistor handsolder") + (path /5D650328) + (attr smd) + (fp_text reference R18 (at 2.4625 0) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text value 100k (at 0 1.43 270) (layer F.Fab) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text user %R (at 0 0 270) (layer F.Fab) + (effects (font (size 0.4 0.4) (thickness 0.06))) + ) + (fp_line (start 1.65 0.73) (end -1.65 0.73) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.65 -0.73) (end 1.65 0.73) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.65 -0.73) (end 1.65 -0.73) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.65 0.73) (end -1.65 -0.73) (layer F.CrtYd) (width 0.05)) + (fp_line (start -0.171267 0.51) (end 0.171267 0.51) (layer F.SilkS) (width 0.12)) + (fp_line (start -0.171267 -0.51) (end 0.171267 -0.51) (layer F.SilkS) (width 0.12)) + (fp_line (start 0.8 0.4) (end -0.8 0.4) (layer F.Fab) (width 0.1)) + (fp_line (start 0.8 -0.4) (end 0.8 0.4) (layer F.Fab) (width 0.1)) + (fp_line (start -0.8 -0.4) (end 0.8 -0.4) (layer F.Fab) (width 0.1)) + (fp_line (start -0.8 0.4) (end -0.8 -0.4) (layer F.Fab) (width 0.1)) + (pad 2 smd roundrect (at 0.875 0 270) (size 1.05 0.95) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.25) + (net 37 /PPS)) + (pad 1 smd roundrect (at -0.875 0 270) (size 1.05 0.95) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.25) + (net 1 GND)) + (model ${KISYS3DMOD}/Resistor_SMD.3dshapes/R_0603_1608Metric.wrl + (at (xyz 0 0 0)) + (scale (xyz 1 1 1)) + (rotate (xyz 0 0 0)) + ) + ) + + (module Resistor_SMD:R_0805_2012Metric_Pad1.15x1.40mm_HandSolder (layer F.Cu) (tedit 5B36C52B) (tstamp 5D152562) + (at 89.2895 84.5425) + (descr "Resistor SMD 0805 (2012 Metric), square (rectangular) end terminal, IPC_7351 nominal with elongated pad for handsoldering. (Body size source: https://docs.google.com/spreadsheets/d/1BsfQQcO9C6DZCsRaXUlFlo91Tg2WpOkGARC1WS5S8t0/edit?usp=sharing), generated with kicad-footprint-generator") + (tags "resistor handsolder") + (path /5D72A0DE) + (attr smd) + (fp_text reference R19 (at 3.438 0.127) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text value 4k7 (at 0 1.65) (layer F.Fab) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_line (start -1 0.6) (end -1 -0.6) (layer F.Fab) (width 0.1)) + (fp_line (start -1 -0.6) (end 1 -0.6) (layer F.Fab) (width 0.1)) + (fp_line (start 1 -0.6) (end 1 0.6) (layer F.Fab) (width 0.1)) + (fp_line (start 1 0.6) (end -1 0.6) (layer F.Fab) (width 0.1)) + (fp_line (start -0.261252 -0.71) (end 0.261252 -0.71) (layer F.SilkS) (width 0.12)) + (fp_line (start -0.261252 0.71) (end 0.261252 0.71) (layer F.SilkS) (width 0.12)) + (fp_line (start -1.85 0.95) (end -1.85 -0.95) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.85 -0.95) (end 1.85 -0.95) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.85 -0.95) (end 1.85 0.95) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.85 0.95) (end -1.85 0.95) (layer F.CrtYd) (width 0.05)) + (fp_text user %R (at 0 0) (layer F.Fab) + (effects (font (size 0.5 0.5) (thickness 0.08))) + ) + (pad 1 smd roundrect (at -1.025 0) (size 1.15 1.4) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.217391) + (net 19 "Net-(J6-Pad1)")) + (pad 2 smd roundrect (at 1.025 0) (size 1.15 1.4) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.217391) + (net 36 "Net-(R17-Pad2)")) + (model ${KISYS3DMOD}/Resistor_SMD.3dshapes/R_0805_2012Metric.wrl + (at (xyz 0 0 0)) + (scale (xyz 1 1 1)) + (rotate (xyz 0 0 0)) + ) + ) + + (module Resistor_SMD:R_0805_2012Metric_Pad1.15x1.40mm_HandSolder (layer F.Cu) (tedit 5B36C52B) (tstamp 5D155E3C) + (at 89.988 70.0645) + (descr "Resistor SMD 0805 (2012 Metric), square (rectangular) end terminal, IPC_7351 nominal with elongated pad for handsoldering. (Body size source: https://docs.google.com/spreadsheets/d/1BsfQQcO9C6DZCsRaXUlFlo91Tg2WpOkGARC1WS5S8t0/edit?usp=sharing), generated with kicad-footprint-generator") + (tags "resistor handsolder") + (path /5D72A0BE) + (attr smd) + (fp_text reference R20 (at 0 -1.65) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text value 4k7 (at 0 1.65) (layer F.Fab) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text user %R (at 0 0) (layer F.Fab) + (effects (font (size 0.5 0.5) (thickness 0.08))) + ) + (fp_line (start 1.85 0.95) (end -1.85 0.95) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.85 -0.95) (end 1.85 0.95) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.85 -0.95) (end 1.85 -0.95) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.85 0.95) (end -1.85 -0.95) (layer F.CrtYd) (width 0.05)) + (fp_line (start -0.261252 0.71) (end 0.261252 0.71) (layer F.SilkS) (width 0.12)) + (fp_line (start -0.261252 -0.71) (end 0.261252 -0.71) (layer F.SilkS) (width 0.12)) + (fp_line (start 1 0.6) (end -1 0.6) (layer F.Fab) (width 0.1)) + (fp_line (start 1 -0.6) (end 1 0.6) (layer F.Fab) (width 0.1)) + (fp_line (start -1 -0.6) (end 1 -0.6) (layer F.Fab) (width 0.1)) + (fp_line (start -1 0.6) (end -1 -0.6) (layer F.Fab) (width 0.1)) + (pad 2 smd roundrect (at 1.025 0) (size 1.15 1.4) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.217391) + (net 38 /TRIG2)) + (pad 1 smd roundrect (at -1.025 0) (size 1.15 1.4) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.217391) + (net 2 +3V3)) + (model ${KISYS3DMOD}/Resistor_SMD.3dshapes/R_0805_2012Metric.wrl + (at (xyz 0 0 0)) + (scale (xyz 1 1 1)) + (rotate (xyz 0 0 0)) + ) + ) + + (module Buttons_Switches_SMD:SW_SPST_FSMSM (layer F.Cu) (tedit 5A02FC95) (tstamp 5D15258E) + (at 92.8545 58.208 90) + (descr http://www.te.com/commerce/DocumentDelivery/DDEController?Action=srchrtrv&DocNm=1437566-3&DocType=Customer+Drawing&DocLang=English) + (tags "SPST button tactile switch") + (path /5D34785B) + (attr smd) + (fp_text reference SW1 (at -0.0455 -3.429 180) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text value Reset (at 0 3 90) (layer F.Fab) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text user %R (at 0 -2.6 90) (layer F.Fab) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_line (start -1.75 -1) (end 1.75 -1) (layer F.Fab) (width 0.1)) + (fp_line (start 1.75 -1) (end 1.75 1) (layer F.Fab) (width 0.1)) + (fp_line (start 1.75 1) (end -1.75 1) (layer F.Fab) (width 0.1)) + (fp_line (start -1.75 1) (end -1.75 -1) (layer F.Fab) (width 0.1)) + (fp_line (start -3.06 -1.81) (end 3.06 -1.81) (layer F.SilkS) (width 0.12)) + (fp_line (start 3.06 -1.81) (end 3.06 1.81) (layer F.SilkS) (width 0.12)) + (fp_line (start 3.06 1.81) (end -3.06 1.81) (layer F.SilkS) (width 0.12)) + (fp_line (start -3.06 1.81) (end -3.06 -1.81) (layer F.SilkS) (width 0.12)) + (fp_line (start -1.5 0.8) (end 1.5 0.8) (layer F.Fab) (width 0.1)) + (fp_line (start -1.5 -0.8) (end 1.5 -0.8) (layer F.Fab) (width 0.1)) + (fp_line (start 1.5 -0.8) (end 1.5 0.8) (layer F.Fab) (width 0.1)) + (fp_line (start -1.5 -0.8) (end -1.5 0.8) (layer F.Fab) (width 0.1)) + (fp_line (start -5.95 2) (end 5.95 2) (layer F.CrtYd) (width 0.05)) + (fp_line (start 5.95 -2) (end 5.95 2) (layer F.CrtYd) (width 0.05)) + (fp_line (start -3 1.75) (end 3 1.75) (layer F.Fab) (width 0.1)) + (fp_line (start -3 -1.75) (end 3 -1.75) (layer F.Fab) (width 0.1)) + (fp_line (start -3 -1.75) (end -3 1.75) (layer F.Fab) (width 0.1)) + (fp_line (start 3 -1.75) (end 3 1.75) (layer F.Fab) (width 0.1)) + (fp_line (start -5.95 -2) (end -5.95 2) (layer F.CrtYd) (width 0.05)) + (fp_line (start -5.95 -2) (end 5.95 -2) (layer F.CrtYd) (width 0.05)) + (pad 1 smd rect (at -4.59 0 90) (size 2.18 1.6) (layers F.Cu F.Paste F.Mask) + (net 39 /NRST)) + (pad 2 smd rect (at 4.59 0 90) (size 2.18 1.6) (layers F.Cu F.Paste F.Mask) + (net 1 GND)) + (model ${KISYS3DMOD}/Button_Switch_SMD.3dshapes/SW_SPST_FSMSM.wrl + (at (xyz 0 0 0)) + (scale (xyz 1 1 1)) + (rotate (xyz 0 0 0)) + ) + ) + + (module Buttons_Switches_SMD:SW_SPST_FSMSM (layer F.Cu) (tedit 5A02FC95) (tstamp 5D1525A9) + (at 114.8435 49.3635) + (descr http://www.te.com/commerce/DocumentDelivery/DDEController?Action=srchrtrv&DocNm=1437566-3&DocType=Customer+Drawing&DocLang=English) + (tags "SPST button tactile switch") + (path /5D34785A) + (attr smd) + (fp_text reference SW2 (at 0.0455 2.8575) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text value Boot (at 0 3) (layer F.Fab) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_line (start -5.95 -2) (end 5.95 -2) (layer F.CrtYd) (width 0.05)) + (fp_line (start -5.95 -2) (end -5.95 2) (layer F.CrtYd) (width 0.05)) + (fp_line (start 3 -1.75) (end 3 1.75) (layer F.Fab) (width 0.1)) + (fp_line (start -3 -1.75) (end -3 1.75) (layer F.Fab) (width 0.1)) + (fp_line (start -3 -1.75) (end 3 -1.75) (layer F.Fab) (width 0.1)) + (fp_line (start -3 1.75) (end 3 1.75) (layer F.Fab) (width 0.1)) + (fp_line (start 5.95 -2) (end 5.95 2) (layer F.CrtYd) (width 0.05)) + (fp_line (start -5.95 2) (end 5.95 2) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.5 -0.8) (end -1.5 0.8) (layer F.Fab) (width 0.1)) + (fp_line (start 1.5 -0.8) (end 1.5 0.8) (layer F.Fab) (width 0.1)) + (fp_line (start -1.5 -0.8) (end 1.5 -0.8) (layer F.Fab) (width 0.1)) + (fp_line (start -1.5 0.8) (end 1.5 0.8) (layer F.Fab) (width 0.1)) + (fp_line (start -3.06 1.81) (end -3.06 -1.81) (layer F.SilkS) (width 0.12)) + (fp_line (start 3.06 1.81) (end -3.06 1.81) (layer F.SilkS) (width 0.12)) + (fp_line (start 3.06 -1.81) (end 3.06 1.81) (layer F.SilkS) (width 0.12)) + (fp_line (start -3.06 -1.81) (end 3.06 -1.81) (layer F.SilkS) (width 0.12)) + (fp_line (start -1.75 1) (end -1.75 -1) (layer F.Fab) (width 0.1)) + (fp_line (start 1.75 1) (end -1.75 1) (layer F.Fab) (width 0.1)) + (fp_line (start 1.75 -1) (end 1.75 1) (layer F.Fab) (width 0.1)) + (fp_line (start -1.75 -1) (end 1.75 -1) (layer F.Fab) (width 0.1)) + (fp_text user %R (at 0 -2.6) (layer F.Fab) + (effects (font (size 1 1) (thickness 0.15))) + ) + (pad 2 smd rect (at 4.59 0) (size 2.18 1.6) (layers F.Cu F.Paste F.Mask) + (net 2 +3V3)) + (pad 1 smd rect (at -4.59 0) (size 2.18 1.6) (layers F.Cu F.Paste F.Mask) + (net 40 /BOOT0)) + (model ${KISYS3DMOD}/Button_Switch_SMD.3dshapes/SW_SPST_FSMSM.wrl + (at (xyz 0 0 0)) + (scale (xyz 1 1 1)) + (rotate (xyz 0 0 0)) + ) + ) + + (module TO_SOT_Packages_SMD:SOT-23-6_Handsoldering (layer F.Cu) (tedit 5A02FF57) (tstamp 5D156089) + (at 126.065 59.7013) + (descr "6-pin SOT-23 package, Handsoldering") + (tags "SOT-23-6 Handsoldering") + (path /5CED0250) + (attr smd) + (fp_text reference U1 (at 0 2.4892) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text value USBLC6-2SC6 (at 0 2.9) (layer F.Fab) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text user %R (at 0 0 90) (layer F.Fab) + (effects (font (size 0.5 0.5) (thickness 0.075))) + ) + (fp_line (start -0.9 1.61) (end 0.9 1.61) (layer F.SilkS) (width 0.12)) + (fp_line (start 0.9 -1.61) (end -2.05 -1.61) (layer F.SilkS) (width 0.12)) + (fp_line (start -2.4 1.8) (end -2.4 -1.8) (layer F.CrtYd) (width 0.05)) + (fp_line (start 2.4 1.8) (end -2.4 1.8) (layer F.CrtYd) (width 0.05)) + (fp_line (start 2.4 -1.8) (end 2.4 1.8) (layer F.CrtYd) (width 0.05)) + (fp_line (start -2.4 -1.8) (end 2.4 -1.8) (layer F.CrtYd) (width 0.05)) + (fp_line (start -0.9 -0.9) (end -0.25 -1.55) (layer F.Fab) (width 0.1)) + (fp_line (start 0.9 -1.55) (end -0.25 -1.55) (layer F.Fab) (width 0.1)) + (fp_line (start -0.9 -0.9) (end -0.9 1.55) (layer F.Fab) (width 0.1)) + (fp_line (start 0.9 1.55) (end -0.9 1.55) (layer F.Fab) (width 0.1)) + (fp_line (start 0.9 -1.55) (end 0.9 1.55) (layer F.Fab) (width 0.1)) + (pad 1 smd rect (at -1.35 -0.95) (size 1.56 0.65) (layers F.Cu F.Paste F.Mask) + (net 28 "Net-(R3-Pad1)")) + (pad 2 smd rect (at -1.35 0) (size 1.56 0.65) (layers F.Cu F.Paste F.Mask) + (net 1 GND)) + (pad 3 smd rect (at -1.35 0.95) (size 1.56 0.65) (layers F.Cu F.Paste F.Mask) + (net 29 "Net-(R4-Pad1)")) + (pad 4 smd rect (at 1.35 0.95) (size 1.56 0.65) (layers F.Cu F.Paste F.Mask) + (net 23 "Net-(P1-Pad2)")) + (pad 6 smd rect (at 1.35 -0.95) (size 1.56 0.65) (layers F.Cu F.Paste F.Mask) + (net 24 "Net-(P1-Pad3)")) + (pad 5 smd rect (at 1.35 0) (size 1.56 0.65) (layers F.Cu F.Paste F.Mask) + (net 7 "Net-(D2-Pad2)")) + (model ${KISYS3DMOD}/Package_TO_SOT_SMD.3dshapes/SOT-23-6.wrl + (at (xyz 0 0 0)) + (scale (xyz 1 1 1)) + (rotate (xyz 0 0 0)) + ) + ) + + (module TO_SOT_Packages_THT:TO-220-5_P3.4x3.7mm_StaggerEven_Lead3.8mm_Vertical (layer B.Cu) (tedit 5AF05A31) (tstamp 5D1525E5) + (at 119.969 82.193) + (descr "TO-220-5, Vertical, RM 1.7mm, Pentawatt, Multiwatt-5, staggered type-2, see http://www.analog.com/media/en/package-pcb-resources/package/pkg_pdf/ltc-legacy-to-220/to-220_5_05-08-1421.pdf?domain=www.linear.com, https://www.diodes.com/assets/Package-Files/TO220-5.pdf") + (tags "TO-220-5 Vertical RM 1.7mm Pentawatt Multiwatt-5 staggered type-2") + (path /58C43093) + (fp_text reference U2 (at 3.4 5.62) (layer B.SilkS) + (effects (font (size 1 1) (thickness 0.15)) (justify mirror)) + ) + (fp_text value LM2576HV (at 3.4 -5.85) (layer B.Fab) + (effects (font (size 1 1) (thickness 0.15)) (justify mirror)) + ) + (fp_line (start -1.6 4.5) (end -1.6 0.1) (layer B.Fab) (width 0.1)) + (fp_line (start -1.6 0.1) (end 8.4 0.1) (layer B.Fab) (width 0.1)) + (fp_line (start 8.4 0.1) (end 8.4 4.5) (layer B.Fab) (width 0.1)) + (fp_line (start 8.4 4.5) (end -1.6 4.5) (layer B.Fab) (width 0.1)) + (fp_line (start -1.6 3.23) (end 8.4 3.23) (layer B.Fab) (width 0.1)) + (fp_line (start 1.55 4.5) (end 1.55 3.23) (layer B.Fab) (width 0.1)) + (fp_line (start 5.25 4.5) (end 5.25 3.23) (layer B.Fab) (width 0.1)) + (fp_line (start 0 0.1) (end 0 0) (layer B.Fab) (width 0.1)) + (fp_line (start 1.7 0.1) (end 1.7 -3.7) (layer B.Fab) (width 0.1)) + (fp_line (start 3.4 0.1) (end 3.4 0) (layer B.Fab) (width 0.1)) + (fp_line (start 5.1 0.1) (end 5.1 -3.7) (layer B.Fab) (width 0.1)) + (fp_line (start 6.8 0.1) (end 6.8 0) (layer B.Fab) (width 0.1)) + (fp_line (start -1.721 4.62) (end 8.52 4.62) (layer B.SilkS) (width 0.12)) + (fp_line (start -1.721 -0.021) (end -1.05 -0.021) (layer B.SilkS) (width 0.12)) + (fp_line (start 1.05 -0.021) (end 2.335 -0.021) (layer B.SilkS) (width 0.12)) + (fp_line (start 4.465 -0.021) (end 5.735 -0.021) (layer B.SilkS) (width 0.12)) + (fp_line (start 7.865 -0.021) (end 8.52 -0.021) (layer B.SilkS) (width 0.12)) + (fp_line (start -1.721 4.62) (end -1.721 -0.021) (layer B.SilkS) (width 0.12)) + (fp_line (start 8.52 4.62) (end 8.52 -0.021) (layer B.SilkS) (width 0.12)) + (fp_line (start -1.721 3.111) (end 8.52 3.111) (layer B.SilkS) (width 0.12)) + (fp_line (start 1.55 4.62) (end 1.55 3.111) (layer B.SilkS) (width 0.12)) + (fp_line (start 5.25 4.62) (end 5.25 3.111) (layer B.SilkS) (width 0.12)) + (fp_line (start 1.7 -0.021) (end 1.7 -2.635) (layer B.SilkS) (width 0.12)) + (fp_line (start 5.1 -0.021) (end 5.1 -2.635) (layer B.SilkS) (width 0.12)) + (fp_line (start -1.85 4.75) (end -1.85 -4.85) (layer B.CrtYd) (width 0.05)) + (fp_line (start -1.85 -4.85) (end 8.65 -4.85) (layer B.CrtYd) (width 0.05)) + (fp_line (start 8.65 -4.85) (end 8.65 4.75) (layer B.CrtYd) (width 0.05)) + (fp_line (start 8.65 4.75) (end -1.85 4.75) (layer B.CrtYd) (width 0.05)) + (fp_text user %R (at 3.4 5.62) (layer B.Fab) + (effects (font (size 1 1) (thickness 0.15)) (justify mirror)) + ) + (pad 1 thru_hole rect (at 0 0) (size 1.8 1.8) (drill 1.1) (layers *.Cu *.Mask) + (net 6 "Net-(C3-Pad1)")) + (pad 2 thru_hole oval (at 1.7 -3.7) (size 1.8 1.8) (drill 1.1) (layers *.Cu *.Mask) + (net 8 "Net-(D3-Pad1)")) + (pad 3 thru_hole oval (at 3.4 0) (size 1.8 1.8) (drill 1.1) (layers *.Cu *.Mask) + (net 1 GND)) + (pad 4 thru_hole oval (at 5.1 -3.7) (size 1.8 1.8) (drill 1.1) (layers *.Cu *.Mask) + (net 3 +5V)) + (pad 5 thru_hole oval (at 6.8 0) (size 1.8 1.8) (drill 1.1) (layers *.Cu *.Mask) + (net 1 GND)) + (model ${KISYS3DMOD}/Package_TO_SOT_THT.3dshapes/TO-220-5_P3.4x3.7mm_StaggerEven_Lead3.8mm_Vertical.wrl + (at (xyz 0 0 0)) + (scale (xyz 1 1 1)) + (rotate (xyz 0 0 0)) + ) + ) + + (module TO_SOT_Packages_SMD:SOT-223 (layer F.Cu) (tedit 5A02FF57) (tstamp 5D15C2A9) + (at 126.5345 49.3775 180) + (descr "module CMS SOT223 4 pins") + (tags "CMS SOT") + (path /58C431FC) + (attr smd) + (fp_text reference U4 (at 0.787 4.3955 180) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text value LM1117-3.3 (at 0 4.5 180) (layer F.Fab) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text user %R (at 0 0 270) (layer F.Fab) + (effects (font (size 0.8 0.8) (thickness 0.12))) + ) + (fp_line (start -1.85 -2.3) (end -0.8 -3.35) (layer F.Fab) (width 0.1)) + (fp_line (start 1.91 3.41) (end 1.91 2.15) (layer F.SilkS) (width 0.12)) + (fp_line (start 1.91 -3.41) (end 1.91 -2.15) (layer F.SilkS) (width 0.12)) + (fp_line (start 4.4 -3.6) (end -4.4 -3.6) (layer F.CrtYd) (width 0.05)) + (fp_line (start 4.4 3.6) (end 4.4 -3.6) (layer F.CrtYd) (width 0.05)) + (fp_line (start -4.4 3.6) (end 4.4 3.6) (layer F.CrtYd) (width 0.05)) + (fp_line (start -4.4 -3.6) (end -4.4 3.6) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.85 -2.3) (end -1.85 3.35) (layer F.Fab) (width 0.1)) + (fp_line (start -1.85 3.41) (end 1.91 3.41) (layer F.SilkS) (width 0.12)) + (fp_line (start -0.8 -3.35) (end 1.85 -3.35) (layer F.Fab) (width 0.1)) + (fp_line (start -4.1 -3.41) (end 1.91 -3.41) (layer F.SilkS) (width 0.12)) + (fp_line (start -1.85 3.35) (end 1.85 3.35) (layer F.Fab) (width 0.1)) + (fp_line (start 1.85 -3.35) (end 1.85 3.35) (layer F.Fab) (width 0.1)) + (pad 4 smd rect (at 3.15 0 180) (size 2 3.8) (layers F.Cu F.Paste F.Mask) + (net 2 +3V3)) + (pad 2 smd rect (at -3.15 0 180) (size 2 1.5) (layers F.Cu F.Paste F.Mask) + (net 2 +3V3)) + (pad 3 smd rect (at -3.15 2.3 180) (size 2 1.5) (layers F.Cu F.Paste F.Mask) + (net 3 +5V)) + (pad 1 smd rect (at -3.15 -2.3 180) (size 2 1.5) (layers F.Cu F.Paste F.Mask) + (net 1 GND)) + (model ${KISYS3DMOD}/Package_TO_SOT_SMD.3dshapes/SOT-223.wrl + (at (xyz 0 0 0)) + (scale (xyz 1 1 1)) + (rotate (xyz 0 0 0)) + ) + ) + + (module Package_DIP:DIP-4_W7.62mm (layer B.Cu) (tedit 5A02E8C5) (tstamp 5D163D76) + (at 64.216 82.447 180) + (descr "4-lead though-hole mounted DIP package, row spacing 7.62 mm (300 mils)") + (tags "THT DIP DIL PDIP 2.54mm 7.62mm 300mil") + (path /5D68F125) + (fp_text reference U5 (at 9.8425 -1.2065 180) (layer B.SilkS) + (effects (font (size 1 1) (thickness 0.15)) (justify mirror)) + ) + (fp_text value PC817 (at 3.81 -4.87 180) (layer B.Fab) + (effects (font (size 1 1) (thickness 0.15)) (justify mirror)) + ) + (fp_arc (start 3.81 1.33) (end 2.81 1.33) (angle 180) (layer B.SilkS) (width 0.12)) + (fp_line (start 1.635 1.27) (end 6.985 1.27) (layer B.Fab) (width 0.1)) + (fp_line (start 6.985 1.27) (end 6.985 -3.81) (layer B.Fab) (width 0.1)) + (fp_line (start 6.985 -3.81) (end 0.635 -3.81) (layer B.Fab) (width 0.1)) + (fp_line (start 0.635 -3.81) (end 0.635 0.27) (layer B.Fab) (width 0.1)) + (fp_line (start 0.635 0.27) (end 1.635 1.27) (layer B.Fab) (width 0.1)) + (fp_line (start 2.81 1.33) (end 1.16 1.33) (layer B.SilkS) (width 0.12)) + (fp_line (start 1.16 1.33) (end 1.16 -3.87) (layer B.SilkS) (width 0.12)) + (fp_line (start 1.16 -3.87) (end 6.46 -3.87) (layer B.SilkS) (width 0.12)) + (fp_line (start 6.46 -3.87) (end 6.46 1.33) (layer B.SilkS) (width 0.12)) + (fp_line (start 6.46 1.33) (end 4.81 1.33) (layer B.SilkS) (width 0.12)) + (fp_line (start -1.1 1.55) (end -1.1 -4.1) (layer B.CrtYd) (width 0.05)) + (fp_line (start -1.1 -4.1) (end 8.7 -4.1) (layer B.CrtYd) (width 0.05)) + (fp_line (start 8.7 -4.1) (end 8.7 1.55) (layer B.CrtYd) (width 0.05)) + (fp_line (start 8.7 1.55) (end -1.1 1.55) (layer B.CrtYd) (width 0.05)) + (fp_text user %R (at 3.81 -1.27 180) (layer B.Fab) + (effects (font (size 1 1) (thickness 0.15)) (justify mirror)) + ) + (pad 1 thru_hole rect (at 0 0 180) (size 1.6 1.6) (drill 0.8) (layers *.Cu *.Mask) + (net 31 "Net-(R10-Pad1)")) + (pad 3 thru_hole oval (at 7.62 -2.54 180) (size 1.6 1.6) (drill 0.8) (layers *.Cu *.Mask) + (net 1 GND)) + (pad 2 thru_hole oval (at 0 -2.54 180) (size 1.6 1.6) (drill 0.8) (layers *.Cu *.Mask) + (net 15 "Net-(J3-Pad2)")) + (pad 4 thru_hole oval (at 7.62 0 180) (size 1.6 1.6) (drill 0.8) (layers *.Cu *.Mask) + (net 32 /TRIG0)) + (model ${KISYS3DMOD}/Package_DIP.3dshapes/DIP-4_W7.62mm.wrl + (at (xyz 0 0 0)) + (scale (xyz 1 1 1)) + (rotate (xyz 0 0 0)) + ) + ) + + (module Package_DIP:DIP-4_W7.62mm (layer B.Cu) (tedit 5A02E8C5) (tstamp 5D15DBA8) + (at 78.413 82.478 180) + (descr "4-lead though-hole mounted DIP package, row spacing 7.62 mm (300 mils)") + (tags "THT DIP DIL PDIP 2.54mm 7.62mm 300mil") + (path /5D710D2A) + (fp_text reference U6 (at -2.313 -1.4295 180) (layer B.SilkS) + (effects (font (size 1 1) (thickness 0.15)) (justify mirror)) + ) + (fp_text value PC817 (at 3.81 -4.87 180) (layer B.Fab) + (effects (font (size 1 1) (thickness 0.15)) (justify mirror)) + ) + (fp_arc (start 3.81 1.33) (end 2.81 1.33) (angle 180) (layer B.SilkS) (width 0.12)) + (fp_line (start 1.635 1.27) (end 6.985 1.27) (layer B.Fab) (width 0.1)) + (fp_line (start 6.985 1.27) (end 6.985 -3.81) (layer B.Fab) (width 0.1)) + (fp_line (start 6.985 -3.81) (end 0.635 -3.81) (layer B.Fab) (width 0.1)) + (fp_line (start 0.635 -3.81) (end 0.635 0.27) (layer B.Fab) (width 0.1)) + (fp_line (start 0.635 0.27) (end 1.635 1.27) (layer B.Fab) (width 0.1)) + (fp_line (start 2.81 1.33) (end 1.16 1.33) (layer B.SilkS) (width 0.12)) + (fp_line (start 1.16 1.33) (end 1.16 -3.87) (layer B.SilkS) (width 0.12)) + (fp_line (start 1.16 -3.87) (end 6.46 -3.87) (layer B.SilkS) (width 0.12)) + (fp_line (start 6.46 -3.87) (end 6.46 1.33) (layer B.SilkS) (width 0.12)) + (fp_line (start 6.46 1.33) (end 4.81 1.33) (layer B.SilkS) (width 0.12)) + (fp_line (start -1.1 1.55) (end -1.1 -4.1) (layer B.CrtYd) (width 0.05)) + (fp_line (start -1.1 -4.1) (end 8.7 -4.1) (layer B.CrtYd) (width 0.05)) + (fp_line (start 8.7 -4.1) (end 8.7 1.55) (layer B.CrtYd) (width 0.05)) + (fp_line (start 8.7 1.55) (end -1.1 1.55) (layer B.CrtYd) (width 0.05)) + (fp_text user %R (at 3.81 -1.27 180) (layer F.Fab) + (effects (font (size 1 1) (thickness 0.15))) + ) + (pad 1 thru_hole rect (at 0 0 180) (size 1.6 1.6) (drill 0.8) (layers *.Cu *.Mask) + (net 34 "Net-(R14-Pad1)")) + (pad 3 thru_hole oval (at 7.62 -2.54 180) (size 1.6 1.6) (drill 0.8) (layers *.Cu *.Mask) + (net 1 GND)) + (pad 2 thru_hole oval (at 0 -2.54 180) (size 1.6 1.6) (drill 0.8) (layers *.Cu *.Mask) + (net 18 "Net-(J5-Pad2)")) + (pad 4 thru_hole oval (at 7.62 0 180) (size 1.6 1.6) (drill 0.8) (layers *.Cu *.Mask) + (net 35 /TRIG1)) + (model ${KISYS3DMOD}/Package_DIP.3dshapes/DIP-4_W7.62mm.wrl + (at (xyz 0 0 0)) + (scale (xyz 1 1 1)) + (rotate (xyz 0 0 0)) + ) + ) + + (module Package_QFP:LQFP-48_7x7mm_P0.5mm (layer F.Cu) (tedit 5C18330E) (tstamp 5D15631F) + (at 110.3963 60.4372) + (descr "LQFP, 48 Pin (https://www.analog.com/media/en/technical-documentation/data-sheets/ltc2358-16.pdf), generated with kicad-footprint-generator ipc_gullwing_generator.py") + (tags "LQFP QFP") + (path /5D13BBBF) + (attr smd) + (fp_text reference U7 (at 0 -5.85) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text value STM32F103C6Tx (at 0 5.85) (layer F.Fab) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_line (start 3.16 3.61) (end 3.61 3.61) (layer F.SilkS) (width 0.12)) + (fp_line (start 3.61 3.61) (end 3.61 3.16) (layer F.SilkS) (width 0.12)) + (fp_line (start -3.16 3.61) (end -3.61 3.61) (layer F.SilkS) (width 0.12)) + (fp_line (start -3.61 3.61) (end -3.61 3.16) (layer F.SilkS) (width 0.12)) + (fp_line (start 3.16 -3.61) (end 3.61 -3.61) (layer F.SilkS) (width 0.12)) + (fp_line (start 3.61 -3.61) (end 3.61 -3.16) (layer F.SilkS) (width 0.12)) + (fp_line (start -3.16 -3.61) (end -3.61 -3.61) (layer F.SilkS) (width 0.12)) + (fp_line (start -3.61 -3.61) (end -3.61 -3.16) (layer F.SilkS) (width 0.12)) + (fp_line (start -3.61 -3.16) (end -4.9 -3.16) (layer F.SilkS) (width 0.12)) + (fp_line (start -2.5 -3.5) (end 3.5 -3.5) (layer F.Fab) (width 0.1)) + (fp_line (start 3.5 -3.5) (end 3.5 3.5) (layer F.Fab) (width 0.1)) + (fp_line (start 3.5 3.5) (end -3.5 3.5) (layer F.Fab) (width 0.1)) + (fp_line (start -3.5 3.5) (end -3.5 -2.5) (layer F.Fab) (width 0.1)) + (fp_line (start -3.5 -2.5) (end -2.5 -3.5) (layer F.Fab) (width 0.1)) + (fp_line (start 0 -5.15) (end -3.15 -5.15) (layer F.CrtYd) (width 0.05)) + (fp_line (start -3.15 -5.15) (end -3.15 -3.75) (layer F.CrtYd) (width 0.05)) + (fp_line (start -3.15 -3.75) (end -3.75 -3.75) (layer F.CrtYd) (width 0.05)) + (fp_line (start -3.75 -3.75) (end -3.75 -3.15) (layer F.CrtYd) (width 0.05)) + (fp_line (start -3.75 -3.15) (end -5.15 -3.15) (layer F.CrtYd) (width 0.05)) + (fp_line (start -5.15 -3.15) (end -5.15 0) (layer F.CrtYd) (width 0.05)) + (fp_line (start 0 -5.15) (end 3.15 -5.15) (layer F.CrtYd) (width 0.05)) + (fp_line (start 3.15 -5.15) (end 3.15 -3.75) (layer F.CrtYd) (width 0.05)) + (fp_line (start 3.15 -3.75) (end 3.75 -3.75) (layer F.CrtYd) (width 0.05)) + (fp_line (start 3.75 -3.75) (end 3.75 -3.15) (layer F.CrtYd) (width 0.05)) + (fp_line (start 3.75 -3.15) (end 5.15 -3.15) (layer F.CrtYd) (width 0.05)) + (fp_line (start 5.15 -3.15) (end 5.15 0) (layer F.CrtYd) (width 0.05)) + (fp_line (start 0 5.15) (end -3.15 5.15) (layer F.CrtYd) (width 0.05)) + (fp_line (start -3.15 5.15) (end -3.15 3.75) (layer F.CrtYd) (width 0.05)) + (fp_line (start -3.15 3.75) (end -3.75 3.75) (layer F.CrtYd) (width 0.05)) + (fp_line (start -3.75 3.75) (end -3.75 3.15) (layer F.CrtYd) (width 0.05)) + (fp_line (start -3.75 3.15) (end -5.15 3.15) (layer F.CrtYd) (width 0.05)) + (fp_line (start -5.15 3.15) (end -5.15 0) (layer F.CrtYd) (width 0.05)) + (fp_line (start 0 5.15) (end 3.15 5.15) (layer F.CrtYd) (width 0.05)) + (fp_line (start 3.15 5.15) (end 3.15 3.75) (layer F.CrtYd) (width 0.05)) + (fp_line (start 3.15 3.75) (end 3.75 3.75) (layer F.CrtYd) (width 0.05)) + (fp_line (start 3.75 3.75) (end 3.75 3.15) (layer F.CrtYd) (width 0.05)) + (fp_line (start 3.75 3.15) (end 5.15 3.15) (layer F.CrtYd) (width 0.05)) + (fp_line (start 5.15 3.15) (end 5.15 0) (layer F.CrtYd) (width 0.05)) + (fp_text user %R (at 0 0) (layer F.Fab) + (effects (font (size 1 1) (thickness 0.15))) + ) + (pad 1 smd roundrect (at -4.1625 -2.75) (size 1.475 0.3) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.25) + (net 2 +3V3)) + (pad 2 smd roundrect (at -4.1625 -2.25) (size 1.475 0.3) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.25)) + (pad 3 smd roundrect (at -4.1625 -1.75) (size 1.475 0.3) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.25)) + (pad 4 smd roundrect (at -4.1625 -1.25) (size 1.475 0.3) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.25)) + (pad 5 smd roundrect (at -4.1625 -0.75) (size 1.475 0.3) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.25) + (net 4 /OSC_IN)) + (pad 6 smd roundrect (at -4.1625 -0.25) (size 1.475 0.3) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.25) + (net 5 /OSC_OUT)) + (pad 7 smd roundrect (at -4.1625 0.25) (size 1.475 0.3) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.25) + (net 39 /NRST)) + (pad 8 smd roundrect (at -4.1625 0.75) (size 1.475 0.3) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.25) + (net 1 GND)) + (pad 9 smd roundrect (at -4.1625 1.25) (size 1.475 0.3) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.25) + (net 2 +3V3)) + (pad 10 smd roundrect (at -4.1625 1.75) (size 1.475 0.3) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.25)) + (pad 11 smd roundrect (at -4.1625 2.25) (size 1.475 0.3) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.25) + (net 37 /PPS)) + (pad 12 smd roundrect (at -4.1625 2.75) (size 1.475 0.3) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.25) + (net 41 /U3Tx)) + (pad 13 smd roundrect (at -2.75 4.1625) (size 0.3 1.475) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.25) + (net 42 /U3Rx)) + (pad 14 smd roundrect (at -2.25 4.1625) (size 0.3 1.475) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.25) + (net 38 /TRIG2)) + (pad 15 smd roundrect (at -1.75 4.1625) (size 0.3 1.475) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.25)) + (pad 16 smd roundrect (at -1.25 4.1625) (size 0.3 1.475) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.25)) + (pad 17 smd roundrect (at -0.75 4.1625) (size 0.3 1.475) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.25)) + (pad 18 smd roundrect (at -0.25 4.1625) (size 0.3 1.475) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.25)) + (pad 19 smd roundrect (at 0.25 4.1625) (size 0.3 1.475) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.25)) + (pad 20 smd roundrect (at 0.75 4.1625) (size 0.3 1.475) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.25) + (net 33 "Net-(R13-Pad1)")) + (pad 21 smd roundrect (at 1.25 4.1625) (size 0.3 1.475) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.25) + (net 16 /U2Tx)) + (pad 22 smd roundrect (at 1.75 4.1625) (size 0.3 1.475) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.25) + (net 17 /U2Rx)) + (pad 23 smd roundrect (at 2.25 4.1625) (size 0.3 1.475) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.25) + (net 1 GND)) + (pad 24 smd roundrect (at 2.75 4.1625) (size 0.3 1.475) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.25) + (net 2 +3V3)) + (pad 25 smd roundrect (at 4.1625 2.75) (size 1.475 0.3) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.25)) + (pad 26 smd roundrect (at 4.1625 2.25) (size 1.475 0.3) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.25)) + (pad 27 smd roundrect (at 4.1625 1.75) (size 1.475 0.3) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.25)) + (pad 28 smd roundrect (at 4.1625 1.25) (size 1.475 0.3) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.25)) + (pad 29 smd roundrect (at 4.1625 0.75) (size 1.475 0.3) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.25)) + (pad 30 smd roundrect (at 4.1625 0.25) (size 1.475 0.3) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.25) + (net 21 /U1Tx)) + (pad 31 smd roundrect (at 4.1625 -0.25) (size 1.475 0.3) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.25) + (net 22 /U1Rx)) + (pad 32 smd roundrect (at 4.1625 -0.75) (size 1.475 0.3) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.25) + (net 27 /USBDM)) + (pad 33 smd roundrect (at 4.1625 -1.25) (size 1.475 0.3) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.25) + (net 30 /USBDP)) + (pad 34 smd roundrect (at 4.1625 -1.75) (size 1.475 0.3) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.25) + (net 32 /TRIG0)) + (pad 35 smd roundrect (at 4.1625 -2.25) (size 1.475 0.3) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.25) + (net 1 GND)) + (pad 36 smd roundrect (at 4.1625 -2.75) (size 1.475 0.3) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.25) + (net 2 +3V3)) + (pad 37 smd roundrect (at 2.75 -4.1625) (size 0.3 1.475) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.25) + (net 35 /TRIG1)) + (pad 38 smd roundrect (at 2.25 -4.1625) (size 0.3 1.475) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.25) + (net 25 /USB_PU)) + (pad 39 smd roundrect (at 1.75 -4.1625) (size 0.3 1.475) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.25)) + (pad 40 smd roundrect (at 1.25 -4.1625) (size 0.3 1.475) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.25)) + (pad 41 smd roundrect (at 0.75 -4.1625) (size 0.3 1.475) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.25)) + (pad 42 smd roundrect (at 0.25 -4.1625) (size 0.3 1.475) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.25)) + (pad 43 smd roundrect (at -0.25 -4.1625) (size 0.3 1.475) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.25)) + (pad 44 smd roundrect (at -0.75 -4.1625) (size 0.3 1.475) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.25) + (net 40 /BOOT0)) + (pad 45 smd roundrect (at -1.25 -4.1625) (size 0.3 1.475) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.25) + (net 9 /LED0)) + (pad 46 smd roundrect (at -1.75 -4.1625) (size 0.3 1.475) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.25) + (net 12 /LED1)) + (pad 47 smd roundrect (at -2.25 -4.1625) (size 0.3 1.475) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.25) + (net 1 GND)) + (pad 48 smd roundrect (at -2.75 -4.1625) (size 0.3 1.475) (layers F.Cu F.Paste F.Mask) (roundrect_rratio 0.25) + (net 2 +3V3)) + (model ${KISYS3DMOD}/Package_QFP.3dshapes/LQFP-48_7x7mm_P0.5mm.wrl + (at (xyz 0 0 0)) + (scale (xyz 1 1 1)) + (rotate (xyz 0 0 0)) + ) + ) + + (module Package_DIP:DIP-4_W7.62mm (layer B.Cu) (tedit 5A02E8C5) (tstamp 5D1616CB) + (at 90.3145 81.6215 90) + (descr "4-lead though-hole mounted DIP package, row spacing 7.62 mm (300 mils)") + (tags "THT DIP DIL PDIP 2.54mm 7.62mm 300mil") + (path /5D72A0B8) + (fp_text reference U8 (at 3.937 2.667 180) (layer B.SilkS) + (effects (font (size 1 1) (thickness 0.15)) (justify mirror)) + ) + (fp_text value PC817 (at 3.81 -4.87 90) (layer B.Fab) + (effects (font (size 1 1) (thickness 0.15)) (justify mirror)) + ) + (fp_arc (start 3.81 1.33) (end 2.81 1.33) (angle 180) (layer B.SilkS) (width 0.12)) + (fp_line (start 1.635 1.27) (end 6.985 1.27) (layer B.Fab) (width 0.1)) + (fp_line (start 6.985 1.27) (end 6.985 -3.81) (layer B.Fab) (width 0.1)) + (fp_line (start 6.985 -3.81) (end 0.635 -3.81) (layer B.Fab) (width 0.1)) + (fp_line (start 0.635 -3.81) (end 0.635 0.27) (layer B.Fab) (width 0.1)) + (fp_line (start 0.635 0.27) (end 1.635 1.27) (layer B.Fab) (width 0.1)) + (fp_line (start 2.81 1.33) (end 1.16 1.33) (layer B.SilkS) (width 0.12)) + (fp_line (start 1.16 1.33) (end 1.16 -3.87) (layer B.SilkS) (width 0.12)) + (fp_line (start 1.16 -3.87) (end 6.46 -3.87) (layer B.SilkS) (width 0.12)) + (fp_line (start 6.46 -3.87) (end 6.46 1.33) (layer B.SilkS) (width 0.12)) + (fp_line (start 6.46 1.33) (end 4.81 1.33) (layer B.SilkS) (width 0.12)) + (fp_line (start -1.1 1.55) (end -1.1 -4.1) (layer B.CrtYd) (width 0.05)) + (fp_line (start -1.1 -4.1) (end 8.7 -4.1) (layer B.CrtYd) (width 0.05)) + (fp_line (start 8.7 -4.1) (end 8.7 1.55) (layer B.CrtYd) (width 0.05)) + (fp_line (start 8.7 1.55) (end -1.1 1.55) (layer B.CrtYd) (width 0.05)) + (fp_text user %R (at 3.81 -1.27 90) (layer B.Fab) + (effects (font (size 1 1) (thickness 0.15)) (justify mirror)) + ) + (pad 1 thru_hole rect (at 0 0 90) (size 1.6 1.6) (drill 0.8) (layers *.Cu *.Mask) + (net 36 "Net-(R17-Pad2)")) + (pad 3 thru_hole oval (at 7.62 -2.54 90) (size 1.6 1.6) (drill 0.8) (layers *.Cu *.Mask) + (net 1 GND)) + (pad 2 thru_hole oval (at 0 -2.54 90) (size 1.6 1.6) (drill 0.8) (layers *.Cu *.Mask) + (net 19 "Net-(J6-Pad1)")) + (pad 4 thru_hole oval (at 7.62 0 90) (size 1.6 1.6) (drill 0.8) (layers *.Cu *.Mask) + (net 38 /TRIG2)) + (model ${KISYS3DMOD}/Package_DIP.3dshapes/DIP-4_W7.62mm.wrl + (at (xyz 0 0 0)) + (scale (xyz 1 1 1)) + (rotate (xyz 0 0 0)) + ) + ) + + (module Crystal:Crystal_HC49-U_Vertical (layer B.Cu) (tedit 5A1AD3B8) (tstamp 5D1598D4) + (at 98.3155 54.6975 270) + (descr "Crystal THT HC-49/U http://5hertz.com/pdfs/04404_D.pdf") + (tags "THT crystalHC-49/U") + (path /5D1F4994) + (fp_text reference Y1 (at 2.44 3.525 270) (layer B.SilkS) + (effects (font (size 1 1) (thickness 0.15)) (justify mirror)) + ) + (fp_text value 8MHz (at 2.44 -3.525 270) (layer B.Fab) + (effects (font (size 1 1) (thickness 0.15)) (justify mirror)) + ) + (fp_text user %R (at 2.44 0 270) (layer B.Fab) + (effects (font (size 1 1) (thickness 0.15)) (justify mirror)) + ) + (fp_line (start -0.685 2.325) (end 5.565 2.325) (layer B.Fab) (width 0.1)) + (fp_line (start -0.685 -2.325) (end 5.565 -2.325) (layer B.Fab) (width 0.1)) + (fp_line (start -0.56 2) (end 5.44 2) (layer B.Fab) (width 0.1)) + (fp_line (start -0.56 -2) (end 5.44 -2) (layer B.Fab) (width 0.1)) + (fp_line (start -0.685 2.525) (end 5.565 2.525) (layer B.SilkS) (width 0.12)) + (fp_line (start -0.685 -2.525) (end 5.565 -2.525) (layer B.SilkS) (width 0.12)) + (fp_line (start -3.5 2.8) (end -3.5 -2.8) (layer B.CrtYd) (width 0.05)) + (fp_line (start -3.5 -2.8) (end 8.4 -2.8) (layer B.CrtYd) (width 0.05)) + (fp_line (start 8.4 -2.8) (end 8.4 2.8) (layer B.CrtYd) (width 0.05)) + (fp_line (start 8.4 2.8) (end -3.5 2.8) (layer B.CrtYd) (width 0.05)) + (fp_arc (start -0.685 0) (end -0.685 2.325) (angle 180) (layer B.Fab) (width 0.1)) + (fp_arc (start 5.565 0) (end 5.565 2.325) (angle -180) (layer B.Fab) (width 0.1)) + (fp_arc (start -0.56 0) (end -0.56 2) (angle 180) (layer B.Fab) (width 0.1)) + (fp_arc (start 5.44 0) (end 5.44 2) (angle -180) (layer B.Fab) (width 0.1)) + (fp_arc (start -0.685 0) (end -0.685 2.525) (angle 180) (layer B.SilkS) (width 0.12)) + (fp_arc (start 5.565 0) (end 5.565 2.525) (angle -180) (layer B.SilkS) (width 0.12)) + (pad 1 thru_hole circle (at 0 0 270) (size 1.5 1.5) (drill 0.8) (layers *.Cu *.Mask) + (net 4 /OSC_IN)) + (pad 2 thru_hole circle (at 4.88 0 270) (size 1.5 1.5) (drill 0.8) (layers *.Cu *.Mask) + (net 5 /OSC_OUT)) + (model ${KISYS3DMOD}/Crystal.3dshapes/Crystal_HC49-U_Vertical.wrl + (at (xyz 0 0 0)) + (scale (xyz 1 1 1)) + (rotate (xyz 0 0 0)) + ) + ) + + (dimension 54.5 (width 0.15) (layer Dwgs.User) + (gr_text "54.500 mm" (at 150.3 70.25 270) (layer Dwgs.User) + (effects (font (size 1 1) (thickness 0.15))) + ) + (feature1 (pts (xy 142.5 97.5) (xy 149.586421 97.5))) + (feature2 (pts (xy 142.5 43) (xy 149.586421 43))) + (crossbar (pts (xy 149 43) (xy 149 97.5))) + (arrow1a (pts (xy 149 97.5) (xy 148.413579 96.373496))) + (arrow1b (pts (xy 149 97.5) (xy 149.586421 96.373496))) + (arrow2a (pts (xy 149 43) (xy 148.413579 44.126504))) + (arrow2b (pts (xy 149 43) (xy 149.586421 44.126504))) + ) + (dimension 95 (width 0.15) (layer Dwgs.User) + (gr_text "95.000 mm" (at 95 38.2) (layer Dwgs.User) + (effects (font (size 1 1) (thickness 0.15))) + ) + (feature1 (pts (xy 142.5 43) (xy 142.5 38.913579))) + (feature2 (pts (xy 47.5 43) (xy 47.5 38.913579))) + (crossbar (pts (xy 47.5 39.5) (xy 142.5 39.5))) + (arrow1a (pts (xy 142.5 39.5) (xy 141.373496 40.086421))) + (arrow1b (pts (xy 142.5 39.5) (xy 141.373496 38.913579))) + (arrow2a (pts (xy 47.5 39.5) (xy 48.626504 40.086421))) + (arrow2b (pts (xy 47.5 39.5) (xy 48.626504 38.913579))) + ) + (gr_text LED1 (at 108.666 44.9185) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (gr_text LED0 (at 89.8065 46.125) (layer F.SilkS) + (effects (font (size 2 2) (thickness 0.15))) + ) + (gr_text Boot (at 114.508 45.871) (layer F.SilkS) + (effects (font (size 2 2) (thickness 0.15))) + ) + (gr_text Reset (at 90.124 51.1415) (layer F.SilkS) + (effects (font (size 2 2) (thickness 0.15))) + ) + (gr_text "Ext0\nColl gnd" (at 63.0476 78.51) (layer B.SilkS) + (effects (font (size 1 1) (thickness 0.15)) (justify mirror)) + ) + (gr_text "Ext1\nColl gnd" (at 74.5665 78.4465) (layer B.SilkS) + (effects (font (size 1 1) (thickness 0.15)) (justify mirror)) + ) + (gr_text "Trig.\n+ 12V -" (at 86.949 85.3045) (layer B.SilkS) + (effects (font (size 1 1) (thickness 0.15)) (justify mirror)) + ) + (gr_text "Power\n+ 12V -" (at 103 85) (layer B.SilkS) + (effects (font (size 1 1) (thickness 0.15)) (justify mirror)) + ) + (gr_text "+5V out" (at 134 86) (layer B.SilkS) + (effects (font (size 1 1) (thickness 0.15)) (justify mirror)) + ) + (gr_line (start 142.5 43) (end 47.5 43) (layer Edge.Cuts) (width 0.05) (tstamp 5D164A1B)) + (gr_line (start 142.5 97.5) (end 142.5 43) (layer Edge.Cuts) (width 0.05)) + (gr_line (start 47.5 97.5) (end 142.5 97.5) (layer Edge.Cuts) (width 0.05)) + (gr_line (start 47.5 43) (end 47.5 97.5) (layer Edge.Cuts) (width 0.05)) + + (segment (start 115.3963 58.1872) (end 115.3991 58.19) (width 0.25) (layer F.Cu) (net 1)) + (segment (start 114.5588 58.1872) (end 115.3963 58.1872) (width 0.25) (layer F.Cu) (net 1) (status 10)) + (segment (start 115.3991 58.19) (end 116.2225 58.19) (width 0.25) (layer F.Cu) (net 1)) + (segment (start 117.1115 57.301) (end 117.1115 56.0945) (width 0.25) (layer F.Cu) (net 1) (status 20)) + (segment (start 116.2225 58.19) (end 117.1115 57.301) (width 0.25) (layer F.Cu) (net 1)) + (via (at 118.8895 59.714) (size 1.5) (drill 0.6) (layers F.Cu B.Cu) (net 1)) + (segment (start 124.715 59.7013) (end 118.9022 59.7013) (width 0.5) (layer F.Cu) (net 1) (status 10)) + (segment (start 118.9022 59.7013) (end 118.8895 59.714) (width 0.5) (layer F.Cu) (net 1)) + (via (at 117.1115 54.4435) (size 1.5) (drill 0.6) (layers F.Cu B.Cu) (net 1)) + (segment (start 117.1115 56.0945) (end 117.1115 54.4435) (width 0.25) (layer F.Cu) (net 1) (status 10)) + (segment (start 132.8402 65.234081) (end 132.8595 65.253381) (width 0.5) (layer F.Cu) (net 1)) + (segment (start 132.8402 64.032) (end 132.8402 65.234081) (width 0.5) (layer F.Cu) (net 1) (status 10)) + (via (at 135.463 74.319) (size 1.5) (drill 0.6) (layers F.Cu B.Cu) (net 1)) + (segment (start 132.8595 71.7155) (end 135.463 74.319) (width 0.5) (layer F.Cu) (net 1)) + (segment (start 112.6463 64.5997) (end 112.6463 66.2343) (width 0.25) (layer F.Cu) (net 1) (status 10)) + (segment (start 113.2735 66.8615) (end 114.5715 66.8615) (width 0.25) (layer F.Cu) (net 1) (status 20)) + (segment (start 112.6463 66.2343) (end 113.2735 66.8615) (width 0.25) (layer F.Cu) (net 1)) + (segment (start 118.5212 66.7536) (end 118.5212 65.4036) (width 0.5) (layer F.Cu) (net 1) (status 20)) + (segment (start 118.4133 66.8615) (end 118.5212 66.7536) (width 0.5) (layer F.Cu) (net 1)) + (segment (start 114.5715 66.8615) (end 118.4133 66.8615) (width 0.5) (layer F.Cu) (net 1) (status 10)) + (segment (start 115.524 67.814) (end 114.5715 66.8615) (width 0.5) (layer F.Cu) (net 1) (status 20)) + (segment (start 96.4105 56.2215) (end 96.4105 57.936) (width 0.5) (layer F.Cu) (net 1) (status 30)) + (segment (start 95.8355 56.2215) (end 96.4105 56.2215) (width 0.5) (layer F.Cu) (net 1) (status 20)) + (segment (start 93.868 56.2215) (end 95.8355 56.2215) (width 0.5) (layer F.Cu) (net 1)) + (segment (start 92.8545 55.208) (end 93.868 56.2215) (width 0.5) (layer F.Cu) (net 1)) + (segment (start 92.8545 53.618) (end 92.8545 55.208) (width 0.5) (layer F.Cu) (net 1) (status 10)) + (segment (start 90.3815 60.6945) (end 93.868 57.208) (width 0.5) (layer F.Cu) (net 1)) + (segment (start 93.868 57.208) (end 93.868 56.2215) (width 0.5) (layer F.Cu) (net 1)) + (segment (start 89.8065 60.6945) (end 90.3815 60.6945) (width 0.5) (layer F.Cu) (net 1) (status 10)) + (segment (start 106.2338 61.1872) (end 104.6147 61.1872) (width 0.25) (layer F.Cu) (net 1) (status 10)) + (segment (start 102.21701 60.59201) (end 102.1925 60.5675) (width 0.25) (layer F.Cu) (net 1)) + (segment (start 102.1925 60.5675) (end 101.6175 60.5675) (width 0.25) (layer F.Cu) (net 1) (status 20)) + (segment (start 104.01951 60.59201) (end 102.21701 60.59201) (width 0.25) (layer F.Cu) (net 1)) + (segment (start 104.6147 61.1872) (end 104.01951 60.59201) (width 0.25) (layer F.Cu) (net 1)) + (segment (start 100.03 63.298) (end 100.03 61.4285) (width 0.5) (layer F.Cu) (net 1) (status 10)) + (segment (start 100.891 60.5675) (end 101.6175 60.5675) (width 0.5) (layer F.Cu) (net 1) (status 20)) + (segment (start 100.03 61.4285) (end 100.891 60.5675) (width 0.5) (layer F.Cu) (net 1) (tstamp 5D166066)) + (segment (start 89.2315 60.6945) (end 88.473 61.453) (width 0.5) (layer F.Cu) (net 1)) + (segment (start 89.8065 60.6945) (end 89.2315 60.6945) (width 0.5) (layer F.Cu) (net 1) (status 10)) + (segment (start 88.473 63.3335) (end 89.9335 64.794) (width 0.5) (layer F.Cu) (net 1)) + (segment (start 89.9335 64.794) (end 96.601 64.794) (width 0.5) (layer F.Cu) (net 1)) + (segment (start 98.097 63.298) (end 100.03 63.298) (width 0.5) (layer F.Cu) (net 1) (status 20)) + (segment (start 96.601 64.794) (end 98.097 63.298) (width 0.5) (layer F.Cu) (net 1)) + (segment (start 115.524 72.981081) (end 114.249581 74.2555) (width 0.5) (layer F.Cu) (net 1)) + (segment (start 107.65 68.0325) (end 108.2215 67.461) (width 0.5) (layer F.Cu) (net 1) (status 20)) + (segment (start 115.524 71.779) (end 115.524 72.981081) (width 0.5) (layer F.Cu) (net 1) (status 10)) + (segment (start 106.126 54.154) (end 106.126 52.2845) (width 0.5) (layer F.Cu) (net 1) (status 30)) + (segment (start 107.478572 54.653072) (end 108.1463 55.3208) (width 0.25) (layer F.Cu) (net 1)) + (segment (start 106.126 54.154) (end 106.625072 54.653072) (width 0.25) (layer F.Cu) (net 1) (status 10)) + (segment (start 106.625072 54.653072) (end 107.478572 54.653072) (width 0.25) (layer F.Cu) (net 1)) + (segment (start 108.1463 56.2747) (end 108.1463 55.3208) (width 0.25) (layer F.Cu) (net 1) (status 10)) + (segment (start 133.124 51.6775) (end 133.558 52.1115) (width 0.5) (layer F.Cu) (net 1) (status 30)) + (segment (start 129.6845 51.6775) (end 133.124 51.6775) (width 0.5) (layer F.Cu) (net 1) (status 30)) + (segment (start 133.690199 63.182001) (end 134.407999 63.182001) (width 0.5) (layer F.Cu) (net 1)) + (segment (start 132.8402 64.032) (end 133.690199 63.182001) (width 0.5) (layer F.Cu) (net 1) (status 10)) + (segment (start 134.407999 63.182001) (end 134.701 62.889) (width 0.5) (layer F.Cu) (net 1)) + (segment (start 134.701 62.889) (end 134.701 60.5395) (width 0.5) (layer F.Cu) (net 1)) + (segment (start 134.701 60.5395) (end 132.8595 58.698) (width 0.5) (layer F.Cu) (net 1)) + (segment (start 133.558 54.0625) (end 133.558 52.1115) (width 0.5) (layer F.Cu) (net 1) (status 20)) + (segment (start 132.8595 54.761) (end 133.558 54.0625) (width 0.5) (layer F.Cu) (net 1)) + (segment (start 118.8895 65.0353) (end 118.5212 65.4036) (width 0.5) (layer B.Cu) (net 1) (status 30)) + (segment (start 118.8895 59.714) (end 118.8895 65.0353) (width 0.5) (layer B.Cu) (net 1) (status 20)) + (via (at 118.5085 68.477) (size 1.5) (drill 0.6) (layers F.Cu B.Cu) (net 1)) + (segment (start 118.5212 65.4036) (end 118.5212 68.4643) (width 0.5) (layer B.Cu) (net 1) (status 10)) + (segment (start 118.5212 68.4643) (end 118.5085 68.477) (width 0.5) (layer B.Cu) (net 1)) + (segment (start 115.524 68.477) (end 118.5085 68.477) (width 0.5) (layer F.Cu) (net 1)) + (segment (start 115.524 68.477) (end 115.524 67.814) (width 0.5) (layer F.Cu) (net 1)) + (segment (start 115.524 71.779) (end 115.524 68.477) (width 0.5) (layer F.Cu) (net 1) (status 10)) + (segment (start 119.56916 68.477) (end 120.604 69.51184) (width 0.5) (layer B.Cu) (net 1)) + (segment (start 118.5085 68.477) (end 119.56916 68.477) (width 0.5) (layer B.Cu) (net 1)) + (segment (start 120.604 69.51184) (end 120.604 73.303) (width 0.5) (layer B.Cu) (net 1)) + (segment (start 121.62 74.319) (end 135.463 74.319) (width 0.5) (layer B.Cu) (net 1)) + (segment (start 120.604 73.303) (end 121.62 74.319) (width 0.5) (layer B.Cu) (net 1)) + (segment (start 133.0575 68.802) (end 135.5502 68.802) (width 0.5) (layer F.Cu) (net 1) (status 20)) + (segment (start 132.8595 68.604) (end 133.0575 68.802) (width 0.5) (layer F.Cu) (net 1)) + (segment (start 132.8595 68.604) (end 132.8595 71.7155) (width 0.5) (layer F.Cu) (net 1)) + (segment (start 132.8595 65.253381) (end 132.8595 68.604) (width 0.5) (layer F.Cu) (net 1)) + (segment (start 133.075327 56.762) (end 135.5502 56.762) (width 0.5) (layer F.Cu) (net 1) (status 20)) + (segment (start 132.8595 56.4755) (end 132.8595 56.546173) (width 0.5) (layer F.Cu) (net 1)) + (segment (start 132.8595 56.546173) (end 133.075327 56.762) (width 0.5) (layer F.Cu) (net 1)) + (segment (start 132.8595 56.4755) (end 132.8595 54.761) (width 0.5) (layer F.Cu) (net 1)) + (segment (start 132.8595 58.698) (end 132.8595 56.4755) (width 0.5) (layer F.Cu) (net 1)) + (segment (start 133.3955 78.411) (end 133.939 77.8675) (width 1) (layer F.Cu) (net 1)) + (segment (start 131.78 78.411) (end 133.3955 78.411) (width 1) (layer F.Cu) (net 1)) + (segment (start 133.939 75.843) (end 135.463 74.319) (width 1) (layer F.Cu) (net 1)) + (segment (start 133.939 77.8675) (end 133.939 75.843) (width 1) (layer F.Cu) (net 1)) + (segment (start 112.984 76.417523) (end 112.984 74.2555) (width 1) (layer F.Cu) (net 1)) + (segment (start 113.0475 76.481023) (end 112.984 76.417523) (width 1) (layer F.Cu) (net 1)) + (segment (start 113.0475 78.3195) (end 113.0475 76.481023) (width 1) (layer F.Cu) (net 1)) + (segment (start 114.249581 74.2555) (end 112.984 74.2555) (width 0.5) (layer F.Cu) (net 1)) + (segment (start 113.0475 78.3195) (end 113.0475 81.7485) (width 1) (layer F.Cu) (net 1)) + (segment (start 115.143 80.415) (end 113.0475 78.3195) (width 1) (layer F.Cu) (net 1)) + (segment (start 117.048 80.415) (end 115.143 80.415) (width 1) (layer F.Cu) (net 1)) + (segment (start 139.08 92) (end 139.08 81.111) (width 0.5) (layer F.Cu) (net 1)) + (segment (start 135.8365 77.8675) (end 133.939 77.8675) (width 0.5) (layer F.Cu) (net 1)) + (segment (start 139.08 81.111) (end 135.8365 77.8675) (width 0.5) (layer F.Cu) (net 1)) + (segment (start 114.347499 77.019501) (end 122.669501 77.019501) (width 0.5) (layer F.Cu) (net 1)) + (segment (start 113.0475 78.3195) (end 114.347499 77.019501) (width 0.5) (layer F.Cu) (net 1)) + (segment (start 123.369 77.719) (end 123.369 82.193) (width 0.5) (layer F.Cu) (net 1)) + (segment (start 122.669501 77.019501) (end 123.369 77.719) (width 0.5) (layer F.Cu) (net 1)) + (segment (start 139.08 93.838477) (end 138.406477 94.512) (width 0.5) (layer F.Cu) (net 1)) + (segment (start 139.08 92) (end 139.08 93.838477) (width 0.5) (layer F.Cu) (net 1)) + (segment (start 132.034 94.512) (end 130.8275 93.3055) (width 0.5) (layer F.Cu) (net 1)) + (segment (start 130.8275 86.2515) (end 126.769 82.193) (width 0.5) (layer F.Cu) (net 1)) + (segment (start 130.8275 93.3055) (end 130.8275 86.2515) (width 0.5) (layer F.Cu) (net 1)) + (segment (start 100.5 93.8) (end 101.7835 95.0835) (width 0.5) (layer F.Cu) (net 1)) + (segment (start 100.5 92) (end 100.5 93.8) (width 0.5) (layer F.Cu) (net 1)) + (segment (start 138.406477 94.512) (end 132.923 94.512) (width 0.5) (layer F.Cu) (net 1)) + (segment (start 132.3515 95.0835) (end 132.923 94.512) (width 0.5) (layer F.Cu) (net 1)) + (segment (start 132.923 94.512) (end 132.034 94.512) (width 0.5) (layer F.Cu) (net 1)) + (segment (start 109.555 85.6575) (end 107.7135 83.816) (width 0.5) (layer F.Cu) (net 1)) + (segment (start 109.555 95.0835) (end 109.555 85.6575) (width 0.5) (layer F.Cu) (net 1)) + (segment (start 109.555 95.0835) (end 132.3515 95.0835) (width 0.5) (layer F.Cu) (net 1)) + (segment (start 80.6948 61.8323) (end 81.5134 62.6509) (width 0.5) (layer F.Cu) (net 1)) + (segment (start 78.1098 61.8323) (end 80.6948 61.8323) (width 0.5) (layer F.Cu) (net 1)) + (segment (start 77.8278 62.1143) (end 78.1098 61.8323) (width 0.5) (layer F.Cu) (net 1)) + (segment (start 73.8162 62.1143) (end 77.8278 62.1143) (width 0.5) (layer F.Cu) (net 1)) + (segment (start 69.9437 62.1143) (end 73.8162 62.1143) (width 0.5) (layer F.Cu) (net 1)) + (segment (start 64.8637 67.1943) (end 69.9437 62.1143) (width 0.5) (layer F.Cu) (net 1)) + (segment (start 88.4254 62.6509) (end 88.473 62.6985) (width 0.5) (layer F.Cu) (net 1)) + (segment (start 81.5134 62.6509) (end 88.4254 62.6509) (width 0.5) (layer F.Cu) (net 1)) + (segment (start 88.473 61.453) (end 88.473 62.6985) (width 0.5) (layer F.Cu) (net 1)) + (segment (start 88.473 62.6985) (end 88.473 63.3335) (width 0.5) (layer F.Cu) (net 1)) + (segment (start 64.4827 67.1943) (end 66.2353 67.1943) (width 0.5) (layer F.Cu) (net 1)) + (segment (start 64.4827 67.1943) (end 64.8637 67.1943) (width 0.5) (layer F.Cu) (net 1)) + (segment (start 57.8162 67.1943) (end 64.4827 67.1943) (width 0.5) (layer F.Cu) (net 1)) + (segment (start 73.0425 74.0015) (end 87.7745 74.0015) (width 0.5) (layer F.Cu) (net 1)) + (via (at 88.9175 53.5545) (size 1.5) (drill 0.6) (layers F.Cu B.Cu) (net 1)) + (segment (start 92.8545 53.618) (end 88.981 53.618) (width 0.5) (layer F.Cu) (net 1)) + (segment (start 88.981 53.618) (end 88.9175 53.5545) (width 0.5) (layer F.Cu) (net 1)) + (via (at 94.6325 73.303) (size 1.5) (drill 0.6) (layers F.Cu B.Cu) (net 1)) + (segment (start 88.9175 53.5545) (end 94.6325 59.2695) (width 0.5) (layer B.Cu) (net 1)) + (segment (start 94.6325 59.2695) (end 94.6325 73.303) (width 0.5) (layer B.Cu) (net 1)) + (segment (start 95.88366 73.1125) (end 107.65 73.1125) (width 0.5) (layer F.Cu) (net 1)) + (segment (start 95.69316 73.303) (end 95.88366 73.1125) (width 0.5) (layer F.Cu) (net 1)) + (segment (start 94.6325 73.303) (end 95.69316 73.303) (width 0.5) (layer F.Cu) (net 1)) + (segment (start 72 86.225) (end 72 92) (width 0.5) (layer F.Cu) (net 1)) + (segment (start 70.793 85.018) (end 72 86.225) (width 0.5) (layer F.Cu) (net 1)) + (segment (start 106.126 54.154) (end 103.741 54.154) (width 0.5) (layer F.Cu) (net 1)) + (segment (start 103.741 54.154) (end 101.6175 52.0305) (width 0.5) (layer F.Cu) (net 1)) + (segment (start 94.1545 53.618) (end 92.8545 53.618) (width 0.5) (layer F.Cu) (net 1)) + (segment (start 95.742 52.0305) (end 94.1545 53.618) (width 0.5) (layer F.Cu) (net 1)) + (segment (start 101.6175 52.0305) (end 95.742 52.0305) (width 0.5) (layer F.Cu) (net 1)) + (segment (start 66.2353 67.1943) (end 70.47075 71.42975) (width 0.5) (layer F.Cu) (net 1)) + (segment (start 70.47075 71.42975) (end 73.0425 74.0015) (width 0.5) (layer F.Cu) (net 1)) + (segment (start 119.95016 59.714) (end 120.7945 58.86966) (width 0.5) (layer B.Cu) (net 1)) + (segment (start 118.8895 59.714) (end 119.95016 59.714) (width 0.5) (layer B.Cu) (net 1)) + (segment (start 120.7945 58.86966) (end 120.7945 55.9675) (width 0.5) (layer B.Cu) (net 1)) + (segment (start 119.2705 54.4435) (end 117.1115 54.4435) (width 0.5) (layer B.Cu) (net 1)) + (segment (start 120.7945 55.9675) (end 119.2705 54.4435) (width 0.5) (layer B.Cu) (net 1)) + (segment (start 107.65 71.9695) (end 109.936 74.2555) (width 0.5) (layer F.Cu) (net 1)) + (segment (start 107.65 71.906) (end 107.65 71.9695) (width 0.5) (layer F.Cu) (net 1) (tstamp 5D1674DD)) + (segment (start 107.65 73.1125) (end 107.65 71.906) (width 0.5) (layer F.Cu) (net 1)) + (segment (start 107.65 71.906) (end 107.65 68.0325) (width 0.5) (layer F.Cu) (net 1)) + (segment (start 112.984 74.2555) (end 109.936 74.2555) (width 0.5) (layer F.Cu) (net 1)) + (segment (start 59.5 87.891) (end 56.596 84.987) (width 0.5) (layer F.Cu) (net 1)) + (segment (start 59.5 92) (end 59.5 87.891) (width 0.5) (layer F.Cu) (net 1)) + (segment (start 59.5 93.8) (end 60.6565 94.9565) (width 0.5) (layer F.Cu) (net 1)) + (segment (start 59.5 92) (end 59.5 93.8) (width 0.5) (layer F.Cu) (net 1)) + (segment (start 60.6565 94.9565) (end 70.8835 94.9565) (width 0.5) (layer F.Cu) (net 1)) + (segment (start 72 93.84) (end 72 92) (width 0.5) (layer F.Cu) (net 1)) + (segment (start 70.8835 94.9565) (end 72 93.84) (width 0.5) (layer F.Cu) (net 1)) + (segment (start 102.443 95.0835) (end 71.0105 95.0835) (width 0.5) (layer F.Cu) (net 1)) + (segment (start 71.0105 95.0835) (end 70.8835 94.9565) (width 0.5) (layer F.Cu) (net 1)) + (segment (start 102.443 95.0835) (end 109.555 95.0835) (width 0.5) (layer F.Cu) (net 1)) + (segment (start 101.7835 95.0835) (end 102.443 95.0835) (width 0.5) (layer F.Cu) (net 1)) + (via (at 115.3335 54.38) (size 1.5) (drill 0.6) (layers F.Cu B.Cu) (net 2)) + (segment (start 115.3335 53.31934) (end 115.60634 53.0465) (width 0.5) (layer F.Cu) (net 2)) + (segment (start 115.3335 54.38) (end 115.3335 53.31934) (width 0.5) (layer F.Cu) (net 2)) + (segment (start 115.60634 53.0465) (end 118.5085 53.0465) (width 0.5) (layer F.Cu) (net 2)) + (segment (start 114.0597 64.5997) (end 114.5715 65.1115) (width 0.25) (layer F.Cu) (net 2) (status 20)) + (segment (start 113.1463 64.5997) (end 114.0597 64.5997) (width 0.25) (layer F.Cu) (net 2) (status 10)) + (segment (start 113.7213 57.6872) (end 114.5588 57.6872) (width 0.25) (layer F.Cu) (net 2) (status 20)) + (segment (start 113.36701 58.04149) (end 113.7213 57.6872) (width 0.25) (layer F.Cu) (net 2)) + (segment (start 113.1463 64.5997) (end 113.36701 64.37899) (width 0.25) (layer F.Cu) (net 2) (status 10)) + (segment (start 114.5588 57.6872) (end 107.8457 57.6872) (width 0.25) (layer F.Cu) (net 2) (status 10)) + (segment (start 107.6463 57.4878) (end 107.6463 56.2747) (width 0.25) (layer F.Cu) (net 2) (status 20)) + (segment (start 107.8457 57.6872) (end 107.6463 57.4878) (width 0.25) (layer F.Cu) (net 2)) + (segment (start 107.8457 57.6872) (end 106.2338 57.6872) (width 0.25) (layer F.Cu) (net 2) (status 20)) + (segment (start 112.10372 61.6872) (end 113.36701 62.95049) (width 0.25) (layer F.Cu) (net 2)) + (segment (start 106.2338 61.6872) (end 112.10372 61.6872) (width 0.25) (layer F.Cu) (net 2) (status 10)) + (segment (start 113.36701 64.37899) (end 113.36701 62.95049) (width 0.25) (layer F.Cu) (net 2)) + (segment (start 113.36701 62.95049) (end 113.36701 58.04149) (width 0.25) (layer F.Cu) (net 2)) + (segment (start 107.2756 55.904) (end 107.6463 56.2747) (width 0.25) (layer F.Cu) (net 2) (status 20)) + (segment (start 106.126 55.904) (end 107.2756 55.904) (width 0.25) (layer F.Cu) (net 2) (status 10)) + (segment (start 105.3963 61.6872) (end 106.2338 61.6872) (width 0.25) (layer F.Cu) (net 2) (status 20)) + (segment (start 103.78 61.492) (end 103.9752 61.6872) (width 0.25) (layer F.Cu) (net 2)) + (segment (start 103.9752 61.6872) (end 105.3963 61.6872) (width 0.25) (layer F.Cu) (net 2)) + (segment (start 103.205 61.492) (end 103.78 61.492) (width 0.25) (layer F.Cu) (net 2) (status 10)) + (segment (start 102.3795 62.3175) (end 103.205 61.492) (width 0.5) (layer F.Cu) (net 2) (status 20)) + (segment (start 101.6175 62.3175) (end 102.3795 62.3175) (width 0.5) (layer F.Cu) (net 2) (status 10)) + (segment (start 115.3615 54.408) (end 115.3335 54.38) (width 0.5) (layer F.Cu) (net 2)) + (segment (start 115.3615 56.0945) (end 115.3615 54.408) (width 0.5) (layer F.Cu) (net 2) (status 10)) + (segment (start 114.5588 56.8972) (end 114.5588 57.3772) (width 0.5) (layer F.Cu) (net 2)) + (segment (start 115.3615 56.0945) (end 114.5588 56.8972) (width 0.5) (layer F.Cu) (net 2) (status 10)) + (segment (start 114.5588 57.6872) (end 114.5588 57.3772) (width 0.25) (layer F.Cu) (net 2) (status 10)) + (segment (start 115.3335 53.31934) (end 115.86034 52.7925) (width 0.5) (layer B.Cu) (net 2)) + (segment (start 115.3335 54.38) (end 115.3335 53.31934) (width 0.5) (layer B.Cu) (net 2)) + (segment (start 115.86034 52.7925) (end 118.953 52.7925) (width 0.5) (layer B.Cu) (net 2)) + (via (at 121.112 46.3155) (size 1.5) (drill 0.6) (layers F.Cu B.Cu) (net 2)) + (segment (start 118.953 52.7925) (end 121.112 50.6335) (width 0.5) (layer B.Cu) (net 2)) + (segment (start 121.112 50.6335) (end 121.112 46.3155) (width 0.5) (layer B.Cu) (net 2)) + (segment (start 121.112 47.685) (end 119.4335 49.3635) (width 0.5) (layer F.Cu) (net 2) (status 20)) + (segment (start 121.112 46.3155) (end 121.112 47.685) (width 0.5) (layer F.Cu) (net 2)) + (segment (start 123.3705 49.3635) (end 123.3845 49.3775) (width 0.5) (layer F.Cu) (net 2) (status 30)) + (segment (start 119.4335 49.3635) (end 123.3705 49.3635) (width 0.5) (layer F.Cu) (net 2) (status 30)) + (segment (start 123.3845 49.3775) (end 129.6845 49.3775) (width 0.5) (layer F.Cu) (net 2) (status 30)) + (segment (start 133.417 49.3775) (end 133.558 49.2365) (width 0.5) (layer F.Cu) (net 2) (status 30)) + (segment (start 129.6845 49.3775) (end 133.417 49.3775) (width 0.5) (layer F.Cu) (net 2) (status 30)) + (segment (start 73.8162 57.0343) (end 73.8162 59.5743) (width 0.5) (layer F.Cu) (net 2)) + (segment (start 77.6018 59.5743) (end 78.1098 60.0823) (width 0.5) (layer F.Cu) (net 2)) + (segment (start 73.8162 59.5743) (end 77.6018 59.5743) (width 0.5) (layer F.Cu) (net 2)) + (segment (start 81.107 60.0823) (end 81.5134 59.6759) (width 0.5) (layer F.Cu) (net 2)) + (segment (start 78.1098 60.0823) (end 81.107 60.0823) (width 0.5) (layer F.Cu) (net 2)) + (segment (start 121.112 46.3155) (end 108.031 46.3155) (width 0.5) (layer F.Cu) (net 2)) + (segment (start 106.154 48.1925) (end 106.154 50.3795) (width 0.5) (layer F.Cu) (net 2)) + (segment (start 108.031 46.3155) (end 106.154 48.1925) (width 0.5) (layer F.Cu) (net 2)) + (via (at 104.348 50.3795) (size 1.5) (drill 0.6) (layers F.Cu B.Cu) (net 2)) + (segment (start 106.154 50.3795) (end 104.348 50.3795) (width 0.5) (layer F.Cu) (net 2)) + (via (at 81.615 50.3795) (size 1.5) (drill 0.6) (layers F.Cu B.Cu) (net 2)) + (segment (start 81.615 59.5743) (end 81.5134 59.6759) (width 0.5) (layer F.Cu) (net 2)) + (segment (start 81.615 50.3795) (end 81.615 59.5743) (width 0.5) (layer F.Cu) (net 2)) + (via (at 87.1395 61.238) (size 1.5) (drill 0.6) (layers F.Cu B.Cu) (net 2)) + (segment (start 81.5134 59.6759) (end 85.5774 59.6759) (width 0.5) (layer F.Cu) (net 2)) + (segment (start 85.5774 59.6759) (end 87.1395 61.238) (width 0.5) (layer F.Cu) (net 2)) + (via (at 87.1395 70.001) (size 1.5) (drill 0.6) (layers F.Cu B.Cu) (net 2)) + (segment (start 87.1395 61.238) (end 87.1395 70.001) (width 0.5) (layer B.Cu) (net 2)) + (segment (start 88.8995 70.001) (end 88.963 70.0645) (width 0.5) (layer F.Cu) (net 2)) + (segment (start 87.1395 70.001) (end 88.8995 70.001) (width 0.5) (layer F.Cu) (net 2)) + (segment (start 94.696 50.3795) (end 81.615 50.3795) (width 0.5) (layer B.Cu) (net 2)) + (segment (start 95.2675 49.9605) (end 95.1405 50.0875) (width 0.5) (layer B.Cu) (net 2)) + (segment (start 95.2675 49.3355) (end 95.2675 49.9605) (width 0.5) (layer B.Cu) (net 2)) + (segment (start 95.1405 50.0875) (end 95.1405 50.3795) (width 0.5) (layer B.Cu) (net 2)) + (segment (start 95.1405 50.3795) (end 94.696 50.3795) (width 0.5) (layer B.Cu) (net 2)) + (segment (start 101.935 50.2525) (end 101.935 49.3635) (width 0.5) (layer B.Cu) (net 2)) + (segment (start 101.808 50.3795) (end 95.1405 50.3795) (width 0.5) (layer B.Cu) (net 2)) + (segment (start 101.808 50.3795) (end 101.935 50.2525) (width 0.5) (layer B.Cu) (net 2)) + (segment (start 104.348 50.3795) (end 101.808 50.3795) (width 0.5) (layer B.Cu) (net 2)) + (segment (start 83.406 80.428) (end 83.4565 80.4785) (width 0.5) (layer F.Cu) (net 2)) + (segment (start 81.334 80.428) (end 83.406 80.428) (width 0.5) (layer F.Cu) (net 2)) + (via (at 85.044 82.701) (size 1.5) (drill 0.6) (layers F.Cu B.Cu) (net 2)) + (segment (start 83.4565 80.4785) (end 83.4565 81.1135) (width 0.5) (layer F.Cu) (net 2)) + (segment (start 83.4565 81.1135) (end 85.044 82.701) (width 0.5) (layer F.Cu) (net 2)) + (segment (start 85.044 82.701) (end 85.044 71.9695) (width 0.5) (layer B.Cu) (net 2)) + (segment (start 85.171 71.9695) (end 87.1395 70.001) (width 0.5) (layer B.Cu) (net 2)) + (segment (start 85.044 71.9695) (end 85.171 71.9695) (width 0.5) (layer B.Cu) (net 2)) + (segment (start 69.944001 83.603001) (end 70.058 83.717) (width 0.25) (layer F.Cu) (net 2)) + (segment (start 70.058 83.717) (end 71.8995 83.717) (width 0.25) (layer F.Cu) (net 2)) + (segment (start 71.8995 83.717) (end 72.09 83.5265) (width 0.25) (layer F.Cu) (net 2)) + (segment (start 72.09 83.5265) (end 72.09 83.3995) (width 0.5) (layer F.Cu) (net 2)) + (segment (start 72.09 83.3995) (end 72.7885 82.701) (width 0.5) (layer F.Cu) (net 2)) + (segment (start 72.7885 82.701) (end 72.7885 81.812) (width 0.5) (layer F.Cu) (net 2)) + (segment (start 72.7885 81.812) (end 73.4235 81.177) (width 0.5) (layer F.Cu) (net 2)) + (segment (start 73.4235 81.177) (end 77.17 81.177) (width 0.5) (layer F.Cu) (net 2)) + (segment (start 77.17 81.177) (end 77.3605 80.9865) (width 0.5) (layer F.Cu) (net 2)) + (segment (start 80.534 80.428) (end 81.334 80.428) (width 0.5) (layer F.Cu) (net 2)) + (segment (start 79.9755 80.9865) (end 80.534 80.428) (width 0.5) (layer F.Cu) (net 2)) + (segment (start 77.3605 80.9865) (end 79.9755 80.9865) (width 0.5) (layer F.Cu) (net 2)) + (segment (start 68.910001 83.603001) (end 69.663999 83.603001) (width 0.5) (layer F.Cu) (net 2)) + (segment (start 68.026 82.719) (end 68.910001 83.603001) (width 0.5) (layer F.Cu) (net 2)) + (segment (start 69.663999 83.603001) (end 69.944001 83.603001) (width 0.25) (layer F.Cu) (net 2)) + (segment (start 68.425 83.118) (end 68.026 82.719) (width 0.5) (layer F.Cu) (net 2)) + (segment (start 68.425 85.1775) (end 68.425 83.118) (width 0.5) (layer F.Cu) (net 2)) + (segment (start 122.89 56.696) (end 122.158 56.696) (width 0.5) (layer F.Cu) (net 2)) + (segment (start 122.158 56.696) (end 121.96925 56.50725) (width 0.5) (layer F.Cu) (net 2)) + (segment (start 118.5085 53.0465) (end 121.96925 56.50725) (width 0.5) (layer F.Cu) (net 2)) + (segment (start 121.96925 56.50725) (end 122.1684 56.7064) (width 0.5) (layer F.Cu) (net 2)) + (segment (start 118.0767 71.7663) (end 118.064 71.779) (width 0.5) (layer F.Cu) (net 3) (status 30)) + (segment (start 125.0655 71.7663) (end 118.0767 71.7663) (width 0.5) (layer F.Cu) (net 3) (status 30)) + (segment (start 125.5835 91.0195) (end 128.0335 91.0195) (width 1) (layer F.Cu) (net 3)) + (segment (start 125.069 90.505) (end 125.5835 91.0195) (width 1) (layer F.Cu) (net 3)) + (segment (start 125.069 78.493) (end 125.069 90.505) (width 1) (layer F.Cu) (net 3)) + (segment (start 131.78 80.161) (end 129.6845 80.161) (width 1) (layer F.Cu) (net 3)) + (segment (start 128.0165 78.493) (end 125.069 78.493) (width 1) (layer F.Cu) (net 3)) + (segment (start 129.6845 80.161) (end 128.0165 78.493) (width 1) (layer F.Cu) (net 3)) + (segment (start 132.9865 81.3675) (end 131.78 80.161) (width 1) (layer F.Cu) (net 3)) + (segment (start 133.939 81.3675) (end 132.9865 81.3675) (width 1) (layer F.Cu) (net 3)) + (segment (start 125.069 71.7698) (end 125.0655 71.7663) (width 1) (layer F.Cu) (net 3)) + (segment (start 125.069 78.493) (end 125.069 71.7698) (width 1) (layer F.Cu) (net 3)) + (segment (start 133.939 84.6695) (end 133.939 81.3675) (width 0.5) (layer F.Cu) (net 3)) + (via (at 125.049 68.5405) (size 1.5) (drill 0.6) (layers F.Cu B.Cu) (net 3)) + (segment (start 125.0655 71.7663) (end 125.0655 68.557) (width 1) (layer F.Cu) (net 3)) + (segment (start 125.0655 68.557) (end 125.049 68.5405) (width 1) (layer F.Cu) (net 3)) + (via (at 127.589 44.347) (size 1.5) (drill 0.6) (layers F.Cu B.Cu) (net 3)) + (segment (start 125.798999 46.137001) (end 127.589 44.347) (width 1) (layer B.Cu) (net 3)) + (segment (start 125.049 68.5405) (end 125.798999 67.790501) (width 1) (layer B.Cu) (net 3)) + (segment (start 125.798999 67.790501) (end 125.798999 46.137001) (width 1) (layer B.Cu) (net 3)) + (segment (start 127.589 44.982) (end 129.6845 47.0775) (width 1) (layer F.Cu) (net 3)) + (segment (start 127.589 44.347) (end 127.589 44.982) (width 1) (layer F.Cu) (net 3)) + (segment (start 98.0895 54.4715) (end 98.3155 54.6975) (width 0.5) (layer F.Cu) (net 4) (status 30)) + (segment (start 96.4105 54.4715) (end 98.0895 54.4715) (width 0.5) (layer F.Cu) (net 4) (status 30)) + (segment (start 98.3155 55.75816) (end 100.17584 57.6185) (width 0.5) (layer F.Cu) (net 4)) + (segment (start 98.3155 54.6975) (end 98.3155 55.75816) (width 0.5) (layer F.Cu) (net 4) (status 10)) + (segment (start 100.17584 57.6185) (end 103.6495 57.6185) (width 0.5) (layer F.Cu) (net 4)) + (segment (start 105.21161 59.6872) (end 104.602 59.07759) (width 0.25) (layer F.Cu) (net 4)) + (segment (start 106.2338 59.6872) (end 105.21161 59.6872) (width 0.25) (layer F.Cu) (net 4) (status 10)) + (segment (start 104.602 58.571) (end 103.6495 57.6185) (width 0.25) (layer F.Cu) (net 4)) + (segment (start 104.602 59.07759) (end 104.602 58.571) (width 0.25) (layer F.Cu) (net 4)) + (segment (start 98.207 59.686) (end 98.3155 59.5775) (width 0.5) (layer F.Cu) (net 5) (status 30)) + (segment (start 96.4105 59.686) (end 98.207 59.686) (width 0.5) (layer F.Cu) (net 5) (status 30)) + (segment (start 98.3155 59.5775) (end 99.5125 58.3805) (width 0.5) (layer F.Cu) (net 5) (status 10)) + (segment (start 99.5125 58.3805) (end 103.2685 58.3805) (width 0.5) (layer F.Cu) (net 5)) + (segment (start 104.88752 60.1872) (end 106.2338 60.1872) (width 0.25) (layer F.Cu) (net 5) (status 20)) + (segment (start 104.15199 58.81949) (end 104.15199 59.45167) (width 0.25) (layer F.Cu) (net 5)) + (segment (start 104.15199 59.45167) (end 104.88752 60.1872) (width 0.25) (layer F.Cu) (net 5)) + (segment (start 103.2685 58.3805) (end 103.713 58.3805) (width 0.25) (layer F.Cu) (net 5)) + (segment (start 103.713 58.3805) (end 104.15199 58.81949) (width 0.25) (layer F.Cu) (net 5)) + (segment (start 117.076 82.193) (end 117.048 82.165) (width 1) (layer F.Cu) (net 6)) + (segment (start 119.969 82.193) (end 117.076 82.193) (width 1) (layer F.Cu) (net 6)) + (segment (start 114.5895 84.6235) (end 117.048 82.165) (width 1) (layer F.Cu) (net 6)) + (segment (start 113.0475 84.6235) (end 114.5895 84.6235) (width 1) (layer F.Cu) (net 6)) + (segment (start 104.874 77.748) (end 104.8715 77.7505) (width 0.5) (layer F.Cu) (net 6)) + (segment (start 107.7135 77.748) (end 104.874 77.748) (width 0.5) (layer F.Cu) (net 6)) + (segment (start 112.2725 84.6235) (end 110.19 82.541) (width 0.5) (layer F.Cu) (net 6)) + (segment (start 113.0475 84.6235) (end 112.2725 84.6235) (width 0.5) (layer F.Cu) (net 6)) + (segment (start 110.19 82.541) (end 110.19 79.145) (width 0.5) (layer F.Cu) (net 6)) + (segment (start 108.793 77.748) (end 107.7135 77.748) (width 0.5) (layer F.Cu) (net 6)) + (segment (start 110.19 79.145) (end 108.793 77.748) (width 0.5) (layer F.Cu) (net 6)) + (segment (start 130.0655 64.8067) (end 130.8402 64.032) (width 0.5) (layer F.Cu) (net 7) (status 30)) + (segment (start 130.0655 71.7663) (end 130.0655 64.8067) (width 0.5) (layer F.Cu) (net 7) (status 30)) + (segment (start 126.385 59.7013) (end 126.3723 59.714) (width 0.25) (layer F.Cu) (net 7)) + (segment (start 127.415 59.7013) (end 126.385 59.7013) (width 0.25) (layer F.Cu) (net 7) (status 10)) + (segment (start 126.3723 59.714) (end 126.192 59.714) (width 0.25) (layer F.Cu) (net 7)) + (segment (start 126.192 59.714) (end 126.065 59.841) (width 0.25) (layer F.Cu) (net 7)) + (segment (start 126.065 61.873) (end 126.065 63.397) (width 0.5) (layer F.Cu) (net 7)) + (segment (start 126.065 59.841) (end 126.065 61.873) (width 0.25) (layer F.Cu) (net 7)) + (segment (start 126.7 64.032) (end 130.8402 64.032) (width 0.5) (layer F.Cu) (net 7)) + (segment (start 126.065 63.397) (end 126.7 64.032) (width 0.5) (layer F.Cu) (net 7)) + (segment (start 120.5835 91.0195) (end 118.1335 91.0195) (width 1) (layer F.Cu) (net 8)) + (segment (start 121.669 89.934) (end 120.5835 91.0195) (width 1) (layer F.Cu) (net 8)) + (segment (start 121.669 78.493) (end 121.669 89.934) (width 1) (layer F.Cu) (net 8)) + (segment (start 113.0475 91.0195) (end 118.1335 91.0195) (width 1) (layer F.Cu) (net 8)) + (segment (start 109.1463 56.2747) (end 109.1463 54.7252) (width 0.25) (layer F.Cu) (net 9)) + (via (at 109.809 52.856) (size 1.5) (drill 0.6) (layers F.Cu B.Cu) (net 9)) + (segment (start 109.1463 54.7252) (end 109.809 54.0625) (width 0.25) (layer F.Cu) (net 9)) + (segment (start 109.809 54.0625) (end 109.809 52.856) (width 0.25) (layer F.Cu) (net 9)) + (segment (start 109.809 52.856) (end 109.809 50.57) (width 0.5) (layer B.Cu) (net 9)) + (segment (start 109.809 50.57) (end 106.38 47.141) (width 0.5) (layer B.Cu) (net 9)) + (segment (start 106.38 47.141) (end 106.38 44.474) (width 0.5) (layer B.Cu) (net 9)) + (segment (start 106.38 44.474) (end 105.9355 44.0295) (width 0.5) (layer B.Cu) (net 9)) + (segment (start 99.271 45.8075) (end 97.871 45.8075) (width 0.5) (layer B.Cu) (net 9)) + (segment (start 101.049 44.0295) (end 99.271 45.8075) (width 0.5) (layer B.Cu) (net 9)) + (segment (start 105.9355 44.0295) (end 101.049 44.0295) (width 0.5) (layer B.Cu) (net 9)) + (segment (start 95.331 47.522) (end 95.2675 47.5855) (width 0.5) (layer B.Cu) (net 10)) + (segment (start 95.331 45.8075) (end 95.331 47.522) (width 0.5) (layer B.Cu) (net 10)) + (segment (start 101.935 47.6135) (end 101.935 45.8075) (width 0.5) (layer B.Cu) (net 11)) + (via (at 108.285 53.872) (size 1.5) (drill 0.6) (layers F.Cu B.Cu) (net 12)) + (segment (start 108.6463 56.2747) (end 108.6463 54.2333) (width 0.25) (layer F.Cu) (net 12)) + (segment (start 108.6463 54.2333) (end 108.285 53.872) (width 0.25) (layer F.Cu) (net 12)) + (segment (start 108.285 52.81134) (end 108.285 53.872) (width 0.5) (layer B.Cu) (net 12)) + (segment (start 108.285 51.0175) (end 108.285 52.81134) (width 0.5) (layer B.Cu) (net 12)) + (segment (start 104.475 47.2075) (end 108.285 51.0175) (width 0.5) (layer B.Cu) (net 12)) + (segment (start 104.475 45.8075) (end 104.475 47.2075) (width 0.5) (layer B.Cu) (net 12)) + (segment (start 105.58 90.161523) (end 105.5545 90.136023) (width 0.5) (layer F.Cu) (net 13)) + (segment (start 105.58 92) (end 105.58 90.161523) (width 0.5) (layer F.Cu) (net 13)) + (segment (start 105.5545 90.136023) (end 105.5545 83.9075) (width 0.5) (layer F.Cu) (net 13)) + (segment (start 101.8715 80.2245) (end 101.8715 78.7005) (width 0.5) (layer F.Cu) (net 13)) + (segment (start 105.5545 83.9075) (end 101.8715 80.2245) (width 0.5) (layer F.Cu) (net 13)) + (segment (start 133.939 91.939) (end 134 92) (width 0.5) (layer F.Cu) (net 14)) + (segment (start 133.939 86.4195) (end 133.939 91.939) (width 0.5) (layer F.Cu) (net 14)) + (segment (start 64.58 85.351) (end 64.216 84.987) (width 0.5) (layer F.Cu) (net 15)) + (segment (start 64.58 92) (end 64.58 85.351) (width 0.5) (layer F.Cu) (net 15)) + (segment (start 61.658 84.987) (end 61.295 84.624) (width 0.5) (layer F.Cu) (net 15)) + (segment (start 64.216 84.987) (end 61.658 84.987) (width 0.5) (layer F.Cu) (net 15)) + (segment (start 110.444 70.429) (end 111.333 69.54) (width 0.5) (layer F.Cu) (net 16)) + (segment (start 110.444 71.779) (end 110.444 70.429) (width 0.5) (layer F.Cu) (net 16) (status 10)) + (segment (start 111.333 69.54) (end 111.333 66.699) (width 0.5) (layer F.Cu) (net 16)) + (segment (start 111.6463 66.3857) (end 111.333 66.699) (width 0.25) (layer F.Cu) (net 16)) + (segment (start 111.6463 64.5997) (end 111.6463 66.3857) (width 0.25) (layer F.Cu) (net 16) (status 10)) + (segment (start 112.984 70.576919) (end 112.222 69.814919) (width 0.5) (layer F.Cu) (net 17)) + (segment (start 112.984 71.779) (end 112.984 70.576919) (width 0.5) (layer F.Cu) (net 17) (status 10)) + (segment (start 112.222 69.814919) (end 112.222 67.08) (width 0.5) (layer F.Cu) (net 17)) + (segment (start 112.1463 67.0043) (end 112.222 67.08) (width 0.25) (layer F.Cu) (net 17)) + (segment (start 112.1463 64.5997) (end 112.1463 67.0043) (width 0.25) (layer F.Cu) (net 17) (status 10)) + (segment (start 76 85.018) (end 75.619 84.637) (width 0.5) (layer F.Cu) (net 18)) + (segment (start 78.413 85.018) (end 76 85.018) (width 0.5) (layer F.Cu) (net 18)) + (segment (start 77.08 86.351) (end 78.413 85.018) (width 0.5) (layer F.Cu) (net 18)) + (segment (start 77.08 92) (end 77.08 86.351) (width 0.5) (layer F.Cu) (net 18)) + (segment (start 87.7745 84.0525) (end 88.2645 84.5425) (width 0.5) (layer F.Cu) (net 19)) + (segment (start 87.7745 81.6215) (end 87.7745 84.0525) (width 0.5) (layer F.Cu) (net 19)) + (segment (start 84.42 88.387) (end 84.42 92) (width 0.5) (layer F.Cu) (net 19)) + (segment (start 88.2645 84.5425) (end 84.42 88.387) (width 0.5) (layer F.Cu) (net 19)) + (segment (start 89.5 89.693) (end 90.378 88.815) (width 0.5) (layer F.Cu) (net 20)) + (segment (start 89.5 92) (end 89.5 89.693) (width 0.5) (layer F.Cu) (net 20)) + (segment (start 121.0612 64.201519) (end 120.828181 63.9685) (width 0.5) (layer F.Cu) (net 21)) + (segment (start 121.0612 65.4036) (end 121.0612 64.201519) (width 0.5) (layer F.Cu) (net 21) (status 10)) + (segment (start 120.828181 63.9685) (end 120.7945 63.9685) (width 0.5) (layer F.Cu) (net 21)) + (segment (start 120.7945 63.9685) (end 120.1595 63.3335) (width 0.5) (layer F.Cu) (net 21)) + (segment (start 120.1595 63.3335) (end 117.556 63.3335) (width 0.5) (layer F.Cu) (net 21)) + (segment (start 117.556 63.3335) (end 116.667 62.4445) (width 0.5) (layer F.Cu) (net 21)) + (segment (start 114.5588 60.6872) (end 115.5447 60.6872) (width 0.25) (layer F.Cu) (net 21) (status 10)) + (segment (start 116.028492 61.805992) (end 116.667 62.4445) (width 0.25) (layer F.Cu) (net 21)) + (segment (start 116.028492 61.170992) (end 116.028492 61.805992) (width 0.25) (layer F.Cu) (net 21)) + (segment (start 115.5447 60.6872) (end 116.028492 61.170992) (width 0.25) (layer F.Cu) (net 21)) + (segment (start 123.6012 64.201519) (end 121.907681 62.508) (width 0.5) (layer F.Cu) (net 22)) + (segment (start 123.6012 65.4036) (end 123.6012 64.201519) (width 0.5) (layer F.Cu) (net 22) (status 10)) + (segment (start 121.907681 62.508) (end 117.937 62.508) (width 0.5) (layer F.Cu) (net 22)) + (segment (start 117.937 62.508) (end 116.6035 61.1745) (width 0.5) (layer F.Cu) (net 22)) + (segment (start 115.3963 60.1872) (end 114.5588 60.1872) (width 0.25) (layer F.Cu) (net 22) (status 20)) + (segment (start 115.7432 60.1872) (end 115.3963 60.1872) (width 0.25) (layer F.Cu) (net 22)) + (segment (start 116.6035 61.0475) (end 115.7432 60.1872) (width 0.25) (layer F.Cu) (net 22)) + (segment (start 116.6035 61.1745) (end 116.6035 61.0475) (width 0.25) (layer F.Cu) (net 22)) + (segment (start 129.9595 60.6513) (end 130.8402 61.532) (width 0.5) (layer F.Cu) (net 23) (status 20)) + (segment (start 127.415 60.6513) (end 129.9595 60.6513) (width 0.5) (layer F.Cu) (net 23) (status 10)) + (via (at 127.7795 56.031) (size 1.5) (drill 0.6) (layers F.Cu B.Cu) (net 23)) + (segment (start 127.3985 53.872) (end 127.3985 55.65) (width 0.5) (layer F.Cu) (net 23)) + (segment (start 127.3985 55.65) (end 127.7795 56.031) (width 0.5) (layer F.Cu) (net 23)) + (via (at 127.7795 62.5715) (size 1.5) (drill 0.6) (layers F.Cu B.Cu) (net 23)) + (segment (start 127.7795 56.031) (end 127.7795 62.5715) (width 0.5) (layer B.Cu) (net 23)) + (segment (start 127.7795 61.0158) (end 127.415 60.6513) (width 0.5) (layer F.Cu) (net 23)) + (segment (start 127.7795 62.5715) (end 127.7795 61.0158) (width 0.5) (layer F.Cu) (net 23)) + (segment (start 127.415 58.7513) (end 131.7825 58.7513) (width 0.25) (layer F.Cu) (net 24) (status 10)) + (segment (start 132.8402 59.809) (end 132.8402 61.532) (width 0.25) (layer F.Cu) (net 24) (status 20)) + (segment (start 131.7825 58.7513) (end 132.8402 59.809) (width 0.25) (layer F.Cu) (net 24)) + (segment (start 112.6463 55.4372) (end 112.6665 55.417) (width 0.25) (layer F.Cu) (net 25)) + (segment (start 112.6463 56.2747) (end 112.6463 55.4372) (width 0.25) (layer F.Cu) (net 25) (status 10)) + (segment (start 112.6665 54.253) (end 112.349 53.9355) (width 0.25) (layer F.Cu) (net 25)) + (segment (start 112.6665 55.417) (end 112.6665 54.253) (width 0.25) (layer F.Cu) (net 25)) + (segment (start 112.349 53.11) (end 112.349 53.9355) (width 0.5) (layer F.Cu) (net 25)) + (segment (start 113.3015 52.1575) (end 112.349 53.11) (width 0.5) (layer F.Cu) (net 25)) + (segment (start 118.953 52.1575) (end 113.3015 52.1575) (width 0.5) (layer F.Cu) (net 25)) + (segment (start 122.89 55.396) (end 122.1915 55.396) (width 0.5) (layer F.Cu) (net 25)) + (segment (start 122.1915 55.396) (end 118.953 52.1575) (width 0.5) (layer F.Cu) (net 25)) + (segment (start 125.55 53.9705) (end 125.6485 53.872) (width 0.5) (layer F.Cu) (net 26)) + (segment (start 125.55 56.046) (end 125.55 53.9705) (width 0.5) (layer F.Cu) (net 26)) + (segment (start 115.3963 59.6872) (end 115.4231 59.714) (width 0.25) (layer F.Cu) (net 27)) + (segment (start 114.5588 59.6872) (end 115.3963 59.6872) (width 0.25) (layer F.Cu) (net 27) (status 10)) + (segment (start 115.4231 59.714) (end 116.2352 59.714) (width 0.25) (layer F.Cu) (net 27)) + (segment (start 117.6957 61.1745) (end 117.30835 60.78715) (width 0.5) (layer F.Cu) (net 27)) + (segment (start 120.632 61.1745) (end 117.6957 61.1745) (width 0.5) (layer F.Cu) (net 27) (status 10)) + (segment (start 116.2352 59.714) (end 117.30835 60.78715) (width 0.25) (layer F.Cu) (net 27)) + (segment (start 124.2172 58.2535) (end 124.715 58.7513) (width 0.5) (layer F.Cu) (net 28) (status 20)) + (segment (start 122.382 58.2535) (end 124.2172 58.2535) (width 0.5) (layer F.Cu) (net 28) (tstamp 5D165583) (status 10)) + (segment (start 124.1918 61.1745) (end 124.715 60.6513) (width 0.5) (layer F.Cu) (net 29) (status 20)) + (segment (start 122.382 61.1745) (end 124.1918 61.1745) (width 0.5) (layer F.Cu) (net 29) (status 10)) + (segment (start 114.5588 59.1872) (end 115.3963 59.1872) (width 0.25) (layer F.Cu) (net 30) (status 10)) + (segment (start 115.3963 59.1872) (end 115.4151 59.206) (width 0.25) (layer F.Cu) (net 30)) + (segment (start 116.159 59.206) (end 116.850598 59.206) (width 0.25) (layer F.Cu) (net 30)) + (segment (start 115.4151 59.206) (end 116.159 59.206) (width 0.25) (layer F.Cu) (net 30)) + (segment (start 119.883451 58.377049) (end 117.679549 58.377049) (width 0.5) (layer F.Cu) (net 30)) + (segment (start 120.632 58.2535) (end 120.007 58.2535) (width 0.5) (layer F.Cu) (net 30) (status 10)) + (segment (start 120.007 58.2535) (end 119.883451 58.377049) (width 0.5) (layer F.Cu) (net 30)) + (segment (start 116.850598 59.206) (end 117.679549 58.377049) (width 0.25) (layer F.Cu) (net 30)) + (segment (start 66.375 83.306) (end 66.375 85.1775) (width 0.5) (layer F.Cu) (net 31)) + (segment (start 64.216 82.447) (end 65.516 82.447) (width 0.5) (layer F.Cu) (net 31)) + (segment (start 65.516 82.447) (end 66.375 83.306) (width 0.5) (layer F.Cu) (net 31)) + (segment (start 61.422 82.447) (end 61.295 82.574) (width 0.5) (layer F.Cu) (net 31)) + (segment (start 64.216 82.447) (end 61.422 82.447) (width 0.5) (layer F.Cu) (net 31)) + (segment (start 114.5588 58.6872) (end 116.4873 58.6872) (width 0.25) (layer F.Cu) (net 32) (status 10)) + (via (at 118.953 56.9835) (size 1.5) (drill 0.6) (layers F.Cu B.Cu) (net 32)) + (segment (start 116.4873 58.6872) (end 118.191 56.9835) (width 0.25) (layer F.Cu) (net 32)) + (segment (start 118.191 56.9835) (end 118.953 56.9835) (width 0.25) (layer F.Cu) (net 32)) + (segment (start 118.953 56.9835) (end 111.587 56.9835) (width 0.5) (layer B.Cu) (net 32)) + (segment (start 111.587 56.9835) (end 108.2215 60.349) (width 0.5) (layer B.Cu) (net 32)) + (segment (start 108.2215 60.349) (end 108.2215 74.0015) (width 0.5) (layer B.Cu) (net 32)) + (via (at 108.420721 74.437279) (size 1.5) (drill 0.6) (layers F.Cu B.Cu) (net 32)) + (segment (start 108.2215 74.0015) (end 108.2215 74.238058) (width 0.5) (layer B.Cu) (net 32)) + (segment (start 108.2215 74.238058) (end 108.420721 74.437279) (width 0.5) (layer B.Cu) (net 32)) + (segment (start 106.325221 74.437279) (end 108.420721 74.437279) (width 0.5) (layer F.Cu) (net 32)) + (segment (start 106.0625 74.7) (end 106.325221 74.437279) (width 0.5) (layer F.Cu) (net 32)) + (segment (start 69.3595 79.3355) (end 78.694 79.3355) (width 0.5) (layer F.Cu) (net 32)) + (segment (start 91.394 77.8115) (end 94.5055 74.7) (width 0.5) (layer F.Cu) (net 32)) + (segment (start 68.026 80.669) (end 69.3595 79.3355) (width 0.5) (layer F.Cu) (net 32)) + (segment (start 94.5055 74.7) (end 106.0625 74.7) (width 0.5) (layer F.Cu) (net 32)) + (segment (start 78.694 79.3355) (end 80.218 77.8115) (width 0.5) (layer F.Cu) (net 32)) + (segment (start 80.218 77.8115) (end 91.394 77.8115) (width 0.5) (layer F.Cu) (net 32)) + (segment (start 58.374 80.669) (end 56.596 82.447) (width 0.5) (layer F.Cu) (net 32)) + (segment (start 68.026 80.669) (end 58.374 80.669) (width 0.5) (layer F.Cu) (net 32)) + (segment (start 109.9715 66.886) (end 109.9715 67.461) (width 0.25) (layer F.Cu) (net 33) (status 20)) + (segment (start 109.9715 66.612) (end 109.9715 66.886) (width 0.25) (layer F.Cu) (net 33)) + (segment (start 111.1463 65.4372) (end 109.9715 66.612) (width 0.25) (layer F.Cu) (net 33)) + (segment (start 111.1463 64.5997) (end 111.1463 65.4372) (width 0.25) (layer F.Cu) (net 33) (status 10)) + (segment (start 81.334 82.478) (end 78.413 82.478) (width 0.5) (layer F.Cu) (net 34)) + (segment (start 75.728 82.478) (end 75.619 82.587) (width 0.5) (layer F.Cu) (net 34)) + (segment (start 78.413 82.478) (end 75.728 82.478) (width 0.5) (layer F.Cu) (net 34)) + (via (at 113.746 53.5545) (size 1.5) (drill 0.6) (layers F.Cu B.Cu) (net 35)) + (segment (start 113.1463 56.2747) (end 113.1463 54.1542) (width 0.25) (layer F.Cu) (net 35) (status 10)) + (segment (start 113.1463 54.1542) (end 113.746 53.5545) (width 0.25) (layer F.Cu) (net 35)) + (segment (start 70.793 81.34663) (end 71.97863 80.161) (width 0.5) (layer F.Cu) (net 35)) + (segment (start 70.793 82.478) (end 70.793 81.34663) (width 0.5) (layer F.Cu) (net 35)) + (segment (start 71.97863 80.161) (end 79.075 80.161) (width 0.5) (layer F.Cu) (net 35) (tstamp 5D164F3B)) + (segment (start 79.075 80.161) (end 80.5355 78.7005) (width 0.5) (layer F.Cu) (net 35)) + (segment (start 80.5355 78.7005) (end 85.044 78.7005) (width 0.5) (layer F.Cu) (net 35) (tstamp 5D165441)) + (segment (start 85.5065 79.163) (end 85.5065 80.4785) (width 0.5) (layer F.Cu) (net 35)) + (segment (start 85.044 78.7005) (end 85.5065 79.163) (width 0.5) (layer F.Cu) (net 35)) + (segment (start 85.044 78.7005) (end 91.775 78.7005) (width 0.5) (layer F.Cu) (net 35)) + (segment (start 107.2055 60.095) (end 113.746 53.5545) (width 0.5) (layer B.Cu) (net 35)) + (segment (start 107.2055 70.509) (end 107.2055 75.6525) (width 0.5) (layer B.Cu) (net 35)) + (via (at 107.2055 75.6525) (size 1.5) (drill 0.6) (layers F.Cu B.Cu) (net 35)) + (segment (start 107.2055 70.509) (end 107.2055 60.095) (width 0.5) (layer B.Cu) (net 35)) + (segment (start 106.14484 75.6525) (end 106.11309 75.62075) (width 0.5) (layer F.Cu) (net 35)) + (segment (start 106.11309 75.62075) (end 94.85475 75.62075) (width 0.5) (layer F.Cu) (net 35)) + (segment (start 107.2055 75.6525) (end 106.14484 75.6525) (width 0.5) (layer F.Cu) (net 35)) + (segment (start 91.775 78.7005) (end 94.85475 75.62075) (width 0.5) (layer F.Cu) (net 35)) + (segment (start 90.3145 81.6215) (end 90.3145 84.5425) (width 0.5) (layer F.Cu) (net 36)) + (segment (start 90.3145 86.7015) (end 90.378 86.765) (width 0.5) (layer F.Cu) (net 36)) + (segment (start 90.3145 84.5425) (end 90.3145 86.7015) (width 0.5) (layer F.Cu) (net 36)) + (segment (start 106.2338 62.6872) (end 104.9943 62.6872) (width 0.25) (layer F.Cu) (net 37) (status 10)) + (segment (start 78.1225 56.3006) (end 78.1225 56.92) (width 0.5) (layer F.Cu) (net 37)) + (via (at 78.1225 56.92) (size 1.5) (drill 0.6) (layers F.Cu B.Cu) (net 37)) + (segment (start 73.8162 54.4943) (end 76.3162 54.4943) (width 0.5) (layer F.Cu) (net 37)) + (segment (start 76.3162 54.4943) (end 78.1225 56.3006) (width 0.5) (layer F.Cu) (net 37)) + (via (at 78.1225 65.2385) (size 1.5) (drill 0.6) (layers F.Cu B.Cu) (net 37)) + (segment (start 78.1225 56.92) (end 78.1225 65.2385) (width 0.5) (layer B.Cu) (net 37)) + (segment (start 99.089501 65.988499) (end 99.530928 65.547072) (width 0.5) (layer F.Cu) (net 37)) + (segment (start 99.530928 65.547072) (end 100.03 65.048) (width 0.5) (layer F.Cu) (net 37)) + (segment (start 78.872499 65.988499) (end 99.089501 65.988499) (width 0.5) (layer F.Cu) (net 37)) + (segment (start 78.1225 65.2385) (end 78.872499 65.988499) (width 0.5) (layer F.Cu) (net 37)) + (segment (start 102.6335 65.048) (end 103.9035 63.778) (width 0.5) (layer F.Cu) (net 37)) + (segment (start 100.03 65.048) (end 102.6335 65.048) (width 0.5) (layer F.Cu) (net 37)) + (segment (start 104.9943 62.6872) (end 103.9035 63.778) (width 0.25) (layer F.Cu) (net 37)) + (segment (start 108.1463 64.5997) (end 108.1463 65.7582) (width 0.25) (layer F.Cu) (net 38)) + (segment (start 108.1463 65.7582) (end 107.7135 66.191) (width 0.25) (layer F.Cu) (net 38)) + (segment (start 107.7135 66.191) (end 106.9515 66.191) (width 0.25) (layer F.Cu) (net 38)) + (segment (start 91.013 73.303) (end 90.3145 74.0015) (width 0.5) (layer F.Cu) (net 38)) + (segment (start 91.013 70.0645) (end 91.013 73.303) (width 0.5) (layer F.Cu) (net 38)) + (segment (start 91.013 70.0645) (end 102.3795 70.0645) (width 0.5) (layer F.Cu) (net 38)) + (segment (start 106.253 66.191) (end 106.9515 66.191) (width 0.5) (layer F.Cu) (net 38)) + (segment (start 102.3795 70.0645) (end 106.253 66.191) (width 0.5) (layer F.Cu) (net 38)) + (segment (start 97.327 62.798) (end 96.9545 62.798) (width 0.5) (layer F.Cu) (net 39)) + (segment (start 100.882072 59.242928) (end 97.327 62.798) (width 0.5) (layer F.Cu) (net 39)) + (segment (start 92.8545 62.798) (end 96.9545 62.798) (width 0.5) (layer F.Cu) (net 39) (status 10)) + (segment (start 100.891 59.234) (end 100.882072 59.242928) (width 0.5) (layer F.Cu) (net 39)) + (segment (start 92.501 62.4445) (end 92.8545 62.798) (width 0.5) (layer F.Cu) (net 39) (status 30)) + (segment (start 89.8065 62.4445) (end 92.501 62.4445) (width 0.5) (layer F.Cu) (net 39) (status 30)) + (segment (start 103.80591 59.742) (end 103.205 59.742) (width 0.25) (layer F.Cu) (net 39) (status 20)) + (segment (start 106.2338 60.6872) (end 104.75111 60.6872) (width 0.25) (layer F.Cu) (net 39) (status 10)) + (segment (start 104.75111 60.6872) (end 103.80591 59.742) (width 0.25) (layer F.Cu) (net 39)) + (segment (start 102.705928 59.242928) (end 103.205 59.742) (width 0.5) (layer F.Cu) (net 39) (status 20)) + (segment (start 100.882072 59.242928) (end 102.705928 59.242928) (width 0.5) (layer F.Cu) (net 39)) + (segment (start 107.876 50.4075) (end 107.904 50.3795) (width 0.5) (layer F.Cu) (net 40) (status 30)) + (segment (start 107.876 52.2845) (end 107.876 50.4075) (width 0.5) (layer F.Cu) (net 40) (status 30)) + (segment (start 109.6463 56.2747) (end 109.6463 55.1777) (width 0.25) (layer F.Cu) (net 40) (status 10)) + (segment (start 109.6463 55.1777) (end 110.571 54.253) (width 0.25) (layer F.Cu) (net 40)) + (segment (start 110.571 54.253) (end 110.571 54.126) (width 0.25) (layer F.Cu) (net 40)) + (segment (start 109.2375 50.3795) (end 110.2535 49.3635) (width 0.5) (layer F.Cu) (net 40) (status 20)) + (segment (start 107.904 50.3795) (end 109.2375 50.3795) (width 0.5) (layer F.Cu) (net 40) (status 10)) + (segment (start 111.1425 53.5545) (end 110.571 54.126) (width 0.5) (layer F.Cu) (net 40)) + (segment (start 111.1425 51.5525) (end 111.1425 53.5545) (width 0.5) (layer F.Cu) (net 40)) + (segment (start 110.2535 50.6635) (end 111.1425 51.5525) (width 0.5) (layer F.Cu) (net 40)) + (segment (start 110.2535 49.3635) (end 110.2535 50.6635) (width 0.5) (layer F.Cu) (net 40) (status 10)) + (segment (start 106.2338 63.1872) (end 105.5795 63.8415) (width 0.25) (layer F.Cu) (net 41) (status 10)) + (segment (start 105.5795 63.8415) (end 105.1735 63.8415) (width 0.25) (layer F.Cu) (net 41)) + (segment (start 105.1735 63.8415) (end 102.8875 66.1275) (width 0.25) (layer F.Cu) (net 41)) + (segment (start 101.8207 67.1943) (end 102.8875 66.1275) (width 0.5) (layer F.Cu) (net 41)) + (segment (start 73.8162 67.1943) (end 101.8207 67.1943) (width 0.5) (layer F.Cu) (net 41)) + (segment (start 107.3963 64.5997) (end 107.3925 64.6035) (width 0.25) (layer F.Cu) (net 42)) + (segment (start 107.6463 64.5997) (end 107.3963 64.5997) (width 0.25) (layer F.Cu) (net 42)) + (segment (start 107.3925 64.6035) (end 106.761 64.6035) (width 0.25) (layer F.Cu) (net 42)) + (segment (start 76.3162 64.6543) (end 77.3195 63.651) (width 0.5) (layer F.Cu) (net 42)) + (segment (start 73.8162 64.6543) (end 76.3162 64.6543) (width 0.5) (layer F.Cu) (net 42)) + (via (at 80.091 64.667) (size 1.5) (drill 0.6) (layers F.Cu B.Cu) (net 42)) + (segment (start 77.3195 63.651) (end 79.075 63.651) (width 0.5) (layer F.Cu) (net 42)) + (segment (start 79.075 63.651) (end 80.091 64.667) (width 0.5) (layer F.Cu) (net 42)) + (via (at 80.091 68.477) (size 1.5) (drill 0.6) (layers F.Cu B.Cu) (net 42)) + (segment (start 80.091 64.667) (end 80.091 68.477) (width 0.5) (layer B.Cu) (net 42)) + (segment (start 105.872 64.6035) (end 107.3925 64.6035) (width 0.5) (layer F.Cu) (net 42)) + (segment (start 101.9985 68.477) (end 105.872 64.6035) (width 0.5) (layer F.Cu) (net 42)) + (segment (start 80.091 68.477) (end 101.9985 68.477) (width 0.5) (layer F.Cu) (net 42)) + (segment (start 107.566 79.6505) (end 107.7135 79.798) (width 0.5) (layer F.Cu) (net 43)) + (segment (start 104.8715 79.6505) (end 107.566 79.6505) (width 0.5) (layer F.Cu) (net 43)) + (segment (start 107.7135 79.798) (end 107.7135 82.066) (width 0.5) (layer F.Cu) (net 43)) + + (zone (net 2) (net_name +3V3) (layer F.Cu) (tstamp 5D168E41) (hatch edge 0.508) + (connect_pads (clearance 0.508)) + (min_thickness 0.254) + (fill yes (arc_segments 32) (thermal_gap 0.508) (thermal_bridge_width 0.508)) + (polygon + (pts + (xy 106.8245 56.8565) (xy 114 56.8565) (xy 113.9365 63.9685) (xy 106.8245 64.032) + ) + ) + (filled_polygon + (pts + (xy 107.606049 57.473398) (xy 107.6063 57.474658) (xy 107.6063 57.473604) (xy 107.675138 57.530098) (xy 107.798419 57.595993) + (xy 107.842091 57.609241) (xy 107.876531 57.643681) (xy 107.924302 57.634179) (xy 107.932187 57.636571) (xy 108.0713 57.650272) + (xy 108.2213 57.650272) (xy 108.360413 57.636571) (xy 108.3963 57.625685) (xy 108.432187 57.636571) (xy 108.5713 57.650272) + (xy 108.7213 57.650272) (xy 108.860413 57.636571) (xy 108.8963 57.625685) (xy 108.932187 57.636571) (xy 109.0713 57.650272) + (xy 109.2213 57.650272) (xy 109.360413 57.636571) (xy 109.3963 57.625685) (xy 109.432187 57.636571) (xy 109.5713 57.650272) + (xy 109.7213 57.650272) (xy 109.860413 57.636571) (xy 109.8963 57.625685) (xy 109.932187 57.636571) (xy 110.0713 57.650272) + (xy 110.2213 57.650272) (xy 110.360413 57.636571) (xy 110.3963 57.625685) (xy 110.432187 57.636571) (xy 110.5713 57.650272) + (xy 110.7213 57.650272) (xy 110.860413 57.636571) (xy 110.8963 57.625685) (xy 110.932187 57.636571) (xy 111.0713 57.650272) + (xy 111.2213 57.650272) (xy 111.360413 57.636571) (xy 111.3963 57.625685) (xy 111.432187 57.636571) (xy 111.5713 57.650272) + (xy 111.7213 57.650272) (xy 111.860413 57.636571) (xy 111.8963 57.625685) (xy 111.932187 57.636571) (xy 112.0713 57.650272) + (xy 112.2213 57.650272) (xy 112.360413 57.636571) (xy 112.3963 57.625685) (xy 112.432187 57.636571) (xy 112.5713 57.650272) + (xy 112.7213 57.650272) (xy 112.860413 57.636571) (xy 112.8963 57.625685) (xy 112.932187 57.636571) (xy 113.0713 57.650272) + (xy 113.2213 57.650272) (xy 113.360413 57.636571) (xy 113.37134 57.633256) (xy 113.303402 57.716038) (xy 113.237507 57.839319) + (xy 113.224259 57.882991) (xy 113.189819 57.917431) (xy 113.199321 57.965202) (xy 113.196929 57.973087) (xy 113.183228 58.1122) + (xy 113.183228 58.2622) (xy 113.196929 58.401313) (xy 113.207815 58.4372) (xy 113.196929 58.473087) (xy 113.183228 58.6122) + (xy 113.183228 58.7622) (xy 113.196929 58.901313) (xy 113.207815 58.9372) (xy 113.196929 58.973087) (xy 113.183228 59.1122) + (xy 113.183228 59.2622) (xy 113.196929 59.401313) (xy 113.207815 59.4372) (xy 113.196929 59.473087) (xy 113.183228 59.6122) + (xy 113.183228 59.7622) (xy 113.196929 59.901313) (xy 113.207815 59.9372) (xy 113.196929 59.973087) (xy 113.183228 60.1122) + (xy 113.183228 60.2622) (xy 113.196929 60.401313) (xy 113.207815 60.4372) (xy 113.196929 60.473087) (xy 113.183228 60.6122) + (xy 113.183228 60.7622) (xy 113.196929 60.901313) (xy 113.207815 60.9372) (xy 113.196929 60.973087) (xy 113.183228 61.1122) + (xy 113.183228 61.2622) (xy 113.196929 61.401313) (xy 113.207815 61.4372) (xy 113.196929 61.473087) (xy 113.183228 61.6122) + (xy 113.183228 61.7622) (xy 113.196929 61.901313) (xy 113.207815 61.9372) (xy 113.196929 61.973087) (xy 113.183228 62.1122) + (xy 113.183228 62.2622) (xy 113.196929 62.401313) (xy 113.207815 62.4372) (xy 113.196929 62.473087) (xy 113.183228 62.6122) + (xy 113.183228 62.7622) (xy 113.196929 62.901313) (xy 113.207815 62.9372) (xy 113.196929 62.973087) (xy 113.183228 63.1122) + (xy 113.183228 63.2622) (xy 113.196929 63.401313) (xy 113.200244 63.41224) (xy 113.117462 63.344302) (xy 112.994181 63.278407) + (xy 112.950509 63.265159) (xy 112.916069 63.230719) (xy 112.868298 63.240221) (xy 112.860413 63.237829) (xy 112.752492 63.2272) + (xy 112.91255 63.2272) (xy 112.916069 63.230719) (xy 112.933758 63.2272) (xy 112.91255 63.2272) (xy 112.752492 63.2272) + (xy 112.7213 63.224128) (xy 112.5713 63.224128) (xy 112.432187 63.237829) (xy 112.3963 63.248715) (xy 112.360413 63.237829) + (xy 112.2213 63.224128) (xy 112.0713 63.224128) (xy 111.932187 63.237829) (xy 111.8963 63.248715) (xy 111.860413 63.237829) + (xy 111.7213 63.224128) (xy 111.5713 63.224128) (xy 111.432187 63.237829) (xy 111.3963 63.248715) (xy 111.360413 63.237829) + (xy 111.2213 63.224128) (xy 111.0713 63.224128) (xy 110.932187 63.237829) (xy 110.8963 63.248715) (xy 110.860413 63.237829) + (xy 110.7213 63.224128) (xy 110.5713 63.224128) (xy 110.432187 63.237829) (xy 110.3963 63.248715) (xy 110.360413 63.237829) + (xy 110.2213 63.224128) (xy 110.0713 63.224128) (xy 109.932187 63.237829) (xy 109.8963 63.248715) (xy 109.860413 63.237829) + (xy 109.7213 63.224128) (xy 109.5713 63.224128) (xy 109.432187 63.237829) (xy 109.3963 63.248715) (xy 109.360413 63.237829) + (xy 109.2213 63.224128) (xy 109.0713 63.224128) (xy 108.932187 63.237829) (xy 108.8963 63.248715) (xy 108.860413 63.237829) + (xy 108.7213 63.224128) (xy 108.5713 63.224128) (xy 108.432187 63.237829) (xy 108.3963 63.248715) (xy 108.360413 63.237829) + (xy 108.2213 63.224128) (xy 108.0713 63.224128) (xy 107.932187 63.237829) (xy 107.8963 63.248715) (xy 107.860413 63.237829) + (xy 107.7213 63.224128) (xy 107.609372 63.224128) (xy 107.609372 63.1122) (xy 107.595671 62.973087) (xy 107.584785 62.9372) + (xy 107.595671 62.901313) (xy 107.609372 62.7622) (xy 107.609372 62.6122) (xy 107.595671 62.473087) (xy 107.584785 62.4372) + (xy 107.595671 62.401313) (xy 107.609372 62.2622) (xy 107.609372 62.1122) (xy 107.595671 61.973087) (xy 107.593279 61.965202) + (xy 107.602781 61.917431) (xy 107.6063 61.92095) (xy 107.6063 61.899742) (xy 107.602781 61.917431) (xy 107.568341 61.882991) + (xy 107.555093 61.839319) (xy 107.489198 61.716038) (xy 107.465531 61.6872) (xy 107.489198 61.658362) (xy 107.555093 61.535081) + (xy 107.568341 61.491409) (xy 107.602781 61.456969) (xy 107.6063 61.474658) (xy 107.6063 61.45345) (xy 107.602781 61.456969) + (xy 107.593279 61.409198) (xy 107.595671 61.401313) (xy 107.609372 61.2622) (xy 107.609372 61.1122) (xy 107.595671 60.973087) + (xy 107.584785 60.9372) (xy 107.595671 60.901313) (xy 107.609372 60.7622) (xy 107.609372 60.6122) (xy 107.595671 60.473087) + (xy 107.584785 60.4372) (xy 107.595671 60.401313) (xy 107.609372 60.2622) (xy 107.609372 60.1122) (xy 107.595671 59.973087) + (xy 107.584785 59.9372) (xy 107.595671 59.901313) (xy 107.609372 59.7622) (xy 107.609372 59.6122) (xy 107.595671 59.473087) + (xy 107.584785 59.4372) (xy 107.595671 59.401313) (xy 107.609372 59.2622) (xy 107.609372 59.1122) (xy 107.595671 58.973087) + (xy 107.584785 58.9372) (xy 107.595671 58.901313) (xy 107.609372 58.7622) (xy 107.609372 58.6122) (xy 107.595671 58.473087) + (xy 107.584785 58.4372) (xy 107.595671 58.401313) (xy 107.609372 58.2622) (xy 107.609372 58.1122) (xy 107.595671 57.973087) + (xy 107.593279 57.965202) (xy 107.602781 57.917431) (xy 107.6063 57.92095) (xy 113.1863 57.92095) (xy 113.189819 57.917431) + (xy 113.1863 57.899742) (xy 113.1863 57.92095) (xy 107.6063 57.92095) (xy 107.6063 57.899742) (xy 107.602781 57.917431) + (xy 107.568341 57.882991) (xy 107.555093 57.839319) (xy 107.489198 57.716038) (xy 107.432704 57.6472) (xy 107.433758 57.6472) + (xy 107.858842 57.6472) (xy 107.88005 57.6472) (xy 107.876531 57.643681) (xy 107.858842 57.6472) (xy 107.433758 57.6472) + (xy 107.432498 57.646949) (xy 107.423619 57.636131) (xy 107.595231 57.464519) + ) + ) + (filled_polygon + (pts + (xy 107.6063 57.473604) (xy 107.606049 57.473398) (xy 107.602781 57.456969) (xy 107.6063 57.45345) + ) + ) + ) + (zone (net 1) (net_name GND) (layer F.Cu) (tstamp 5D168E3E) (hatch edge 0.508) + (connect_pads (clearance 0.508)) + (min_thickness 0.254) + (fill yes (arc_segments 32) (thermal_gap 0.508) (thermal_bridge_width 0.508)) + (polygon + (pts + (xy 48 43.5) (xy 142 43.5) (xy 142 97) (xy 48 97) + ) + ) + (filled_polygon + (pts + (xy 126.361629 43.690957) (xy 126.257225 43.943011) (xy 126.204 44.210589) (xy 126.204 44.483411) (xy 126.257225 44.750989) + (xy 126.361629 45.003043) (xy 126.46596 45.159185) (xy 126.470423 45.204499) (xy 126.535324 45.418447) (xy 126.640717 45.615623) + (xy 126.782552 45.788449) (xy 126.82586 45.823991) (xy 128.046428 47.04456) (xy 128.046428 47.8275) (xy 128.058688 47.951982) + (xy 128.094998 48.07168) (xy 128.153963 48.181994) (xy 128.191309 48.2275) (xy 128.153963 48.273006) (xy 128.094998 48.38332) + (xy 128.061879 48.4925) (xy 125.022572 48.4925) (xy 125.022572 47.4775) (xy 125.010312 47.353018) (xy 124.974002 47.23332) + (xy 124.915037 47.123006) (xy 124.835685 47.026315) (xy 124.738994 46.946963) (xy 124.62868 46.887998) (xy 124.508982 46.851688) + (xy 124.3845 46.839428) (xy 122.394095 46.839428) (xy 122.443775 46.719489) (xy 122.497 46.451911) (xy 122.497 46.179089) + (xy 122.443775 45.911511) (xy 122.339371 45.659457) (xy 122.187799 45.432614) (xy 121.994886 45.239701) (xy 121.768043 45.088129) + (xy 121.515989 44.983725) (xy 121.248411 44.9305) (xy 120.975589 44.9305) (xy 120.708011 44.983725) (xy 120.455957 45.088129) + (xy 120.229114 45.239701) (xy 120.038315 45.4305) (xy 108.074469 45.4305) (xy 108.031 45.426219) (xy 107.987531 45.4305) + (xy 107.987523 45.4305) (xy 107.85751 45.443305) (xy 107.690687 45.493911) (xy 107.540155 45.574371) (xy 107.536941 45.576089) + (xy 107.435953 45.658968) (xy 107.435951 45.65897) (xy 107.402183 45.686683) (xy 107.37447 45.720451) (xy 105.558956 47.535966) + (xy 105.525183 47.563683) (xy 105.414589 47.698442) (xy 105.332411 47.852188) (xy 105.281805 48.019011) (xy 105.269 48.149024) + (xy 105.269 48.149031) (xy 105.264719 48.1925) (xy 105.269 48.235969) (xy 105.269001 49.341816) (xy 105.230886 49.303701) + (xy 105.004043 49.152129) (xy 104.751989 49.047725) (xy 104.484411 48.9945) (xy 104.211589 48.9945) (xy 103.944011 49.047725) + (xy 103.691957 49.152129) (xy 103.465114 49.303701) (xy 103.272201 49.496614) (xy 103.120629 49.723457) (xy 103.016225 49.975511) + (xy 102.963 50.243089) (xy 102.963 50.515911) (xy 103.016225 50.783489) (xy 103.120629 51.035543) (xy 103.272201 51.262386) + (xy 103.465114 51.455299) (xy 103.691957 51.606871) (xy 103.944011 51.711275) (xy 104.211589 51.7645) (xy 104.484411 51.7645) + (xy 104.751989 51.711275) (xy 104.996281 51.610086) (xy 104.990403 51.624277) (xy 104.966 51.746958) (xy 104.966 51.99875) + (xy 105.12475 52.1575) (xy 105.999 52.1575) (xy 105.999 52.1375) (xy 106.253 52.1375) (xy 106.253 52.1575) + (xy 106.273 52.1575) (xy 106.273 52.4115) (xy 106.253 52.4115) (xy 106.253 54.027) (xy 106.273 54.027) + (xy 106.273 54.281) (xy 106.253 54.281) (xy 106.253 54.301) (xy 105.999 54.301) (xy 105.999 54.281) + (xy 105.17475 54.281) (xy 105.016 54.43975) (xy 105.016 54.741542) (xy 105.040403 54.864223) (xy 105.08827 54.979785) + (xy 105.157763 55.083789) (xy 105.180116 55.106142) (xy 105.160488 55.130058) (xy 105.079577 55.281433) (xy 105.029752 55.445684) + (xy 105.012928 55.6165) (xy 105.012928 56.1915) (xy 105.029752 56.362316) (xy 105.079577 56.526567) (xy 105.160488 56.677942) + (xy 105.269377 56.810623) (xy 105.402058 56.919512) (xy 105.40499 56.921079) (xy 105.298419 56.953407) (xy 105.175138 57.019302) + (xy 105.067082 57.107982) (xy 104.978402 57.216038) (xy 104.912507 57.339319) (xy 104.871929 57.473087) (xy 104.858228 57.6122) + (xy 104.858228 57.752426) (xy 104.509016 57.403215) (xy 104.471089 57.278187) (xy 104.388911 57.124441) (xy 104.278317 56.989683) + (xy 104.143559 56.879089) (xy 103.989813 56.796911) (xy 103.82299 56.746305) (xy 103.692977 56.7335) (xy 100.542419 56.7335) + (xy 99.390302 55.581383) (xy 99.391299 55.580386) (xy 99.542871 55.353543) (xy 99.647275 55.101489) (xy 99.7005 54.833911) + (xy 99.7005 54.561089) (xy 99.647275 54.293511) (xy 99.542871 54.041457) (xy 99.391299 53.814614) (xy 99.198386 53.621701) + (xy 98.971543 53.470129) (xy 98.719489 53.365725) (xy 98.451911 53.3125) (xy 98.179089 53.3125) (xy 97.911511 53.365725) + (xy 97.659457 53.470129) (xy 97.485296 53.5865) (xy 97.284869 53.5865) (xy 97.267123 53.564877) (xy 97.134442 53.455988) + (xy 96.983067 53.375077) (xy 96.818816 53.325252) (xy 96.648 53.308428) (xy 96.173 53.308428) (xy 96.002184 53.325252) + (xy 95.837933 53.375077) (xy 95.686558 53.455988) (xy 95.553877 53.564877) (xy 95.444988 53.697558) (xy 95.364077 53.848933) + (xy 95.314252 54.013184) (xy 95.297428 54.184) (xy 95.297428 54.759) (xy 95.314252 54.929816) (xy 95.364077 55.094067) + (xy 95.444988 55.245442) (xy 95.464616 55.269358) (xy 95.442263 55.291711) (xy 95.37277 55.395715) (xy 95.324903 55.511277) + (xy 95.3005 55.633958) (xy 95.3005 55.93575) (xy 95.45925 56.0945) (xy 96.2835 56.0945) (xy 96.2835 56.0745) + (xy 96.5375 56.0745) (xy 96.5375 56.0945) (xy 97.36175 56.0945) (xy 97.462226 55.994024) (xy 97.493912 56.098473) + (xy 97.57609 56.252219) (xy 97.658968 56.353206) (xy 97.658971 56.353209) (xy 97.686684 56.386977) (xy 97.720451 56.414689) + (xy 98.97912 57.673359) (xy 98.917453 57.723968) (xy 98.917451 57.72397) (xy 98.883683 57.751683) (xy 98.85597 57.785451) + (xy 98.448921 58.1925) (xy 98.179089 58.1925) (xy 97.911511 58.245725) (xy 97.659457 58.350129) (xy 97.5205 58.442977) + (xy 97.5205 58.22175) (xy 97.36175 58.063) (xy 96.5375 58.063) (xy 96.5375 58.083) (xy 96.2835 58.083) + (xy 96.2835 58.063) (xy 95.45925 58.063) (xy 95.3005 58.22175) (xy 95.3005 58.523542) (xy 95.324903 58.646223) + (xy 95.37277 58.761785) (xy 95.442263 58.865789) (xy 95.464616 58.888142) (xy 95.444988 58.912058) (xy 95.364077 59.063433) + (xy 95.314252 59.227684) (xy 95.297428 59.3985) (xy 95.297428 59.9735) (xy 95.314252 60.144316) (xy 95.364077 60.308567) + (xy 95.444988 60.459942) (xy 95.553877 60.592623) (xy 95.686558 60.701512) (xy 95.837933 60.782423) (xy 96.002184 60.832248) + (xy 96.173 60.849072) (xy 96.648 60.849072) (xy 96.818816 60.832248) (xy 96.983067 60.782423) (xy 97.134442 60.701512) + (xy 97.267123 60.592623) (xy 97.284869 60.571) (xy 97.350315 60.571) (xy 97.432614 60.653299) (xy 97.659457 60.804871) + (xy 97.911511 60.909275) (xy 97.955414 60.918008) (xy 96.960422 61.913) (xy 94.292572 61.913) (xy 94.292572 61.708) + (xy 94.280312 61.583518) (xy 94.244002 61.46382) (xy 94.185037 61.353506) (xy 94.105685 61.256815) (xy 94.008994 61.177463) + (xy 93.89868 61.118498) (xy 93.778982 61.082188) (xy 93.6545 61.069928) (xy 92.0545 61.069928) (xy 91.930018 61.082188) + (xy 91.81032 61.118498) (xy 91.700006 61.177463) (xy 91.603315 61.256815) (xy 91.523963 61.353506) (xy 91.464998 61.46382) + (xy 91.435974 61.5595) (xy 90.818027 61.5595) (xy 90.84423 61.520285) (xy 90.892097 61.404723) (xy 90.9165 61.282042) + (xy 90.9165 60.98025) (xy 90.75775 60.8215) (xy 89.9335 60.8215) (xy 89.9335 60.8415) (xy 89.6795 60.8415) + (xy 89.6795 60.8215) (xy 88.85525 60.8215) (xy 88.6965 60.98025) (xy 88.6965 61.282042) (xy 88.720903 61.404723) + (xy 88.76877 61.520285) (xy 88.838263 61.624289) (xy 88.860616 61.646642) (xy 88.840988 61.670558) (xy 88.760077 61.821933) + (xy 88.710252 61.986184) (xy 88.693428 62.157) (xy 88.693428 62.732) (xy 88.710252 62.902816) (xy 88.760077 63.067067) + (xy 88.840988 63.218442) (xy 88.949877 63.351123) (xy 89.082558 63.460012) (xy 89.233933 63.540923) (xy 89.398184 63.590748) + (xy 89.569 63.607572) (xy 90.044 63.607572) (xy 90.214816 63.590748) (xy 90.379067 63.540923) (xy 90.530442 63.460012) + (xy 90.663123 63.351123) (xy 90.680869 63.3295) (xy 91.416428 63.3295) (xy 91.416428 63.888) (xy 91.428688 64.012482) + (xy 91.464998 64.13218) (xy 91.523963 64.242494) (xy 91.603315 64.339185) (xy 91.700006 64.418537) (xy 91.81032 64.477502) + (xy 91.930018 64.513812) (xy 92.0545 64.526072) (xy 93.6545 64.526072) (xy 93.778982 64.513812) (xy 93.89868 64.477502) + (xy 94.008994 64.418537) (xy 94.105685 64.339185) (xy 94.185037 64.242494) (xy 94.244002 64.13218) (xy 94.280312 64.012482) + (xy 94.292572 63.888) (xy 94.292572 63.683) (xy 97.283531 63.683) (xy 97.327 63.687281) (xy 97.370469 63.683) + (xy 97.370477 63.683) (xy 97.50049 63.670195) (xy 97.667313 63.619589) (xy 97.821059 63.537411) (xy 97.955817 63.426817) + (xy 97.983534 63.393044) (xy 98.66612 62.710458) (xy 98.92 62.710458) (xy 98.92 63.01225) (xy 99.07875 63.171) + (xy 99.903 63.171) (xy 99.903 62.29675) (xy 99.74425 62.138) (xy 99.492458 62.138) (xy 99.369777 62.162403) + (xy 99.254215 62.21027) (xy 99.150211 62.279763) (xy 99.061763 62.368211) (xy 98.99227 62.472215) (xy 98.944403 62.587777) + (xy 98.92 62.710458) (xy 98.66612 62.710458) (xy 100.5075 60.869079) (xy 100.5075 61.155042) (xy 100.531903 61.277723) + (xy 100.57977 61.393285) (xy 100.649263 61.497289) (xy 100.671616 61.519642) (xy 100.651988 61.543558) (xy 100.571077 61.694933) + (xy 100.521252 61.859184) (xy 100.504428 62.03) (xy 100.504428 62.138) (xy 100.31575 62.138) (xy 100.157 62.29675) + (xy 100.157 63.171) (xy 100.177 63.171) (xy 100.177 63.425) (xy 100.157 63.425) (xy 100.157 63.445) + (xy 99.903 63.445) (xy 99.903 63.425) (xy 99.07875 63.425) (xy 98.92 63.58375) (xy 98.92 63.885542) + (xy 98.944403 64.008223) (xy 98.99227 64.123785) (xy 99.061763 64.227789) (xy 99.084116 64.250142) (xy 99.064488 64.274058) + (xy 98.983577 64.425433) (xy 98.933752 64.589684) (xy 98.916928 64.7605) (xy 98.916928 64.909494) (xy 98.722923 65.103499) + (xy 81.409309 65.103499) (xy 81.422775 65.070989) (xy 81.476 64.803411) (xy 81.476 64.530589) (xy 81.422775 64.263011) + (xy 81.318371 64.010957) (xy 81.277004 63.949046) (xy 81.3864 63.83965) (xy 81.3864 62.7779) (xy 81.6404 62.7779) + (xy 81.6404 63.83965) (xy 81.79915 63.9984) (xy 82.450942 63.9984) (xy 82.573623 63.973997) (xy 82.689185 63.92613) + (xy 82.793189 63.856637) (xy 82.881637 63.768189) (xy 82.95113 63.664185) (xy 82.998997 63.548623) (xy 83.0234 63.425942) + (xy 83.0234 62.93665) (xy 82.86465 62.7779) (xy 81.6404 62.7779) (xy 81.3864 62.7779) (xy 80.16215 62.7779) + (xy 80.0034 62.93665) (xy 80.0034 63.282) (xy 79.957578 63.282) (xy 79.731534 63.055956) (xy 79.703817 63.022183) + (xy 79.569059 62.911589) (xy 79.415313 62.829411) (xy 79.24849 62.778805) (xy 79.118477 62.766) (xy 79.118469 62.766) + (xy 79.078081 62.762022) (xy 79.14753 62.658085) (xy 79.195397 62.542523) (xy 79.2198 62.419842) (xy 79.2198 62.11805) + (xy 79.06105 61.9593) (xy 78.2368 61.9593) (xy 78.2368 61.9793) (xy 77.9828 61.9793) (xy 77.9828 61.9593) + (xy 77.15855 61.9593) (xy 76.9998 62.11805) (xy 76.9998 62.419842) (xy 77.024203 62.542523) (xy 77.07207 62.658085) + (xy 77.141563 62.762089) (xy 77.157179 62.777705) (xy 77.14601 62.778805) (xy 76.979187 62.829411) (xy 76.825441 62.911589) + (xy 76.815156 62.92003) (xy 76.724453 62.994468) (xy 76.724451 62.99447) (xy 76.690683 63.022183) (xy 76.66297 63.055951) + (xy 76.428634 63.290287) (xy 76.4512 63.176842) (xy 76.4512 62.40005) (xy 76.29245 62.2413) (xy 73.9432 62.2413) + (xy 73.9432 62.2613) (xy 73.6892 62.2613) (xy 73.6892 62.2413) (xy 71.33995 62.2413) (xy 71.1812 62.40005) + (xy 71.1812 63.176842) (xy 71.205603 63.299523) (xy 71.240623 63.384069) (xy 71.226698 63.41012) (xy 71.190388 63.529818) + (xy 71.178128 63.6543) (xy 71.178128 65.6543) (xy 71.190388 65.778782) (xy 71.226698 65.89848) (xy 71.240499 65.9243) + (xy 71.226698 65.95012) (xy 71.190388 66.069818) (xy 71.178128 66.1943) (xy 71.178128 68.1943) (xy 71.190388 68.318782) + (xy 71.226698 68.43848) (xy 71.285663 68.548794) (xy 71.365015 68.645485) (xy 71.461706 68.724837) (xy 71.57202 68.783802) + (xy 71.691718 68.820112) (xy 71.8162 68.832372) (xy 75.8162 68.832372) (xy 75.940682 68.820112) (xy 76.06038 68.783802) + (xy 76.170694 68.724837) (xy 76.267385 68.645485) (xy 76.346737 68.548794) (xy 76.405702 68.43848) (xy 76.442012 68.318782) + (xy 76.454272 68.1943) (xy 76.454272 68.0793) (xy 78.757974 68.0793) (xy 78.706 68.340589) (xy 78.706 68.613411) + (xy 78.759225 68.880989) (xy 78.863629 69.133043) (xy 79.015201 69.359886) (xy 79.208114 69.552799) (xy 79.434957 69.704371) + (xy 79.687011 69.808775) (xy 79.954589 69.862) (xy 80.227411 69.862) (xy 80.494989 69.808775) (xy 80.747043 69.704371) + (xy 80.973886 69.552799) (xy 81.164685 69.362) (xy 85.90507 69.362) (xy 85.807725 69.597011) (xy 85.7545 69.864589) + (xy 85.7545 70.137411) (xy 85.807725 70.404989) (xy 85.912129 70.657043) (xy 86.063701 70.883886) (xy 86.256614 71.076799) + (xy 86.483457 71.228371) (xy 86.735511 71.332775) (xy 87.003089 71.386) (xy 87.275911 71.386) (xy 87.543489 71.332775) + (xy 87.795543 71.228371) (xy 87.979608 71.105383) (xy 88.010038 71.142462) (xy 88.144613 71.252905) (xy 88.298149 71.334972) + (xy 88.464745 71.385508) (xy 88.637999 71.402572) (xy 89.288001 71.402572) (xy 89.461255 71.385508) (xy 89.627851 71.334972) + (xy 89.781387 71.252905) (xy 89.915962 71.142462) (xy 89.988 71.054684) (xy 90.060038 71.142462) (xy 90.128 71.198237) + (xy 90.128001 72.577926) (xy 90.033191 72.587264) (xy 89.762692 72.669318) (xy 89.513399 72.802568) (xy 89.294892 72.981892) + (xy 89.115568 73.200399) (xy 89.041921 73.338182) (xy 88.926885 73.146369) (xy 88.737914 72.937981) (xy 88.51192 72.770463) + (xy 88.257587 72.650254) (xy 88.123539 72.609596) (xy 87.9015 72.731585) (xy 87.9015 73.8745) (xy 87.9215 73.8745) + (xy 87.9215 74.1285) (xy 87.9015 74.1285) (xy 87.9015 75.271415) (xy 88.123539 75.393404) (xy 88.257587 75.352746) + (xy 88.51192 75.232537) (xy 88.737914 75.065019) (xy 88.926885 74.856631) (xy 89.041921 74.664818) (xy 89.115568 74.802601) + (xy 89.294892 75.021108) (xy 89.513399 75.200432) (xy 89.762692 75.333682) (xy 90.033191 75.415736) (xy 90.244008 75.4365) + (xy 90.384992 75.4365) (xy 90.595809 75.415736) (xy 90.866308 75.333682) (xy 91.115601 75.200432) (xy 91.334108 75.021108) + (xy 91.513432 74.802601) (xy 91.646682 74.553308) (xy 91.728736 74.282809) (xy 91.756443 74.0015) (xy 91.738033 73.814579) + (xy 91.75241 73.79706) (xy 91.760868 73.781236) (xy 91.834589 73.643313) (xy 91.885195 73.47649) (xy 91.898 73.346477) + (xy 91.898 73.346467) (xy 91.902281 73.303001) (xy 91.898 73.259535) (xy 91.898 71.198237) (xy 91.965962 71.142462) + (xy 92.076405 71.007887) (xy 92.107614 70.9495) (xy 102.336031 70.9495) (xy 102.3795 70.953781) (xy 102.422969 70.9495) + (xy 102.422977 70.9495) (xy 102.55299 70.936695) (xy 102.719813 70.886089) (xy 102.873559 70.803911) (xy 103.008317 70.693317) + (xy 103.036034 70.659544) (xy 105.948828 67.74675) (xy 107.0615 67.74675) (xy 107.0615 67.998542) (xy 107.085903 68.121223) + (xy 107.13377 68.236785) (xy 107.203263 68.340789) (xy 107.291711 68.429237) (xy 107.395715 68.49873) (xy 107.511277 68.546597) + (xy 107.633958 68.571) (xy 107.93575 68.571) (xy 108.0945 68.41225) (xy 108.0945 67.588) (xy 107.22025 67.588) + (xy 107.0615 67.74675) (xy 105.948828 67.74675) (xy 106.619579 67.076) (xy 106.994977 67.076) (xy 107.0615 67.069448) + (xy 107.0615 67.17525) (xy 107.22025 67.334) (xy 108.0945 67.334) (xy 108.0945 67.314) (xy 108.3485 67.314) + (xy 108.3485 67.334) (xy 108.3685 67.334) (xy 108.3685 67.588) (xy 108.3485 67.588) (xy 108.3485 68.41225) + (xy 108.50725 68.571) (xy 108.809042 68.571) (xy 108.931723 68.546597) (xy 109.047285 68.49873) (xy 109.151289 68.429237) + (xy 109.173642 68.406884) (xy 109.197558 68.426512) (xy 109.348933 68.507423) (xy 109.513184 68.557248) (xy 109.684 68.574072) + (xy 110.259 68.574072) (xy 110.429816 68.557248) (xy 110.448 68.551732) (xy 110.448 69.173421) (xy 109.848951 69.772471) + (xy 109.815184 69.800183) (xy 109.787471 69.833951) (xy 109.787468 69.833954) (xy 109.70459 69.934941) (xy 109.622412 70.088687) + (xy 109.571805 70.25551) (xy 109.568065 70.293482) (xy 109.469518 70.303188) (xy 109.34982 70.339498) (xy 109.239506 70.398463) + (xy 109.142815 70.477815) (xy 109.063463 70.574506) (xy 109.004498 70.68482) (xy 108.968188 70.804518) (xy 108.955928 70.929) + (xy 108.955928 72.629) (xy 108.968188 72.753482) (xy 109.004498 72.87318) (xy 109.063463 72.983494) (xy 109.142815 73.080185) + (xy 109.239506 73.159537) (xy 109.34982 73.218502) (xy 109.469518 73.254812) (xy 109.594 73.267072) (xy 111.294 73.267072) + (xy 111.418482 73.254812) (xy 111.53818 73.218502) (xy 111.648494 73.159537) (xy 111.745185 73.080185) (xy 111.824537 72.983494) + (xy 111.883502 72.87318) (xy 111.904393 72.804313) (xy 111.928866 72.834134) (xy 112.154986 73.019706) (xy 112.412966 73.157599) + (xy 112.692889 73.242513) (xy 112.91105 73.264) (xy 113.05695 73.264) (xy 113.275111 73.242513) (xy 113.555034 73.157599) + (xy 113.813014 73.019706) (xy 114.039134 72.834134) (xy 114.224706 72.608014) (xy 114.259201 72.543477) (xy 114.328822 72.660355) + (xy 114.523731 72.876588) (xy 114.75708 73.050641) (xy 115.019901 73.175825) (xy 115.16711 73.220476) (xy 115.397 73.099155) + (xy 115.397 71.906) (xy 115.377 71.906) (xy 115.377 71.652) (xy 115.397 71.652) (xy 115.397 70.458845) + (xy 115.651 70.458845) (xy 115.651 71.652) (xy 115.671 71.652) (xy 115.671 71.906) (xy 115.651 71.906) + (xy 115.651 73.099155) (xy 115.88089 73.220476) (xy 116.028099 73.175825) (xy 116.29092 73.050641) (xy 116.524269 72.876588) + (xy 116.719178 72.660355) (xy 116.788799 72.543477) (xy 116.823294 72.608014) (xy 117.008866 72.834134) (xy 117.234986 73.019706) + (xy 117.492966 73.157599) (xy 117.772889 73.242513) (xy 117.99105 73.264) (xy 118.13695 73.264) (xy 118.355111 73.242513) + (xy 118.635034 73.157599) (xy 118.893014 73.019706) (xy 119.119134 72.834134) (xy 119.269182 72.6513) (xy 122.677428 72.6513) + (xy 122.677428 72.6663) (xy 122.689688 72.790782) (xy 122.725998 72.91048) (xy 122.784963 73.020794) (xy 122.864315 73.117485) + (xy 122.961006 73.196837) (xy 123.07132 73.255802) (xy 123.191018 73.292112) (xy 123.3155 73.304372) (xy 123.934001 73.304372) + (xy 123.934 77.456366) (xy 123.786519 77.636073) (xy 123.643983 77.902739) (xy 123.55621 78.192087) (xy 123.526573 78.493) + (xy 123.55621 78.793913) (xy 123.643983 79.083261) (xy 123.786519 79.349927) (xy 123.934 79.529634) (xy 123.934 80.772367) + (xy 123.733741 80.701959) (xy 123.496 80.822008) (xy 123.496 82.066) (xy 123.516 82.066) (xy 123.516 82.32) + (xy 123.496 82.32) (xy 123.496 83.563992) (xy 123.733741 83.684041) (xy 123.934 83.613633) (xy 123.934001 90.449239) + (xy 123.928509 90.505) (xy 123.950423 90.727498) (xy 124.015324 90.941446) (xy 124.057045 91.0195) (xy 124.120717 91.138623) + (xy 124.262552 91.311449) (xy 124.30586 91.346991) (xy 124.741504 91.782635) (xy 124.777051 91.825949) (xy 124.949877 91.967784) + (xy 125.147053 92.073176) (xy 125.361001 92.138077) (xy 125.5835 92.159991) (xy 125.639252 92.1545) (xy 125.945428 92.1545) + (xy 125.945428 93.7195) (xy 125.957688 93.843982) (xy 125.993998 93.96368) (xy 126.052963 94.073994) (xy 126.132315 94.170685) + (xy 126.229006 94.250037) (xy 126.33932 94.309002) (xy 126.459018 94.345312) (xy 126.5835 94.357572) (xy 129.4835 94.357572) + (xy 129.607982 94.345312) (xy 129.72768 94.309002) (xy 129.837994 94.250037) (xy 129.934685 94.170685) (xy 130.014037 94.073994) + (xy 130.073002 93.96368) (xy 130.109312 93.843982) (xy 130.121572 93.7195) (xy 130.121572 88.3195) (xy 130.109312 88.195018) + (xy 130.073002 88.07532) (xy 130.014037 87.965006) (xy 129.934685 87.868315) (xy 129.837994 87.788963) (xy 129.72768 87.729998) + (xy 129.607982 87.693688) (xy 129.4835 87.681428) (xy 126.5835 87.681428) (xy 126.459018 87.693688) (xy 126.33932 87.729998) + (xy 126.229006 87.788963) (xy 126.204 87.809485) (xy 126.204 83.613633) (xy 126.404259 83.684041) (xy 126.642 83.563992) + (xy 126.642 82.32) (xy 126.896 82.32) (xy 126.896 83.563992) (xy 127.133741 83.684041) (xy 127.41762 83.584234) + (xy 127.676573 83.430962) (xy 127.900649 83.230116) (xy 128.081236 82.989414) (xy 128.211394 82.718107) (xy 128.260036 82.55774) + (xy 128.139378 82.32) (xy 126.896 82.32) (xy 126.642 82.32) (xy 126.622 82.32) (xy 126.622 82.066) + (xy 126.642 82.066) (xy 126.642 80.822008) (xy 126.896 80.822008) (xy 126.896 82.066) (xy 128.139378 82.066) + (xy 128.260036 81.82826) (xy 128.211394 81.667893) (xy 128.081236 81.396586) (xy 127.900649 81.155884) (xy 127.676573 80.955038) + (xy 127.41762 80.801766) (xy 127.133741 80.701959) (xy 126.896 80.822008) (xy 126.642 80.822008) (xy 126.404259 80.701959) + (xy 126.204 80.772367) (xy 126.204 79.628) (xy 127.546369 79.628) (xy 128.842509 80.92414) (xy 128.878051 80.967449) + (xy 129.050877 81.109284) (xy 129.248053 81.214676) (xy 129.38897 81.257423) (xy 129.462 81.279577) (xy 129.478348 81.281187) + (xy 129.628748 81.296) (xy 129.628755 81.296) (xy 129.684499 81.30149) (xy 129.740243 81.296) (xy 131.309868 81.296) + (xy 132.144513 82.130646) (xy 132.180051 82.173949) (xy 132.223354 82.209487) (xy 132.223356 82.209489) (xy 132.352877 82.315784) + (xy 132.550053 82.421176) (xy 132.555449 82.422813) (xy 132.608463 82.521994) (xy 132.687815 82.618685) (xy 132.784506 82.698037) + (xy 132.89482 82.757002) (xy 133.014518 82.793312) (xy 133.054001 82.797201) (xy 133.054 83.797454) (xy 132.973488 83.895558) + (xy 132.892577 84.046933) (xy 132.842752 84.211184) (xy 132.825928 84.382) (xy 132.825928 84.957) (xy 132.842752 85.127816) + (xy 132.892577 85.292067) (xy 132.973488 85.443442) (xy 133.056425 85.5445) (xy 132.973488 85.645558) (xy 132.892577 85.796933) + (xy 132.842752 85.961184) (xy 132.825928 86.132) (xy 132.825928 86.707) (xy 132.842752 86.877816) (xy 132.892577 87.042067) + (xy 132.973488 87.193442) (xy 133.054 87.291546) (xy 133.054001 90.061928) (xy 132.7 90.061928) (xy 132.575518 90.074188) + (xy 132.45582 90.110498) (xy 132.345506 90.169463) (xy 132.248815 90.248815) (xy 132.169463 90.345506) (xy 132.110498 90.45582) + (xy 132.074188 90.575518) (xy 132.061928 90.7) (xy 132.061928 93.3) (xy 132.074188 93.424482) (xy 132.110498 93.54418) + (xy 132.169463 93.654494) (xy 132.248815 93.751185) (xy 132.345506 93.830537) (xy 132.45582 93.889502) (xy 132.575518 93.925812) + (xy 132.7 93.938072) (xy 135.3 93.938072) (xy 135.424482 93.925812) (xy 135.54418 93.889502) (xy 135.654494 93.830537) + (xy 135.751185 93.751185) (xy 135.830537 93.654494) (xy 135.889502 93.54418) (xy 135.925812 93.424482) (xy 135.933224 93.349224) + (xy 137.910381 93.349224) (xy 138.042317 93.644312) (xy 138.383045 93.815159) (xy 138.750557 93.91625) (xy 139.130729 93.943701) + (xy 139.508951 93.896457) (xy 139.87069 93.776333) (xy 140.117683 93.644312) (xy 140.249619 93.349224) (xy 139.08 92.179605) + (xy 137.910381 93.349224) (xy 135.933224 93.349224) (xy 135.938072 93.3) (xy 135.938072 92.050729) (xy 137.136299 92.050729) + (xy 137.183543 92.428951) (xy 137.303667 92.79069) (xy 137.435688 93.037683) (xy 137.730776 93.169619) (xy 138.900395 92) + (xy 139.259605 92) (xy 140.429224 93.169619) (xy 140.724312 93.037683) (xy 140.895159 92.696955) (xy 140.99625 92.329443) + (xy 141.023701 91.949271) (xy 140.976457 91.571049) (xy 140.856333 91.20931) (xy 140.724312 90.962317) (xy 140.429224 90.830381) + (xy 139.259605 92) (xy 138.900395 92) (xy 137.730776 90.830381) (xy 137.435688 90.962317) (xy 137.264841 91.303045) + (xy 137.16375 91.670557) (xy 137.136299 92.050729) (xy 135.938072 92.050729) (xy 135.938072 90.7) (xy 135.933225 90.650776) + (xy 137.910381 90.650776) (xy 139.08 91.820395) (xy 140.249619 90.650776) (xy 140.117683 90.355688) (xy 139.776955 90.184841) + (xy 139.409443 90.08375) (xy 139.029271 90.056299) (xy 138.651049 90.103543) (xy 138.28931 90.223667) (xy 138.042317 90.355688) + (xy 137.910381 90.650776) (xy 135.933225 90.650776) (xy 135.925812 90.575518) (xy 135.889502 90.45582) (xy 135.830537 90.345506) + (xy 135.751185 90.248815) (xy 135.654494 90.169463) (xy 135.54418 90.110498) (xy 135.424482 90.074188) (xy 135.3 90.061928) + (xy 134.824 90.061928) (xy 134.824 87.291546) (xy 134.904512 87.193442) (xy 134.985423 87.042067) (xy 135.035248 86.877816) + (xy 135.052072 86.707) (xy 135.052072 86.132) (xy 135.035248 85.961184) (xy 134.985423 85.796933) (xy 134.904512 85.645558) + (xy 134.821575 85.5445) (xy 134.904512 85.443442) (xy 134.985423 85.292067) (xy 135.035248 85.127816) (xy 135.052072 84.957) + (xy 135.052072 84.382) (xy 135.035248 84.211184) (xy 134.985423 84.046933) (xy 134.904512 83.895558) (xy 134.824 83.797454) + (xy 134.824 82.797201) (xy 134.863482 82.793312) (xy 134.98318 82.757002) (xy 135.093494 82.698037) (xy 135.190185 82.618685) + (xy 135.269537 82.521994) (xy 135.328502 82.41168) (xy 135.364812 82.291982) (xy 135.377072 82.1675) (xy 135.377072 80.5675) + (xy 135.364812 80.443018) (xy 135.328502 80.32332) (xy 135.269537 80.213006) (xy 135.190185 80.116315) (xy 135.093494 80.036963) + (xy 134.98318 79.977998) (xy 134.863482 79.941688) (xy 134.739 79.929428) (xy 133.15356 79.929428) (xy 132.854229 79.630098) + (xy 132.826423 79.538433) (xy 132.745512 79.387058) (xy 132.725884 79.363142) (xy 132.748237 79.340789) (xy 132.81773 79.236785) + (xy 132.865597 79.121223) (xy 132.89 78.998542) (xy 132.89 78.860202) (xy 133.125903 78.860202) (xy 133.197486 79.104171) + (xy 133.452996 79.225071) (xy 133.727184 79.2938) (xy 134.009512 79.307717) (xy 134.28913 79.266287) (xy 134.555292 79.171103) + (xy 134.680514 79.104171) (xy 134.752097 78.860202) (xy 133.939 78.047105) (xy 133.125903 78.860202) (xy 132.89 78.860202) + (xy 132.89 78.69675) (xy 132.843762 78.650512) (xy 132.946298 78.680597) (xy 133.759395 77.8675) (xy 134.118605 77.8675) + (xy 134.931702 78.680597) (xy 135.175671 78.609014) (xy 135.296571 78.353504) (xy 135.3653 78.079316) (xy 135.379217 77.796988) + (xy 135.337787 77.51737) (xy 135.242603 77.251208) (xy 135.175671 77.125986) (xy 134.931702 77.054403) (xy 134.118605 77.8675) + (xy 133.759395 77.8675) (xy 132.946298 77.054403) (xy 132.702329 77.125986) (xy 132.596202 77.350275) (xy 132.555785 77.32327) + (xy 132.440223 77.275403) (xy 132.317542 77.251) (xy 132.06575 77.251) (xy 131.907 77.40975) (xy 131.907 78.284) + (xy 131.927 78.284) (xy 131.927 78.538) (xy 131.907 78.538) (xy 131.907 78.558) (xy 131.653 78.558) + (xy 131.653 78.538) (xy 130.82875 78.538) (xy 130.67 78.69675) (xy 130.67 78.998542) (xy 130.675462 79.026) + (xy 130.154632 79.026) (xy 128.95209 77.823458) (xy 130.67 77.823458) (xy 130.67 78.12525) (xy 130.82875 78.284) + (xy 131.653 78.284) (xy 131.653 77.40975) (xy 131.49425 77.251) (xy 131.242458 77.251) (xy 131.119777 77.275403) + (xy 131.004215 77.32327) (xy 130.900211 77.392763) (xy 130.811763 77.481211) (xy 130.74227 77.585215) (xy 130.694403 77.700777) + (xy 130.67 77.823458) (xy 128.95209 77.823458) (xy 128.858496 77.729865) (xy 128.822949 77.686551) (xy 128.650123 77.544716) + (xy 128.452947 77.439324) (xy 128.238999 77.374423) (xy 128.072252 77.358) (xy 128.072251 77.358) (xy 128.0165 77.352509) + (xy 127.960749 77.358) (xy 126.204 77.358) (xy 126.204 76.874798) (xy 133.125903 76.874798) (xy 133.939 77.687895) + (xy 134.752097 76.874798) (xy 134.680514 76.630829) (xy 134.425004 76.509929) (xy 134.150816 76.4412) (xy 133.868488 76.427283) + (xy 133.58887 76.468713) (xy 133.322708 76.563897) (xy 133.197486 76.630829) (xy 133.125903 76.874798) (xy 126.204 76.874798) + (xy 126.204 73.304372) (xy 126.8155 73.304372) (xy 126.939982 73.292112) (xy 127.05968 73.255802) (xy 127.169994 73.196837) + (xy 127.266685 73.117485) (xy 127.346037 73.020794) (xy 127.405002 72.91048) (xy 127.441312 72.790782) (xy 127.453572 72.6663) + (xy 127.453572 70.8663) (xy 127.441312 70.741818) (xy 127.405002 70.62212) (xy 127.346037 70.511806) (xy 127.266685 70.415115) + (xy 127.169994 70.335763) (xy 127.05968 70.276798) (xy 126.939982 70.240488) (xy 126.8155 70.228228) (xy 126.2005 70.228228) + (xy 126.2005 69.310092) (xy 126.276371 69.196543) (xy 126.380775 68.944489) (xy 126.434 68.676911) (xy 126.434 68.404089) + (xy 126.380775 68.136511) (xy 126.276371 67.884457) (xy 126.124799 67.657614) (xy 125.931886 67.464701) (xy 125.705043 67.313129) + (xy 125.452989 67.208725) (xy 125.185411 67.1555) (xy 124.912589 67.1555) (xy 124.645011 67.208725) (xy 124.392957 67.313129) + (xy 124.166114 67.464701) (xy 123.973201 67.657614) (xy 123.821629 67.884457) (xy 123.717225 68.136511) (xy 123.664 68.404089) + (xy 123.664 68.676911) (xy 123.717225 68.944489) (xy 123.821629 69.196543) (xy 123.930501 69.359481) (xy 123.9305 70.228228) + (xy 123.3155 70.228228) (xy 123.191018 70.240488) (xy 123.07132 70.276798) (xy 122.961006 70.335763) (xy 122.864315 70.415115) + (xy 122.784963 70.511806) (xy 122.725998 70.62212) (xy 122.689688 70.741818) (xy 122.677428 70.8663) (xy 122.677428 70.8813) + (xy 119.248337 70.8813) (xy 119.119134 70.723866) (xy 118.893014 70.538294) (xy 118.635034 70.400401) (xy 118.355111 70.315487) + (xy 118.13695 70.294) (xy 117.99105 70.294) (xy 117.772889 70.315487) (xy 117.492966 70.400401) (xy 117.234986 70.538294) + (xy 117.008866 70.723866) (xy 116.823294 70.949986) (xy 116.788799 71.014523) (xy 116.719178 70.897645) (xy 116.524269 70.681412) + (xy 116.29092 70.507359) (xy 116.028099 70.382175) (xy 115.88089 70.337524) (xy 115.651 70.458845) (xy 115.397 70.458845) + (xy 115.16711 70.337524) (xy 115.019901 70.382175) (xy 114.75708 70.507359) (xy 114.523731 70.681412) (xy 114.328822 70.897645) + (xy 114.259201 71.014523) (xy 114.224706 70.949986) (xy 114.039134 70.723866) (xy 113.872294 70.586944) (xy 113.873281 70.576919) + (xy 113.869 70.53345) (xy 113.869 70.533442) (xy 113.856195 70.403429) (xy 113.805589 70.236606) (xy 113.723411 70.08286) + (xy 113.672663 70.021024) (xy 113.640532 69.981872) (xy 113.64053 69.98187) (xy 113.612817 69.948102) (xy 113.579049 69.920389) + (xy 113.107 69.448341) (xy 113.107 67.14725) (xy 113.4615 67.14725) (xy 113.4615 67.449042) (xy 113.485903 67.571723) + (xy 113.53377 67.687285) (xy 113.603263 67.791289) (xy 113.691711 67.879737) (xy 113.795715 67.94923) (xy 113.911277 67.997097) + (xy 114.033958 68.0215) (xy 114.28575 68.0215) (xy 114.4445 67.86275) (xy 114.4445 66.9885) (xy 114.6985 66.9885) + (xy 114.6985 67.86275) (xy 114.85725 68.0215) (xy 115.109042 68.0215) (xy 115.231723 67.997097) (xy 115.347285 67.94923) + (xy 115.451289 67.879737) (xy 115.539737 67.791289) (xy 115.60923 67.687285) (xy 115.657097 67.571723) (xy 115.6815 67.449042) + (xy 115.6815 67.14725) (xy 115.52275 66.9885) (xy 114.6985 66.9885) (xy 114.4445 66.9885) (xy 113.62025 66.9885) + (xy 113.4615 67.14725) (xy 113.107 67.14725) (xy 113.107 67.036523) (xy 113.094195 66.90651) (xy 113.043589 66.739687) + (xy 112.961411 66.585941) (xy 112.9063 66.518789) (xy 112.9063 65.96276) (xy 112.924302 65.959179) (xy 112.932187 65.961571) + (xy 113.0713 65.975272) (xy 113.2213 65.975272) (xy 113.360413 65.961571) (xy 113.494181 65.920993) (xy 113.595923 65.866611) + (xy 113.605988 65.885442) (xy 113.625616 65.909358) (xy 113.603263 65.931711) (xy 113.53377 66.035715) (xy 113.485903 66.151277) + (xy 113.4615 66.273958) (xy 113.4615 66.57575) (xy 113.62025 66.7345) (xy 114.4445 66.7345) (xy 114.4445 66.7145) + (xy 114.6985 66.7145) (xy 114.6985 66.7345) (xy 115.52275 66.7345) (xy 115.6815 66.57575) (xy 115.6815 66.273958) + (xy 115.657097 66.151277) (xy 115.60923 66.035715) (xy 115.539737 65.931711) (xy 115.517384 65.909358) (xy 115.537012 65.885442) + (xy 115.617923 65.734067) (xy 115.631487 65.68935) (xy 117.0362 65.68935) (xy 117.0362 66.316142) (xy 117.060603 66.438823) + (xy 117.10847 66.554385) (xy 117.177963 66.658389) (xy 117.266411 66.746837) (xy 117.370415 66.81633) (xy 117.485977 66.864197) + (xy 117.608658 66.8886) (xy 118.23545 66.8886) (xy 118.3942 66.72985) (xy 118.3942 65.5306) (xy 117.19495 65.5306) + (xy 117.0362 65.68935) (xy 115.631487 65.68935) (xy 115.667748 65.569816) (xy 115.684572 65.399) (xy 115.684572 64.824) + (xy 115.667748 64.653184) (xy 115.617923 64.488933) (xy 115.537012 64.337558) (xy 115.428123 64.204877) (xy 115.295442 64.095988) + (xy 115.144067 64.015077) (xy 115.012848 63.975272) (xy 115.2213 63.975272) (xy 115.360413 63.961571) (xy 115.494181 63.920993) + (xy 115.617462 63.855098) (xy 115.725518 63.766418) (xy 115.814198 63.658362) (xy 115.880093 63.535081) (xy 115.920671 63.401313) + (xy 115.934372 63.2622) (xy 115.934372 63.1122) (xy 115.920671 62.973087) (xy 115.909785 62.9372) (xy 115.915968 62.916816) + (xy 115.92759 62.938559) (xy 116.010468 63.039546) (xy 116.89947 63.928549) (xy 116.927183 63.962317) (xy 116.960951 63.99003) + (xy 116.960953 63.990032) (xy 117.055091 64.067289) (xy 117.061941 64.072911) (xy 117.187012 64.139762) (xy 117.177963 64.148811) + (xy 117.10847 64.252815) (xy 117.060603 64.368377) (xy 117.0362 64.491058) (xy 117.0362 65.11785) (xy 117.19495 65.2766) + (xy 118.3942 65.2766) (xy 118.3942 65.2566) (xy 118.6482 65.2566) (xy 118.6482 65.2766) (xy 118.6682 65.2766) + (xy 118.6682 65.5306) (xy 118.6482 65.5306) (xy 118.6482 66.72985) (xy 118.80695 66.8886) (xy 119.433742 66.8886) + (xy 119.556423 66.864197) (xy 119.671985 66.81633) (xy 119.775989 66.746837) (xy 119.864437 66.658389) (xy 119.93393 66.554385) + (xy 119.981797 66.438823) (xy 119.983344 66.431047) (xy 120.006066 66.458734) (xy 120.232186 66.644306) (xy 120.490166 66.782199) + (xy 120.770089 66.867113) (xy 120.98825 66.8886) (xy 121.13415 66.8886) (xy 121.352311 66.867113) (xy 121.632234 66.782199) + (xy 121.890214 66.644306) (xy 122.116334 66.458734) (xy 122.301906 66.232614) (xy 122.3312 66.177809) (xy 122.360494 66.232614) + (xy 122.546066 66.458734) (xy 122.772186 66.644306) (xy 123.030166 66.782199) (xy 123.310089 66.867113) (xy 123.52825 66.8886) + (xy 123.67415 66.8886) (xy 123.892311 66.867113) (xy 124.172234 66.782199) (xy 124.430214 66.644306) (xy 124.656334 66.458734) + (xy 124.841906 66.232614) (xy 124.979799 65.974634) (xy 125.064713 65.694711) (xy 125.093385 65.4036) (xy 125.064713 65.112489) + (xy 124.979799 64.832566) (xy 124.841906 64.574586) (xy 124.656334 64.348466) (xy 124.489494 64.211544) (xy 124.490481 64.201519) + (xy 124.4862 64.15805) (xy 124.4862 64.158042) (xy 124.473395 64.028029) (xy 124.46248 63.992046) (xy 124.422789 63.861205) + (xy 124.340611 63.70746) (xy 124.257732 63.606472) (xy 124.25773 63.60647) (xy 124.230017 63.572702) (xy 124.196249 63.544989) + (xy 122.902994 62.251735) (xy 123.004567 62.220923) (xy 123.155942 62.140012) (xy 123.254046 62.0595) (xy 124.148331 62.0595) + (xy 124.1918 62.063781) (xy 124.235269 62.0595) (xy 124.235277 62.0595) (xy 124.36529 62.046695) (xy 124.532113 61.996089) + (xy 124.685859 61.913911) (xy 124.820617 61.803317) (xy 124.848334 61.769544) (xy 125.003506 61.614372) (xy 125.218632 61.614372) + (xy 125.192805 61.699511) (xy 125.18 61.829524) (xy 125.180001 63.353521) (xy 125.175719 63.397) (xy 125.192805 63.57049) + (xy 125.243412 63.737313) (xy 125.32559 63.891059) (xy 125.408468 63.992046) (xy 125.408471 63.992049) (xy 125.436184 64.025817) + (xy 125.469951 64.053529) (xy 126.043468 64.627047) (xy 126.071183 64.660817) (xy 126.104951 64.68853) (xy 126.104953 64.688532) + (xy 126.205941 64.771411) (xy 126.359686 64.853589) (xy 126.52651 64.904195) (xy 126.656523 64.917) (xy 126.656531 64.917) + (xy 126.7 64.921281) (xy 126.743469 64.917) (xy 129.180501 64.917) (xy 129.1805 70.228228) (xy 128.3155 70.228228) + (xy 128.191018 70.240488) (xy 128.07132 70.276798) (xy 127.961006 70.335763) (xy 127.864315 70.415115) (xy 127.784963 70.511806) + (xy 127.725998 70.62212) (xy 127.689688 70.741818) (xy 127.677428 70.8663) (xy 127.677428 72.6663) (xy 127.689688 72.790782) + (xy 127.725998 72.91048) (xy 127.784963 73.020794) (xy 127.864315 73.117485) (xy 127.961006 73.196837) (xy 128.07132 73.255802) + (xy 128.191018 73.292112) (xy 128.3155 73.304372) (xy 131.8155 73.304372) (xy 131.939982 73.292112) (xy 132.05968 73.255802) + (xy 132.169994 73.196837) (xy 132.266685 73.117485) (xy 132.346037 73.020794) (xy 132.405002 72.91048) (xy 132.441312 72.790782) + (xy 132.453572 72.6663) (xy 132.453572 70.8663) (xy 132.441312 70.741818) (xy 132.405002 70.62212) (xy 132.346037 70.511806) + (xy 132.313049 70.471609) (xy 134.060197 70.471609) (xy 134.246273 70.812766) (xy 134.663609 71.028513) (xy 135.115015 71.158696) + (xy 135.583146 71.198313) (xy 136.050011 71.145842) (xy 136.497668 71.003297) (xy 136.854127 70.812766) (xy 137.040203 70.471609) + (xy 135.5502 68.981605) (xy 134.060197 70.471609) (xy 132.313049 70.471609) (xy 132.266685 70.415115) (xy 132.169994 70.335763) + (xy 132.05968 70.276798) (xy 131.939982 70.240488) (xy 131.8155 70.228228) (xy 130.9505 70.228228) (xy 130.9505 68.834946) + (xy 133.153887 68.834946) (xy 133.206358 69.301811) (xy 133.348903 69.749468) (xy 133.539434 70.105927) (xy 133.880591 70.292003) + (xy 135.370595 68.802) (xy 135.729805 68.802) (xy 137.219809 70.292003) (xy 137.560966 70.105927) (xy 137.776713 69.688591) + (xy 137.906896 69.237185) (xy 137.946513 68.769054) (xy 137.894042 68.302189) (xy 137.751497 67.854532) (xy 137.560966 67.498073) + (xy 137.219809 67.311997) (xy 135.729805 68.802) (xy 135.370595 68.802) (xy 133.880591 67.311997) (xy 133.539434 67.498073) + (xy 133.323687 67.915409) (xy 133.193504 68.366815) (xy 133.153887 68.834946) (xy 130.9505 68.834946) (xy 130.9505 67.132391) + (xy 134.060197 67.132391) (xy 135.5502 68.622395) (xy 137.040203 67.132391) (xy 136.854127 66.791234) (xy 136.436791 66.575487) + (xy 135.985385 66.445304) (xy 135.517254 66.405687) (xy 135.050389 66.458158) (xy 134.602732 66.600703) (xy 134.246273 66.791234) + (xy 134.060197 67.132391) (xy 130.9505 67.132391) (xy 130.9505 65.520072) (xy 131.6902 65.520072) (xy 131.814682 65.507812) + (xy 131.93438 65.471502) (xy 132.044694 65.412537) (xy 132.133076 65.340004) (xy 132.333083 65.435371) (xy 132.616611 65.507339) + (xy 132.908731 65.522611) (xy 133.198219 65.480599) (xy 133.473947 65.382919) (xy 133.611357 65.309472) (xy 133.688992 65.060397) + (xy 132.8402 64.211605) (xy 132.826058 64.225748) (xy 132.646453 64.046143) (xy 132.660595 64.032) (xy 133.019805 64.032) + (xy 133.868597 64.880792) (xy 134.117672 64.803157) (xy 134.243571 64.539117) (xy 134.315539 64.255589) (xy 134.330811 63.963469) + (xy 134.288799 63.673981) (xy 134.191119 63.398253) (xy 134.117672 63.260843) (xy 133.868597 63.183208) (xy 133.019805 64.032) + (xy 132.660595 64.032) (xy 132.646453 64.017858) (xy 132.826058 63.838253) (xy 132.8402 63.852395) (xy 133.688992 63.003603) + (xy 133.62379 62.794416) (xy 133.786832 62.685475) (xy 133.993675 62.478632) (xy 134.15619 62.235411) (xy 134.268132 61.965158) + (xy 134.3252 61.67826) (xy 134.3252 61.38574) (xy 134.268132 61.098842) (xy 134.15619 60.828589) (xy 133.993675 60.585368) + (xy 133.786832 60.378525) (xy 133.6002 60.253822) (xy 133.6002 59.846325) (xy 133.603876 59.809) (xy 133.6002 59.771675) + (xy 133.6002 59.771667) (xy 133.589203 59.660014) (xy 133.545746 59.516753) (xy 133.475174 59.384724) (xy 133.380201 59.268999) + (xy 133.351204 59.245202) (xy 132.537611 58.431609) (xy 134.060197 58.431609) (xy 134.246273 58.772766) (xy 134.663609 58.988513) + (xy 135.115015 59.118696) (xy 135.583146 59.158313) (xy 136.050011 59.105842) (xy 136.497668 58.963297) (xy 136.854127 58.772766) + (xy 137.040203 58.431609) (xy 135.5502 56.941605) (xy 134.060197 58.431609) (xy 132.537611 58.431609) (xy 132.346304 58.240302) + (xy 132.322501 58.211299) (xy 132.206776 58.116326) (xy 132.074747 58.045754) (xy 131.931486 58.002297) (xy 131.819833 57.9913) + (xy 131.819822 57.9913) (xy 131.7825 57.987624) (xy 131.745178 57.9913) (xy 128.659468 57.9913) (xy 128.646185 57.975115) + (xy 128.549494 57.895763) (xy 128.43918 57.836798) (xy 128.319482 57.800488) (xy 128.195 57.788228) (xy 126.635 57.788228) + (xy 126.510518 57.800488) (xy 126.39082 57.836798) (xy 126.280506 57.895763) (xy 126.183815 57.975115) (xy 126.104463 58.071806) + (xy 126.065 58.145635) (xy 126.025537 58.071806) (xy 125.946185 57.975115) (xy 125.849494 57.895763) (xy 125.73918 57.836798) + (xy 125.619482 57.800488) (xy 125.495 57.788228) (xy 125.003506 57.788228) (xy 124.873734 57.658456) (xy 124.846017 57.624683) + (xy 124.711259 57.514089) (xy 124.557513 57.431911) (xy 124.39069 57.381305) (xy 124.260677 57.3685) (xy 124.260669 57.3685) + (xy 124.2172 57.364219) (xy 124.173731 57.3685) (xy 124.094209 57.3685) (xy 124.170537 57.275494) (xy 124.229502 57.16518) + (xy 124.265812 57.045482) (xy 124.278072 56.921) (xy 124.278072 56.635984) (xy 124.348815 56.722185) (xy 124.445506 56.801537) + (xy 124.55582 56.860502) (xy 124.675518 56.896812) (xy 124.8 56.909072) (xy 125.346436 56.909072) (xy 125.37651 56.918195) + (xy 125.55 56.935282) (xy 125.723489 56.918195) (xy 125.753563 56.909072) (xy 126.3 56.909072) (xy 126.424482 56.896812) + (xy 126.54418 56.860502) (xy 126.635438 56.811723) (xy 126.703701 56.913886) (xy 126.896614 57.106799) (xy 127.123457 57.258371) + (xy 127.375511 57.362775) (xy 127.643089 57.416) (xy 127.915911 57.416) (xy 128.183489 57.362775) (xy 128.435543 57.258371) + (xy 128.662386 57.106799) (xy 128.855299 56.913886) (xy 128.934772 56.794946) (xy 133.153887 56.794946) (xy 133.206358 57.261811) + (xy 133.348903 57.709468) (xy 133.539434 58.065927) (xy 133.880591 58.252003) (xy 135.370595 56.762) (xy 135.729805 56.762) + (xy 137.219809 58.252003) (xy 137.560966 58.065927) (xy 137.776713 57.648591) (xy 137.906896 57.197185) (xy 137.946513 56.729054) + (xy 137.894042 56.262189) (xy 137.751497 55.814532) (xy 137.560966 55.458073) (xy 137.219809 55.271997) (xy 135.729805 56.762) + (xy 135.370595 56.762) (xy 133.880591 55.271997) (xy 133.539434 55.458073) (xy 133.323687 55.875409) (xy 133.193504 56.326815) + (xy 133.153887 56.794946) (xy 128.934772 56.794946) (xy 129.006871 56.687043) (xy 129.111275 56.434989) (xy 129.1645 56.167411) + (xy 129.1645 55.894589) (xy 129.111275 55.627011) (xy 129.006871 55.374957) (xy 128.855299 55.148114) (xy 128.799576 55.092391) + (xy 134.060197 55.092391) (xy 135.5502 56.582395) (xy 137.040203 55.092391) (xy 136.854127 54.751234) (xy 136.436791 54.535487) + (xy 135.985385 54.405304) (xy 135.517254 54.365687) (xy 135.050389 54.418158) (xy 134.602732 54.560703) (xy 134.246273 54.751234) + (xy 134.060197 55.092391) (xy 128.799576 55.092391) (xy 128.662386 54.955201) (xy 128.435543 54.803629) (xy 128.28813 54.742569) + (xy 128.305123 54.728623) (xy 128.414012 54.595942) (xy 128.494923 54.444567) (xy 128.544748 54.280316) (xy 128.561572 54.1095) + (xy 128.561572 53.6345) (xy 128.544748 53.463684) (xy 128.494923 53.299433) (xy 128.414012 53.148058) (xy 128.305123 53.015377) + (xy 128.172442 52.906488) (xy 128.021067 52.825577) (xy 127.856816 52.775752) (xy 127.686 52.758928) (xy 127.111 52.758928) + (xy 126.940184 52.775752) (xy 126.775933 52.825577) (xy 126.624558 52.906488) (xy 126.5235 52.989425) (xy 126.422442 52.906488) + (xy 126.271067 52.825577) (xy 126.106816 52.775752) (xy 125.936 52.758928) (xy 125.361 52.758928) (xy 125.190184 52.775752) + (xy 125.025933 52.825577) (xy 124.874558 52.906488) (xy 124.741877 53.015377) (xy 124.632988 53.148058) (xy 124.552077 53.299433) + (xy 124.502252 53.463684) (xy 124.485428 53.6345) (xy 124.485428 54.1095) (xy 124.502252 54.280316) (xy 124.552077 54.444567) + (xy 124.632988 54.595942) (xy 124.665001 54.634949) (xy 124.665 55.198378) (xy 124.55582 55.231498) (xy 124.445506 55.290463) + (xy 124.348815 55.369815) (xy 124.278072 55.456016) (xy 124.278072 55.171) (xy 124.265812 55.046518) (xy 124.229502 54.92682) + (xy 124.170537 54.816506) (xy 124.091185 54.719815) (xy 123.994494 54.640463) (xy 123.88418 54.581498) (xy 123.764482 54.545188) + (xy 123.64 54.532928) (xy 123.093564 54.532928) (xy 123.06349 54.523805) (xy 122.933477 54.511) (xy 122.558079 54.511) + (xy 120.010329 51.96325) (xy 128.0495 51.96325) (xy 128.0495 52.490042) (xy 128.073903 52.612723) (xy 128.12177 52.728285) + (xy 128.191263 52.832289) (xy 128.279711 52.920737) (xy 128.383715 52.99023) (xy 128.499277 53.038097) (xy 128.621958 53.0625) + (xy 129.39875 53.0625) (xy 129.5575 52.90375) (xy 129.5575 51.8045) (xy 129.8115 51.8045) (xy 129.8115 52.90375) + (xy 129.97025 53.0625) (xy 130.747042 53.0625) (xy 130.869723 53.038097) (xy 130.985285 52.99023) (xy 131.089289 52.920737) + (xy 131.177737 52.832289) (xy 131.24723 52.728285) (xy 131.295097 52.612723) (xy 131.3195 52.490042) (xy 131.3195 52.39725) + (xy 132.248 52.39725) (xy 132.248 52.961542) (xy 132.272403 53.084223) (xy 132.32027 53.199785) (xy 132.389763 53.303789) + (xy 132.478211 53.392237) (xy 132.582215 53.46173) (xy 132.697777 53.509597) (xy 132.820458 53.534) (xy 133.27225 53.534) + (xy 133.431 53.37525) (xy 133.431 52.2385) (xy 133.685 52.2385) (xy 133.685 53.37525) (xy 133.84375 53.534) + (xy 134.295542 53.534) (xy 134.418223 53.509597) (xy 134.533785 53.46173) (xy 134.637789 53.392237) (xy 134.726237 53.303789) + (xy 134.79573 53.199785) (xy 134.843597 53.084223) (xy 134.868 52.961542) (xy 134.868 52.39725) (xy 134.70925 52.2385) + (xy 133.685 52.2385) (xy 133.431 52.2385) (xy 132.40675 52.2385) (xy 132.248 52.39725) (xy 131.3195 52.39725) + (xy 131.3195 51.96325) (xy 131.16075 51.8045) (xy 129.8115 51.8045) (xy 129.5575 51.8045) (xy 128.20825 51.8045) + (xy 128.0495 51.96325) (xy 120.010329 51.96325) (xy 119.609534 51.562456) (xy 119.581817 51.528683) (xy 119.447059 51.418089) + (xy 119.293313 51.335911) (xy 119.12649 51.285305) (xy 118.996477 51.2725) (xy 118.996469 51.2725) (xy 118.953 51.268219) + (xy 118.909531 51.2725) (xy 113.344965 51.2725) (xy 113.301499 51.268219) (xy 113.258033 51.2725) (xy 113.258023 51.2725) + (xy 113.12801 51.285305) (xy 112.961187 51.335911) (xy 112.807441 51.418089) (xy 112.777952 51.44229) (xy 112.706453 51.500968) + (xy 112.706451 51.50097) (xy 112.672683 51.528683) (xy 112.64497 51.562451) (xy 112.0275 52.179922) (xy 112.0275 51.595969) + (xy 112.031781 51.5525) (xy 112.0275 51.509031) (xy 112.0275 51.509023) (xy 112.014695 51.37901) (xy 111.964089 51.212187) + (xy 111.881911 51.058441) (xy 111.771317 50.923683) (xy 111.73755 50.895971) (xy 111.592177 50.750598) (xy 111.697994 50.694037) + (xy 111.794685 50.614685) (xy 111.874037 50.517994) (xy 111.933002 50.40768) (xy 111.969312 50.287982) (xy 111.981572 50.1635) + (xy 111.981572 48.5635) (xy 111.969312 48.439018) (xy 111.933002 48.31932) (xy 111.874037 48.209006) (xy 111.794685 48.112315) + (xy 111.697994 48.032963) (xy 111.58768 47.973998) (xy 111.467982 47.937688) (xy 111.3435 47.925428) (xy 109.1635 47.925428) + (xy 109.039018 47.937688) (xy 108.91932 47.973998) (xy 108.809006 48.032963) (xy 108.712315 48.112315) (xy 108.632963 48.209006) + (xy 108.573998 48.31932) (xy 108.537688 48.439018) (xy 108.525428 48.5635) (xy 108.525428 49.332731) (xy 108.362316 49.283252) + (xy 108.1915 49.266428) (xy 107.6165 49.266428) (xy 107.445684 49.283252) (xy 107.281433 49.333077) (xy 107.130058 49.413988) + (xy 107.039 49.488718) (xy 107.039 48.559078) (xy 108.397579 47.2005) (xy 120.038315 47.2005) (xy 120.191618 47.353803) + (xy 119.619994 47.925428) (xy 118.3435 47.925428) (xy 118.219018 47.937688) (xy 118.09932 47.973998) (xy 117.989006 48.032963) + (xy 117.892315 48.112315) (xy 117.812963 48.209006) (xy 117.753998 48.31932) (xy 117.717688 48.439018) (xy 117.705428 48.5635) + (xy 117.705428 50.1635) (xy 117.717688 50.287982) (xy 117.753998 50.40768) (xy 117.812963 50.517994) (xy 117.892315 50.614685) + (xy 117.989006 50.694037) (xy 118.09932 50.753002) (xy 118.219018 50.789312) (xy 118.3435 50.801572) (xy 120.5235 50.801572) + (xy 120.647982 50.789312) (xy 120.76768 50.753002) (xy 120.877994 50.694037) (xy 120.974685 50.614685) (xy 121.054037 50.517994) + (xy 121.113002 50.40768) (xy 121.149312 50.287982) (xy 121.153201 50.2485) (xy 121.746428 50.2485) (xy 121.746428 51.2775) + (xy 121.758688 51.401982) (xy 121.794998 51.52168) (xy 121.853963 51.631994) (xy 121.933315 51.728685) (xy 122.030006 51.808037) + (xy 122.14032 51.867002) (xy 122.260018 51.903312) (xy 122.3845 51.915572) (xy 124.3845 51.915572) (xy 124.508982 51.903312) + (xy 124.62868 51.867002) (xy 124.738994 51.808037) (xy 124.835685 51.728685) (xy 124.915037 51.631994) (xy 124.974002 51.52168) + (xy 125.010312 51.401982) (xy 125.022572 51.2775) (xy 125.022572 50.2625) (xy 128.061879 50.2625) (xy 128.094998 50.37168) + (xy 128.153963 50.481994) (xy 128.18952 50.52532) (xy 128.12177 50.626715) (xy 128.073903 50.742277) (xy 128.0495 50.864958) + (xy 128.0495 51.39175) (xy 128.20825 51.5505) (xy 129.5575 51.5505) (xy 129.5575 51.5305) (xy 129.8115 51.5305) + (xy 129.8115 51.5505) (xy 131.16075 51.5505) (xy 131.3195 51.39175) (xy 131.3195 51.261458) (xy 132.248 51.261458) + (xy 132.248 51.82575) (xy 132.40675 51.9845) (xy 133.431 51.9845) (xy 133.431 50.84775) (xy 133.685 50.84775) + (xy 133.685 51.9845) (xy 134.70925 51.9845) (xy 134.868 51.82575) (xy 134.868 51.261458) (xy 134.843597 51.138777) + (xy 134.79573 51.023215) (xy 134.726237 50.919211) (xy 134.637789 50.830763) (xy 134.533785 50.76127) (xy 134.418223 50.713403) + (xy 134.295542 50.689) (xy 133.84375 50.689) (xy 133.685 50.84775) (xy 133.431 50.84775) (xy 133.27225 50.689) + (xy 132.820458 50.689) (xy 132.697777 50.713403) (xy 132.582215 50.76127) (xy 132.478211 50.830763) (xy 132.389763 50.919211) + (xy 132.32027 51.023215) (xy 132.272403 51.138777) (xy 132.248 51.261458) (xy 131.3195 51.261458) (xy 131.3195 50.864958) + (xy 131.295097 50.742277) (xy 131.24723 50.626715) (xy 131.17948 50.52532) (xy 131.215037 50.481994) (xy 131.274002 50.37168) + (xy 131.307121 50.2625) (xy 132.391983 50.2625) (xy 132.394595 50.267387) (xy 132.505038 50.401962) (xy 132.639613 50.512405) + (xy 132.793149 50.594472) (xy 132.959745 50.645008) (xy 133.132999 50.662072) (xy 133.983001 50.662072) (xy 134.156255 50.645008) + (xy 134.322851 50.594472) (xy 134.476387 50.512405) (xy 134.610962 50.401962) (xy 134.721405 50.267387) (xy 134.803472 50.113851) + (xy 134.854008 49.947255) (xy 134.871072 49.774001) (xy 134.871072 48.698999) (xy 134.854008 48.525745) (xy 134.803472 48.359149) + (xy 134.721405 48.205613) (xy 134.610962 48.071038) (xy 134.476387 47.960595) (xy 134.322851 47.878528) (xy 134.156255 47.827992) + (xy 133.983001 47.810928) (xy 133.132999 47.810928) (xy 132.959745 47.827992) (xy 132.793149 47.878528) (xy 132.639613 47.960595) + (xy 132.505038 48.071038) (xy 132.394595 48.205613) (xy 132.312528 48.359149) (xy 132.272077 48.4925) (xy 131.307121 48.4925) + (xy 131.274002 48.38332) (xy 131.215037 48.273006) (xy 131.177691 48.2275) (xy 131.215037 48.181994) (xy 131.274002 48.07168) + (xy 131.310312 47.951982) (xy 131.322572 47.8275) (xy 131.322572 46.779872) (xy 136.265 46.779872) (xy 136.265 47.220128) + (xy 136.35089 47.651925) (xy 136.519369 48.058669) (xy 136.763962 48.424729) (xy 137.075271 48.736038) (xy 137.441331 48.980631) + (xy 137.848075 49.14911) (xy 138.279872 49.235) (xy 138.720128 49.235) (xy 139.151925 49.14911) (xy 139.558669 48.980631) + (xy 139.924729 48.736038) (xy 140.236038 48.424729) (xy 140.480631 48.058669) (xy 140.64911 47.651925) (xy 140.735 47.220128) + (xy 140.735 46.779872) (xy 140.64911 46.348075) (xy 140.480631 45.941331) (xy 140.236038 45.575271) (xy 139.924729 45.263962) + (xy 139.558669 45.019369) (xy 139.151925 44.85089) (xy 138.720128 44.765) (xy 138.279872 44.765) (xy 137.848075 44.85089) + (xy 137.441331 45.019369) (xy 137.075271 45.263962) (xy 136.763962 45.575271) (xy 136.519369 45.941331) (xy 136.35089 46.348075) + (xy 136.265 46.779872) (xy 131.322572 46.779872) (xy 131.322572 46.3275) (xy 131.310312 46.203018) (xy 131.274002 46.08332) + (xy 131.215037 45.973006) (xy 131.135685 45.876315) (xy 131.038994 45.796963) (xy 130.92868 45.737998) (xy 130.808982 45.701688) + (xy 130.6845 45.689428) (xy 129.90156 45.689428) (xy 128.927801 44.715669) (xy 128.974 44.483411) (xy 128.974 44.210589) + (xy 128.920775 43.943011) (xy 128.816371 43.690957) (xy 128.795686 43.66) (xy 141.840001 43.66) (xy 141.84 96.84) + (xy 48.16 96.84) (xy 48.16 93.279872) (xy 49.265 93.279872) (xy 49.265 93.720128) (xy 49.35089 94.151925) + (xy 49.519369 94.558669) (xy 49.763962 94.924729) (xy 50.075271 95.236038) (xy 50.441331 95.480631) (xy 50.848075 95.64911) + (xy 51.279872 95.735) (xy 51.720128 95.735) (xy 52.151925 95.64911) (xy 52.558669 95.480631) (xy 52.924729 95.236038) + (xy 53.236038 94.924729) (xy 53.480631 94.558669) (xy 53.64911 94.151925) (xy 53.735 93.720128) (xy 53.735 93.279872) + (xy 53.64911 92.848075) (xy 53.480631 92.441331) (xy 53.376676 92.28575) (xy 57.565 92.28575) (xy 57.565 93.362542) + (xy 57.589403 93.485223) (xy 57.63727 93.600785) (xy 57.706763 93.704789) (xy 57.795211 93.793237) (xy 57.899215 93.86273) + (xy 58.014777 93.910597) (xy 58.137458 93.935) (xy 59.21425 93.935) (xy 59.373 93.77625) (xy 59.373 92.127) + (xy 59.627 92.127) (xy 59.627 93.77625) (xy 59.78575 93.935) (xy 60.862542 93.935) (xy 60.985223 93.910597) + (xy 61.100785 93.86273) (xy 61.204789 93.793237) (xy 61.293237 93.704789) (xy 61.36273 93.600785) (xy 61.410597 93.485223) + (xy 61.435 93.362542) (xy 61.435 92.28575) (xy 61.27625 92.127) (xy 59.627 92.127) (xy 59.373 92.127) + (xy 57.72375 92.127) (xy 57.565 92.28575) (xy 53.376676 92.28575) (xy 53.236038 92.075271) (xy 52.924729 91.763962) + (xy 52.558669 91.519369) (xy 52.151925 91.35089) (xy 51.720128 91.265) (xy 51.279872 91.265) (xy 50.848075 91.35089) + (xy 50.441331 91.519369) (xy 50.075271 91.763962) (xy 49.763962 92.075271) (xy 49.519369 92.441331) (xy 49.35089 92.848075) + (xy 49.265 93.279872) (xy 48.16 93.279872) (xy 48.16 90.637458) (xy 57.565 90.637458) (xy 57.565 91.71425) + (xy 57.72375 91.873) (xy 59.373 91.873) (xy 59.373 90.22375) (xy 59.627 90.22375) (xy 59.627 91.873) + (xy 61.27625 91.873) (xy 61.435 91.71425) (xy 61.435 90.637458) (xy 61.410597 90.514777) (xy 61.36273 90.399215) + (xy 61.293237 90.295211) (xy 61.204789 90.206763) (xy 61.100785 90.13727) (xy 60.985223 90.089403) (xy 60.862542 90.065) + (xy 59.78575 90.065) (xy 59.627 90.22375) (xy 59.373 90.22375) (xy 59.21425 90.065) (xy 58.137458 90.065) + (xy 58.014777 90.089403) (xy 57.899215 90.13727) (xy 57.795211 90.206763) (xy 57.706763 90.295211) (xy 57.63727 90.399215) + (xy 57.589403 90.514777) (xy 57.565 90.637458) (xy 48.16 90.637458) (xy 48.16 85.336039) (xy 55.204096 85.336039) + (xy 55.244754 85.470087) (xy 55.364963 85.72442) (xy 55.532481 85.950414) (xy 55.740869 86.139385) (xy 55.982119 86.28407) + (xy 56.24696 86.378909) (xy 56.469 86.257624) (xy 56.469 85.114) (xy 56.723 85.114) (xy 56.723 86.257624) + (xy 56.94504 86.378909) (xy 57.209881 86.28407) (xy 57.451131 86.139385) (xy 57.659519 85.950414) (xy 57.827037 85.72442) + (xy 57.947246 85.470087) (xy 57.987904 85.336039) (xy 57.865915 85.114) (xy 56.723 85.114) (xy 56.469 85.114) + (xy 55.326085 85.114) (xy 55.204096 85.336039) (xy 48.16 85.336039) (xy 48.16 82.447) (xy 55.154057 82.447) + (xy 55.181764 82.728309) (xy 55.263818 82.998808) (xy 55.397068 83.248101) (xy 55.576392 83.466608) (xy 55.794899 83.645932) + (xy 55.932682 83.719579) (xy 55.740869 83.834615) (xy 55.532481 84.023586) (xy 55.364963 84.24958) (xy 55.244754 84.503913) + (xy 55.204096 84.637961) (xy 55.326085 84.86) (xy 56.469 84.86) (xy 56.469 84.84) (xy 56.723 84.84) + (xy 56.723 84.86) (xy 57.865915 84.86) (xy 57.987904 84.637961) (xy 57.947246 84.503913) (xy 57.827037 84.24958) + (xy 57.659519 84.023586) (xy 57.451131 83.834615) (xy 57.259318 83.719579) (xy 57.397101 83.645932) (xy 57.615608 83.466608) + (xy 57.794932 83.248101) (xy 57.928182 82.998808) (xy 58.010236 82.728309) (xy 58.037943 82.447) (xy 58.020875 82.273704) + (xy 58.740579 81.554) (xy 60.298724 81.554) (xy 60.217038 81.621038) (xy 60.106595 81.755613) (xy 60.024528 81.909149) + (xy 59.973992 82.075745) (xy 59.956928 82.248999) (xy 59.956928 82.899001) (xy 59.973992 83.072255) (xy 60.024528 83.238851) + (xy 60.106595 83.392387) (xy 60.217038 83.526962) (xy 60.304816 83.599) (xy 60.217038 83.671038) (xy 60.106595 83.805613) + (xy 60.024528 83.959149) (xy 59.973992 84.125745) (xy 59.956928 84.298999) (xy 59.956928 84.949001) (xy 59.973992 85.122255) + (xy 60.024528 85.288851) (xy 60.106595 85.442387) (xy 60.217038 85.576962) (xy 60.351613 85.687405) (xy 60.505149 85.769472) + (xy 60.671745 85.820008) (xy 60.844999 85.837072) (xy 61.411581 85.837072) (xy 61.454436 85.850072) (xy 61.48451 85.859195) + (xy 61.614523 85.872) (xy 61.614531 85.872) (xy 61.658 85.876281) (xy 61.701469 85.872) (xy 63.085922 85.872) + (xy 63.196392 86.006608) (xy 63.414899 86.185932) (xy 63.664192 86.319182) (xy 63.695001 86.328528) (xy 63.695 90.27215) + (xy 63.663434 90.285225) (xy 63.346509 90.496987) (xy 63.076987 90.766509) (xy 62.865225 91.083434) (xy 62.719361 91.435581) + (xy 62.645 91.809419) (xy 62.645 92.190581) (xy 62.719361 92.564419) (xy 62.865225 92.916566) (xy 63.076987 93.233491) + (xy 63.346509 93.503013) (xy 63.663434 93.714775) (xy 64.015581 93.860639) (xy 64.389419 93.935) (xy 64.770581 93.935) + (xy 65.144419 93.860639) (xy 65.496566 93.714775) (xy 65.813491 93.503013) (xy 66.083013 93.233491) (xy 66.294775 92.916566) + (xy 66.440639 92.564419) (xy 66.496069 92.28575) (xy 70.065 92.28575) (xy 70.065 93.362542) (xy 70.089403 93.485223) + (xy 70.13727 93.600785) (xy 70.206763 93.704789) (xy 70.295211 93.793237) (xy 70.399215 93.86273) (xy 70.514777 93.910597) + (xy 70.637458 93.935) (xy 71.71425 93.935) (xy 71.873 93.77625) (xy 71.873 92.127) (xy 72.127 92.127) + (xy 72.127 93.77625) (xy 72.28575 93.935) (xy 73.362542 93.935) (xy 73.485223 93.910597) (xy 73.600785 93.86273) + (xy 73.704789 93.793237) (xy 73.793237 93.704789) (xy 73.86273 93.600785) (xy 73.910597 93.485223) (xy 73.935 93.362542) + (xy 73.935 92.28575) (xy 73.77625 92.127) (xy 72.127 92.127) (xy 71.873 92.127) (xy 70.22375 92.127) + (xy 70.065 92.28575) (xy 66.496069 92.28575) (xy 66.515 92.190581) (xy 66.515 91.809419) (xy 66.440639 91.435581) + (xy 66.294775 91.083434) (xy 66.083013 90.766509) (xy 65.953962 90.637458) (xy 70.065 90.637458) (xy 70.065 91.71425) + (xy 70.22375 91.873) (xy 71.873 91.873) (xy 71.873 90.22375) (xy 72.127 90.22375) (xy 72.127 91.873) + (xy 73.77625 91.873) (xy 73.935 91.71425) (xy 73.935 90.637458) (xy 73.910597 90.514777) (xy 73.86273 90.399215) + (xy 73.793237 90.295211) (xy 73.704789 90.206763) (xy 73.600785 90.13727) (xy 73.485223 90.089403) (xy 73.362542 90.065) + (xy 72.28575 90.065) (xy 72.127 90.22375) (xy 71.873 90.22375) (xy 71.71425 90.065) (xy 70.637458 90.065) + (xy 70.514777 90.089403) (xy 70.399215 90.13727) (xy 70.295211 90.206763) (xy 70.206763 90.295211) (xy 70.13727 90.399215) + (xy 70.089403 90.514777) (xy 70.065 90.637458) (xy 65.953962 90.637458) (xy 65.813491 90.496987) (xy 65.496566 90.285225) + (xy 65.465 90.27215) (xy 65.465 86.29072) (xy 65.556613 86.365905) (xy 65.710149 86.447972) (xy 65.876745 86.498508) + (xy 66.049999 86.515572) (xy 66.700001 86.515572) (xy 66.873255 86.498508) (xy 67.039851 86.447972) (xy 67.193387 86.365905) + (xy 67.327962 86.255462) (xy 67.4 86.167684) (xy 67.472038 86.255462) (xy 67.606613 86.365905) (xy 67.760149 86.447972) + (xy 67.926745 86.498508) (xy 68.099999 86.515572) (xy 68.750001 86.515572) (xy 68.923255 86.498508) (xy 69.089851 86.447972) + (xy 69.243387 86.365905) (xy 69.377962 86.255462) (xy 69.488405 86.120887) (xy 69.570472 85.967351) (xy 69.61362 85.825109) + (xy 69.729481 85.981414) (xy 69.937869 86.170385) (xy 70.179119 86.31507) (xy 70.44396 86.409909) (xy 70.666 86.288624) + (xy 70.666 85.145) (xy 70.92 85.145) (xy 70.92 86.288624) (xy 71.14204 86.409909) (xy 71.406881 86.31507) + (xy 71.648131 86.170385) (xy 71.856519 85.981414) (xy 72.024037 85.75542) (xy 72.144246 85.501087) (xy 72.184904 85.367039) + (xy 72.062915 85.145) (xy 70.92 85.145) (xy 70.666 85.145) (xy 70.646 85.145) (xy 70.646 84.891) + (xy 70.666 84.891) (xy 70.666 84.871) (xy 70.92 84.871) (xy 70.92 84.891) (xy 72.062915 84.891) + (xy 72.184904 84.668961) (xy 72.144246 84.534913) (xy 72.103752 84.449238) (xy 72.191747 84.422546) (xy 72.230242 84.401969) + (xy 72.263489 84.398695) (xy 72.430312 84.348089) (xy 72.584058 84.265911) (xy 72.718817 84.155317) (xy 72.829411 84.020559) + (xy 72.911589 83.866813) (xy 72.927841 83.813237) (xy 73.38355 83.357529) (xy 73.417317 83.329817) (xy 73.448773 83.291489) + (xy 73.513804 83.212248) (xy 73.527911 83.195059) (xy 73.610089 83.041313) (xy 73.660695 82.87449) (xy 73.6735 82.744477) + (xy 73.6735 82.744467) (xy 73.677781 82.701001) (xy 73.6735 82.657535) (xy 73.6735 82.178578) (xy 73.790079 82.062) + (xy 74.306105 82.062) (xy 74.297992 82.088745) (xy 74.280928 82.261999) (xy 74.280928 82.912001) (xy 74.297992 83.085255) + (xy 74.348528 83.251851) (xy 74.430595 83.405387) (xy 74.541038 83.539962) (xy 74.628816 83.612) (xy 74.541038 83.684038) + (xy 74.430595 83.818613) (xy 74.348528 83.972149) (xy 74.297992 84.138745) (xy 74.280928 84.311999) (xy 74.280928 84.962001) + (xy 74.297992 85.135255) (xy 74.348528 85.301851) (xy 74.430595 85.455387) (xy 74.541038 85.589962) (xy 74.675613 85.700405) + (xy 74.829149 85.782472) (xy 74.995745 85.833008) (xy 75.168999 85.850072) (xy 75.694244 85.850072) (xy 75.82651 85.890195) + (xy 75.956523 85.903) (xy 75.956533 85.903) (xy 75.999999 85.907281) (xy 76.043465 85.903) (xy 76.315971 85.903) + (xy 76.258412 86.010687) (xy 76.207805 86.17751) (xy 76.190719 86.351) (xy 76.195001 86.394479) (xy 76.195 90.27215) + (xy 76.163434 90.285225) (xy 75.846509 90.496987) (xy 75.576987 90.766509) (xy 75.365225 91.083434) (xy 75.219361 91.435581) + (xy 75.145 91.809419) (xy 75.145 92.190581) (xy 75.219361 92.564419) (xy 75.365225 92.916566) (xy 75.576987 93.233491) + (xy 75.846509 93.503013) (xy 76.163434 93.714775) (xy 76.515581 93.860639) (xy 76.889419 93.935) (xy 77.270581 93.935) + (xy 77.644419 93.860639) (xy 77.996566 93.714775) (xy 78.313491 93.503013) (xy 78.583013 93.233491) (xy 78.794775 92.916566) + (xy 78.940639 92.564419) (xy 79.015 92.190581) (xy 79.015 91.809419) (xy 78.940639 91.435581) (xy 78.794775 91.083434) + (xy 78.583013 90.766509) (xy 78.313491 90.496987) (xy 77.996566 90.285225) (xy 77.965 90.27215) (xy 77.965 86.717578) + (xy 78.239704 86.442875) (xy 78.342508 86.453) (xy 78.483492 86.453) (xy 78.694309 86.432236) (xy 78.964808 86.350182) + (xy 79.214101 86.216932) (xy 79.432608 86.037608) (xy 79.611932 85.819101) (xy 79.745182 85.569808) (xy 79.827236 85.299309) + (xy 79.854943 85.018) (xy 79.827236 84.736691) (xy 79.745182 84.466192) (xy 79.611932 84.216899) (xy 79.432608 83.998392) + (xy 79.319518 83.905581) (xy 79.337482 83.903812) (xy 79.45718 83.867502) (xy 79.567494 83.808537) (xy 79.664185 83.729185) + (xy 79.743537 83.632494) (xy 79.802502 83.52218) (xy 79.838812 83.402482) (xy 79.842701 83.363) (xy 80.200263 83.363) + (xy 80.256038 83.430962) (xy 80.390613 83.541405) (xy 80.544149 83.623472) (xy 80.710745 83.674008) (xy 80.883999 83.691072) + (xy 81.784001 83.691072) (xy 81.957255 83.674008) (xy 82.123851 83.623472) (xy 82.277387 83.541405) (xy 82.411962 83.430962) + (xy 82.522405 83.296387) (xy 82.604472 83.142851) (xy 82.655008 82.976255) (xy 82.672072 82.803001) (xy 82.672072 82.152999) + (xy 82.655008 81.979745) (xy 82.604472 81.813149) (xy 82.522405 81.659613) (xy 82.411962 81.525038) (xy 82.324184 81.453) + (xy 82.383643 81.404203) (xy 82.393095 81.421887) (xy 82.503538 81.556462) (xy 82.638113 81.666905) (xy 82.791649 81.748972) + (xy 82.861619 81.770197) (xy 83.659 82.567579) (xy 83.659 82.837411) (xy 83.712225 83.104989) (xy 83.816629 83.357043) + (xy 83.968201 83.583886) (xy 84.161114 83.776799) (xy 84.387957 83.928371) (xy 84.640011 84.032775) (xy 84.907589 84.086) + (xy 85.180411 84.086) (xy 85.447989 84.032775) (xy 85.700043 83.928371) (xy 85.926886 83.776799) (xy 86.119799 83.583886) + (xy 86.271371 83.357043) (xy 86.375775 83.104989) (xy 86.429 82.837411) (xy 86.429 82.564589) (xy 86.375775 82.297011) + (xy 86.271371 82.044957) (xy 86.119799 81.818114) (xy 86.078748 81.777063) (xy 86.171351 81.748972) (xy 86.324887 81.666905) + (xy 86.336121 81.657685) (xy 86.360264 81.902809) (xy 86.442318 82.173308) (xy 86.575568 82.422601) (xy 86.754892 82.641108) + (xy 86.8895 82.751578) (xy 86.889501 84.009021) (xy 86.885219 84.0525) (xy 86.902305 84.22599) (xy 86.952912 84.392813) + (xy 87.025954 84.529467) (xy 83.824956 87.730466) (xy 83.791183 87.758183) (xy 83.680589 87.892942) (xy 83.598411 88.046688) + (xy 83.547805 88.213511) (xy 83.535 88.343524) (xy 83.535 88.343531) (xy 83.530719 88.387) (xy 83.535 88.430469) + (xy 83.535 90.061928) (xy 83.12 90.061928) (xy 82.995518 90.074188) (xy 82.87582 90.110498) (xy 82.765506 90.169463) + (xy 82.668815 90.248815) (xy 82.589463 90.345506) (xy 82.530498 90.45582) (xy 82.494188 90.575518) (xy 82.481928 90.7) + (xy 82.481928 93.3) (xy 82.494188 93.424482) (xy 82.530498 93.54418) (xy 82.589463 93.654494) (xy 82.668815 93.751185) + (xy 82.765506 93.830537) (xy 82.87582 93.889502) (xy 82.995518 93.925812) (xy 83.12 93.938072) (xy 85.72 93.938072) + (xy 85.844482 93.925812) (xy 85.96418 93.889502) (xy 86.074494 93.830537) (xy 86.171185 93.751185) (xy 86.250537 93.654494) + (xy 86.309502 93.54418) (xy 86.345812 93.424482) (xy 86.358072 93.3) (xy 86.358072 90.7) (xy 86.345812 90.575518) + (xy 86.309502 90.45582) (xy 86.250537 90.345506) (xy 86.171185 90.248815) (xy 86.074494 90.169463) (xy 85.96418 90.110498) + (xy 85.844482 90.074188) (xy 85.72 90.061928) (xy 85.305 90.061928) (xy 85.305 88.753578) (xy 88.178007 85.880572) + (xy 88.589501 85.880572) (xy 88.762755 85.863508) (xy 88.929351 85.812972) (xy 89.082887 85.730905) (xy 89.217462 85.620462) + (xy 89.2895 85.532684) (xy 89.361538 85.620462) (xy 89.429501 85.676237) (xy 89.429501 85.705791) (xy 89.300038 85.812038) + (xy 89.189595 85.946613) (xy 89.107528 86.100149) (xy 89.056992 86.266745) (xy 89.039928 86.439999) (xy 89.039928 87.090001) + (xy 89.056992 87.263255) (xy 89.107528 87.429851) (xy 89.189595 87.583387) (xy 89.300038 87.717962) (xy 89.387816 87.79) + (xy 89.300038 87.862038) (xy 89.189595 87.996613) (xy 89.107528 88.150149) (xy 89.056992 88.316745) (xy 89.039928 88.489999) + (xy 89.039928 88.901494) (xy 88.904951 89.036471) (xy 88.871184 89.064183) (xy 88.843471 89.097951) (xy 88.843468 89.097954) + (xy 88.76059 89.198941) (xy 88.678412 89.352687) (xy 88.627805 89.51951) (xy 88.610719 89.693) (xy 88.615001 89.736479) + (xy 88.615001 90.27215) (xy 88.583434 90.285225) (xy 88.266509 90.496987) (xy 87.996987 90.766509) (xy 87.785225 91.083434) + (xy 87.639361 91.435581) (xy 87.565 91.809419) (xy 87.565 92.190581) (xy 87.639361 92.564419) (xy 87.785225 92.916566) + (xy 87.996987 93.233491) (xy 88.266509 93.503013) (xy 88.583434 93.714775) (xy 88.935581 93.860639) (xy 89.309419 93.935) + (xy 89.690581 93.935) (xy 90.064419 93.860639) (xy 90.416566 93.714775) (xy 90.733491 93.503013) (xy 91.003013 93.233491) + (xy 91.214775 92.916566) (xy 91.360639 92.564419) (xy 91.416069 92.28575) (xy 98.565 92.28575) (xy 98.565 93.362542) + (xy 98.589403 93.485223) (xy 98.63727 93.600785) (xy 98.706763 93.704789) (xy 98.795211 93.793237) (xy 98.899215 93.86273) + (xy 99.014777 93.910597) (xy 99.137458 93.935) (xy 100.21425 93.935) (xy 100.373 93.77625) (xy 100.373 92.127) + (xy 100.627 92.127) (xy 100.627 93.77625) (xy 100.78575 93.935) (xy 101.862542 93.935) (xy 101.985223 93.910597) + (xy 102.100785 93.86273) (xy 102.204789 93.793237) (xy 102.293237 93.704789) (xy 102.36273 93.600785) (xy 102.410597 93.485223) + (xy 102.435 93.362542) (xy 102.435 92.28575) (xy 102.27625 92.127) (xy 100.627 92.127) (xy 100.373 92.127) + (xy 98.72375 92.127) (xy 98.565 92.28575) (xy 91.416069 92.28575) (xy 91.435 92.190581) (xy 91.435 91.809419) + (xy 91.360639 91.435581) (xy 91.214775 91.083434) (xy 91.003013 90.766509) (xy 90.873962 90.637458) (xy 98.565 90.637458) + (xy 98.565 91.71425) (xy 98.72375 91.873) (xy 100.373 91.873) (xy 100.373 90.22375) (xy 100.627 90.22375) + (xy 100.627 91.873) (xy 102.27625 91.873) (xy 102.435 91.71425) (xy 102.435 90.637458) (xy 102.410597 90.514777) + (xy 102.36273 90.399215) (xy 102.293237 90.295211) (xy 102.204789 90.206763) (xy 102.100785 90.13727) (xy 101.985223 90.089403) + (xy 101.862542 90.065) (xy 100.78575 90.065) (xy 100.627 90.22375) (xy 100.373 90.22375) (xy 100.21425 90.065) + (xy 99.137458 90.065) (xy 99.014777 90.089403) (xy 98.899215 90.13727) (xy 98.795211 90.206763) (xy 98.706763 90.295211) + (xy 98.63727 90.399215) (xy 98.589403 90.514777) (xy 98.565 90.637458) (xy 90.873962 90.637458) (xy 90.733491 90.496987) + (xy 90.416566 90.285225) (xy 90.385 90.27215) (xy 90.385 90.059578) (xy 90.416506 90.028072) (xy 90.828001 90.028072) + (xy 91.001255 90.011008) (xy 91.167851 89.960472) (xy 91.321387 89.878405) (xy 91.455962 89.767962) (xy 91.566405 89.633387) + (xy 91.648472 89.479851) (xy 91.699008 89.313255) (xy 91.716072 89.140001) (xy 91.716072 88.489999) (xy 91.699008 88.316745) + (xy 91.648472 88.150149) (xy 91.566405 87.996613) (xy 91.455962 87.862038) (xy 91.368184 87.79) (xy 91.455962 87.717962) + (xy 91.566405 87.583387) (xy 91.648472 87.429851) (xy 91.699008 87.263255) (xy 91.716072 87.090001) (xy 91.716072 86.439999) + (xy 91.699008 86.266745) (xy 91.648472 86.100149) (xy 91.566405 85.946613) (xy 91.455962 85.812038) (xy 91.321387 85.701595) + (xy 91.228863 85.65214) (xy 91.267462 85.620462) (xy 91.377905 85.485887) (xy 91.459972 85.332351) (xy 91.510508 85.165755) + (xy 91.527572 84.992501) (xy 91.527572 84.092499) (xy 91.510508 83.919245) (xy 91.459972 83.752649) (xy 91.377905 83.599113) + (xy 91.267462 83.464538) (xy 91.1995 83.408763) (xy 91.1995 83.051201) (xy 91.238982 83.047312) (xy 91.35868 83.011002) + (xy 91.468994 82.952037) (xy 91.565685 82.872685) (xy 91.645037 82.775994) (xy 91.704002 82.66568) (xy 91.740312 82.545982) + (xy 91.752572 82.4215) (xy 91.752572 81.779872) (xy 94.765 81.779872) (xy 94.765 82.220128) (xy 94.85089 82.651925) + (xy 95.019369 83.058669) (xy 95.263962 83.424729) (xy 95.575271 83.736038) (xy 95.941331 83.980631) (xy 96.348075 84.14911) + (xy 96.779872 84.235) (xy 97.220128 84.235) (xy 97.651925 84.14911) (xy 98.058669 83.980631) (xy 98.424729 83.736038) + (xy 98.736038 83.424729) (xy 98.980631 83.058669) (xy 99.14911 82.651925) (xy 99.235 82.220128) (xy 99.235 81.779872) + (xy 99.14911 81.348075) (xy 98.980631 80.941331) (xy 98.736038 80.575271) (xy 98.424729 80.263962) (xy 98.058669 80.019369) + (xy 97.651925 79.85089) (xy 97.220128 79.765) (xy 96.779872 79.765) (xy 96.348075 79.85089) (xy 95.941331 80.019369) + (xy 95.575271 80.263962) (xy 95.263962 80.575271) (xy 95.019369 80.941331) (xy 94.85089 81.348075) (xy 94.765 81.779872) + (xy 91.752572 81.779872) (xy 91.752572 80.8215) (xy 91.740312 80.697018) (xy 91.704002 80.57732) (xy 91.645037 80.467006) + (xy 91.565685 80.370315) (xy 91.468994 80.290963) (xy 91.35868 80.231998) (xy 91.238982 80.195688) (xy 91.1145 80.183428) + (xy 89.5145 80.183428) (xy 89.390018 80.195688) (xy 89.27032 80.231998) (xy 89.160006 80.290963) (xy 89.063315 80.370315) + (xy 88.983963 80.467006) (xy 88.924998 80.57732) (xy 88.888688 80.697018) (xy 88.886919 80.714982) (xy 88.794108 80.601892) + (xy 88.575601 80.422568) (xy 88.326308 80.289318) (xy 88.055809 80.207264) (xy 87.844992 80.1865) (xy 87.704008 80.1865) + (xy 87.493191 80.207264) (xy 87.222692 80.289318) (xy 86.973399 80.422568) (xy 86.754892 80.601892) (xy 86.719572 80.64493) + (xy 86.719572 80.028499) (xy 86.702508 79.855245) (xy 86.651972 79.688649) (xy 86.596838 79.5855) (xy 91.731531 79.5855) + (xy 91.775 79.589781) (xy 91.818469 79.5855) (xy 91.818477 79.5855) (xy 91.94849 79.572695) (xy 92.115313 79.522089) + (xy 92.269059 79.439911) (xy 92.403817 79.329317) (xy 92.431534 79.295544) (xy 95.221329 76.50575) (xy 105.908898 76.50575) + (xy 105.97135 76.524695) (xy 106.101363 76.5375) (xy 106.101373 76.5375) (xy 106.135141 76.540826) (xy 106.322614 76.728299) + (xy 106.524208 76.863) (xy 106.228435 76.863) (xy 106.175994 76.819963) (xy 106.06568 76.760998) (xy 105.945982 76.724688) + (xy 105.8215 76.712428) (xy 103.9215 76.712428) (xy 103.797018 76.724688) (xy 103.67732 76.760998) (xy 103.567006 76.819963) + (xy 103.470315 76.899315) (xy 103.390963 76.996006) (xy 103.331998 77.10632) (xy 103.295688 77.226018) (xy 103.283428 77.3505) + (xy 103.283428 77.862405) (xy 103.272685 77.849315) (xy 103.175994 77.769963) (xy 103.06568 77.710998) (xy 102.945982 77.674688) + (xy 102.8215 77.662428) (xy 100.9215 77.662428) (xy 100.797018 77.674688) (xy 100.67732 77.710998) (xy 100.567006 77.769963) + (xy 100.470315 77.849315) (xy 100.390963 77.946006) (xy 100.331998 78.05632) (xy 100.295688 78.176018) (xy 100.283428 78.3005) + (xy 100.283428 79.1005) (xy 100.295688 79.224982) (xy 100.331998 79.34468) (xy 100.390963 79.454994) (xy 100.470315 79.551685) + (xy 100.567006 79.631037) (xy 100.67732 79.690002) (xy 100.797018 79.726312) (xy 100.9215 79.738572) (xy 100.9865 79.738572) + (xy 100.9865 80.18103) (xy 100.982219 80.2245) (xy 100.9865 80.267969) (xy 100.9865 80.267976) (xy 100.999305 80.397989) + (xy 101.049911 80.564812) (xy 101.132089 80.718558) (xy 101.242683 80.853317) (xy 101.276456 80.881034) (xy 104.669501 84.27408) + (xy 104.6695 90.092554) (xy 104.665219 90.136023) (xy 104.6695 90.179492) (xy 104.6695 90.179499) (xy 104.679267 90.278667) + (xy 104.663434 90.285225) (xy 104.346509 90.496987) (xy 104.076987 90.766509) (xy 103.865225 91.083434) (xy 103.719361 91.435581) + (xy 103.645 91.809419) (xy 103.645 92.190581) (xy 103.719361 92.564419) (xy 103.865225 92.916566) (xy 104.076987 93.233491) + (xy 104.346509 93.503013) (xy 104.663434 93.714775) (xy 105.015581 93.860639) (xy 105.389419 93.935) (xy 105.770581 93.935) + (xy 106.144419 93.860639) (xy 106.496566 93.714775) (xy 106.813491 93.503013) (xy 107.083013 93.233491) (xy 107.294775 92.916566) + (xy 107.440639 92.564419) (xy 107.515 92.190581) (xy 107.515 91.809419) (xy 107.440639 91.435581) (xy 107.294775 91.083434) + (xy 107.083013 90.766509) (xy 106.813491 90.496987) (xy 106.496566 90.285225) (xy 106.465 90.27215) (xy 106.465 90.204988) + (xy 106.469281 90.161522) (xy 106.465 90.118056) (xy 106.465 90.118046) (xy 106.452195 89.988033) (xy 106.4395 89.946184) + (xy 106.4395 84.10175) (xy 106.6035 84.10175) (xy 106.6035 84.403542) (xy 106.627903 84.526223) (xy 106.67577 84.641785) + (xy 106.745263 84.745789) (xy 106.833711 84.834237) (xy 106.937715 84.90373) (xy 107.053277 84.951597) (xy 107.175958 84.976) + (xy 107.42775 84.976) (xy 107.5865 84.81725) (xy 107.5865 83.943) (xy 107.8405 83.943) (xy 107.8405 84.81725) + (xy 107.99925 84.976) (xy 108.251042 84.976) (xy 108.373723 84.951597) (xy 108.489285 84.90373) (xy 108.593289 84.834237) + (xy 108.681737 84.745789) (xy 108.75123 84.641785) (xy 108.799097 84.526223) (xy 108.8235 84.403542) (xy 108.8235 84.10175) + (xy 108.66475 83.943) (xy 107.8405 83.943) (xy 107.5865 83.943) (xy 106.76225 83.943) (xy 106.6035 84.10175) + (xy 106.4395 84.10175) (xy 106.4395 83.950969) (xy 106.443781 83.9075) (xy 106.4395 83.864031) (xy 106.4395 83.864023) + (xy 106.426695 83.73401) (xy 106.400092 83.646313) (xy 106.376089 83.567186) (xy 106.293911 83.413441) (xy 106.211032 83.312453) + (xy 106.21103 83.312451) (xy 106.183317 83.278683) (xy 106.149549 83.25097) (xy 102.7565 79.857922) (xy 102.7565 79.738572) + (xy 102.8215 79.738572) (xy 102.945982 79.726312) (xy 103.06568 79.690002) (xy 103.175994 79.631037) (xy 103.272685 79.551685) + (xy 103.283428 79.538595) (xy 103.283428 80.0505) (xy 103.295688 80.174982) (xy 103.331998 80.29468) (xy 103.390963 80.404994) + (xy 103.470315 80.501685) (xy 103.567006 80.581037) (xy 103.67732 80.640002) (xy 103.797018 80.676312) (xy 103.9215 80.688572) + (xy 105.8215 80.688572) (xy 105.945982 80.676312) (xy 106.06568 80.640002) (xy 106.175994 80.581037) (xy 106.231481 80.5355) + (xy 106.48186 80.5355) (xy 106.525095 80.616387) (xy 106.635538 80.750962) (xy 106.770113 80.861405) (xy 106.8285 80.892614) + (xy 106.828501 81.193954) (xy 106.747988 81.292058) (xy 106.667077 81.443433) (xy 106.617252 81.607684) (xy 106.600428 81.7785) + (xy 106.600428 82.3535) (xy 106.617252 82.524316) (xy 106.667077 82.688567) (xy 106.747988 82.839942) (xy 106.767616 82.863858) + (xy 106.745263 82.886211) (xy 106.67577 82.990215) (xy 106.627903 83.105777) (xy 106.6035 83.228458) (xy 106.6035 83.53025) + (xy 106.76225 83.689) (xy 107.5865 83.689) (xy 107.5865 83.669) (xy 107.8405 83.669) (xy 107.8405 83.689) + (xy 108.66475 83.689) (xy 108.8235 83.53025) (xy 108.8235 83.228458) (xy 108.799097 83.105777) (xy 108.75123 82.990215) + (xy 108.681737 82.886211) (xy 108.659384 82.863858) (xy 108.679012 82.839942) (xy 108.759923 82.688567) (xy 108.809748 82.524316) + (xy 108.826572 82.3535) (xy 108.826572 81.7785) (xy 108.809748 81.607684) (xy 108.759923 81.443433) (xy 108.679012 81.292058) + (xy 108.5985 81.193954) (xy 108.5985 80.892614) (xy 108.656887 80.861405) (xy 108.791462 80.750962) (xy 108.901905 80.616387) + (xy 108.983972 80.462851) (xy 109.034508 80.296255) (xy 109.051572 80.123001) (xy 109.051572 79.472999) (xy 109.034508 79.299745) + (xy 109.008966 79.215545) (xy 109.305001 79.51158) (xy 109.305 82.497531) (xy 109.300719 82.541) (xy 109.305 82.584469) + (xy 109.305 82.584476) (xy 109.312447 82.660089) (xy 109.317805 82.71449) (xy 109.326902 82.744477) (xy 109.368411 82.881312) + (xy 109.450589 83.035058) (xy 109.561183 83.169817) (xy 109.594956 83.197534) (xy 111.61597 85.218549) (xy 111.643683 85.252317) + (xy 111.677451 85.28003) (xy 111.677453 85.280032) (xy 111.754133 85.342962) (xy 111.802028 85.500851) (xy 111.884095 85.654387) + (xy 111.994538 85.788962) (xy 112.129113 85.899405) (xy 112.282649 85.981472) (xy 112.449245 86.032008) (xy 112.622499 86.049072) + (xy 113.472501 86.049072) (xy 113.645755 86.032008) (xy 113.812351 85.981472) (xy 113.965887 85.899405) (xy 114.100462 85.788962) + (xy 114.125462 85.7585) (xy 114.533749 85.7585) (xy 114.5895 85.763991) (xy 114.645251 85.7585) (xy 114.645252 85.7585) + (xy 114.811999 85.742077) (xy 115.025947 85.677176) (xy 115.223123 85.571784) (xy 115.395949 85.429949) (xy 115.431496 85.386635) + (xy 117.490132 83.328) (xy 118.476713 83.328) (xy 118.479498 83.33718) (xy 118.538463 83.447494) (xy 118.617815 83.544185) + (xy 118.714506 83.623537) (xy 118.82482 83.682502) (xy 118.944518 83.718812) (xy 119.069 83.731072) (xy 120.534 83.731072) + (xy 120.534001 89.463867) (xy 120.221572 89.776297) (xy 120.221572 88.3195) (xy 120.209312 88.195018) (xy 120.173002 88.07532) + (xy 120.114037 87.965006) (xy 120.034685 87.868315) (xy 119.937994 87.788963) (xy 119.82768 87.729998) (xy 119.707982 87.693688) + (xy 119.5835 87.681428) (xy 116.6835 87.681428) (xy 116.559018 87.693688) (xy 116.43932 87.729998) (xy 116.329006 87.788963) + (xy 116.232315 87.868315) (xy 116.152963 87.965006) (xy 116.093998 88.07532) (xy 116.057688 88.195018) (xy 116.045428 88.3195) + (xy 116.045428 89.8845) (xy 114.985572 89.8845) (xy 114.985572 89.7195) (xy 114.973312 89.595018) (xy 114.937002 89.47532) + (xy 114.878037 89.365006) (xy 114.798685 89.268315) (xy 114.701994 89.188963) (xy 114.59168 89.129998) (xy 114.471982 89.093688) + (xy 114.3475 89.081428) (xy 111.7475 89.081428) (xy 111.623018 89.093688) (xy 111.50332 89.129998) (xy 111.393006 89.188963) + (xy 111.296315 89.268315) (xy 111.216963 89.365006) (xy 111.157998 89.47532) (xy 111.121688 89.595018) (xy 111.109428 89.7195) + (xy 111.109428 92.3195) (xy 111.121688 92.443982) (xy 111.157998 92.56368) (xy 111.216963 92.673994) (xy 111.296315 92.770685) + (xy 111.393006 92.850037) (xy 111.50332 92.909002) (xy 111.623018 92.945312) (xy 111.7475 92.957572) (xy 114.3475 92.957572) + (xy 114.471982 92.945312) (xy 114.59168 92.909002) (xy 114.701994 92.850037) (xy 114.798685 92.770685) (xy 114.878037 92.673994) + (xy 114.937002 92.56368) (xy 114.973312 92.443982) (xy 114.985572 92.3195) (xy 114.985572 92.1545) (xy 116.045428 92.1545) + (xy 116.045428 93.7195) (xy 116.057688 93.843982) (xy 116.093998 93.96368) (xy 116.152963 94.073994) (xy 116.232315 94.170685) + (xy 116.329006 94.250037) (xy 116.43932 94.309002) (xy 116.559018 94.345312) (xy 116.6835 94.357572) (xy 119.5835 94.357572) + (xy 119.707982 94.345312) (xy 119.82768 94.309002) (xy 119.937994 94.250037) (xy 120.034685 94.170685) (xy 120.114037 94.073994) + (xy 120.173002 93.96368) (xy 120.209312 93.843982) (xy 120.221572 93.7195) (xy 120.221572 92.1545) (xy 120.527749 92.1545) + (xy 120.5835 92.159991) (xy 120.639251 92.1545) (xy 120.639252 92.1545) (xy 120.805999 92.138077) (xy 121.019947 92.073176) + (xy 121.217123 91.967784) (xy 121.389949 91.825949) (xy 121.425496 91.782636) (xy 122.43214 90.775992) (xy 122.475449 90.740449) + (xy 122.617284 90.567623) (xy 122.722676 90.370447) (xy 122.787577 90.156499) (xy 122.804 89.989752) (xy 122.809491 89.934) + (xy 122.804 89.878248) (xy 122.804 83.613633) (xy 123.004259 83.684041) (xy 123.242 83.563992) (xy 123.242 82.32) + (xy 123.222 82.32) (xy 123.222 82.066) (xy 123.242 82.066) (xy 123.242 80.822008) (xy 123.004259 80.701959) + (xy 122.804 80.772367) (xy 122.804 79.529634) (xy 122.951481 79.349927) (xy 123.094017 79.083261) (xy 123.18179 78.793913) + (xy 123.211427 78.493) (xy 123.18179 78.192087) (xy 123.094017 77.902739) (xy 122.951481 77.636073) (xy 122.759661 77.402339) + (xy 122.525927 77.210519) (xy 122.259261 77.067983) (xy 121.969913 76.98021) (xy 121.744408 76.958) (xy 121.593592 76.958) + (xy 121.368087 76.98021) (xy 121.078739 77.067983) (xy 120.812073 77.210519) (xy 120.578339 77.402339) (xy 120.386519 77.636073) + (xy 120.243983 77.902739) (xy 120.15621 78.192087) (xy 120.126573 78.493) (xy 120.15621 78.793913) (xy 120.243983 79.083261) + (xy 120.386519 79.349927) (xy 120.534 79.529634) (xy 120.534 80.654928) (xy 119.069 80.654928) (xy 118.944518 80.667188) + (xy 118.82482 80.703498) (xy 118.714506 80.762463) (xy 118.617815 80.841815) (xy 118.538463 80.938506) (xy 118.479498 81.04882) + (xy 118.476713 81.058) (xy 118.146969 81.058) (xy 118.158 81.002542) (xy 118.158 80.70075) (xy 117.99925 80.542) + (xy 117.175 80.542) (xy 117.175 80.562) (xy 116.921 80.562) (xy 116.921 80.542) (xy 116.09675 80.542) + (xy 115.938 80.70075) (xy 115.938 81.002542) (xy 115.962403 81.125223) (xy 116.01027 81.240785) (xy 116.079763 81.344789) + (xy 116.102116 81.367142) (xy 116.082488 81.391058) (xy 116.001577 81.542433) (xy 115.973771 81.634097) (xy 114.122715 83.485154) + (xy 114.100462 83.458038) (xy 113.965887 83.347595) (xy 113.812351 83.265528) (xy 113.645755 83.214992) (xy 113.472501 83.197928) + (xy 112.622499 83.197928) (xy 112.449245 83.214992) (xy 112.282649 83.265528) (xy 112.206702 83.306123) (xy 111.075 82.174422) + (xy 111.075 82.03425) (xy 111.7375 82.03425) (xy 111.7375 82.598542) (xy 111.761903 82.721223) (xy 111.80977 82.836785) + (xy 111.879263 82.940789) (xy 111.967711 83.029237) (xy 112.071715 83.09873) (xy 112.187277 83.146597) (xy 112.309958 83.171) + (xy 112.76175 83.171) (xy 112.9205 83.01225) (xy 112.9205 81.8755) (xy 113.1745 81.8755) (xy 113.1745 83.01225) + (xy 113.33325 83.171) (xy 113.785042 83.171) (xy 113.907723 83.146597) (xy 114.023285 83.09873) (xy 114.127289 83.029237) + (xy 114.215737 82.940789) (xy 114.28523 82.836785) (xy 114.333097 82.721223) (xy 114.3575 82.598542) (xy 114.3575 82.03425) + (xy 114.19875 81.8755) (xy 113.1745 81.8755) (xy 112.9205 81.8755) (xy 111.89625 81.8755) (xy 111.7375 82.03425) + (xy 111.075 82.03425) (xy 111.075 80.898458) (xy 111.7375 80.898458) (xy 111.7375 81.46275) (xy 111.89625 81.6215) + (xy 112.9205 81.6215) (xy 112.9205 80.48475) (xy 113.1745 80.48475) (xy 113.1745 81.6215) (xy 114.19875 81.6215) + (xy 114.3575 81.46275) (xy 114.3575 80.898458) (xy 114.333097 80.775777) (xy 114.28523 80.660215) (xy 114.215737 80.556211) + (xy 114.127289 80.467763) (xy 114.023285 80.39827) (xy 113.907723 80.350403) (xy 113.785042 80.326) (xy 113.33325 80.326) + (xy 113.1745 80.48475) (xy 112.9205 80.48475) (xy 112.76175 80.326) (xy 112.309958 80.326) (xy 112.187277 80.350403) + (xy 112.071715 80.39827) (xy 111.967711 80.467763) (xy 111.879263 80.556211) (xy 111.80977 80.660215) (xy 111.761903 80.775777) + (xy 111.7375 80.898458) (xy 111.075 80.898458) (xy 111.075 79.188465) (xy 111.079281 79.144999) (xy 111.075 79.101533) + (xy 111.075 79.101523) (xy 111.062195 78.97151) (xy 111.011589 78.804687) (xy 110.980747 78.746985) (xy 111.160307 78.746985) + (xy 111.279967 79.106944) (xy 111.467552 79.436642) (xy 111.715854 79.723409) (xy 112.01533 79.956225) (xy 112.354472 80.126142) + (xy 112.620016 80.206689) (xy 112.9205 80.091204) (xy 112.9205 78.4465) (xy 113.1745 78.4465) (xy 113.1745 80.091204) + (xy 113.474984 80.206689) (xy 113.740528 80.126142) (xy 114.07967 79.956225) (xy 114.245305 79.827458) (xy 115.938 79.827458) + (xy 115.938 80.12925) (xy 116.09675 80.288) (xy 116.921 80.288) (xy 116.921 79.41375) (xy 117.175 79.41375) + (xy 117.175 80.288) (xy 117.99925 80.288) (xy 118.158 80.12925) (xy 118.158 79.827458) (xy 118.133597 79.704777) + (xy 118.08573 79.589215) (xy 118.016237 79.485211) (xy 117.927789 79.396763) (xy 117.823785 79.32727) (xy 117.708223 79.279403) + (xy 117.585542 79.255) (xy 117.33375 79.255) (xy 117.175 79.41375) (xy 116.921 79.41375) (xy 116.76225 79.255) + (xy 116.510458 79.255) (xy 116.387777 79.279403) (xy 116.272215 79.32727) (xy 116.168211 79.396763) (xy 116.079763 79.485211) + (xy 116.01027 79.589215) (xy 115.962403 79.704777) (xy 115.938 79.827458) (xy 114.245305 79.827458) (xy 114.379146 79.723409) + (xy 114.627448 79.436642) (xy 114.815033 79.106944) (xy 114.934693 78.746985) (xy 114.819582 78.4465) (xy 113.1745 78.4465) + (xy 112.9205 78.4465) (xy 111.275418 78.4465) (xy 111.160307 78.746985) (xy 110.980747 78.746985) (xy 110.929411 78.650941) + (xy 110.875235 78.584928) (xy 110.846532 78.549953) (xy 110.84653 78.549951) (xy 110.818817 78.516183) (xy 110.785049 78.48847) + (xy 110.188594 77.892015) (xy 111.160307 77.892015) (xy 111.275418 78.1925) (xy 112.9205 78.1925) (xy 112.9205 76.547796) + (xy 113.1745 76.547796) (xy 113.1745 78.1925) (xy 114.819582 78.1925) (xy 114.934693 77.892015) (xy 114.815033 77.532056) + (xy 114.627448 77.202358) (xy 114.379146 76.915591) (xy 114.07967 76.682775) (xy 113.740528 76.512858) (xy 113.474984 76.432311) + (xy 113.1745 76.547796) (xy 112.9205 76.547796) (xy 112.620016 76.432311) (xy 112.354472 76.512858) (xy 112.01533 76.682775) + (xy 111.715854 76.915591) (xy 111.467552 77.202358) (xy 111.279967 77.532056) (xy 111.160307 77.892015) (xy 110.188594 77.892015) + (xy 109.449534 77.152956) (xy 109.421817 77.119183) (xy 109.287059 77.008589) (xy 109.133313 76.926411) (xy 108.96649 76.875805) + (xy 108.848183 76.864153) (xy 108.791462 76.795038) (xy 108.656887 76.684595) (xy 108.503351 76.602528) (xy 108.336755 76.551992) + (xy 108.271154 76.545531) (xy 108.281299 76.535386) (xy 108.432871 76.308543) (xy 108.537275 76.056489) (xy 108.584964 75.816743) + (xy 108.82471 75.769054) (xy 109.076764 75.66465) (xy 109.303607 75.513078) (xy 109.49652 75.320165) (xy 109.648092 75.093322) + (xy 109.752496 74.841268) (xy 109.805721 74.57369) (xy 109.805721 74.300868) (xy 109.752496 74.03329) (xy 109.648092 73.781236) + (xy 109.49652 73.554393) (xy 109.303607 73.36148) (xy 109.076764 73.209908) (xy 108.82471 73.105504) (xy 108.557132 73.052279) + (xy 108.28431 73.052279) (xy 108.016732 73.105504) (xy 107.764678 73.209908) (xy 107.537835 73.36148) (xy 107.347036 73.552279) + (xy 106.36869 73.552279) (xy 106.325221 73.547998) (xy 106.281752 73.552279) (xy 106.281744 73.552279) (xy 106.151731 73.565084) + (xy 105.984908 73.61569) (xy 105.831162 73.697868) (xy 105.696404 73.808462) (xy 105.691038 73.815) (xy 94.548965 73.815) + (xy 94.505499 73.810719) (xy 94.462033 73.815) (xy 94.462023 73.815) (xy 94.33201 73.827805) (xy 94.165187 73.878411) + (xy 94.011441 73.960589) (xy 94.011439 73.96059) (xy 94.01144 73.96059) (xy 93.910453 74.043468) (xy 93.910451 74.04347) + (xy 93.876683 74.071183) (xy 93.84897 74.104951) (xy 91.027422 76.9265) (xy 80.261465 76.9265) (xy 80.217999 76.922219) + (xy 80.174533 76.9265) (xy 80.174523 76.9265) (xy 80.04451 76.939305) (xy 79.877687 76.989911) (xy 79.723941 77.072089) + (xy 79.700328 77.091468) (xy 79.622953 77.154968) (xy 79.622951 77.15497) (xy 79.589183 77.182683) (xy 79.56147 77.216451) + (xy 78.327422 78.4505) (xy 69.402969 78.4505) (xy 69.3595 78.446219) (xy 69.316031 78.4505) (xy 69.316023 78.4505) + (xy 69.18601 78.463305) (xy 69.019187 78.513911) (xy 68.91502 78.569589) (xy 68.865441 78.596089) (xy 68.764453 78.678968) + (xy 68.764451 78.67897) (xy 68.730683 78.706683) (xy 68.70297 78.740451) (xy 67.987494 79.455928) (xy 67.575999 79.455928) + (xy 67.402745 79.472992) (xy 67.236149 79.523528) (xy 67.082613 79.605595) (xy 66.948038 79.716038) (xy 66.892263 79.784) + (xy 58.417469 79.784) (xy 58.374 79.779719) (xy 58.330531 79.784) (xy 58.330523 79.784) (xy 58.20051 79.796805) + (xy 58.033687 79.847411) (xy 57.964466 79.88441) (xy 57.879941 79.929589) (xy 57.778953 80.012468) (xy 57.778951 80.01247) + (xy 57.745183 80.040183) (xy 57.71747 80.073951) (xy 56.769296 81.022125) (xy 56.666492 81.012) (xy 56.525508 81.012) + (xy 56.314691 81.032764) (xy 56.044192 81.114818) (xy 55.794899 81.248068) (xy 55.576392 81.427392) (xy 55.397068 81.645899) + (xy 55.263818 81.895192) (xy 55.181764 82.165691) (xy 55.154057 82.447) (xy 48.16 82.447) (xy 48.16 74.35054) + (xy 86.382591 74.35054) (xy 86.47743 74.615381) (xy 86.622115 74.856631) (xy 86.811086 75.065019) (xy 87.03708 75.232537) + (xy 87.291413 75.352746) (xy 87.425461 75.393404) (xy 87.6475 75.271415) (xy 87.6475 74.1285) (xy 86.503876 74.1285) + (xy 86.382591 74.35054) (xy 48.16 74.35054) (xy 48.16 73.65246) (xy 86.382591 73.65246) (xy 86.503876 73.8745) + (xy 87.6475 73.8745) (xy 87.6475 72.731585) (xy 87.425461 72.609596) (xy 87.291413 72.650254) (xy 87.03708 72.770463) + (xy 86.811086 72.937981) (xy 86.622115 73.146369) (xy 86.47743 73.387619) (xy 86.382591 73.65246) (xy 48.16 73.65246) + (xy 48.16 67.48005) (xy 55.1812 67.48005) (xy 55.1812 68.256842) (xy 55.205603 68.379523) (xy 55.25347 68.495085) + (xy 55.322963 68.599089) (xy 55.411411 68.687537) (xy 55.515415 68.75703) (xy 55.630977 68.804897) (xy 55.753658 68.8293) + (xy 57.53045 68.8293) (xy 57.6892 68.67055) (xy 57.6892 67.3213) (xy 57.9432 67.3213) (xy 57.9432 68.67055) + (xy 58.10195 68.8293) (xy 59.878742 68.8293) (xy 60.001423 68.804897) (xy 60.116985 68.75703) (xy 60.220989 68.687537) + (xy 60.309437 68.599089) (xy 60.37893 68.495085) (xy 60.426797 68.379523) (xy 60.4512 68.256842) (xy 60.4512 67.48005) + (xy 60.29245 67.3213) (xy 57.9432 67.3213) (xy 57.6892 67.3213) (xy 55.33995 67.3213) (xy 55.1812 67.48005) + (xy 48.16 67.48005) (xy 48.16 53.4943) (xy 55.178128 53.4943) (xy 55.178128 55.4943) (xy 55.190388 55.618782) + (xy 55.226698 55.73848) (xy 55.240499 55.7643) (xy 55.226698 55.79012) (xy 55.190388 55.909818) (xy 55.178128 56.0343) + (xy 55.178128 58.0343) (xy 55.190388 58.158782) (xy 55.226698 58.27848) (xy 55.240499 58.3043) (xy 55.226698 58.33012) + (xy 55.190388 58.449818) (xy 55.178128 58.5743) (xy 55.178128 60.5743) (xy 55.190388 60.698782) (xy 55.226698 60.81848) + (xy 55.240499 60.8443) (xy 55.226698 60.87012) (xy 55.190388 60.989818) (xy 55.178128 61.1143) (xy 55.178128 63.1143) + (xy 55.190388 63.238782) (xy 55.226698 63.35848) (xy 55.240499 63.3843) (xy 55.226698 63.41012) (xy 55.190388 63.529818) + (xy 55.178128 63.6543) (xy 55.178128 65.6543) (xy 55.190388 65.778782) (xy 55.226698 65.89848) (xy 55.240623 65.924531) + (xy 55.205603 66.009077) (xy 55.1812 66.131758) (xy 55.1812 66.90855) (xy 55.33995 67.0673) (xy 57.6892 67.0673) + (xy 57.6892 67.0473) (xy 57.9432 67.0473) (xy 57.9432 67.0673) (xy 60.29245 67.0673) (xy 60.4512 66.90855) + (xy 60.4512 66.131758) (xy 60.426797 66.009077) (xy 60.391777 65.924531) (xy 60.405702 65.89848) (xy 60.442012 65.778782) + (xy 60.454272 65.6543) (xy 60.454272 63.6543) (xy 60.442012 63.529818) (xy 60.405702 63.41012) (xy 60.391901 63.3843) + (xy 60.405702 63.35848) (xy 60.442012 63.238782) (xy 60.454272 63.1143) (xy 60.454272 61.1143) (xy 60.442012 60.989818) + (xy 60.405702 60.87012) (xy 60.391901 60.8443) (xy 60.405702 60.81848) (xy 60.441998 60.698828) (xy 64.3392 60.698828) + (xy 64.3392 60.989772) (xy 64.39596 61.275125) (xy 64.507299 61.543922) (xy 64.668939 61.785833) (xy 64.874667 61.991561) + (xy 65.116578 62.153201) (xy 65.385375 62.26454) (xy 65.670728 62.3213) (xy 65.961672 62.3213) (xy 66.247025 62.26454) + (xy 66.515822 62.153201) (xy 66.757733 61.991561) (xy 66.963461 61.785833) (xy 67.125101 61.543922) (xy 67.23644 61.275125) + (xy 67.2932 60.989772) (xy 67.2932 60.698828) (xy 67.23644 60.413475) (xy 67.125101 60.144678) (xy 66.963461 59.902767) + (xy 66.757733 59.697039) (xy 66.515822 59.535399) (xy 66.247025 59.42406) (xy 65.961672 59.3673) (xy 65.670728 59.3673) + (xy 65.385375 59.42406) (xy 65.116578 59.535399) (xy 64.874667 59.697039) (xy 64.668939 59.902767) (xy 64.507299 60.144678) + (xy 64.39596 60.413475) (xy 64.3392 60.698828) (xy 60.441998 60.698828) (xy 60.442012 60.698782) (xy 60.454272 60.5743) + (xy 60.454272 58.5743) (xy 60.442012 58.449818) (xy 60.405702 58.33012) (xy 60.391901 58.3043) (xy 60.405702 58.27848) + (xy 60.442012 58.158782) (xy 60.454272 58.0343) (xy 60.454272 56.0343) (xy 60.442012 55.909818) (xy 60.405702 55.79012) + (xy 60.391901 55.7643) (xy 60.405702 55.73848) (xy 60.442012 55.618782) (xy 60.454272 55.4943) (xy 60.454272 53.4943) + (xy 71.178128 53.4943) (xy 71.178128 55.4943) (xy 71.190388 55.618782) (xy 71.226698 55.73848) (xy 71.240499 55.7643) + (xy 71.226698 55.79012) (xy 71.190388 55.909818) (xy 71.178128 56.0343) (xy 71.178128 58.0343) (xy 71.190388 58.158782) + (xy 71.226698 58.27848) (xy 71.240499 58.3043) (xy 71.226698 58.33012) (xy 71.190388 58.449818) (xy 71.178128 58.5743) + (xy 71.178128 60.5743) (xy 71.190388 60.698782) (xy 71.226698 60.81848) (xy 71.240623 60.844531) (xy 71.205603 60.929077) + (xy 71.1812 61.051758) (xy 71.1812 61.82855) (xy 71.33995 61.9873) (xy 73.6892 61.9873) (xy 73.6892 61.9673) + (xy 73.9432 61.9673) (xy 73.9432 61.9873) (xy 76.29245 61.9873) (xy 76.403892 61.875858) (xy 80.0034 61.875858) + (xy 80.0034 62.36515) (xy 80.16215 62.5239) (xy 81.3864 62.5239) (xy 81.3864 61.46215) (xy 81.6404 61.46215) + (xy 81.6404 62.5239) (xy 82.86465 62.5239) (xy 83.0234 62.36515) (xy 83.0234 61.875858) (xy 82.998997 61.753177) + (xy 82.95113 61.637615) (xy 82.881637 61.533611) (xy 82.793189 61.445163) (xy 82.689185 61.37567) (xy 82.573623 61.327803) + (xy 82.450942 61.3034) (xy 81.79915 61.3034) (xy 81.6404 61.46215) (xy 81.3864 61.46215) (xy 81.22765 61.3034) + (xy 80.575858 61.3034) (xy 80.453177 61.327803) (xy 80.337615 61.37567) (xy 80.233611 61.445163) (xy 80.145163 61.533611) + (xy 80.07567 61.637615) (xy 80.027803 61.753177) (xy 80.0034 61.875858) (xy 76.403892 61.875858) (xy 76.4512 61.82855) + (xy 76.4512 61.051758) (xy 76.426797 60.929077) (xy 76.391777 60.844531) (xy 76.405702 60.81848) (xy 76.442012 60.698782) + (xy 76.454272 60.5743) (xy 76.454272 60.4593) (xy 77.005543 60.4593) (xy 77.013552 60.540616) (xy 77.063377 60.704867) + (xy 77.144288 60.856242) (xy 77.163916 60.880158) (xy 77.141563 60.902511) (xy 77.07207 61.006515) (xy 77.024203 61.122077) + (xy 76.9998 61.244758) (xy 76.9998 61.54655) (xy 77.15855 61.7053) (xy 77.9828 61.7053) (xy 77.9828 61.6853) + (xy 78.2368 61.6853) (xy 78.2368 61.7053) (xy 79.06105 61.7053) (xy 79.2198 61.54655) (xy 79.2198 61.244758) + (xy 79.195397 61.122077) (xy 79.14753 61.006515) (xy 79.121327 60.9673) (xy 80.576334 60.9673) (xy 80.715146 61.009408) + (xy 80.8884 61.026472) (xy 82.1384 61.026472) (xy 82.311654 61.009408) (xy 82.47825 60.958872) (xy 82.631786 60.876805) + (xy 82.766362 60.766362) (xy 82.876805 60.631786) (xy 82.914694 60.5609) (xy 85.210822 60.5609) (xy 85.7545 61.104579) + (xy 85.7545 61.374411) (xy 85.807725 61.641989) (xy 85.912129 61.894043) (xy 86.063701 62.120886) (xy 86.256614 62.313799) + (xy 86.483457 62.465371) (xy 86.735511 62.569775) (xy 87.003089 62.623) (xy 87.275911 62.623) (xy 87.543489 62.569775) + (xy 87.795543 62.465371) (xy 88.022386 62.313799) (xy 88.215299 62.120886) (xy 88.366871 61.894043) (xy 88.471275 61.641989) + (xy 88.5245 61.374411) (xy 88.5245 61.101589) (xy 88.471275 60.834011) (xy 88.366871 60.581957) (xy 88.215299 60.355114) + (xy 88.022386 60.162201) (xy 87.93971 60.106958) (xy 88.6965 60.106958) (xy 88.6965 60.40875) (xy 88.85525 60.5675) + (xy 89.6795 60.5675) (xy 89.6795 59.69325) (xy 89.9335 59.69325) (xy 89.9335 60.5675) (xy 90.75775 60.5675) + (xy 90.9165 60.40875) (xy 90.9165 60.106958) (xy 90.892097 59.984277) (xy 90.84423 59.868715) (xy 90.774737 59.764711) + (xy 90.686289 59.676263) (xy 90.582285 59.60677) (xy 90.466723 59.558903) (xy 90.344042 59.5345) (xy 90.09225 59.5345) + (xy 89.9335 59.69325) (xy 89.6795 59.69325) (xy 89.52075 59.5345) (xy 89.268958 59.5345) (xy 89.146277 59.558903) + (xy 89.030715 59.60677) (xy 88.926711 59.676263) (xy 88.838263 59.764711) (xy 88.76877 59.868715) (xy 88.720903 59.984277) + (xy 88.6965 60.106958) (xy 87.93971 60.106958) (xy 87.795543 60.010629) (xy 87.543489 59.906225) (xy 87.275911 59.853) + (xy 87.006079 59.853) (xy 86.233932 59.080854) (xy 86.206217 59.047083) (xy 86.071459 58.936489) (xy 85.917713 58.854311) + (xy 85.75089 58.803705) (xy 85.620877 58.7909) (xy 85.620869 58.7909) (xy 85.5774 58.786619) (xy 85.533931 58.7909) + (xy 82.914694 58.7909) (xy 82.876805 58.720014) (xy 82.766362 58.585438) (xy 82.631786 58.474995) (xy 82.5 58.404554) + (xy 82.5 56.50725) (xy 95.3005 56.50725) (xy 95.3005 56.809042) (xy 95.324903 56.931723) (xy 95.37277 57.047285) + (xy 95.393794 57.07875) (xy 95.37277 57.110215) (xy 95.324903 57.225777) (xy 95.3005 57.348458) (xy 95.3005 57.65025) + (xy 95.45925 57.809) (xy 96.2835 57.809) (xy 96.2835 56.3485) (xy 96.5375 56.3485) (xy 96.5375 57.809) + (xy 97.36175 57.809) (xy 97.5205 57.65025) (xy 97.5205 57.348458) (xy 97.496097 57.225777) (xy 97.44823 57.110215) + (xy 97.427206 57.07875) (xy 97.44823 57.047285) (xy 97.496097 56.931723) (xy 97.5205 56.809042) (xy 97.5205 56.50725) + (xy 97.36175 56.3485) (xy 96.5375 56.3485) (xy 96.2835 56.3485) (xy 95.45925 56.3485) (xy 95.3005 56.50725) + (xy 82.5 56.50725) (xy 82.5 53.90375) (xy 91.4195 53.90375) (xy 91.4195 54.770542) (xy 91.443903 54.893223) + (xy 91.49177 55.008785) (xy 91.561263 55.112789) (xy 91.649711 55.201237) (xy 91.753715 55.27073) (xy 91.869277 55.318597) + (xy 91.991958 55.343) (xy 92.56875 55.343) (xy 92.7275 55.18425) (xy 92.7275 53.745) (xy 92.9815 53.745) + (xy 92.9815 55.18425) (xy 93.14025 55.343) (xy 93.717042 55.343) (xy 93.839723 55.318597) (xy 93.955285 55.27073) + (xy 94.059289 55.201237) (xy 94.147737 55.112789) (xy 94.21723 55.008785) (xy 94.265097 54.893223) (xy 94.2895 54.770542) + (xy 94.2895 53.90375) (xy 94.13075 53.745) (xy 92.9815 53.745) (xy 92.7275 53.745) (xy 91.57825 53.745) + (xy 91.4195 53.90375) (xy 82.5 53.90375) (xy 82.5 52.465458) (xy 91.4195 52.465458) (xy 91.4195 53.33225) + (xy 91.57825 53.491) (xy 92.7275 53.491) (xy 92.7275 52.05175) (xy 92.9815 52.05175) (xy 92.9815 53.491) + (xy 94.13075 53.491) (xy 94.2895 53.33225) (xy 94.2895 52.57025) (xy 104.966 52.57025) (xy 104.966 52.822042) + (xy 104.990403 52.944723) (xy 105.03827 53.060285) (xy 105.107763 53.164289) (xy 105.162724 53.21925) (xy 105.157763 53.224211) + (xy 105.08827 53.328215) (xy 105.040403 53.443777) (xy 105.016 53.566458) (xy 105.016 53.86825) (xy 105.17475 54.027) + (xy 105.999 54.027) (xy 105.999 52.4115) (xy 105.12475 52.4115) (xy 104.966 52.57025) (xy 94.2895 52.57025) + (xy 94.2895 52.465458) (xy 94.265097 52.342777) (xy 94.21723 52.227215) (xy 94.147737 52.123211) (xy 94.059289 52.034763) + (xy 93.955285 51.96527) (xy 93.839723 51.917403) (xy 93.717042 51.893) (xy 93.14025 51.893) (xy 92.9815 52.05175) + (xy 92.7275 52.05175) (xy 92.56875 51.893) (xy 91.991958 51.893) (xy 91.869277 51.917403) (xy 91.753715 51.96527) + (xy 91.649711 52.034763) (xy 91.561263 52.123211) (xy 91.49177 52.227215) (xy 91.443903 52.342777) (xy 91.4195 52.465458) + (xy 82.5 52.465458) (xy 82.5 51.453185) (xy 82.690799 51.262386) (xy 82.842371 51.035543) (xy 82.946775 50.783489) + (xy 83 50.515911) (xy 83 50.243089) (xy 82.946775 49.975511) (xy 82.842371 49.723457) (xy 82.690799 49.496614) + (xy 82.497886 49.303701) (xy 82.271043 49.152129) (xy 82.018989 49.047725) (xy 81.751411 48.9945) (xy 81.478589 48.9945) + (xy 81.211011 49.047725) (xy 80.958957 49.152129) (xy 80.732114 49.303701) (xy 80.539201 49.496614) (xy 80.387629 49.723457) + (xy 80.283225 49.975511) (xy 80.23 50.243089) (xy 80.23 50.515911) (xy 80.283225 50.783489) (xy 80.387629 51.035543) + (xy 80.539201 51.262386) (xy 80.73 51.453185) (xy 80.730001 58.340929) (xy 80.715146 58.342392) (xy 80.54855 58.392928) + (xy 80.395014 58.474995) (xy 80.260438 58.585438) (xy 80.149995 58.720014) (xy 80.067928 58.87355) (xy 80.017392 59.040146) + (xy 80.001914 59.1973) (xy 78.984169 59.1973) (xy 78.966423 59.175677) (xy 78.833742 59.066788) (xy 78.682367 58.985877) + (xy 78.518116 58.936052) (xy 78.3473 58.919228) (xy 78.198625 58.919228) (xy 78.095859 58.834889) (xy 77.942113 58.752711) + (xy 77.77529 58.702105) (xy 77.645277 58.6893) (xy 77.645269 58.6893) (xy 77.6018 58.685019) (xy 77.558331 58.6893) + (xy 76.454272 58.6893) (xy 76.454272 58.5743) (xy 76.442012 58.449818) (xy 76.405702 58.33012) (xy 76.391901 58.3043) + (xy 76.405702 58.27848) (xy 76.442012 58.158782) (xy 76.454272 58.0343) (xy 76.454272 56.0343) (xy 76.442012 55.909818) + (xy 76.42541 55.855088) (xy 76.877306 56.306985) (xy 76.790725 56.516011) (xy 76.7375 56.783589) (xy 76.7375 57.056411) + (xy 76.790725 57.323989) (xy 76.895129 57.576043) (xy 77.046701 57.802886) (xy 77.239614 57.995799) (xy 77.466457 58.147371) + (xy 77.718511 58.251775) (xy 77.986089 58.305) (xy 78.258911 58.305) (xy 78.526489 58.251775) (xy 78.778543 58.147371) + (xy 79.005386 57.995799) (xy 79.198299 57.802886) (xy 79.349871 57.576043) (xy 79.454275 57.323989) (xy 79.5075 57.056411) + (xy 79.5075 56.783589) (xy 79.454275 56.516011) (xy 79.349871 56.263957) (xy 79.198299 56.037114) (xy 79.005386 55.844201) + (xy 78.778543 55.692629) (xy 78.763214 55.68628) (xy 78.751317 55.671783) (xy 78.71755 55.644071) (xy 76.972734 53.899256) + (xy 76.945017 53.865483) (xy 76.810259 53.754889) (xy 76.656513 53.672711) (xy 76.48969 53.622105) (xy 76.454272 53.618617) + (xy 76.454272 53.4943) (xy 76.442012 53.369818) (xy 76.405702 53.25012) (xy 76.346737 53.139806) (xy 76.267385 53.043115) + (xy 76.170694 52.963763) (xy 76.06038 52.904798) (xy 75.940682 52.868488) (xy 75.8162 52.856228) (xy 71.8162 52.856228) + (xy 71.691718 52.868488) (xy 71.57202 52.904798) (xy 71.461706 52.963763) (xy 71.365015 53.043115) (xy 71.285663 53.139806) + (xy 71.226698 53.25012) (xy 71.190388 53.369818) (xy 71.178128 53.4943) (xy 60.454272 53.4943) (xy 60.442012 53.369818) + (xy 60.405702 53.25012) (xy 60.346737 53.139806) (xy 60.267385 53.043115) (xy 60.170694 52.963763) (xy 60.06038 52.904798) + (xy 59.940682 52.868488) (xy 59.8162 52.856228) (xy 55.8162 52.856228) (xy 55.691718 52.868488) (xy 55.57202 52.904798) + (xy 55.461706 52.963763) (xy 55.365015 53.043115) (xy 55.285663 53.139806) (xy 55.226698 53.25012) (xy 55.190388 53.369818) + (xy 55.178128 53.4943) (xy 48.16 53.4943) (xy 48.16 46.779872) (xy 49.265 46.779872) (xy 49.265 47.220128) + (xy 49.35089 47.651925) (xy 49.519369 48.058669) (xy 49.763962 48.424729) (xy 50.075271 48.736038) (xy 50.441331 48.980631) + (xy 50.848075 49.14911) (xy 51.279872 49.235) (xy 51.720128 49.235) (xy 52.151925 49.14911) (xy 52.558669 48.980631) + (xy 52.924729 48.736038) (xy 53.236038 48.424729) (xy 53.480631 48.058669) (xy 53.64911 47.651925) (xy 53.735 47.220128) + (xy 53.735 46.779872) (xy 53.64911 46.348075) (xy 53.480631 45.941331) (xy 53.290191 45.656316) (xy 93.796 45.656316) + (xy 93.796 45.958684) (xy 93.854989 46.255243) (xy 93.970701 46.534595) (xy 94.138688 46.786005) (xy 94.352495 46.999812) + (xy 94.603905 47.167799) (xy 94.883257 47.283511) (xy 95.179816 47.3425) (xy 95.482184 47.3425) (xy 95.778743 47.283511) + (xy 96.058095 47.167799) (xy 96.309505 46.999812) (xy 96.375944 46.933373) (xy 96.381498 46.95168) (xy 96.440463 47.061994) + (xy 96.519815 47.158685) (xy 96.616506 47.238037) (xy 96.72682 47.297002) (xy 96.846518 47.333312) (xy 96.971 47.345572) + (xy 98.771 47.345572) (xy 98.895482 47.333312) (xy 99.01518 47.297002) (xy 99.125494 47.238037) (xy 99.222185 47.158685) + (xy 99.301537 47.061994) (xy 99.360502 46.95168) (xy 99.396812 46.831982) (xy 99.409072 46.7075) (xy 99.409072 45.656316) + (xy 100.4 45.656316) (xy 100.4 45.958684) (xy 100.458989 46.255243) (xy 100.574701 46.534595) (xy 100.742688 46.786005) + (xy 100.956495 46.999812) (xy 101.207905 47.167799) (xy 101.487257 47.283511) (xy 101.783816 47.3425) (xy 102.086184 47.3425) + (xy 102.382743 47.283511) (xy 102.662095 47.167799) (xy 102.913505 46.999812) (xy 102.979944 46.933373) (xy 102.985498 46.95168) + (xy 103.044463 47.061994) (xy 103.123815 47.158685) (xy 103.220506 47.238037) (xy 103.33082 47.297002) (xy 103.450518 47.333312) + (xy 103.575 47.345572) (xy 105.375 47.345572) (xy 105.499482 47.333312) (xy 105.61918 47.297002) (xy 105.729494 47.238037) + (xy 105.826185 47.158685) (xy 105.905537 47.061994) (xy 105.964502 46.95168) (xy 106.000812 46.831982) (xy 106.013072 46.7075) + (xy 106.013072 44.9075) (xy 106.000812 44.783018) (xy 105.964502 44.66332) (xy 105.905537 44.553006) (xy 105.826185 44.456315) + (xy 105.729494 44.376963) (xy 105.61918 44.317998) (xy 105.499482 44.281688) (xy 105.375 44.269428) (xy 103.575 44.269428) + (xy 103.450518 44.281688) (xy 103.33082 44.317998) (xy 103.220506 44.376963) (xy 103.123815 44.456315) (xy 103.044463 44.553006) + (xy 102.985498 44.66332) (xy 102.979944 44.681627) (xy 102.913505 44.615188) (xy 102.662095 44.447201) (xy 102.382743 44.331489) + (xy 102.086184 44.2725) (xy 101.783816 44.2725) (xy 101.487257 44.331489) (xy 101.207905 44.447201) (xy 100.956495 44.615188) + (xy 100.742688 44.828995) (xy 100.574701 45.080405) (xy 100.458989 45.359757) (xy 100.4 45.656316) (xy 99.409072 45.656316) + (xy 99.409072 44.9075) (xy 99.396812 44.783018) (xy 99.360502 44.66332) (xy 99.301537 44.553006) (xy 99.222185 44.456315) + (xy 99.125494 44.376963) (xy 99.01518 44.317998) (xy 98.895482 44.281688) (xy 98.771 44.269428) (xy 96.971 44.269428) + (xy 96.846518 44.281688) (xy 96.72682 44.317998) (xy 96.616506 44.376963) (xy 96.519815 44.456315) (xy 96.440463 44.553006) + (xy 96.381498 44.66332) (xy 96.375944 44.681627) (xy 96.309505 44.615188) (xy 96.058095 44.447201) (xy 95.778743 44.331489) + (xy 95.482184 44.2725) (xy 95.179816 44.2725) (xy 94.883257 44.331489) (xy 94.603905 44.447201) (xy 94.352495 44.615188) + (xy 94.138688 44.828995) (xy 93.970701 45.080405) (xy 93.854989 45.359757) (xy 93.796 45.656316) (xy 53.290191 45.656316) + (xy 53.236038 45.575271) (xy 52.924729 45.263962) (xy 52.558669 45.019369) (xy 52.151925 44.85089) (xy 51.720128 44.765) + (xy 51.279872 44.765) (xy 50.848075 44.85089) (xy 50.441331 45.019369) (xy 50.075271 45.263962) (xy 49.763962 45.575271) + (xy 49.519369 45.941331) (xy 49.35089 46.348075) (xy 49.265 46.779872) (xy 48.16 46.779872) (xy 48.16 43.66) + (xy 126.382314 43.66) + ) + ) + (filled_polygon + (pts + (xy 101.7445 60.4405) (xy 101.7645 60.4405) (xy 101.7645 60.6945) (xy 101.7445 60.6945) (xy 101.7445 60.7145) + (xy 101.4905 60.7145) (xy 101.4905 60.6945) (xy 101.4705 60.6945) (xy 101.4705 60.4405) (xy 101.4905 60.4405) + (xy 101.4905 60.4205) (xy 101.7445 60.4205) + ) + ) + (filled_polygon + (pts + (xy 121.608058 59.219012) (xy 121.759433 59.299923) (xy 121.923684 59.349748) (xy 122.0945 59.366572) (xy 122.6695 59.366572) + (xy 122.840316 59.349748) (xy 123.004567 59.299923) (xy 123.155942 59.219012) (xy 123.254046 59.1385) (xy 123.303054 59.1385) + (xy 123.309188 59.200782) (xy 123.317211 59.227231) (xy 123.3 59.313758) (xy 123.3 59.41555) (xy 123.45875 59.5743) + (xy 123.540859 59.5743) (xy 123.580506 59.606837) (xy 123.69082 59.665802) (xy 123.807841 59.7013) (xy 123.69082 59.736798) + (xy 123.580506 59.795763) (xy 123.540859 59.8283) (xy 123.45875 59.8283) (xy 123.3 59.98705) (xy 123.3 60.088842) + (xy 123.317211 60.175369) (xy 123.309188 60.201818) (xy 123.300552 60.2895) (xy 123.254046 60.2895) (xy 123.155942 60.208988) + (xy 123.004567 60.128077) (xy 122.840316 60.078252) (xy 122.6695 60.061428) (xy 122.0945 60.061428) (xy 121.923684 60.078252) + (xy 121.759433 60.128077) (xy 121.608058 60.208988) (xy 121.507 60.291925) (xy 121.405942 60.208988) (xy 121.254567 60.128077) + (xy 121.090316 60.078252) (xy 120.9195 60.061428) (xy 120.3445 60.061428) (xy 120.173684 60.078252) (xy 120.009433 60.128077) + (xy 119.858058 60.208988) (xy 119.759954 60.2895) (xy 118.062278 60.2895) (xy 117.903396 60.130618) (xy 117.802409 60.04774) + (xy 117.648663 59.965562) (xy 117.523636 59.927634) (xy 117.363908 59.767906) (xy 117.390599 59.746001) (xy 117.414401 59.716998) + (xy 117.869351 59.262049) (xy 119.839982 59.262049) (xy 119.883451 59.26633) (xy 119.92692 59.262049) (xy 119.926928 59.262049) + (xy 119.936763 59.26108) (xy 120.009433 59.299923) (xy 120.173684 59.349748) (xy 120.3445 59.366572) (xy 120.9195 59.366572) + (xy 121.090316 59.349748) (xy 121.254567 59.299923) (xy 121.405942 59.219012) (xy 121.507 59.136075) + ) + ) + (filled_polygon + (pts + (xy 116.181711 57.062737) (xy 116.285715 57.13223) (xy 116.401277 57.180097) (xy 116.523958 57.2045) (xy 116.82575 57.2045) + (xy 116.984498 57.045752) (xy 116.984498 57.1152) (xy 116.172499 57.9272) (xy 115.92186 57.9272) (xy 115.918279 57.909198) + (xy 115.920671 57.901313) (xy 115.934372 57.7622) (xy 115.934372 57.6122) (xy 115.920671 57.473087) (xy 115.880093 57.339319) + (xy 115.814198 57.216038) (xy 115.795415 57.193151) (xy 115.819816 57.190748) (xy 115.984067 57.140923) (xy 116.135442 57.060012) + (xy 116.159358 57.040384) + ) + ) + (filled_polygon + (pts + (xy 121.374203 57.163782) (xy 121.374209 57.163787) (xy 121.501466 57.291044) (xy 121.529183 57.324817) (xy 121.546182 57.338768) + (xy 121.507 57.370925) (xy 121.405942 57.287988) (xy 121.254567 57.207077) (xy 121.090316 57.157252) (xy 120.9195 57.140428) + (xy 120.3445 57.140428) (xy 120.333707 57.141491) (xy 120.338 57.119911) (xy 120.338 56.847089) (xy 120.284775 56.579511) + (xy 120.180371 56.327457) (xy 120.028799 56.100614) (xy 119.835886 55.907701) (xy 119.609043 55.756129) (xy 119.356989 55.651725) + (xy 119.089411 55.5985) (xy 118.816589 55.5985) (xy 118.549011 55.651725) (xy 118.296957 55.756129) (xy 118.2715 55.773139) + (xy 118.2715 55.556958) (xy 118.247097 55.434277) (xy 118.19923 55.318715) (xy 118.129737 55.214711) (xy 118.041289 55.126263) + (xy 117.937285 55.05677) (xy 117.821723 55.008903) (xy 117.699042 54.9845) (xy 117.39725 54.9845) (xy 117.2385 55.14325) + (xy 117.2385 55.9675) (xy 117.2585 55.9675) (xy 117.2585 56.2215) (xy 117.2385 56.2215) (xy 117.2385 56.2415) + (xy 116.9845 56.2415) (xy 116.9845 56.2215) (xy 116.9645 56.2215) (xy 116.9645 55.9675) (xy 116.9845 55.9675) + (xy 116.9845 55.14325) (xy 116.82575 54.9845) (xy 116.582221 54.9845) (xy 116.665275 54.783989) (xy 116.7185 54.516411) + (xy 116.7185 54.243589) (xy 116.665275 53.976011) (xy 116.646838 53.9315) (xy 118.141922 53.9315) + ) + ) + ) + (zone (net 1) (net_name GND) (layer B.Cu) (tstamp 5D168E3B) (hatch edge 0.508) + (connect_pads (clearance 0.508)) + (min_thickness 0.254) + (fill yes (arc_segments 32) (thermal_gap 0.508) (thermal_bridge_width 0.508)) + (polygon + (pts + (xy 48 43.5) (xy 142 43.5) (xy 142 97) (xy 48 97) + ) + ) + (filled_polygon + (pts + (xy 99.289087 44.537835) (xy 99.222185 44.456315) (xy 99.125494 44.376963) (xy 99.01518 44.317998) (xy 98.895482 44.281688) + (xy 98.771 44.269428) (xy 96.971 44.269428) (xy 96.846518 44.281688) (xy 96.72682 44.317998) (xy 96.616506 44.376963) + (xy 96.519815 44.456315) (xy 96.440463 44.553006) (xy 96.381498 44.66332) (xy 96.375944 44.681627) (xy 96.309505 44.615188) + (xy 96.058095 44.447201) (xy 95.778743 44.331489) (xy 95.482184 44.2725) (xy 95.179816 44.2725) (xy 94.883257 44.331489) + (xy 94.603905 44.447201) (xy 94.352495 44.615188) (xy 94.138688 44.828995) (xy 93.970701 45.080405) (xy 93.854989 45.359757) + (xy 93.796 45.656316) (xy 93.796 45.958684) (xy 93.854989 46.255243) (xy 93.970701 46.534595) (xy 94.138688 46.786005) + (xy 94.254007 46.901324) (xy 94.221077 46.962933) (xy 94.171252 47.127184) (xy 94.154428 47.298) (xy 94.154428 47.873) + (xy 94.171252 48.043816) (xy 94.221077 48.208067) (xy 94.301988 48.359442) (xy 94.384925 48.4605) (xy 94.301988 48.561558) + (xy 94.221077 48.712933) (xy 94.171252 48.877184) (xy 94.154428 49.048) (xy 94.154428 49.4945) (xy 82.688685 49.4945) + (xy 82.497886 49.303701) (xy 82.271043 49.152129) (xy 82.018989 49.047725) (xy 81.751411 48.9945) (xy 81.478589 48.9945) + (xy 81.211011 49.047725) (xy 80.958957 49.152129) (xy 80.732114 49.303701) (xy 80.539201 49.496614) (xy 80.387629 49.723457) + (xy 80.283225 49.975511) (xy 80.23 50.243089) (xy 80.23 50.515911) (xy 80.283225 50.783489) (xy 80.387629 51.035543) + (xy 80.539201 51.262386) (xy 80.732114 51.455299) (xy 80.958957 51.606871) (xy 81.211011 51.711275) (xy 81.478589 51.7645) + (xy 81.751411 51.7645) (xy 82.018989 51.711275) (xy 82.271043 51.606871) (xy 82.497886 51.455299) (xy 82.688685 51.2645) + (xy 95.097024 51.2645) (xy 95.1405 51.268782) (xy 95.183977 51.2645) (xy 101.764531 51.2645) (xy 101.808 51.268781) + (xy 101.851469 51.2645) (xy 103.274315 51.2645) (xy 103.465114 51.455299) (xy 103.691957 51.606871) (xy 103.944011 51.711275) + (xy 104.211589 51.7645) (xy 104.484411 51.7645) (xy 104.751989 51.711275) (xy 105.004043 51.606871) (xy 105.230886 51.455299) + (xy 105.423799 51.262386) (xy 105.575371 51.035543) (xy 105.679775 50.783489) (xy 105.733 50.515911) (xy 105.733 50.243089) + (xy 105.679775 49.975511) (xy 105.575371 49.723457) (xy 105.423799 49.496614) (xy 105.230886 49.303701) (xy 105.004043 49.152129) + (xy 104.751989 49.047725) (xy 104.484411 48.9945) (xy 104.211589 48.9945) (xy 103.944011 49.047725) (xy 103.691957 49.152129) + (xy 103.465114 49.303701) (xy 103.274315 49.4945) (xy 103.048072 49.4945) (xy 103.048072 49.076) (xy 103.031248 48.905184) + (xy 102.981423 48.740933) (xy 102.900512 48.589558) (xy 102.817575 48.4885) (xy 102.900512 48.387442) (xy 102.981423 48.236067) + (xy 103.031248 48.071816) (xy 103.048072 47.901) (xy 103.048072 47.326) (xy 103.031248 47.155184) (xy 102.981423 46.990933) + (xy 102.960858 46.952459) (xy 102.979944 46.933373) (xy 102.985498 46.95168) (xy 103.044463 47.061994) (xy 103.123815 47.158685) + (xy 103.220506 47.238037) (xy 103.33082 47.297002) (xy 103.450518 47.333312) (xy 103.575 47.345572) (xy 103.599317 47.345572) + (xy 103.602805 47.38099) (xy 103.653412 47.547813) (xy 103.73559 47.701559) (xy 103.818468 47.802546) (xy 103.818471 47.802549) + (xy 103.846184 47.836317) (xy 103.879951 47.86403) (xy 107.4 51.384079) (xy 107.400001 52.767854) (xy 107.4 52.767864) + (xy 107.4 52.798315) (xy 107.209201 52.989114) (xy 107.057629 53.215957) (xy 106.953225 53.468011) (xy 106.9 53.735589) + (xy 106.9 54.008411) (xy 106.953225 54.275989) (xy 107.057629 54.528043) (xy 107.209201 54.754886) (xy 107.402114 54.947799) + (xy 107.628957 55.099371) (xy 107.881011 55.203775) (xy 108.148589 55.257) (xy 108.421411 55.257) (xy 108.688989 55.203775) + (xy 108.941043 55.099371) (xy 109.167886 54.947799) (xy 109.360799 54.754886) (xy 109.512371 54.528043) (xy 109.616775 54.275989) + (xy 109.625594 54.231652) (xy 109.672589 54.241) (xy 109.945411 54.241) (xy 110.212989 54.187775) (xy 110.465043 54.083371) + (xy 110.691886 53.931799) (xy 110.884799 53.738886) (xy 111.036371 53.512043) (xy 111.140775 53.259989) (xy 111.194 52.992411) + (xy 111.194 52.719589) (xy 111.140775 52.452011) (xy 111.036371 52.199957) (xy 110.884799 51.973114) (xy 110.694 51.782315) + (xy 110.694 50.613465) (xy 110.698281 50.569999) (xy 110.694 50.526533) (xy 110.694 50.526523) (xy 110.681195 50.39651) + (xy 110.630589 50.229687) (xy 110.548411 50.075941) (xy 110.474653 49.986067) (xy 110.465532 49.974953) (xy 110.46553 49.974951) + (xy 110.437817 49.941183) (xy 110.404049 49.91347) (xy 107.265 46.774422) (xy 107.265 44.517469) (xy 107.269281 44.474) + (xy 107.265 44.430531) (xy 107.265 44.430523) (xy 107.252195 44.30051) (xy 107.246486 44.281688) (xy 107.222612 44.20299) + (xy 107.201589 44.133687) (xy 107.119411 43.979941) (xy 107.008817 43.845183) (xy 106.975044 43.817466) (xy 106.817578 43.66) + (xy 126.382314 43.66) (xy 126.361629 43.690957) (xy 126.257225 43.943011) (xy 126.224788 44.106079) (xy 125.035859 45.29501) + (xy 124.992551 45.330552) (xy 124.850716 45.503378) (xy 124.794383 45.608771) (xy 124.745323 45.700555) (xy 124.680422 45.914503) + (xy 124.658508 46.137001) (xy 124.664 46.192763) (xy 124.663999 64.357806) (xy 124.656334 64.348466) (xy 124.430214 64.162894) + (xy 124.172234 64.025001) (xy 123.892311 63.940087) (xy 123.67415 63.9186) (xy 123.52825 63.9186) (xy 123.310089 63.940087) + (xy 123.030166 64.025001) (xy 122.772186 64.162894) (xy 122.546066 64.348466) (xy 122.360494 64.574586) (xy 122.3312 64.629391) + (xy 122.301906 64.574586) (xy 122.116334 64.348466) (xy 121.890214 64.162894) (xy 121.632234 64.025001) (xy 121.352311 63.940087) + (xy 121.13415 63.9186) (xy 120.98825 63.9186) (xy 120.770089 63.940087) (xy 120.490166 64.025001) (xy 120.232186 64.162894) + (xy 120.006066 64.348466) (xy 119.983344 64.376153) (xy 119.981797 64.368377) (xy 119.93393 64.252815) (xy 119.864437 64.148811) + (xy 119.775989 64.060363) (xy 119.671985 63.99087) (xy 119.556423 63.943003) (xy 119.433742 63.9186) (xy 118.80695 63.9186) + (xy 118.6482 64.07735) (xy 118.6482 65.2766) (xy 118.6682 65.2766) (xy 118.6682 65.5306) (xy 118.6482 65.5306) + (xy 118.6482 66.72985) (xy 118.80695 66.8886) (xy 119.433742 66.8886) (xy 119.556423 66.864197) (xy 119.671985 66.81633) + (xy 119.775989 66.746837) (xy 119.864437 66.658389) (xy 119.93393 66.554385) (xy 119.981797 66.438823) (xy 119.983344 66.431047) + (xy 120.006066 66.458734) (xy 120.232186 66.644306) (xy 120.490166 66.782199) (xy 120.770089 66.867113) (xy 120.98825 66.8886) + (xy 121.13415 66.8886) (xy 121.352311 66.867113) (xy 121.632234 66.782199) (xy 121.890214 66.644306) (xy 122.116334 66.458734) + (xy 122.301906 66.232614) (xy 122.3312 66.177809) (xy 122.360494 66.232614) (xy 122.546066 66.458734) (xy 122.772186 66.644306) + (xy 123.030166 66.782199) (xy 123.310089 66.867113) (xy 123.52825 66.8886) (xy 123.67415 66.8886) (xy 123.892311 66.867113) + (xy 124.172234 66.782199) (xy 124.430214 66.644306) (xy 124.656334 66.458734) (xy 124.663999 66.449394) (xy 124.663999 67.204948) + (xy 124.645011 67.208725) (xy 124.392957 67.313129) (xy 124.166114 67.464701) (xy 123.973201 67.657614) (xy 123.821629 67.884457) + (xy 123.717225 68.136511) (xy 123.664 68.404089) (xy 123.664 68.676911) (xy 123.717225 68.944489) (xy 123.821629 69.196543) + (xy 123.973201 69.423386) (xy 124.166114 69.616299) (xy 124.392957 69.767871) (xy 124.645011 69.872275) (xy 124.912589 69.9255) + (xy 125.185411 69.9255) (xy 125.452989 69.872275) (xy 125.705043 69.767871) (xy 125.931886 69.616299) (xy 126.124799 69.423386) + (xy 126.276371 69.196543) (xy 126.380775 68.944489) (xy 126.402564 68.834946) (xy 133.153887 68.834946) (xy 133.206358 69.301811) + (xy 133.348903 69.749468) (xy 133.539434 70.105927) (xy 133.880591 70.292003) (xy 135.370595 68.802) (xy 135.729805 68.802) + (xy 137.219809 70.292003) (xy 137.560966 70.105927) (xy 137.776713 69.688591) (xy 137.906896 69.237185) (xy 137.946513 68.769054) + (xy 137.894042 68.302189) (xy 137.751497 67.854532) (xy 137.560966 67.498073) (xy 137.219809 67.311997) (xy 135.729805 68.802) + (xy 135.370595 68.802) (xy 133.880591 67.311997) (xy 133.539434 67.498073) (xy 133.323687 67.915409) (xy 133.193504 68.366815) + (xy 133.153887 68.834946) (xy 126.402564 68.834946) (xy 126.413212 68.781419) (xy 126.562134 68.632497) (xy 126.605448 68.59695) + (xy 126.747283 68.424124) (xy 126.852675 68.226948) (xy 126.917576 68.013) (xy 126.933999 67.846253) (xy 126.933999 67.846252) + (xy 126.93949 67.790501) (xy 126.933999 67.734749) (xy 126.933999 67.132391) (xy 134.060197 67.132391) (xy 135.5502 68.622395) + (xy 137.040203 67.132391) (xy 136.854127 66.791234) (xy 136.436791 66.575487) (xy 135.985385 66.445304) (xy 135.517254 66.405687) + (xy 135.050389 66.458158) (xy 134.602732 66.600703) (xy 134.246273 66.791234) (xy 134.060197 67.132391) (xy 126.933999 67.132391) + (xy 126.933999 63.672279) (xy 127.123457 63.798871) (xy 127.375511 63.903275) (xy 127.643089 63.9565) (xy 127.915911 63.9565) + (xy 128.183489 63.903275) (xy 128.435543 63.798871) (xy 128.662386 63.647299) (xy 128.855299 63.454386) (xy 129.006871 63.227543) + (xy 129.025735 63.182) (xy 129.352128 63.182) (xy 129.352128 64.882) (xy 129.364388 65.006482) (xy 129.400698 65.12618) + (xy 129.459663 65.236494) (xy 129.539015 65.333185) (xy 129.635706 65.412537) (xy 129.74602 65.471502) (xy 129.865718 65.507812) + (xy 129.9902 65.520072) (xy 131.6902 65.520072) (xy 131.814682 65.507812) (xy 131.93438 65.471502) (xy 132.044694 65.412537) + (xy 132.133076 65.340004) (xy 132.333083 65.435371) (xy 132.616611 65.507339) (xy 132.908731 65.522611) (xy 133.198219 65.480599) + (xy 133.473947 65.382919) (xy 133.611357 65.309472) (xy 133.688992 65.060397) (xy 132.8402 64.211605) (xy 132.826058 64.225748) + (xy 132.646453 64.046143) (xy 132.660595 64.032) (xy 133.019805 64.032) (xy 133.868597 64.880792) (xy 134.117672 64.803157) + (xy 134.243571 64.539117) (xy 134.315539 64.255589) (xy 134.330811 63.963469) (xy 134.288799 63.673981) (xy 134.191119 63.398253) + (xy 134.117672 63.260843) (xy 133.868597 63.183208) (xy 133.019805 64.032) (xy 132.660595 64.032) (xy 132.646453 64.017858) + (xy 132.826058 63.838253) (xy 132.8402 63.852395) (xy 133.688992 63.003603) (xy 133.62379 62.794416) (xy 133.786832 62.685475) + (xy 133.993675 62.478632) (xy 134.15619 62.235411) (xy 134.268132 61.965158) (xy 134.3252 61.67826) (xy 134.3252 61.38574) + (xy 134.268132 61.098842) (xy 134.15619 60.828589) (xy 133.993675 60.585368) (xy 133.786832 60.378525) (xy 133.543611 60.21601) + (xy 133.273358 60.104068) (xy 132.98646 60.047) (xy 132.69394 60.047) (xy 132.407042 60.104068) (xy 132.136789 60.21601) + (xy 131.893568 60.378525) (xy 131.8402 60.431893) (xy 131.786832 60.378525) (xy 131.543611 60.21601) (xy 131.273358 60.104068) + (xy 130.98646 60.047) (xy 130.69394 60.047) (xy 130.407042 60.104068) (xy 130.136789 60.21601) (xy 129.893568 60.378525) + (xy 129.686725 60.585368) (xy 129.52421 60.828589) (xy 129.412268 61.098842) (xy 129.3552 61.38574) (xy 129.3552 61.67826) + (xy 129.412268 61.965158) (xy 129.52421 62.235411) (xy 129.686725 62.478632) (xy 129.78789 62.579797) (xy 129.74602 62.592498) + (xy 129.635706 62.651463) (xy 129.539015 62.730815) (xy 129.459663 62.827506) (xy 129.400698 62.93782) (xy 129.364388 63.057518) + (xy 129.352128 63.182) (xy 129.025735 63.182) (xy 129.111275 62.975489) (xy 129.1645 62.707911) (xy 129.1645 62.435089) + (xy 129.111275 62.167511) (xy 129.006871 61.915457) (xy 128.855299 61.688614) (xy 128.6645 61.497815) (xy 128.6645 58.431609) + (xy 134.060197 58.431609) (xy 134.246273 58.772766) (xy 134.663609 58.988513) (xy 135.115015 59.118696) (xy 135.583146 59.158313) + (xy 136.050011 59.105842) (xy 136.497668 58.963297) (xy 136.854127 58.772766) (xy 137.040203 58.431609) (xy 135.5502 56.941605) + (xy 134.060197 58.431609) (xy 128.6645 58.431609) (xy 128.6645 57.104685) (xy 128.855299 56.913886) (xy 128.934772 56.794946) + (xy 133.153887 56.794946) (xy 133.206358 57.261811) (xy 133.348903 57.709468) (xy 133.539434 58.065927) (xy 133.880591 58.252003) + (xy 135.370595 56.762) (xy 135.729805 56.762) (xy 137.219809 58.252003) (xy 137.560966 58.065927) (xy 137.776713 57.648591) + (xy 137.906896 57.197185) (xy 137.946513 56.729054) (xy 137.894042 56.262189) (xy 137.751497 55.814532) (xy 137.560966 55.458073) + (xy 137.219809 55.271997) (xy 135.729805 56.762) (xy 135.370595 56.762) (xy 133.880591 55.271997) (xy 133.539434 55.458073) + (xy 133.323687 55.875409) (xy 133.193504 56.326815) (xy 133.153887 56.794946) (xy 128.934772 56.794946) (xy 129.006871 56.687043) + (xy 129.111275 56.434989) (xy 129.1645 56.167411) (xy 129.1645 55.894589) (xy 129.111275 55.627011) (xy 129.006871 55.374957) + (xy 128.855299 55.148114) (xy 128.799576 55.092391) (xy 134.060197 55.092391) (xy 135.5502 56.582395) (xy 137.040203 55.092391) + (xy 136.854127 54.751234) (xy 136.436791 54.535487) (xy 135.985385 54.405304) (xy 135.517254 54.365687) (xy 135.050389 54.418158) + (xy 134.602732 54.560703) (xy 134.246273 54.751234) (xy 134.060197 55.092391) (xy 128.799576 55.092391) (xy 128.662386 54.955201) + (xy 128.435543 54.803629) (xy 128.183489 54.699225) (xy 127.915911 54.646) (xy 127.643089 54.646) (xy 127.375511 54.699225) + (xy 127.123457 54.803629) (xy 126.933999 54.930221) (xy 126.933999 46.779872) (xy 136.265 46.779872) (xy 136.265 47.220128) + (xy 136.35089 47.651925) (xy 136.519369 48.058669) (xy 136.763962 48.424729) (xy 137.075271 48.736038) (xy 137.441331 48.980631) + (xy 137.848075 49.14911) (xy 138.279872 49.235) (xy 138.720128 49.235) (xy 139.151925 49.14911) (xy 139.558669 48.980631) + (xy 139.924729 48.736038) (xy 140.236038 48.424729) (xy 140.480631 48.058669) (xy 140.64911 47.651925) (xy 140.735 47.220128) + (xy 140.735 46.779872) (xy 140.64911 46.348075) (xy 140.480631 45.941331) (xy 140.236038 45.575271) (xy 139.924729 45.263962) + (xy 139.558669 45.019369) (xy 139.151925 44.85089) (xy 138.720128 44.765) (xy 138.279872 44.765) (xy 137.848075 44.85089) + (xy 137.441331 45.019369) (xy 137.075271 45.263962) (xy 136.763962 45.575271) (xy 136.519369 45.941331) (xy 136.35089 46.348075) + (xy 136.265 46.779872) (xy 126.933999 46.779872) (xy 126.933999 46.607132) (xy 127.829921 45.711212) (xy 127.992989 45.678775) + (xy 128.245043 45.574371) (xy 128.471886 45.422799) (xy 128.664799 45.229886) (xy 128.816371 45.003043) (xy 128.920775 44.750989) + (xy 128.974 44.483411) (xy 128.974 44.210589) (xy 128.920775 43.943011) (xy 128.816371 43.690957) (xy 128.795686 43.66) + (xy 141.840001 43.66) (xy 141.84 96.84) (xy 48.16 96.84) (xy 48.16 93.279872) (xy 49.265 93.279872) + (xy 49.265 93.720128) (xy 49.35089 94.151925) (xy 49.519369 94.558669) (xy 49.763962 94.924729) (xy 50.075271 95.236038) + (xy 50.441331 95.480631) (xy 50.848075 95.64911) (xy 51.279872 95.735) (xy 51.720128 95.735) (xy 52.151925 95.64911) + (xy 52.558669 95.480631) (xy 52.924729 95.236038) (xy 53.236038 94.924729) (xy 53.480631 94.558669) (xy 53.64911 94.151925) + (xy 53.735 93.720128) (xy 53.735 93.279872) (xy 53.64911 92.848075) (xy 53.480631 92.441331) (xy 53.376676 92.28575) + (xy 57.565 92.28575) (xy 57.565 93.362542) (xy 57.589403 93.485223) (xy 57.63727 93.600785) (xy 57.706763 93.704789) + (xy 57.795211 93.793237) (xy 57.899215 93.86273) (xy 58.014777 93.910597) (xy 58.137458 93.935) (xy 59.21425 93.935) + (xy 59.373 93.77625) (xy 59.373 92.127) (xy 59.627 92.127) (xy 59.627 93.77625) (xy 59.78575 93.935) + (xy 60.862542 93.935) (xy 60.985223 93.910597) (xy 61.100785 93.86273) (xy 61.204789 93.793237) (xy 61.293237 93.704789) + (xy 61.36273 93.600785) (xy 61.410597 93.485223) (xy 61.435 93.362542) (xy 61.435 92.28575) (xy 61.27625 92.127) + (xy 59.627 92.127) (xy 59.373 92.127) (xy 57.72375 92.127) (xy 57.565 92.28575) (xy 53.376676 92.28575) + (xy 53.236038 92.075271) (xy 52.924729 91.763962) (xy 52.558669 91.519369) (xy 52.151925 91.35089) (xy 51.720128 91.265) + (xy 51.279872 91.265) (xy 50.848075 91.35089) (xy 50.441331 91.519369) (xy 50.075271 91.763962) (xy 49.763962 92.075271) + (xy 49.519369 92.441331) (xy 49.35089 92.848075) (xy 49.265 93.279872) (xy 48.16 93.279872) (xy 48.16 90.637458) + (xy 57.565 90.637458) (xy 57.565 91.71425) (xy 57.72375 91.873) (xy 59.373 91.873) (xy 59.373 90.22375) + (xy 59.627 90.22375) (xy 59.627 91.873) (xy 61.27625 91.873) (xy 61.339831 91.809419) (xy 62.645 91.809419) + (xy 62.645 92.190581) (xy 62.719361 92.564419) (xy 62.865225 92.916566) (xy 63.076987 93.233491) (xy 63.346509 93.503013) + (xy 63.663434 93.714775) (xy 64.015581 93.860639) (xy 64.389419 93.935) (xy 64.770581 93.935) (xy 65.144419 93.860639) + (xy 65.496566 93.714775) (xy 65.813491 93.503013) (xy 66.083013 93.233491) (xy 66.294775 92.916566) (xy 66.440639 92.564419) + (xy 66.496069 92.28575) (xy 70.065 92.28575) (xy 70.065 93.362542) (xy 70.089403 93.485223) (xy 70.13727 93.600785) + (xy 70.206763 93.704789) (xy 70.295211 93.793237) (xy 70.399215 93.86273) (xy 70.514777 93.910597) (xy 70.637458 93.935) + (xy 71.71425 93.935) (xy 71.873 93.77625) (xy 71.873 92.127) (xy 72.127 92.127) (xy 72.127 93.77625) + (xy 72.28575 93.935) (xy 73.362542 93.935) (xy 73.485223 93.910597) (xy 73.600785 93.86273) (xy 73.704789 93.793237) + (xy 73.793237 93.704789) (xy 73.86273 93.600785) (xy 73.910597 93.485223) (xy 73.935 93.362542) (xy 73.935 92.28575) + (xy 73.77625 92.127) (xy 72.127 92.127) (xy 71.873 92.127) (xy 70.22375 92.127) (xy 70.065 92.28575) + (xy 66.496069 92.28575) (xy 66.515 92.190581) (xy 66.515 91.809419) (xy 66.440639 91.435581) (xy 66.294775 91.083434) + (xy 66.083013 90.766509) (xy 65.953962 90.637458) (xy 70.065 90.637458) (xy 70.065 91.71425) (xy 70.22375 91.873) + (xy 71.873 91.873) (xy 71.873 90.22375) (xy 72.127 90.22375) (xy 72.127 91.873) (xy 73.77625 91.873) + (xy 73.839831 91.809419) (xy 75.145 91.809419) (xy 75.145 92.190581) (xy 75.219361 92.564419) (xy 75.365225 92.916566) + (xy 75.576987 93.233491) (xy 75.846509 93.503013) (xy 76.163434 93.714775) (xy 76.515581 93.860639) (xy 76.889419 93.935) + (xy 77.270581 93.935) (xy 77.644419 93.860639) (xy 77.996566 93.714775) (xy 78.313491 93.503013) (xy 78.583013 93.233491) + (xy 78.794775 92.916566) (xy 78.940639 92.564419) (xy 79.015 92.190581) (xy 79.015 91.809419) (xy 78.940639 91.435581) + (xy 78.794775 91.083434) (xy 78.583013 90.766509) (xy 78.516504 90.7) (xy 82.481928 90.7) (xy 82.481928 93.3) + (xy 82.494188 93.424482) (xy 82.530498 93.54418) (xy 82.589463 93.654494) (xy 82.668815 93.751185) (xy 82.765506 93.830537) + (xy 82.87582 93.889502) (xy 82.995518 93.925812) (xy 83.12 93.938072) (xy 85.72 93.938072) (xy 85.844482 93.925812) + (xy 85.96418 93.889502) (xy 86.074494 93.830537) (xy 86.171185 93.751185) (xy 86.250537 93.654494) (xy 86.309502 93.54418) + (xy 86.345812 93.424482) (xy 86.358072 93.3) (xy 86.358072 91.809419) (xy 87.565 91.809419) (xy 87.565 92.190581) + (xy 87.639361 92.564419) (xy 87.785225 92.916566) (xy 87.996987 93.233491) (xy 88.266509 93.503013) (xy 88.583434 93.714775) + (xy 88.935581 93.860639) (xy 89.309419 93.935) (xy 89.690581 93.935) (xy 90.064419 93.860639) (xy 90.416566 93.714775) + (xy 90.733491 93.503013) (xy 91.003013 93.233491) (xy 91.214775 92.916566) (xy 91.360639 92.564419) (xy 91.416069 92.28575) + (xy 98.565 92.28575) (xy 98.565 93.362542) (xy 98.589403 93.485223) (xy 98.63727 93.600785) (xy 98.706763 93.704789) + (xy 98.795211 93.793237) (xy 98.899215 93.86273) (xy 99.014777 93.910597) (xy 99.137458 93.935) (xy 100.21425 93.935) + (xy 100.373 93.77625) (xy 100.373 92.127) (xy 100.627 92.127) (xy 100.627 93.77625) (xy 100.78575 93.935) + (xy 101.862542 93.935) (xy 101.985223 93.910597) (xy 102.100785 93.86273) (xy 102.204789 93.793237) (xy 102.293237 93.704789) + (xy 102.36273 93.600785) (xy 102.410597 93.485223) (xy 102.435 93.362542) (xy 102.435 92.28575) (xy 102.27625 92.127) + (xy 100.627 92.127) (xy 100.373 92.127) (xy 98.72375 92.127) (xy 98.565 92.28575) (xy 91.416069 92.28575) + (xy 91.435 92.190581) (xy 91.435 91.809419) (xy 91.360639 91.435581) (xy 91.214775 91.083434) (xy 91.003013 90.766509) + (xy 90.873962 90.637458) (xy 98.565 90.637458) (xy 98.565 91.71425) (xy 98.72375 91.873) (xy 100.373 91.873) + (xy 100.373 90.22375) (xy 100.627 90.22375) (xy 100.627 91.873) (xy 102.27625 91.873) (xy 102.339831 91.809419) + (xy 103.645 91.809419) (xy 103.645 92.190581) (xy 103.719361 92.564419) (xy 103.865225 92.916566) (xy 104.076987 93.233491) + (xy 104.346509 93.503013) (xy 104.663434 93.714775) (xy 105.015581 93.860639) (xy 105.389419 93.935) (xy 105.770581 93.935) + (xy 106.144419 93.860639) (xy 106.496566 93.714775) (xy 106.813491 93.503013) (xy 107.083013 93.233491) (xy 107.294775 92.916566) + (xy 107.440639 92.564419) (xy 107.515 92.190581) (xy 107.515 91.809419) (xy 107.440639 91.435581) (xy 107.294775 91.083434) + (xy 107.083013 90.766509) (xy 106.813491 90.496987) (xy 106.496566 90.285225) (xy 106.144419 90.139361) (xy 105.770581 90.065) + (xy 105.389419 90.065) (xy 105.015581 90.139361) (xy 104.663434 90.285225) (xy 104.346509 90.496987) (xy 104.076987 90.766509) + (xy 103.865225 91.083434) (xy 103.719361 91.435581) (xy 103.645 91.809419) (xy 102.339831 91.809419) (xy 102.435 91.71425) + (xy 102.435 90.637458) (xy 102.410597 90.514777) (xy 102.36273 90.399215) (xy 102.293237 90.295211) (xy 102.204789 90.206763) + (xy 102.100785 90.13727) (xy 101.985223 90.089403) (xy 101.862542 90.065) (xy 100.78575 90.065) (xy 100.627 90.22375) + (xy 100.373 90.22375) (xy 100.21425 90.065) (xy 99.137458 90.065) (xy 99.014777 90.089403) (xy 98.899215 90.13727) + (xy 98.795211 90.206763) (xy 98.706763 90.295211) (xy 98.63727 90.399215) (xy 98.589403 90.514777) (xy 98.565 90.637458) + (xy 90.873962 90.637458) (xy 90.733491 90.496987) (xy 90.416566 90.285225) (xy 90.064419 90.139361) (xy 89.690581 90.065) + (xy 89.309419 90.065) (xy 88.935581 90.139361) (xy 88.583434 90.285225) (xy 88.266509 90.496987) (xy 87.996987 90.766509) + (xy 87.785225 91.083434) (xy 87.639361 91.435581) (xy 87.565 91.809419) (xy 86.358072 91.809419) (xy 86.358072 90.7) + (xy 86.345812 90.575518) (xy 86.309502 90.45582) (xy 86.250537 90.345506) (xy 86.171185 90.248815) (xy 86.074494 90.169463) + (xy 85.96418 90.110498) (xy 85.844482 90.074188) (xy 85.72 90.061928) (xy 83.12 90.061928) (xy 82.995518 90.074188) + (xy 82.87582 90.110498) (xy 82.765506 90.169463) (xy 82.668815 90.248815) (xy 82.589463 90.345506) (xy 82.530498 90.45582) + (xy 82.494188 90.575518) (xy 82.481928 90.7) (xy 78.516504 90.7) (xy 78.313491 90.496987) (xy 77.996566 90.285225) + (xy 77.644419 90.139361) (xy 77.270581 90.065) (xy 76.889419 90.065) (xy 76.515581 90.139361) (xy 76.163434 90.285225) + (xy 75.846509 90.496987) (xy 75.576987 90.766509) (xy 75.365225 91.083434) (xy 75.219361 91.435581) (xy 75.145 91.809419) + (xy 73.839831 91.809419) (xy 73.935 91.71425) (xy 73.935 90.637458) (xy 73.910597 90.514777) (xy 73.86273 90.399215) + (xy 73.793237 90.295211) (xy 73.704789 90.206763) (xy 73.600785 90.13727) (xy 73.485223 90.089403) (xy 73.362542 90.065) + (xy 72.28575 90.065) (xy 72.127 90.22375) (xy 71.873 90.22375) (xy 71.71425 90.065) (xy 70.637458 90.065) + (xy 70.514777 90.089403) (xy 70.399215 90.13727) (xy 70.295211 90.206763) (xy 70.206763 90.295211) (xy 70.13727 90.399215) + (xy 70.089403 90.514777) (xy 70.065 90.637458) (xy 65.953962 90.637458) (xy 65.813491 90.496987) (xy 65.496566 90.285225) + (xy 65.144419 90.139361) (xy 64.770581 90.065) (xy 64.389419 90.065) (xy 64.015581 90.139361) (xy 63.663434 90.285225) + (xy 63.346509 90.496987) (xy 63.076987 90.766509) (xy 62.865225 91.083434) (xy 62.719361 91.435581) (xy 62.645 91.809419) + (xy 61.339831 91.809419) (xy 61.435 91.71425) (xy 61.435 90.637458) (xy 61.410597 90.514777) (xy 61.36273 90.399215) + (xy 61.293237 90.295211) (xy 61.204789 90.206763) (xy 61.100785 90.13727) (xy 60.985223 90.089403) (xy 60.862542 90.065) + (xy 59.78575 90.065) (xy 59.627 90.22375) (xy 59.373 90.22375) (xy 59.21425 90.065) (xy 58.137458 90.065) + (xy 58.014777 90.089403) (xy 57.899215 90.13727) (xy 57.795211 90.206763) (xy 57.706763 90.295211) (xy 57.63727 90.399215) + (xy 57.589403 90.514777) (xy 57.565 90.637458) (xy 48.16 90.637458) (xy 48.16 89.7195) (xy 111.109428 89.7195) + (xy 111.109428 92.3195) (xy 111.121688 92.443982) (xy 111.157998 92.56368) (xy 111.216963 92.673994) (xy 111.296315 92.770685) + (xy 111.393006 92.850037) (xy 111.50332 92.909002) (xy 111.623018 92.945312) (xy 111.7475 92.957572) (xy 114.3475 92.957572) + (xy 114.471982 92.945312) (xy 114.59168 92.909002) (xy 114.701994 92.850037) (xy 114.798685 92.770685) (xy 114.878037 92.673994) + (xy 114.937002 92.56368) (xy 114.973312 92.443982) (xy 114.985572 92.3195) (xy 114.985572 90.7) (xy 132.061928 90.7) + (xy 132.061928 93.3) (xy 132.074188 93.424482) (xy 132.110498 93.54418) (xy 132.169463 93.654494) (xy 132.248815 93.751185) + (xy 132.345506 93.830537) (xy 132.45582 93.889502) (xy 132.575518 93.925812) (xy 132.7 93.938072) (xy 135.3 93.938072) + (xy 135.424482 93.925812) (xy 135.54418 93.889502) (xy 135.654494 93.830537) (xy 135.751185 93.751185) (xy 135.830537 93.654494) + (xy 135.889502 93.54418) (xy 135.925812 93.424482) (xy 135.933224 93.349224) (xy 137.910381 93.349224) (xy 138.042317 93.644312) + (xy 138.383045 93.815159) (xy 138.750557 93.91625) (xy 139.130729 93.943701) (xy 139.508951 93.896457) (xy 139.87069 93.776333) + (xy 140.117683 93.644312) (xy 140.249619 93.349224) (xy 139.08 92.179605) (xy 137.910381 93.349224) (xy 135.933224 93.349224) + (xy 135.938072 93.3) (xy 135.938072 92.050729) (xy 137.136299 92.050729) (xy 137.183543 92.428951) (xy 137.303667 92.79069) + (xy 137.435688 93.037683) (xy 137.730776 93.169619) (xy 138.900395 92) (xy 139.259605 92) (xy 140.429224 93.169619) + (xy 140.724312 93.037683) (xy 140.895159 92.696955) (xy 140.99625 92.329443) (xy 141.023701 91.949271) (xy 140.976457 91.571049) + (xy 140.856333 91.20931) (xy 140.724312 90.962317) (xy 140.429224 90.830381) (xy 139.259605 92) (xy 138.900395 92) + (xy 137.730776 90.830381) (xy 137.435688 90.962317) (xy 137.264841 91.303045) (xy 137.16375 91.670557) (xy 137.136299 92.050729) + (xy 135.938072 92.050729) (xy 135.938072 90.7) (xy 135.933225 90.650776) (xy 137.910381 90.650776) (xy 139.08 91.820395) + (xy 140.249619 90.650776) (xy 140.117683 90.355688) (xy 139.776955 90.184841) (xy 139.409443 90.08375) (xy 139.029271 90.056299) + (xy 138.651049 90.103543) (xy 138.28931 90.223667) (xy 138.042317 90.355688) (xy 137.910381 90.650776) (xy 135.933225 90.650776) + (xy 135.925812 90.575518) (xy 135.889502 90.45582) (xy 135.830537 90.345506) (xy 135.751185 90.248815) (xy 135.654494 90.169463) + (xy 135.54418 90.110498) (xy 135.424482 90.074188) (xy 135.3 90.061928) (xy 132.7 90.061928) (xy 132.575518 90.074188) + (xy 132.45582 90.110498) (xy 132.345506 90.169463) (xy 132.248815 90.248815) (xy 132.169463 90.345506) (xy 132.110498 90.45582) + (xy 132.074188 90.575518) (xy 132.061928 90.7) (xy 114.985572 90.7) (xy 114.985572 89.7195) (xy 114.973312 89.595018) + (xy 114.937002 89.47532) (xy 114.878037 89.365006) (xy 114.798685 89.268315) (xy 114.701994 89.188963) (xy 114.59168 89.129998) + (xy 114.471982 89.093688) (xy 114.3475 89.081428) (xy 111.7475 89.081428) (xy 111.623018 89.093688) (xy 111.50332 89.129998) + (xy 111.393006 89.188963) (xy 111.296315 89.268315) (xy 111.216963 89.365006) (xy 111.157998 89.47532) (xy 111.121688 89.595018) + (xy 111.109428 89.7195) (xy 48.16 89.7195) (xy 48.16 85.336039) (xy 55.204096 85.336039) (xy 55.244754 85.470087) + (xy 55.364963 85.72442) (xy 55.532481 85.950414) (xy 55.740869 86.139385) (xy 55.982119 86.28407) (xy 56.24696 86.378909) + (xy 56.469 86.257624) (xy 56.469 85.114) (xy 56.723 85.114) (xy 56.723 86.257624) (xy 56.94504 86.378909) + (xy 57.209881 86.28407) (xy 57.451131 86.139385) (xy 57.659519 85.950414) (xy 57.827037 85.72442) (xy 57.947246 85.470087) + (xy 57.987904 85.336039) (xy 57.865915 85.114) (xy 56.723 85.114) (xy 56.469 85.114) (xy 55.326085 85.114) + (xy 55.204096 85.336039) (xy 48.16 85.336039) (xy 48.16 84.987) (xy 62.774057 84.987) (xy 62.801764 85.268309) + (xy 62.883818 85.538808) (xy 63.017068 85.788101) (xy 63.196392 86.006608) (xy 63.414899 86.185932) (xy 63.664192 86.319182) + (xy 63.934691 86.401236) (xy 64.145508 86.422) (xy 64.286492 86.422) (xy 64.497309 86.401236) (xy 64.767808 86.319182) + (xy 65.017101 86.185932) (xy 65.235608 86.006608) (xy 65.414932 85.788101) (xy 65.548182 85.538808) (xy 65.600286 85.367039) + (xy 69.401096 85.367039) (xy 69.441754 85.501087) (xy 69.561963 85.75542) (xy 69.729481 85.981414) (xy 69.937869 86.170385) + (xy 70.179119 86.31507) (xy 70.44396 86.409909) (xy 70.666 86.288624) (xy 70.666 85.145) (xy 70.92 85.145) + (xy 70.92 86.288624) (xy 71.14204 86.409909) (xy 71.406881 86.31507) (xy 71.648131 86.170385) (xy 71.856519 85.981414) + (xy 72.024037 85.75542) (xy 72.144246 85.501087) (xy 72.184904 85.367039) (xy 72.062915 85.145) (xy 70.92 85.145) + (xy 70.666 85.145) (xy 69.523085 85.145) (xy 69.401096 85.367039) (xy 65.600286 85.367039) (xy 65.630236 85.268309) + (xy 65.654889 85.018) (xy 76.971057 85.018) (xy 76.998764 85.299309) (xy 77.080818 85.569808) (xy 77.214068 85.819101) + (xy 77.393392 86.037608) (xy 77.611899 86.216932) (xy 77.861192 86.350182) (xy 78.131691 86.432236) (xy 78.342508 86.453) + (xy 78.483492 86.453) (xy 78.694309 86.432236) (xy 78.964808 86.350182) (xy 79.214101 86.216932) (xy 79.432608 86.037608) + (xy 79.611932 85.819101) (xy 79.745182 85.569808) (xy 79.827236 85.299309) (xy 79.854943 85.018) (xy 79.827236 84.736691) + (xy 79.745182 84.466192) (xy 79.611932 84.216899) (xy 79.432608 83.998392) (xy 79.319518 83.905581) (xy 79.337482 83.903812) + (xy 79.45718 83.867502) (xy 79.567494 83.808537) (xy 79.664185 83.729185) (xy 79.743537 83.632494) (xy 79.802502 83.52218) + (xy 79.838812 83.402482) (xy 79.851072 83.278) (xy 79.851072 82.564589) (xy 83.659 82.564589) (xy 83.659 82.837411) + (xy 83.712225 83.104989) (xy 83.816629 83.357043) (xy 83.968201 83.583886) (xy 84.161114 83.776799) (xy 84.387957 83.928371) + (xy 84.640011 84.032775) (xy 84.907589 84.086) (xy 85.180411 84.086) (xy 85.447989 84.032775) (xy 85.700043 83.928371) + (xy 85.926886 83.776799) (xy 86.119799 83.583886) (xy 86.271371 83.357043) (xy 86.375775 83.104989) (xy 86.429 82.837411) + (xy 86.429 82.564589) (xy 86.375775 82.297011) (xy 86.271371 82.044957) (xy 86.119799 81.818114) (xy 85.929 81.627315) + (xy 85.929 81.6215) (xy 86.332557 81.6215) (xy 86.360264 81.902809) (xy 86.442318 82.173308) (xy 86.575568 82.422601) + (xy 86.754892 82.641108) (xy 86.973399 82.820432) (xy 87.222692 82.953682) (xy 87.493191 83.035736) (xy 87.704008 83.0565) + (xy 87.844992 83.0565) (xy 88.055809 83.035736) (xy 88.326308 82.953682) (xy 88.575601 82.820432) (xy 88.794108 82.641108) + (xy 88.886919 82.528018) (xy 88.888688 82.545982) (xy 88.924998 82.66568) (xy 88.983963 82.775994) (xy 89.063315 82.872685) + (xy 89.160006 82.952037) (xy 89.27032 83.011002) (xy 89.390018 83.047312) (xy 89.5145 83.059572) (xy 91.1145 83.059572) + (xy 91.238982 83.047312) (xy 91.35868 83.011002) (xy 91.468994 82.952037) (xy 91.565685 82.872685) (xy 91.645037 82.775994) + (xy 91.704002 82.66568) (xy 91.740312 82.545982) (xy 91.752572 82.4215) (xy 91.752572 81.779872) (xy 94.765 81.779872) + (xy 94.765 82.220128) (xy 94.85089 82.651925) (xy 95.019369 83.058669) (xy 95.263962 83.424729) (xy 95.575271 83.736038) + (xy 95.941331 83.980631) (xy 96.348075 84.14911) (xy 96.779872 84.235) (xy 97.220128 84.235) (xy 97.651925 84.14911) + (xy 98.058669 83.980631) (xy 98.424729 83.736038) (xy 98.736038 83.424729) (xy 98.980631 83.058669) (xy 99.14911 82.651925) + (xy 99.235 82.220128) (xy 99.235 81.779872) (xy 99.14911 81.348075) (xy 99.126298 81.293) (xy 118.430928 81.293) + (xy 118.430928 83.093) (xy 118.443188 83.217482) (xy 118.479498 83.33718) (xy 118.538463 83.447494) (xy 118.617815 83.544185) + (xy 118.714506 83.623537) (xy 118.82482 83.682502) (xy 118.944518 83.718812) (xy 119.069 83.731072) (xy 120.869 83.731072) + (xy 120.993482 83.718812) (xy 121.11318 83.682502) (xy 121.223494 83.623537) (xy 121.320185 83.544185) (xy 121.399537 83.447494) + (xy 121.458502 83.33718) (xy 121.494812 83.217482) (xy 121.507072 83.093) (xy 121.507072 82.55774) (xy 121.877964 82.55774) + (xy 121.926606 82.718107) (xy 122.056764 82.989414) (xy 122.237351 83.230116) (xy 122.461427 83.430962) (xy 122.72038 83.584234) + (xy 123.004259 83.684041) (xy 123.242 83.563992) (xy 123.242 82.32) (xy 123.496 82.32) (xy 123.496 83.563992) + (xy 123.733741 83.684041) (xy 124.01762 83.584234) (xy 124.276573 83.430962) (xy 124.500649 83.230116) (xy 124.681236 82.989414) + (xy 124.811394 82.718107) (xy 124.860036 82.55774) (xy 125.277964 82.55774) (xy 125.326606 82.718107) (xy 125.456764 82.989414) + (xy 125.637351 83.230116) (xy 125.861427 83.430962) (xy 126.12038 83.584234) (xy 126.404259 83.684041) (xy 126.642 83.563992) + (xy 126.642 82.32) (xy 126.896 82.32) (xy 126.896 83.563992) (xy 127.133741 83.684041) (xy 127.41762 83.584234) + (xy 127.676573 83.430962) (xy 127.900649 83.230116) (xy 128.081236 82.989414) (xy 128.211394 82.718107) (xy 128.260036 82.55774) + (xy 128.139378 82.32) (xy 126.896 82.32) (xy 126.642 82.32) (xy 125.398622 82.32) (xy 125.277964 82.55774) + (xy 124.860036 82.55774) (xy 124.739378 82.32) (xy 123.496 82.32) (xy 123.242 82.32) (xy 121.998622 82.32) + (xy 121.877964 82.55774) (xy 121.507072 82.55774) (xy 121.507072 81.82826) (xy 121.877964 81.82826) (xy 121.998622 82.066) + (xy 123.242 82.066) (xy 123.242 80.822008) (xy 123.496 80.822008) (xy 123.496 82.066) (xy 124.739378 82.066) + (xy 124.860036 81.82826) (xy 125.277964 81.82826) (xy 125.398622 82.066) (xy 126.642 82.066) (xy 126.642 80.822008) + (xy 126.896 80.822008) (xy 126.896 82.066) (xy 128.139378 82.066) (xy 128.260036 81.82826) (xy 128.211394 81.667893) + (xy 128.081236 81.396586) (xy 127.900649 81.155884) (xy 127.676573 80.955038) (xy 127.41762 80.801766) (xy 127.133741 80.701959) + (xy 126.896 80.822008) (xy 126.642 80.822008) (xy 126.404259 80.701959) (xy 126.12038 80.801766) (xy 125.861427 80.955038) + (xy 125.637351 81.155884) (xy 125.456764 81.396586) (xy 125.326606 81.667893) (xy 125.277964 81.82826) (xy 124.860036 81.82826) + (xy 124.811394 81.667893) (xy 124.681236 81.396586) (xy 124.500649 81.155884) (xy 124.276573 80.955038) (xy 124.01762 80.801766) + (xy 123.733741 80.701959) (xy 123.496 80.822008) (xy 123.242 80.822008) (xy 123.004259 80.701959) (xy 122.72038 80.801766) + (xy 122.461427 80.955038) (xy 122.237351 81.155884) (xy 122.056764 81.396586) (xy 121.926606 81.667893) (xy 121.877964 81.82826) + (xy 121.507072 81.82826) (xy 121.507072 81.293) (xy 121.494812 81.168518) (xy 121.458502 81.04882) (xy 121.399537 80.938506) + (xy 121.320185 80.841815) (xy 121.223494 80.762463) (xy 121.11318 80.703498) (xy 120.993482 80.667188) (xy 120.869 80.654928) + (xy 119.069 80.654928) (xy 118.944518 80.667188) (xy 118.82482 80.703498) (xy 118.714506 80.762463) (xy 118.617815 80.841815) + (xy 118.538463 80.938506) (xy 118.479498 81.04882) (xy 118.443188 81.168518) (xy 118.430928 81.293) (xy 99.126298 81.293) + (xy 98.980631 80.941331) (xy 98.736038 80.575271) (xy 98.728267 80.5675) (xy 132.500928 80.5675) (xy 132.500928 82.1675) + (xy 132.513188 82.291982) (xy 132.549498 82.41168) (xy 132.608463 82.521994) (xy 132.687815 82.618685) (xy 132.784506 82.698037) + (xy 132.89482 82.757002) (xy 133.014518 82.793312) (xy 133.139 82.805572) (xy 134.739 82.805572) (xy 134.863482 82.793312) + (xy 134.98318 82.757002) (xy 135.093494 82.698037) (xy 135.190185 82.618685) (xy 135.269537 82.521994) (xy 135.328502 82.41168) + (xy 135.364812 82.291982) (xy 135.377072 82.1675) (xy 135.377072 80.5675) (xy 135.364812 80.443018) (xy 135.328502 80.32332) + (xy 135.269537 80.213006) (xy 135.190185 80.116315) (xy 135.093494 80.036963) (xy 134.98318 79.977998) (xy 134.863482 79.941688) + (xy 134.739 79.929428) (xy 133.139 79.929428) (xy 133.014518 79.941688) (xy 132.89482 79.977998) (xy 132.784506 80.036963) + (xy 132.687815 80.116315) (xy 132.608463 80.213006) (xy 132.549498 80.32332) (xy 132.513188 80.443018) (xy 132.500928 80.5675) + (xy 98.728267 80.5675) (xy 98.424729 80.263962) (xy 98.058669 80.019369) (xy 97.651925 79.85089) (xy 97.220128 79.765) + (xy 96.779872 79.765) (xy 96.348075 79.85089) (xy 95.941331 80.019369) (xy 95.575271 80.263962) (xy 95.263962 80.575271) + (xy 95.019369 80.941331) (xy 94.85089 81.348075) (xy 94.765 81.779872) (xy 91.752572 81.779872) (xy 91.752572 80.8215) + (xy 91.740312 80.697018) (xy 91.704002 80.57732) (xy 91.645037 80.467006) (xy 91.565685 80.370315) (xy 91.468994 80.290963) + (xy 91.35868 80.231998) (xy 91.238982 80.195688) (xy 91.1145 80.183428) (xy 89.5145 80.183428) (xy 89.390018 80.195688) + (xy 89.27032 80.231998) (xy 89.160006 80.290963) (xy 89.063315 80.370315) (xy 88.983963 80.467006) (xy 88.924998 80.57732) + (xy 88.888688 80.697018) (xy 88.886919 80.714982) (xy 88.794108 80.601892) (xy 88.575601 80.422568) (xy 88.326308 80.289318) + (xy 88.055809 80.207264) (xy 87.844992 80.1865) (xy 87.704008 80.1865) (xy 87.493191 80.207264) (xy 87.222692 80.289318) + (xy 86.973399 80.422568) (xy 86.754892 80.601892) (xy 86.575568 80.820399) (xy 86.442318 81.069692) (xy 86.360264 81.340191) + (xy 86.332557 81.6215) (xy 85.929 81.6215) (xy 85.929 78.746985) (xy 111.160307 78.746985) (xy 111.279967 79.106944) + (xy 111.467552 79.436642) (xy 111.715854 79.723409) (xy 112.01533 79.956225) (xy 112.354472 80.126142) (xy 112.620016 80.206689) + (xy 112.9205 80.091204) (xy 112.9205 78.4465) (xy 113.1745 78.4465) (xy 113.1745 80.091204) (xy 113.474984 80.206689) + (xy 113.740528 80.126142) (xy 114.07967 79.956225) (xy 114.379146 79.723409) (xy 114.627448 79.436642) (xy 114.815033 79.106944) + (xy 114.934693 78.746985) (xy 114.837396 78.493) (xy 120.126573 78.493) (xy 120.15621 78.793913) (xy 120.243983 79.083261) + (xy 120.386519 79.349927) (xy 120.578339 79.583661) (xy 120.812073 79.775481) (xy 121.078739 79.918017) (xy 121.368087 80.00579) + (xy 121.593592 80.028) (xy 121.744408 80.028) (xy 121.969913 80.00579) (xy 122.259261 79.918017) (xy 122.525927 79.775481) + (xy 122.759661 79.583661) (xy 122.951481 79.349927) (xy 123.094017 79.083261) (xy 123.18179 78.793913) (xy 123.211427 78.493) + (xy 123.526573 78.493) (xy 123.55621 78.793913) (xy 123.643983 79.083261) (xy 123.786519 79.349927) (xy 123.978339 79.583661) + (xy 124.212073 79.775481) (xy 124.478739 79.918017) (xy 124.768087 80.00579) (xy 124.993592 80.028) (xy 125.144408 80.028) + (xy 125.369913 80.00579) (xy 125.659261 79.918017) (xy 125.925927 79.775481) (xy 126.159661 79.583661) (xy 126.351481 79.349927) + (xy 126.494017 79.083261) (xy 126.561681 78.860202) (xy 133.125903 78.860202) (xy 133.197486 79.104171) (xy 133.452996 79.225071) + (xy 133.727184 79.2938) (xy 134.009512 79.307717) (xy 134.28913 79.266287) (xy 134.555292 79.171103) (xy 134.680514 79.104171) + (xy 134.752097 78.860202) (xy 133.939 78.047105) (xy 133.125903 78.860202) (xy 126.561681 78.860202) (xy 126.58179 78.793913) + (xy 126.611427 78.493) (xy 126.58179 78.192087) (xy 126.504717 77.938012) (xy 132.498783 77.938012) (xy 132.540213 78.21763) + (xy 132.635397 78.483792) (xy 132.702329 78.609014) (xy 132.946298 78.680597) (xy 133.759395 77.8675) (xy 134.118605 77.8675) + (xy 134.931702 78.680597) (xy 135.175671 78.609014) (xy 135.296571 78.353504) (xy 135.3653 78.079316) (xy 135.379217 77.796988) + (xy 135.337787 77.51737) (xy 135.242603 77.251208) (xy 135.175671 77.125986) (xy 134.931702 77.054403) (xy 134.118605 77.8675) + (xy 133.759395 77.8675) (xy 132.946298 77.054403) (xy 132.702329 77.125986) (xy 132.581429 77.381496) (xy 132.5127 77.655684) + (xy 132.498783 77.938012) (xy 126.504717 77.938012) (xy 126.494017 77.902739) (xy 126.351481 77.636073) (xy 126.159661 77.402339) + (xy 125.925927 77.210519) (xy 125.659261 77.067983) (xy 125.369913 76.98021) (xy 125.144408 76.958) (xy 124.993592 76.958) + (xy 124.768087 76.98021) (xy 124.478739 77.067983) (xy 124.212073 77.210519) (xy 123.978339 77.402339) (xy 123.786519 77.636073) + (xy 123.643983 77.902739) (xy 123.55621 78.192087) (xy 123.526573 78.493) (xy 123.211427 78.493) (xy 123.18179 78.192087) + (xy 123.094017 77.902739) (xy 122.951481 77.636073) (xy 122.759661 77.402339) (xy 122.525927 77.210519) (xy 122.259261 77.067983) + (xy 121.969913 76.98021) (xy 121.744408 76.958) (xy 121.593592 76.958) (xy 121.368087 76.98021) (xy 121.078739 77.067983) + (xy 120.812073 77.210519) (xy 120.578339 77.402339) (xy 120.386519 77.636073) (xy 120.243983 77.902739) (xy 120.15621 78.192087) + (xy 120.126573 78.493) (xy 114.837396 78.493) (xy 114.819582 78.4465) (xy 113.1745 78.4465) (xy 112.9205 78.4465) + (xy 111.275418 78.4465) (xy 111.160307 78.746985) (xy 85.929 78.746985) (xy 85.929 77.892015) (xy 111.160307 77.892015) + (xy 111.275418 78.1925) (xy 112.9205 78.1925) (xy 112.9205 76.547796) (xy 113.1745 76.547796) (xy 113.1745 78.1925) + (xy 114.819582 78.1925) (xy 114.934693 77.892015) (xy 114.815033 77.532056) (xy 114.627448 77.202358) (xy 114.379146 76.915591) + (xy 114.326674 76.874798) (xy 133.125903 76.874798) (xy 133.939 77.687895) (xy 134.752097 76.874798) (xy 134.680514 76.630829) + (xy 134.425004 76.509929) (xy 134.150816 76.4412) (xy 133.868488 76.427283) (xy 133.58887 76.468713) (xy 133.322708 76.563897) + (xy 133.197486 76.630829) (xy 133.125903 76.874798) (xy 114.326674 76.874798) (xy 114.07967 76.682775) (xy 113.740528 76.512858) + (xy 113.474984 76.432311) (xy 113.1745 76.547796) (xy 112.9205 76.547796) (xy 112.620016 76.432311) (xy 112.354472 76.512858) + (xy 112.01533 76.682775) (xy 111.715854 76.915591) (xy 111.467552 77.202358) (xy 111.279967 77.532056) (xy 111.160307 77.892015) + (xy 85.929 77.892015) (xy 85.929 75.516089) (xy 105.8205 75.516089) (xy 105.8205 75.788911) (xy 105.873725 76.056489) + (xy 105.978129 76.308543) (xy 106.129701 76.535386) (xy 106.322614 76.728299) (xy 106.549457 76.879871) (xy 106.801511 76.984275) + (xy 107.069089 77.0375) (xy 107.341911 77.0375) (xy 107.609489 76.984275) (xy 107.861543 76.879871) (xy 108.088386 76.728299) + (xy 108.281299 76.535386) (xy 108.432871 76.308543) (xy 108.537275 76.056489) (xy 108.584964 75.816743) (xy 108.82471 75.769054) + (xy 109.076764 75.66465) (xy 109.303607 75.513078) (xy 109.49652 75.320165) (xy 109.648092 75.093322) (xy 109.752496 74.841268) + (xy 109.805721 74.57369) (xy 109.805721 74.300868) (xy 109.752496 74.03329) (xy 109.648092 73.781236) (xy 109.49652 73.554393) + (xy 109.303607 73.36148) (xy 109.1065 73.229777) (xy 109.1065 73.035935) (xy 109.142815 73.080185) (xy 109.239506 73.159537) + (xy 109.34982 73.218502) (xy 109.469518 73.254812) (xy 109.594 73.267072) (xy 111.294 73.267072) (xy 111.418482 73.254812) + (xy 111.53818 73.218502) (xy 111.648494 73.159537) (xy 111.745185 73.080185) (xy 111.824537 72.983494) (xy 111.883502 72.87318) + (xy 111.904393 72.804313) (xy 111.928866 72.834134) (xy 112.154986 73.019706) (xy 112.412966 73.157599) (xy 112.692889 73.242513) + (xy 112.91105 73.264) (xy 113.05695 73.264) (xy 113.275111 73.242513) (xy 113.555034 73.157599) (xy 113.813014 73.019706) + (xy 114.039134 72.834134) (xy 114.224706 72.608014) (xy 114.259201 72.543477) (xy 114.328822 72.660355) (xy 114.523731 72.876588) + (xy 114.75708 73.050641) (xy 115.019901 73.175825) (xy 115.16711 73.220476) (xy 115.397 73.099155) (xy 115.397 71.906) + (xy 115.377 71.906) (xy 115.377 71.652) (xy 115.397 71.652) (xy 115.397 70.458845) (xy 115.651 70.458845) + (xy 115.651 71.652) (xy 115.671 71.652) (xy 115.671 71.906) (xy 115.651 71.906) (xy 115.651 73.099155) + (xy 115.88089 73.220476) (xy 116.028099 73.175825) (xy 116.29092 73.050641) (xy 116.524269 72.876588) (xy 116.719178 72.660355) + (xy 116.788799 72.543477) (xy 116.823294 72.608014) (xy 117.008866 72.834134) (xy 117.234986 73.019706) (xy 117.492966 73.157599) + (xy 117.772889 73.242513) (xy 117.99105 73.264) (xy 118.13695 73.264) (xy 118.355111 73.242513) (xy 118.635034 73.157599) + (xy 118.893014 73.019706) (xy 119.119134 72.834134) (xy 119.304706 72.608014) (xy 119.442599 72.350034) (xy 119.527513 72.070111) + (xy 119.556185 71.779) (xy 119.527513 71.487889) (xy 119.442599 71.207966) (xy 119.304706 70.949986) (xy 119.119134 70.723866) + (xy 118.893014 70.538294) (xy 118.768255 70.471609) (xy 134.060197 70.471609) (xy 134.246273 70.812766) (xy 134.663609 71.028513) + (xy 135.115015 71.158696) (xy 135.583146 71.198313) (xy 136.050011 71.145842) (xy 136.497668 71.003297) (xy 136.854127 70.812766) + (xy 137.040203 70.471609) (xy 135.5502 68.981605) (xy 134.060197 70.471609) (xy 118.768255 70.471609) (xy 118.635034 70.400401) + (xy 118.355111 70.315487) (xy 118.13695 70.294) (xy 117.99105 70.294) (xy 117.772889 70.315487) (xy 117.492966 70.400401) + (xy 117.234986 70.538294) (xy 117.008866 70.723866) (xy 116.823294 70.949986) (xy 116.788799 71.014523) (xy 116.719178 70.897645) + (xy 116.524269 70.681412) (xy 116.29092 70.507359) (xy 116.028099 70.382175) (xy 115.88089 70.337524) (xy 115.651 70.458845) + (xy 115.397 70.458845) (xy 115.16711 70.337524) (xy 115.019901 70.382175) (xy 114.75708 70.507359) (xy 114.523731 70.681412) + (xy 114.328822 70.897645) (xy 114.259201 71.014523) (xy 114.224706 70.949986) (xy 114.039134 70.723866) (xy 113.813014 70.538294) + (xy 113.555034 70.400401) (xy 113.275111 70.315487) (xy 113.05695 70.294) (xy 112.91105 70.294) (xy 112.692889 70.315487) + (xy 112.412966 70.400401) (xy 112.154986 70.538294) (xy 111.928866 70.723866) (xy 111.904393 70.753687) (xy 111.883502 70.68482) + (xy 111.824537 70.574506) (xy 111.745185 70.477815) (xy 111.648494 70.398463) (xy 111.53818 70.339498) (xy 111.418482 70.303188) + (xy 111.294 70.290928) (xy 109.594 70.290928) (xy 109.469518 70.303188) (xy 109.34982 70.339498) (xy 109.239506 70.398463) + (xy 109.142815 70.477815) (xy 109.1065 70.522065) (xy 109.1065 65.68935) (xy 117.0362 65.68935) (xy 117.0362 66.316142) + (xy 117.060603 66.438823) (xy 117.10847 66.554385) (xy 117.177963 66.658389) (xy 117.266411 66.746837) (xy 117.370415 66.81633) + (xy 117.485977 66.864197) (xy 117.608658 66.8886) (xy 118.23545 66.8886) (xy 118.3942 66.72985) (xy 118.3942 65.5306) + (xy 117.19495 65.5306) (xy 117.0362 65.68935) (xy 109.1065 65.68935) (xy 109.1065 64.491058) (xy 117.0362 64.491058) + (xy 117.0362 65.11785) (xy 117.19495 65.2766) (xy 118.3942 65.2766) (xy 118.3942 64.07735) (xy 118.23545 63.9186) + (xy 117.608658 63.9186) (xy 117.485977 63.943003) (xy 117.370415 63.99087) (xy 117.266411 64.060363) (xy 117.177963 64.148811) + (xy 117.10847 64.252815) (xy 117.060603 64.368377) (xy 117.0362 64.491058) (xy 109.1065 64.491058) (xy 109.1065 60.715578) + (xy 111.953579 57.8685) (xy 117.879315 57.8685) (xy 118.070114 58.059299) (xy 118.296957 58.210871) (xy 118.549011 58.315275) + (xy 118.816589 58.3685) (xy 119.089411 58.3685) (xy 119.356989 58.315275) (xy 119.609043 58.210871) (xy 119.835886 58.059299) + (xy 120.028799 57.866386) (xy 120.180371 57.639543) (xy 120.284775 57.387489) (xy 120.338 57.119911) (xy 120.338 56.847089) + (xy 120.284775 56.579511) (xy 120.180371 56.327457) (xy 120.028799 56.100614) (xy 119.835886 55.907701) (xy 119.609043 55.756129) + (xy 119.356989 55.651725) (xy 119.089411 55.5985) (xy 118.816589 55.5985) (xy 118.549011 55.651725) (xy 118.296957 55.756129) + (xy 118.070114 55.907701) (xy 117.879315 56.0985) (xy 112.453579 56.0985) (xy 113.612579 54.9395) (xy 113.882411 54.9395) + (xy 114.052154 54.905736) (xy 114.106129 55.036043) (xy 114.257701 55.262886) (xy 114.450614 55.455799) (xy 114.677457 55.607371) + (xy 114.929511 55.711775) (xy 115.197089 55.765) (xy 115.469911 55.765) (xy 115.737489 55.711775) (xy 115.989543 55.607371) + (xy 116.216386 55.455799) (xy 116.409299 55.262886) (xy 116.560871 55.036043) (xy 116.665275 54.783989) (xy 116.7185 54.516411) + (xy 116.7185 54.243589) (xy 116.665275 53.976011) (xy 116.560871 53.723957) (xy 116.529829 53.6775) (xy 118.909531 53.6775) + (xy 118.953 53.681781) (xy 118.996469 53.6775) (xy 118.996477 53.6775) (xy 119.12649 53.664695) (xy 119.293313 53.614089) + (xy 119.447059 53.531911) (xy 119.581817 53.421317) (xy 119.609534 53.387544) (xy 121.70705 51.290029) (xy 121.740817 51.262317) + (xy 121.770186 51.226532) (xy 121.85141 51.12756) (xy 121.851411 51.127559) (xy 121.933589 50.973813) (xy 121.984195 50.80699) + (xy 121.997 50.676977) (xy 121.997 50.676967) (xy 122.001281 50.633501) (xy 121.997 50.590034) (xy 121.997 47.389185) + (xy 122.187799 47.198386) (xy 122.339371 46.971543) (xy 122.443775 46.719489) (xy 122.497 46.451911) (xy 122.497 46.179089) + (xy 122.443775 45.911511) (xy 122.339371 45.659457) (xy 122.187799 45.432614) (xy 121.994886 45.239701) (xy 121.768043 45.088129) + (xy 121.515989 44.983725) (xy 121.248411 44.9305) (xy 120.975589 44.9305) (xy 120.708011 44.983725) (xy 120.455957 45.088129) + (xy 120.229114 45.239701) (xy 120.036201 45.432614) (xy 119.884629 45.659457) (xy 119.780225 45.911511) (xy 119.727 46.179089) + (xy 119.727 46.451911) (xy 119.780225 46.719489) (xy 119.884629 46.971543) (xy 120.036201 47.198386) (xy 120.227001 47.389186) + (xy 120.227 50.266921) (xy 118.586422 51.9075) (xy 115.903805 51.9075) (xy 115.860339 51.903219) (xy 115.816873 51.9075) + (xy 115.816863 51.9075) (xy 115.68685 51.920305) (xy 115.520027 51.970911) (xy 115.366281 52.053089) (xy 115.231523 52.163683) + (xy 115.203808 52.197454) (xy 114.775724 52.625539) (xy 114.628886 52.478701) (xy 114.402043 52.327129) (xy 114.149989 52.222725) + (xy 113.882411 52.1695) (xy 113.609589 52.1695) (xy 113.342011 52.222725) (xy 113.089957 52.327129) (xy 112.863114 52.478701) + (xy 112.670201 52.671614) (xy 112.518629 52.898457) (xy 112.414225 53.150511) (xy 112.361 53.418089) (xy 112.361 53.687921) + (xy 106.610452 59.43847) (xy 106.576684 59.466183) (xy 106.548971 59.499951) (xy 106.548968 59.499954) (xy 106.46609 59.600941) + (xy 106.383912 59.754687) (xy 106.333305 59.92151) (xy 106.316219 60.095) (xy 106.320501 60.138479) (xy 106.3205 70.465523) + (xy 106.3205 70.465524) (xy 106.320501 74.578814) (xy 106.129701 74.769614) (xy 105.978129 74.996457) (xy 105.873725 75.248511) + (xy 105.8205 75.516089) (xy 85.929 75.516089) (xy 85.929 74.35054) (xy 86.382591 74.35054) (xy 86.47743 74.615381) + (xy 86.622115 74.856631) (xy 86.811086 75.065019) (xy 87.03708 75.232537) (xy 87.291413 75.352746) (xy 87.425461 75.393404) + (xy 87.6475 75.271415) (xy 87.6475 74.1285) (xy 86.503876 74.1285) (xy 86.382591 74.35054) (xy 85.929 74.35054) + (xy 85.929 73.65246) (xy 86.382591 73.65246) (xy 86.503876 73.8745) (xy 87.6475 73.8745) (xy 87.6475 72.731585) + (xy 87.9015 72.731585) (xy 87.9015 73.8745) (xy 87.9215 73.8745) (xy 87.9215 74.1285) (xy 87.9015 74.1285) + (xy 87.9015 75.271415) (xy 88.123539 75.393404) (xy 88.257587 75.352746) (xy 88.51192 75.232537) (xy 88.737914 75.065019) + (xy 88.926885 74.856631) (xy 89.041921 74.664818) (xy 89.115568 74.802601) (xy 89.294892 75.021108) (xy 89.513399 75.200432) + (xy 89.762692 75.333682) (xy 90.033191 75.415736) (xy 90.244008 75.4365) (xy 90.384992 75.4365) (xy 90.595809 75.415736) + (xy 90.866308 75.333682) (xy 91.115601 75.200432) (xy 91.334108 75.021108) (xy 91.513432 74.802601) (xy 91.646682 74.553308) + (xy 91.728736 74.282809) (xy 91.756443 74.0015) (xy 91.728736 73.720191) (xy 91.646682 73.449692) (xy 91.513432 73.200399) + (xy 91.334108 72.981892) (xy 91.115601 72.802568) (xy 90.866308 72.669318) (xy 90.595809 72.587264) (xy 90.384992 72.5665) + (xy 90.244008 72.5665) (xy 90.033191 72.587264) (xy 89.762692 72.669318) (xy 89.513399 72.802568) (xy 89.294892 72.981892) + (xy 89.115568 73.200399) (xy 89.041921 73.338182) (xy 88.926885 73.146369) (xy 88.737914 72.937981) (xy 88.51192 72.770463) + (xy 88.257587 72.650254) (xy 88.123539 72.609596) (xy 87.9015 72.731585) (xy 87.6475 72.731585) (xy 87.425461 72.609596) + (xy 87.291413 72.650254) (xy 87.03708 72.770463) (xy 86.811086 72.937981) (xy 86.622115 73.146369) (xy 86.47743 73.387619) + (xy 86.382591 73.65246) (xy 85.929 73.65246) (xy 85.929 72.463078) (xy 87.006079 71.386) (xy 87.275911 71.386) + (xy 87.543489 71.332775) (xy 87.795543 71.228371) (xy 88.022386 71.076799) (xy 88.215299 70.883886) (xy 88.366871 70.657043) + (xy 88.471275 70.404989) (xy 88.5245 70.137411) (xy 88.5245 69.864589) (xy 88.471275 69.597011) (xy 88.366871 69.344957) + (xy 88.215299 69.118114) (xy 88.0245 68.927315) (xy 88.0245 62.311685) (xy 88.215299 62.120886) (xy 88.366871 61.894043) + (xy 88.471275 61.641989) (xy 88.5245 61.374411) (xy 88.5245 61.101589) (xy 88.471275 60.834011) (xy 88.366871 60.581957) + (xy 88.215299 60.355114) (xy 88.022386 60.162201) (xy 87.795543 60.010629) (xy 87.543489 59.906225) (xy 87.275911 59.853) + (xy 87.003089 59.853) (xy 86.735511 59.906225) (xy 86.483457 60.010629) (xy 86.256614 60.162201) (xy 86.063701 60.355114) + (xy 85.912129 60.581957) (xy 85.807725 60.834011) (xy 85.7545 61.101589) (xy 85.7545 61.374411) (xy 85.807725 61.641989) + (xy 85.912129 61.894043) (xy 86.063701 62.120886) (xy 86.2545 62.311685) (xy 86.254501 68.927314) (xy 86.063701 69.118114) + (xy 85.912129 69.344957) (xy 85.807725 69.597011) (xy 85.7545 69.864589) (xy 85.7545 70.134421) (xy 84.757263 71.131659) + (xy 84.703687 71.147911) (xy 84.549941 71.230089) (xy 84.415183 71.340683) (xy 84.304589 71.475441) (xy 84.222411 71.629187) + (xy 84.171805 71.79601) (xy 84.154718 71.9695) (xy 84.159001 72.012987) (xy 84.159 81.627315) (xy 83.968201 81.818114) + (xy 83.816629 82.044957) (xy 83.712225 82.297011) (xy 83.659 82.564589) (xy 79.851072 82.564589) (xy 79.851072 81.678) + (xy 79.838812 81.553518) (xy 79.802502 81.43382) (xy 79.743537 81.323506) (xy 79.664185 81.226815) (xy 79.567494 81.147463) + (xy 79.45718 81.088498) (xy 79.337482 81.052188) (xy 79.213 81.039928) (xy 77.613 81.039928) (xy 77.488518 81.052188) + (xy 77.36882 81.088498) (xy 77.258506 81.147463) (xy 77.161815 81.226815) (xy 77.082463 81.323506) (xy 77.023498 81.43382) + (xy 76.987188 81.553518) (xy 76.974928 81.678) (xy 76.974928 83.278) (xy 76.987188 83.402482) (xy 77.023498 83.52218) + (xy 77.082463 83.632494) (xy 77.161815 83.729185) (xy 77.258506 83.808537) (xy 77.36882 83.867502) (xy 77.488518 83.903812) + (xy 77.506482 83.905581) (xy 77.393392 83.998392) (xy 77.214068 84.216899) (xy 77.080818 84.466192) (xy 76.998764 84.736691) + (xy 76.971057 85.018) (xy 65.654889 85.018) (xy 65.657943 84.987) (xy 65.630236 84.705691) (xy 65.548182 84.435192) + (xy 65.414932 84.185899) (xy 65.235608 83.967392) (xy 65.122518 83.874581) (xy 65.140482 83.872812) (xy 65.26018 83.836502) + (xy 65.370494 83.777537) (xy 65.467185 83.698185) (xy 65.546537 83.601494) (xy 65.605502 83.49118) (xy 65.641812 83.371482) + (xy 65.654072 83.247) (xy 65.654072 82.478) (xy 69.351057 82.478) (xy 69.378764 82.759309) (xy 69.460818 83.029808) + (xy 69.594068 83.279101) (xy 69.773392 83.497608) (xy 69.991899 83.676932) (xy 70.129682 83.750579) (xy 69.937869 83.865615) + (xy 69.729481 84.054586) (xy 69.561963 84.28058) (xy 69.441754 84.534913) (xy 69.401096 84.668961) (xy 69.523085 84.891) + (xy 70.666 84.891) (xy 70.666 84.871) (xy 70.92 84.871) (xy 70.92 84.891) (xy 72.062915 84.891) + (xy 72.184904 84.668961) (xy 72.144246 84.534913) (xy 72.024037 84.28058) (xy 71.856519 84.054586) (xy 71.648131 83.865615) + (xy 71.456318 83.750579) (xy 71.594101 83.676932) (xy 71.812608 83.497608) (xy 71.991932 83.279101) (xy 72.125182 83.029808) + (xy 72.207236 82.759309) (xy 72.234943 82.478) (xy 72.207236 82.196691) (xy 72.125182 81.926192) (xy 71.991932 81.676899) + (xy 71.812608 81.458392) (xy 71.594101 81.279068) (xy 71.344808 81.145818) (xy 71.074309 81.063764) (xy 70.863492 81.043) + (xy 70.722508 81.043) (xy 70.511691 81.063764) (xy 70.241192 81.145818) (xy 69.991899 81.279068) (xy 69.773392 81.458392) + (xy 69.594068 81.676899) (xy 69.460818 81.926192) (xy 69.378764 82.196691) (xy 69.351057 82.478) (xy 65.654072 82.478) + (xy 65.654072 81.647) (xy 65.641812 81.522518) (xy 65.605502 81.40282) (xy 65.546537 81.292506) (xy 65.467185 81.195815) + (xy 65.370494 81.116463) (xy 65.26018 81.057498) (xy 65.140482 81.021188) (xy 65.016 81.008928) (xy 63.416 81.008928) + (xy 63.291518 81.021188) (xy 63.17182 81.057498) (xy 63.061506 81.116463) (xy 62.964815 81.195815) (xy 62.885463 81.292506) + (xy 62.826498 81.40282) (xy 62.790188 81.522518) (xy 62.777928 81.647) (xy 62.777928 83.247) (xy 62.790188 83.371482) + (xy 62.826498 83.49118) (xy 62.885463 83.601494) (xy 62.964815 83.698185) (xy 63.061506 83.777537) (xy 63.17182 83.836502) + (xy 63.291518 83.872812) (xy 63.309482 83.874581) (xy 63.196392 83.967392) (xy 63.017068 84.185899) (xy 62.883818 84.435192) + (xy 62.801764 84.705691) (xy 62.774057 84.987) (xy 48.16 84.987) (xy 48.16 82.447) (xy 55.154057 82.447) + (xy 55.181764 82.728309) (xy 55.263818 82.998808) (xy 55.397068 83.248101) (xy 55.576392 83.466608) (xy 55.794899 83.645932) + (xy 55.932682 83.719579) (xy 55.740869 83.834615) (xy 55.532481 84.023586) (xy 55.364963 84.24958) (xy 55.244754 84.503913) + (xy 55.204096 84.637961) (xy 55.326085 84.86) (xy 56.469 84.86) (xy 56.469 84.84) (xy 56.723 84.84) + (xy 56.723 84.86) (xy 57.865915 84.86) (xy 57.987904 84.637961) (xy 57.947246 84.503913) (xy 57.827037 84.24958) + (xy 57.659519 84.023586) (xy 57.451131 83.834615) (xy 57.259318 83.719579) (xy 57.397101 83.645932) (xy 57.615608 83.466608) + (xy 57.794932 83.248101) (xy 57.928182 82.998808) (xy 58.010236 82.728309) (xy 58.037943 82.447) (xy 58.010236 82.165691) + (xy 57.928182 81.895192) (xy 57.794932 81.645899) (xy 57.615608 81.427392) (xy 57.397101 81.248068) (xy 57.147808 81.114818) + (xy 56.877309 81.032764) (xy 56.666492 81.012) (xy 56.525508 81.012) (xy 56.314691 81.032764) (xy 56.044192 81.114818) + (xy 55.794899 81.248068) (xy 55.576392 81.427392) (xy 55.397068 81.645899) (xy 55.263818 81.895192) (xy 55.181764 82.165691) + (xy 55.154057 82.447) (xy 48.16 82.447) (xy 48.16 60.698828) (xy 64.3392 60.698828) (xy 64.3392 60.989772) + (xy 64.39596 61.275125) (xy 64.507299 61.543922) (xy 64.668939 61.785833) (xy 64.874667 61.991561) (xy 65.116578 62.153201) + (xy 65.385375 62.26454) (xy 65.670728 62.3213) (xy 65.961672 62.3213) (xy 66.247025 62.26454) (xy 66.515822 62.153201) + (xy 66.757733 61.991561) (xy 66.963461 61.785833) (xy 67.125101 61.543922) (xy 67.23644 61.275125) (xy 67.2932 60.989772) + (xy 67.2932 60.698828) (xy 67.23644 60.413475) (xy 67.125101 60.144678) (xy 66.963461 59.902767) (xy 66.757733 59.697039) + (xy 66.515822 59.535399) (xy 66.247025 59.42406) (xy 65.961672 59.3673) (xy 65.670728 59.3673) (xy 65.385375 59.42406) + (xy 65.116578 59.535399) (xy 64.874667 59.697039) (xy 64.668939 59.902767) (xy 64.507299 60.144678) (xy 64.39596 60.413475) + (xy 64.3392 60.698828) (xy 48.16 60.698828) (xy 48.16 56.783589) (xy 76.7375 56.783589) (xy 76.7375 57.056411) + (xy 76.790725 57.323989) (xy 76.895129 57.576043) (xy 77.046701 57.802886) (xy 77.2375 57.993685) (xy 77.237501 64.164814) + (xy 77.046701 64.355614) (xy 76.895129 64.582457) (xy 76.790725 64.834511) (xy 76.7375 65.102089) (xy 76.7375 65.374911) + (xy 76.790725 65.642489) (xy 76.895129 65.894543) (xy 77.046701 66.121386) (xy 77.239614 66.314299) (xy 77.466457 66.465871) + (xy 77.718511 66.570275) (xy 77.986089 66.6235) (xy 78.258911 66.6235) (xy 78.526489 66.570275) (xy 78.778543 66.465871) + (xy 79.005386 66.314299) (xy 79.198299 66.121386) (xy 79.206 66.10986) (xy 79.206001 67.403314) (xy 79.015201 67.594114) + (xy 78.863629 67.820957) (xy 78.759225 68.073011) (xy 78.706 68.340589) (xy 78.706 68.613411) (xy 78.759225 68.880989) + (xy 78.863629 69.133043) (xy 79.015201 69.359886) (xy 79.208114 69.552799) (xy 79.434957 69.704371) (xy 79.687011 69.808775) + (xy 79.954589 69.862) (xy 80.227411 69.862) (xy 80.494989 69.808775) (xy 80.747043 69.704371) (xy 80.973886 69.552799) + (xy 81.166799 69.359886) (xy 81.318371 69.133043) (xy 81.422775 68.880989) (xy 81.476 68.613411) (xy 81.476 68.340589) + (xy 81.422775 68.073011) (xy 81.318371 67.820957) (xy 81.166799 67.594114) (xy 80.976 67.403315) (xy 80.976 65.740685) + (xy 81.166799 65.549886) (xy 81.318371 65.323043) (xy 81.422775 65.070989) (xy 81.476 64.803411) (xy 81.476 64.530589) + (xy 81.422775 64.263011) (xy 81.318371 64.010957) (xy 81.166799 63.784114) (xy 80.973886 63.591201) (xy 80.747043 63.439629) + (xy 80.494989 63.335225) (xy 80.227411 63.282) (xy 79.954589 63.282) (xy 79.687011 63.335225) (xy 79.434957 63.439629) + (xy 79.208114 63.591201) (xy 79.015201 63.784114) (xy 79.0075 63.795639) (xy 79.0075 59.441089) (xy 96.9305 59.441089) + (xy 96.9305 59.713911) (xy 96.983725 59.981489) (xy 97.088129 60.233543) (xy 97.239701 60.460386) (xy 97.432614 60.653299) + (xy 97.659457 60.804871) (xy 97.911511 60.909275) (xy 98.179089 60.9625) (xy 98.451911 60.9625) (xy 98.719489 60.909275) + (xy 98.971543 60.804871) (xy 99.198386 60.653299) (xy 99.391299 60.460386) (xy 99.542871 60.233543) (xy 99.647275 59.981489) + (xy 99.7005 59.713911) (xy 99.7005 59.441089) (xy 99.647275 59.173511) (xy 99.542871 58.921457) (xy 99.391299 58.694614) + (xy 99.198386 58.501701) (xy 98.971543 58.350129) (xy 98.719489 58.245725) (xy 98.451911 58.1925) (xy 98.179089 58.1925) + (xy 97.911511 58.245725) (xy 97.659457 58.350129) (xy 97.432614 58.501701) (xy 97.239701 58.694614) (xy 97.088129 58.921457) + (xy 96.983725 59.173511) (xy 96.9305 59.441089) (xy 79.0075 59.441089) (xy 79.0075 57.993685) (xy 79.198299 57.802886) + (xy 79.349871 57.576043) (xy 79.454275 57.323989) (xy 79.5075 57.056411) (xy 79.5075 56.783589) (xy 79.454275 56.516011) + (xy 79.349871 56.263957) (xy 79.198299 56.037114) (xy 79.005386 55.844201) (xy 78.778543 55.692629) (xy 78.526489 55.588225) + (xy 78.258911 55.535) (xy 77.986089 55.535) (xy 77.718511 55.588225) (xy 77.466457 55.692629) (xy 77.239614 55.844201) + (xy 77.046701 56.037114) (xy 76.895129 56.263957) (xy 76.790725 56.516011) (xy 76.7375 56.783589) (xy 48.16 56.783589) + (xy 48.16 54.561089) (xy 96.9305 54.561089) (xy 96.9305 54.833911) (xy 96.983725 55.101489) (xy 97.088129 55.353543) + (xy 97.239701 55.580386) (xy 97.432614 55.773299) (xy 97.659457 55.924871) (xy 97.911511 56.029275) (xy 98.179089 56.0825) + (xy 98.451911 56.0825) (xy 98.719489 56.029275) (xy 98.971543 55.924871) (xy 99.198386 55.773299) (xy 99.391299 55.580386) + (xy 99.542871 55.353543) (xy 99.647275 55.101489) (xy 99.7005 54.833911) (xy 99.7005 54.561089) (xy 99.647275 54.293511) + (xy 99.542871 54.041457) (xy 99.391299 53.814614) (xy 99.198386 53.621701) (xy 98.971543 53.470129) (xy 98.719489 53.365725) + (xy 98.451911 53.3125) (xy 98.179089 53.3125) (xy 97.911511 53.365725) (xy 97.659457 53.470129) (xy 97.432614 53.621701) + (xy 97.239701 53.814614) (xy 97.088129 54.041457) (xy 96.983725 54.293511) (xy 96.9305 54.561089) (xy 48.16 54.561089) + (xy 48.16 46.779872) (xy 49.265 46.779872) (xy 49.265 47.220128) (xy 49.35089 47.651925) (xy 49.519369 48.058669) + (xy 49.763962 48.424729) (xy 50.075271 48.736038) (xy 50.441331 48.980631) (xy 50.848075 49.14911) (xy 51.279872 49.235) + (xy 51.720128 49.235) (xy 52.151925 49.14911) (xy 52.558669 48.980631) (xy 52.924729 48.736038) (xy 53.236038 48.424729) + (xy 53.480631 48.058669) (xy 53.64911 47.651925) (xy 53.735 47.220128) (xy 53.735 46.779872) (xy 53.64911 46.348075) + (xy 53.480631 45.941331) (xy 53.236038 45.575271) (xy 52.924729 45.263962) (xy 52.558669 45.019369) (xy 52.151925 44.85089) + (xy 51.720128 44.765) (xy 51.279872 44.765) (xy 50.848075 44.85089) (xy 50.441331 45.019369) (xy 50.075271 45.263962) + (xy 49.763962 45.575271) (xy 49.519369 45.941331) (xy 49.35089 46.348075) (xy 49.265 46.779872) (xy 48.16 46.779872) + (xy 48.16 43.66) (xy 100.166921 43.66) + ) + ) + ) +) diff --git a/F1-nolib/chronometer/kicad/chrono/chrono.net b/F1-nolib/chronometer/kicad/chrono/chrono.net new file mode 100644 index 0000000..118983c --- /dev/null +++ b/F1-nolib/chronometer/kicad/chrono/chrono.net @@ -0,0 +1,1047 @@ +(export (version D) + (design + (source /home/eddy/Docs/SAO/ELECTRONICS/STM32/F1-srcs/chronometer/kicad/chrono/chrono.sch) + (date "Чт 27 июн 2019 16:20:59") + (tool "Eeschema (6.0.0-rc1-dev-1613-ga55d9819b)") + (sheet (number 1) (name /) (tstamps /) + (title_block + (title) + (company) + (rev) + (date) + (source chrono.sch) + (comment (number 1) (value "")) + (comment (number 2) (value "")) + (comment (number 3) (value "")) + (comment (number 4) (value ""))))) + (components + (comp (ref U7) + (value STM32F103C6Tx) + (footprint Package_QFP:LQFP-48_7x7mm_P0.5mm) + (datasheet http://www.st.com/st-web-ui/static/active/en/resource/technical/document/datasheet/CD00210843.pdf) + (libsource (lib MCU_ST_STM32F1) (part STM32F103C6Tx) (description "ARM Cortex-M3 MCU, 32KB flash, 10KB RAM, 72MHz, 2-3.6V, 37 GPIO, LQFP-48")) + (sheetpath (names /) (tstamps /)) + (tstamp 5D13BBBF)) + (comp (ref J7) + (value USART1) + (footprint Connector_PinSocket_2.54mm:PinSocket_1x03_P2.54mm_Vertical) + (datasheet ~) + (libsource (lib Connector) (part Conn_01x03_Female) (description "Generic connector, single row, 01x03, script generated (kicad-library-utils/schlib/autogen/connector/)")) + (sheetpath (names /) (tstamps /)) + (tstamp 5D14396C)) + (comp (ref J3) + (value Ext_trig0) + (footprint TerminalBlock_Phoenix:TerminalBlock_Phoenix_MKDS-1,5-2-5.08_1x02_P5.08mm_Horizontal) + (datasheet ~) + (libsource (lib Connector_Generic) (part Conn_01x02) (description "Generic connector, single row, 01x02, script generated (kicad-library-utils/schlib/autogen/connector/)")) + (sheetpath (names /) (tstamps /)) + (tstamp 5D1444DC)) + (comp (ref R1) + (value 10k) + (footprint Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder) + (libsource (lib stm32-rescue) (part R) (description "")) + (sheetpath (names /) (tstamps /)) + (tstamp 5D347863)) + (comp (ref R2) + (value 10k) + (footprint Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder) + (libsource (lib stm32-rescue) (part R) (description "")) + (sheetpath (names /) (tstamps /)) + (tstamp 590D3334)) + (comp (ref C2) + (value 0.1) + (footprint Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder) + (libsource (lib stm32-rescue) (part C) (description "")) + (sheetpath (names /) (tstamps /)) + (tstamp 590D4150)) + (comp (ref C1) + (value 0.1) + (footprint Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder) + (libsource (lib stm32-rescue) (part C) (description "")) + (sheetpath (names /) (tstamps /)) + (tstamp 5D4AE2B9)) + (comp (ref SW2) + (value Boot) + (footprint Buttons_Switches_SMD:SW_SPST_FSMSM) + (libsource (lib Switch) (part SW_Push) (description "Push button switch, generic, two pins")) + (sheetpath (names /) (tstamps /)) + (tstamp 5D34785A)) + (comp (ref SW1) + (value Reset) + (footprint Buttons_Switches_SMD:SW_SPST_FSMSM) + (libsource (lib Switch) (part SW_Push) (description "Push button switch, generic, two pins")) + (sheetpath (names /) (tstamps /)) + (tstamp 5D34785B)) + (comp (ref J5) + (value Ext_trig1) + (footprint TerminalBlock_Phoenix:TerminalBlock_Phoenix_MKDS-1,5-2-5.08_1x02_P5.08mm_Horizontal) + (datasheet ~) + (libsource (lib Connector_Generic) (part Conn_01x02) (description "Generic connector, single row, 01x02, script generated (kicad-library-utils/schlib/autogen/connector/)")) + (sheetpath (names /) (tstamps /)) + (tstamp 5D145441)) + (comp (ref J6) + (value Ext_trig2) + (footprint TerminalBlock_Phoenix:TerminalBlock_Phoenix_MKDS-1,5-2-5.08_1x02_P5.08mm_Horizontal) + (datasheet ~) + (libsource (lib Connector_Generic) (part Conn_01x02) (description "Generic connector, single row, 01x02, script generated (kicad-library-utils/schlib/autogen/connector/)")) + (sheetpath (names /) (tstamps /)) + (tstamp 5D1457FF)) + (comp (ref C12) + (value 0.1) + (footprint Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder) + (libsource (lib stm32-rescue) (part C) (description "")) + (sheetpath (names /) (tstamps /)) + (tstamp 58C42D39)) + (comp (ref U2) + (value LM2576HV) + (footprint TO_SOT_Packages_THT:TO-220-5_P3.4x3.7mm_StaggerEven_Lead3.8mm_Vertical) + (fields + (field (name Manufacturer) "Texas Instruments")) + (libsource (lib stm32-rescue) (part LM2576HV) (description "")) + (sheetpath (names /) (tstamps /)) + (tstamp 58C43093)) + (comp (ref U4) + (value LM1117-3.3) + (footprint TO_SOT_Packages_SMD:SOT-223) + (libsource (lib stm32-rescue) (part LM1117-3.3-RESCUE-stm32) (description "")) + (sheetpath (names /) (tstamps /)) + (tstamp 58C431FC)) + (comp (ref D3) + (value 1n5822) + (footprint Diode_THT:D_DO-201_P12.70mm_Horizontal) + (libsource (lib stm32-rescue) (part D) (description "")) + (sheetpath (names /) (tstamps /)) + (tstamp 58C43816)) + (comp (ref L1) + (value 100u) + (footprint Inductor_SMD:L_12x12mm_H4.5mm) + (libsource (lib stm32-rescue) (part L) (description "")) + (sheetpath (names /) (tstamps /)) + (tstamp 58C43929)) + (comp (ref C6) + (value 100u) + (footprint Capacitor_THT:CP_Radial_D8.0mm_P3.50mm) + (libsource (lib stm32-rescue) (part CP) (description "")) + (sheetpath (names /) (tstamps /)) + (tstamp 58C4396A)) + (comp (ref C4) + (value 47u) + (footprint Capacitor_Tantalum_SMD:CP_EIA-3216-18_Kemet-A_Pad1.58x1.35mm_HandSolder) + (libsource (lib stm32-rescue) (part CP) (description "")) + (sheetpath (names /) (tstamps /)) + (tstamp 58C43A3B)) + (comp (ref C9) + (value 47u) + (footprint Capacitor_Tantalum_SMD:CP_EIA-3216-18_Kemet-A_Pad1.58x1.35mm_HandSolder) + (libsource (lib stm32-rescue) (part CP) (description "")) + (sheetpath (names /) (tstamps /)) + (tstamp 5D4AE2B5)) + (comp (ref D4) + (value LED0) + (footprint LED_THT:LED_D5.0mm) + (libsource (lib stm32-rescue) (part LED-RESCUE-stm32) (description "")) + (sheetpath (names /) (tstamps /)) + (tstamp 5908EA64)) + (comp (ref R8) + (value 330) + (footprint Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder) + (libsource (lib stm32-rescue) (part R) (description "")) + (sheetpath (names /) (tstamps /)) + (tstamp 5908EB17)) + (comp (ref C13) + (value 0.1) + (footprint Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder) + (libsource (lib stm32-rescue) (part C) (description "")) + (sheetpath (names /) (tstamps /)) + (tstamp 590935EA)) + (comp (ref C14) + (value 0.1) + (footprint Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder) + (libsource (lib stm32-rescue) (part C) (description "")) + (sheetpath (names /) (tstamps /)) + (tstamp 59093675)) + (comp (ref D5) + (value LED1) + (footprint LED_THT:LED_D5.0mm) + (libsource (lib stm32-rescue) (part LED-RESCUE-stm32) (description "")) + (sheetpath (names /) (tstamps /)) + (tstamp 5909AF9A)) + (comp (ref R9) + (value 330) + (footprint Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder) + (libsource (lib stm32-rescue) (part R) (description "")) + (sheetpath (names /) (tstamps /)) + (tstamp 5909AFA0)) + (comp (ref C15) + (value 0.1) + (footprint Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder) + (libsource (lib stm32-rescue) (part C) (description "")) + (sheetpath (names /) (tstamps /)) + (tstamp 590A8102)) + (comp (ref Q1) + (value AO3407) + (footprint TO_SOT_Packages_SMD:SOT-23_Handsoldering) + (libsource (lib stm32-rescue) (part Q_PMOS_GSD) (description "")) + (sheetpath (names /) (tstamps /)) + (tstamp 5910E2F2)) + (comp (ref C3) + (value 0.1) + (footprint Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder) + (libsource (lib stm32-rescue) (part C) (description "")) + (sheetpath (names /) (tstamps /)) + (tstamp 596772D4)) + (comp (ref C8) + (value 0.1) + (footprint Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder) + (libsource (lib stm32-rescue) (part C) (description "")) + (sheetpath (names /) (tstamps /)) + (tstamp 5A4FA4E4)) + (comp (ref R5) + (value 10k) + (footprint Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder) + (libsource (lib stm32-rescue) (part R) (description "")) + (sheetpath (names /) (tstamps /)) + (tstamp 5D16EDDD)) + (comp (ref D1) + (value MM3Z7V5) + (footprint Diode_SMD:D_0805_2012Metric_Pad1.15x1.40mm_HandSolder) + (datasheet ~) + (libsource (lib Device) (part D_Zener) (description "Zener diode")) + (sheetpath (names /) (tstamps /)) + (tstamp 5D1735CA)) + (comp (ref P1) + (value USB_B) + (footprint Connectors_USB:USB_B_OST_USB-B1HSxx_Horizontal) + (libsource (lib stm32-rescue) (part USB_A-RESCUE-stm32) (description "")) + (sheetpath (names /) (tstamps /)) + (tstamp 5CEABE76)) + (comp (ref R3) + (value 22) + (footprint Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder) + (libsource (lib stm32-rescue) (part R) (description "")) + (sheetpath (names /) (tstamps /)) + (tstamp 5CEABEA6)) + (comp (ref R4) + (value 22) + (footprint Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder) + (libsource (lib stm32-rescue) (part R) (description "")) + (sheetpath (names /) (tstamps /)) + (tstamp 5CEABEAC)) + (comp (ref U1) + (value USBLC6-2SC6) + (footprint TO_SOT_Packages_SMD:SOT-23-6_Handsoldering) + (datasheet http://www2.st.com/resource/en/datasheet/CD00050750.pdf) + (libsource (lib Power_Protection) (part USBLC6-2SC6) (description "Bidirectional ESD Protection Diode, SOT-23-6")) + (sheetpath (names /) (tstamps /)) + (tstamp 5CED0250)) + (comp (ref R13) + (value 100k) + (footprint Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder) + (libsource (lib stm32-rescue) (part R) (description "")) + (sheetpath (names /) (tstamps /)) + (tstamp 5D1076F1)) + (comp (ref Y1) + (value 8MHz) + (footprint Crystal:Crystal_HC49-U_Vertical) + (datasheet ~) + (libsource (lib Device) (part Crystal) (description "Two pin crystal")) + (sheetpath (names /) (tstamps /)) + (tstamp 5D1F4994)) + (comp (ref C11) + (value 12) + (footprint Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder) + (libsource (lib stm32-rescue) (part C) (description "")) + (sheetpath (names /) (tstamps /)) + (tstamp 5D1F64B1)) + (comp (ref C10) + (value 12) + (footprint Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder) + (libsource (lib stm32-rescue) (part C) (description "")) + (sheetpath (names /) (tstamps /)) + (tstamp 5D1F7471)) + (comp (ref Q2) + (value DTA114Y) + (footprint TO_SOT_Packages_SMD:SOT-323_SC-70_Handsoldering) + (libsource (lib Transistor_BJT) (part DTA114Y) (description "Digital PNP Transistor, 10k/47k, SOT-23")) + (sheetpath (names /) (tstamps /)) + (tstamp 5D5EB488)) + (comp (ref R18) + (value 100k) + (footprint Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder) + (libsource (lib stm32-rescue) (part R) (description "")) + (sheetpath (names /) (tstamps /)) + (tstamp 5D650328)) + (comp (ref U5) + (value PC817) + (footprint Package_DIP:DIP-4_W7.62mm) + (datasheet http://www.soselectronic.cz/a_info/resource/d/pc817.pdf) + (libsource (lib Isolator) (part PC817) (description "DC Optocoupler, Vce 35V, CTR 50-300%, DIP4")) + (sheetpath (names /) (tstamps /)) + (tstamp 5D68F125)) + (comp (ref R12) + (value 4k7) + (footprint Resistor_SMD:R_0805_2012Metric_Pad1.15x1.40mm_HandSolder) + (datasheet ~) + (libsource (lib Device) (part R) (description Resistor)) + (sheetpath (names /) (tstamps /)) + (tstamp 5D6934BF)) + (comp (ref R10) + (value 330) + (footprint Resistor_SMD:R_0805_2012Metric_Pad1.15x1.40mm_HandSolder) + (datasheet ~) + (libsource (lib Device) (part R) (description Resistor)) + (sheetpath (names /) (tstamps /)) + (tstamp 5D6BDDB4)) + (comp (ref R11) + (value 4k7) + (footprint Resistor_SMD:R_0805_2012Metric_Pad1.15x1.40mm_HandSolder) + (datasheet ~) + (libsource (lib Device) (part R) (description Resistor)) + (sheetpath (names /) (tstamps /)) + (tstamp 5D6D432A)) + (comp (ref U6) + (value PC817) + (footprint Package_DIP:DIP-4_W7.62mm) + (datasheet http://www.soselectronic.cz/a_info/resource/d/pc817.pdf) + (libsource (lib Isolator) (part PC817) (description "DC Optocoupler, Vce 35V, CTR 50-300%, DIP4")) + (sheetpath (names /) (tstamps /)) + (tstamp 5D710D2A)) + (comp (ref R16) + (value 4k7) + (footprint Resistor_SMD:R_0805_2012Metric_Pad1.15x1.40mm_HandSolder) + (datasheet ~) + (libsource (lib Device) (part R) (description Resistor)) + (sheetpath (names /) (tstamps /)) + (tstamp 5D710D30)) + (comp (ref R14) + (value 330) + (footprint Resistor_SMD:R_0805_2012Metric_Pad1.15x1.40mm_HandSolder) + (datasheet ~) + (libsource (lib Device) (part R) (description Resistor)) + (sheetpath (names /) (tstamps /)) + (tstamp 5D710D44)) + (comp (ref R15) + (value 4k7) + (footprint Resistor_SMD:R_0805_2012Metric_Pad1.15x1.40mm_HandSolder) + (datasheet ~) + (libsource (lib Device) (part R) (description Resistor)) + (sheetpath (names /) (tstamps /)) + (tstamp 5D710D50)) + (comp (ref U8) + (value PC817) + (footprint Package_DIP:DIP-4_W7.62mm) + (datasheet http://www.soselectronic.cz/a_info/resource/d/pc817.pdf) + (libsource (lib Isolator) (part PC817) (description "DC Optocoupler, Vce 35V, CTR 50-300%, DIP4")) + (sheetpath (names /) (tstamps /)) + (tstamp 5D72A0B8)) + (comp (ref R20) + (value 4k7) + (footprint Resistor_SMD:R_0805_2012Metric_Pad1.15x1.40mm_HandSolder) + (datasheet ~) + (libsource (lib Device) (part R) (description Resistor)) + (sheetpath (names /) (tstamps /)) + (tstamp 5D72A0BE)) + (comp (ref R19) + (value 4k7) + (footprint Resistor_SMD:R_0805_2012Metric_Pad1.15x1.40mm_HandSolder) + (datasheet ~) + (libsource (lib Device) (part R) (description Resistor)) + (sheetpath (names /) (tstamps /)) + (tstamp 5D72A0DE)) + (comp (ref R17) + (value 2k2) + (footprint Resistor_SMD:R_0805_2012Metric_Pad1.15x1.40mm_HandSolder) + (datasheet ~) + (libsource (lib Device) (part R) (description Resistor)) + (sheetpath (names /) (tstamps /)) + (tstamp 5D74F6B4)) + (comp (ref J1) + (value "Power 12V") + (footprint TerminalBlock_Phoenix:TerminalBlock_Phoenix_MKDS-1,5-2-5.08_1x02_P5.08mm_Horizontal) + (datasheet ~) + (libsource (lib Connector_Generic) (part Conn_01x02) (description "Generic connector, single row, 01x02, script generated (kicad-library-utils/schlib/autogen/connector/)")) + (sheetpath (names /) (tstamps /)) + (tstamp 5D79C13C)) + (comp (ref D2) + (value SS14) + (footprint Diode_SMD:D_SMA_Handsoldering) + (datasheet ~) + (libsource (lib Device) (part D_Schottky) (description "Schottky diode")) + (sheetpath (names /) (tstamps /)) + (tstamp 5D89B9B8)) + (comp (ref R6) + (value 1k5) + (footprint Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder) + (libsource (lib stm32-rescue) (part R) (description "")) + (sheetpath (names /) (tstamps /)) + (tstamp 5D5EA0B2)) + (comp (ref J4) + (value LIDAR) + (footprint Connector_PinSocket_2.54mm:PinSocket_1x04_P2.54mm_Vertical) + (datasheet ~) + (libsource (lib Connector) (part Conn_01x04_Female) (description "Generic connector, single row, 01x04, script generated (kicad-library-utils/schlib/autogen/connector/)")) + (sheetpath (names /) (tstamps /)) + (tstamp 5D927958)) + (comp (ref J2) + (value +5Vout) + (footprint TerminalBlock_Phoenix:TerminalBlock_Phoenix_MKDS-1,5-2-5.08_1x02_P5.08mm_Horizontal) + (datasheet ~) + (libsource (lib Connector_Generic) (part Conn_01x02) (description "Generic connector, single row, 01x02, script generated (kicad-library-utils/schlib/autogen/connector/)")) + (sheetpath (names /) (tstamps /)) + (tstamp 5D93AD09)) + (comp (ref R7) + (value 22) + (footprint Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder) + (datasheet ~) + (libsource (lib Device) (part R) (description Resistor)) + (sheetpath (names /) (tstamps /)) + (tstamp 5D93EDCC)) + (comp (ref U3) + (value L80-R) + (footprint chrono:L80-R) + (libsource (lib Chrono) (part L80-R) (description "")) + (sheetpath (names /) (tstamps /)) + (tstamp 5D13B322)) + (comp (ref C5) + (value 10u) + (footprint Capacitor_SMD:C_1206_3216Metric_Pad1.42x1.75mm_HandSolder) + (datasheet ~) + (libsource (lib Device) (part C) (description "Unpolarized capacitor")) + (sheetpath (names /) (tstamps /)) + (tstamp 5DB80168)) + (comp (ref C7) + (value 0.1) + (footprint Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder) + (libsource (lib stm32-rescue) (part C) (description "")) + (sheetpath (names /) (tstamps /)) + (tstamp 5DB8A65B))) + (libparts + (libpart (lib Chrono) (part L80-R) + (footprints + (fp L80-R)) + (fields + (field (name Reference) U) + (field (name Value) L80-R) + (field (name Footprint) chrono:L80-R)) + (pins + (pin (num 1) (name RXD) (type passive)) + (pin (num 2) (name TXD) (type passive)) + (pin (num 3) (name Gnd) (type passive)) + (pin (num 4) (name Vcc) (type passive)) + (pin (num 5) (name V_BKP) (type passive)) + (pin (num 6) (name PPS) (type passive)) + (pin (num 7) (name Res) (type passive)) + (pin (num 8) (name Res) (type passive)) + (pin (num 9) (name NC) (type passive)) + (pin (num 10) (name RESET) (type passive)) + (pin (num 11) (name Res) (type passive)) + (pin (num 12) (name Gnd) (type passive)))) + (libpart (lib Connector) (part Conn_01x03_Female) + (description "Generic connector, single row, 01x03, script generated (kicad-library-utils/schlib/autogen/connector/)") + (docs ~) + (footprints + (fp Connector*:*_1x??_*)) + (fields + (field (name Reference) J) + (field (name Value) Conn_01x03_Female)) + (pins + (pin (num 1) (name Pin_1) (type passive)) + (pin (num 2) (name Pin_2) (type passive)) + (pin (num 3) (name Pin_3) (type passive)))) + (libpart (lib Connector) (part Conn_01x04_Female) + (description "Generic connector, single row, 01x04, script generated (kicad-library-utils/schlib/autogen/connector/)") + (docs ~) + (footprints + (fp Connector*:*_1x??_*)) + (fields + (field (name Reference) J) + (field (name Value) Conn_01x04_Female)) + (pins + (pin (num 1) (name Pin_1) (type passive)) + (pin (num 2) (name Pin_2) (type passive)) + (pin (num 3) (name Pin_3) (type passive)) + (pin (num 4) (name Pin_4) (type passive)))) + (libpart (lib Connector_Generic) (part Conn_01x02) + (description "Generic connector, single row, 01x02, script generated (kicad-library-utils/schlib/autogen/connector/)") + (docs ~) + (footprints + (fp Connector*:*_1x??_*)) + (fields + (field (name Reference) J) + (field (name Value) Conn_01x02)) + (pins + (pin (num 1) (name Pin_1) (type passive)) + (pin (num 2) (name Pin_2) (type passive)))) + (libpart (lib Device) (part C) + (description "Unpolarized capacitor") + (docs ~) + (footprints + (fp C_*)) + (fields + (field (name Reference) C) + (field (name Value) C)) + (pins + (pin (num 1) (name ~) (type passive)) + (pin (num 2) (name ~) (type passive)))) + (libpart (lib Device) (part Crystal) + (description "Two pin crystal") + (docs ~) + (footprints + (fp Crystal*)) + (fields + (field (name Reference) Y) + (field (name Value) Crystal)) + (pins + (pin (num 1) (name 1) (type passive)) + (pin (num 2) (name 2) (type passive)))) + (libpart (lib Device) (part D_Schottky) + (description "Schottky diode") + (docs ~) + (footprints + (fp TO-???*) + (fp *_Diode_*) + (fp *SingleDiode*) + (fp D_*)) + (fields + (field (name Reference) D) + (field (name Value) D_Schottky)) + (pins + (pin (num 1) (name K) (type passive)) + (pin (num 2) (name A) (type passive)))) + (libpart (lib Device) (part D_Zener) + (description "Zener diode") + (docs ~) + (footprints + (fp TO-???*) + (fp *_Diode_*) + (fp *SingleDiode*) + (fp D_*)) + (fields + (field (name Reference) D) + (field (name Value) D_Zener)) + (pins + (pin (num 1) (name K) (type passive)) + (pin (num 2) (name A) (type passive)))) + (libpart (lib Device) (part R) + (description Resistor) + (docs ~) + (footprints + (fp R_*)) + (fields + (field (name Reference) R) + (field (name Value) R)) + (pins + (pin (num 1) (name ~) (type passive)) + (pin (num 2) (name ~) (type passive)))) + (libpart (lib Isolator) (part PC817) + (description "DC Optocoupler, Vce 35V, CTR 50-300%, DIP4") + (docs http://www.soselectronic.cz/a_info/resource/d/pc817.pdf) + (footprints + (fp DIP*W7.62mm*)) + (fields + (field (name Reference) U) + (field (name Value) PC817) + (field (name Footprint) Package_DIP:DIP-4_W7.62mm)) + (pins + (pin (num 1) (name ~) (type passive)) + (pin (num 2) (name ~) (type passive)) + (pin (num 3) (name ~) (type passive)) + (pin (num 4) (name ~) (type passive)))) + (libpart (lib MCU_ST_STM32F1) (part STM32F103C4Tx) + (aliases + (alias STM32F103C6Tx)) + (description "ARM Cortex-M3 MCU, 16KB flash, 6KB RAM, 72MHz, 2-3.6V, 37 GPIO, LQFP-48") + (docs http://www.st.com/st-web-ui/static/active/en/resource/technical/document/datasheet/CD00210843.pdf) + (footprints + (fp LQFP*7x7mm*P0.5mm*)) + (fields + (field (name Reference) U) + (field (name Value) STM32F103C4Tx) + (field (name Footprint) Package_QFP:LQFP-48_7x7mm_P0.5mm)) + (pins + (pin (num 1) (name VBAT) (type power_in)) + (pin (num 2) (name PC13) (type BiDi)) + (pin (num 3) (name PC14) (type BiDi)) + (pin (num 4) (name PC15) (type BiDi)) + (pin (num 5) (name PD0) (type input)) + (pin (num 6) (name PD1) (type input)) + (pin (num 7) (name NRST) (type input)) + (pin (num 8) (name VSSA) (type power_in)) + (pin (num 9) (name VDDA) (type power_in)) + (pin (num 10) (name PA0) (type BiDi)) + (pin (num 11) (name PA1) (type BiDi)) + (pin (num 12) (name PA2) (type BiDi)) + (pin (num 13) (name PA3) (type BiDi)) + (pin (num 14) (name PA4) (type BiDi)) + (pin (num 15) (name PA5) (type BiDi)) + (pin (num 16) (name PA6) (type BiDi)) + (pin (num 17) (name PA7) (type BiDi)) + (pin (num 18) (name PB0) (type BiDi)) + (pin (num 19) (name PB1) (type BiDi)) + (pin (num 20) (name PB2) (type BiDi)) + (pin (num 21) (name PB10) (type BiDi)) + (pin (num 22) (name PB11) (type BiDi)) + (pin (num 23) (name VSS) (type power_in)) + (pin (num 24) (name VDD) (type power_in)) + (pin (num 25) (name PB12) (type BiDi)) + (pin (num 26) (name PB13) (type BiDi)) + (pin (num 27) (name PB14) (type BiDi)) + (pin (num 28) (name PB15) (type BiDi)) + (pin (num 29) (name PA8) (type BiDi)) + (pin (num 30) (name PA9) (type BiDi)) + (pin (num 31) (name PA10) (type BiDi)) + (pin (num 32) (name PA11) (type BiDi)) + (pin (num 33) (name PA12) (type BiDi)) + (pin (num 34) (name PA13) (type BiDi)) + (pin (num 35) (name VSS) (type power_in)) + (pin (num 36) (name VDD) (type power_in)) + (pin (num 37) (name PA14) (type BiDi)) + (pin (num 38) (name PA15) (type BiDi)) + (pin (num 39) (name PB3) (type BiDi)) + (pin (num 40) (name PB4) (type BiDi)) + (pin (num 41) (name PB5) (type BiDi)) + (pin (num 42) (name PB6) (type BiDi)) + (pin (num 43) (name PB7) (type BiDi)) + (pin (num 44) (name BOOT0) (type input)) + (pin (num 45) (name PB8) (type BiDi)) + (pin (num 46) (name PB9) (type BiDi)) + (pin (num 47) (name VSS) (type power_in)) + (pin (num 48) (name VDD) (type power_in)))) + (libpart (lib Power_Protection) (part USBLC6-2SC6) + (description "Bidirectional ESD Protection Diode, SOT-23-6") + (docs http://www2.st.com/resource/en/datasheet/CD00050750.pdf) + (footprints + (fp SOT?23*)) + (fields + (field (name Reference) U) + (field (name Value) USBLC6-2SC6) + (field (name Footprint) Package_TO_SOT_SMD:SOT-23-6)) + (pins + (pin (num 1) (name IO1) (type passive)) + (pin (num 2) (name GND) (type passive)) + (pin (num 3) (name IO2) (type passive)) + (pin (num 4) (name IO2) (type passive)) + (pin (num 5) (name VBUS) (type passive)) + (pin (num 6) (name IO1) (type passive)))) + (libpart (lib Switch) (part SW_Push) + (description "Push button switch, generic, two pins") + (docs ~) + (fields + (field (name Reference) SW) + (field (name Value) SW_Push)) + (pins + (pin (num 1) (name 1) (type passive)) + (pin (num 2) (name 2) (type passive)))) + (libpart (lib Transistor_BJT) (part DTA114Y) + (description "Digital PNP Transistor, 10k/47k, SOT-23") + (footprints + (fp SOT?23*) + (fp SC?59*)) + (fields + (field (name Reference) Q) + (field (name Value) DTA114Y)) + (pins + (pin (num 1) (name B) (type input)) + (pin (num 2) (name E) (type passive)) + (pin (num 3) (name C) (type passive)))) + (libpart (lib stm32-rescue) (part C) + (footprints + (fp C_*)) + (fields + (field (name Reference) C) + (field (name Value) C)) + (pins + (pin (num 1) (name ~) (type passive)) + (pin (num 2) (name ~) (type passive)))) + (libpart (lib stm32-rescue) (part CP) + (footprints + (fp CP_*)) + (fields + (field (name Reference) C) + (field (name Value) CP)) + (pins + (pin (num 1) (name ~) (type passive)) + (pin (num 2) (name ~) (type passive)))) + (libpart (lib stm32-rescue) (part D) + (footprints + (fp TO-???*) + (fp *SingleDiode) + (fp *_Diode_*) + (fp *SingleDiode*) + (fp D_*)) + (fields + (field (name Reference) D) + (field (name Value) D)) + (pins + (pin (num 1) (name K) (type passive)) + (pin (num 2) (name A) (type passive)))) + (libpart (lib stm32-rescue) (part L) + (footprints + (fp Choke_*) + (fp *Coil*) + (fp Inductor_*) + (fp L_*)) + (fields + (field (name Reference) L) + (field (name Value) L)) + (pins + (pin (num 1) (name 1) (type passive)) + (pin (num 2) (name 2) (type passive)))) + (libpart (lib stm32-rescue) (part LED-RESCUE-stm32) + (footprints + (fp LED*)) + (fields + (field (name Reference) D) + (field (name Value) LED-RESCUE-stm32)) + (pins + (pin (num 1) (name K) (type passive)) + (pin (num 2) (name A) (type passive)))) + (libpart (lib stm32-rescue) (part LM1117-3.3-RESCUE-stm32) + (footprints + (fp SOT-223*) + (fp TO-263*) + (fp TO-252*)) + (fields + (field (name Reference) U) + (field (name Value) LM1117-3.3-RESCUE-stm32)) + (pins + (pin (num 1) (name GND/ADJ) (type power_in)) + (pin (num 2) (name VO) (type passive)) + (pin (num 3) (name VI) (type power_in)) + (pin (num 4) (name VO) (type power_out)))) + (libpart (lib stm32-rescue) (part LM2576HV) + (footprints + (fp *DIP8) + (fp SOIC8)) + (fields + (field (name Reference) U) + (field (name Value) LM2576HV) + (field (name Manufacturer) "Texas Instruments")) + (pins + (pin (num 1) (name VIN) (type power_in)) + (pin (num 2) (name VOUT) (type power_out)) + (pin (num 3) (name GND) (type power_in)) + (pin (num 4) (name FB) (type input)) + (pin (num 5) (name ON/OFF) (type input)))) + (libpart (lib stm32-rescue) (part Q_PMOS_GSD) + (fields + (field (name Reference) Q) + (field (name Value) Q_PMOS_GSD)) + (pins + (pin (num 1) (name G) (type input)) + (pin (num 2) (name S) (type passive)) + (pin (num 3) (name D) (type passive)))) + (libpart (lib stm32-rescue) (part R) + (footprints + (fp R_*) + (fp R_*)) + (fields + (field (name Reference) R) + (field (name Value) R)) + (pins + (pin (num 1) (name ~) (type passive)) + (pin (num 2) (name ~) (type passive)))) + (libpart (lib stm32-rescue) (part USB_A-RESCUE-stm32) + (footprints + (fp USB*)) + (fields + (field (name Reference) P) + (field (name Value) USB_A-RESCUE-stm32)) + (pins + (pin (num 1) (name VBUS) (type power_in)) + (pin (num 2) (name D-) (type passive)) + (pin (num 3) (name D+) (type passive)) + (pin (num 4) (name GND) (type power_in)) + (pin (num 5) (name shield) (type passive))))) + (libraries + (library (logical Chrono) + (uri /home/eddy/Docs/SAO/ELECTRONICS/STM32/F1-srcs/chronometer/kicad/chrono/Chrono.lib)) + (library (logical Connector) + (uri /usr/share/kicad/kicad-symbols//Connector.lib)) + (library (logical Connector_Generic) + (uri /usr/share/kicad/kicad-symbols//Connector_Generic.lib)) + (library (logical Device) + (uri /usr/share/kicad/kicad-symbols//Device.lib)) + (library (logical Isolator) + (uri /usr/share/kicad/kicad-symbols//Isolator.lib)) + (library (logical MCU_ST_STM32F1) + (uri /usr/share/kicad/kicad-symbols//MCU_ST_STM32F1.lib)) + (library (logical Power_Protection) + (uri /usr/share/kicad/kicad-symbols//Power_Protection.lib)) + (library (logical Switch) + (uri /usr/share/kicad/kicad-symbols//Switch.lib)) + (library (logical Transistor_BJT) + (uri /usr/share/kicad/kicad-symbols//Transistor_BJT.lib)) + (library (logical stm32-rescue) + (uri /tmp/T/stm32-rescue.lib))) + (nets + (net (code 1) (name /TRIG1) + (node (ref R16) (pin 2)) + (node (ref U6) (pin 4)) + (node (ref U7) (pin 37))) + (net (code 2) (name GND) + (node (ref U2) (pin 5)) + (node (ref SW1) (pin 2)) + (node (ref D3) (pin 2)) + (node (ref C6) (pin 2)) + (node (ref C4) (pin 2)) + (node (ref U4) (pin 1)) + (node (ref U3) (pin 3)) + (node (ref C7) (pin 1)) + (node (ref C5) (pin 1)) + (node (ref U3) (pin 12)) + (node (ref J4) (pin 3)) + (node (ref J2) (pin 2)) + (node (ref C14) (pin 1)) + (node (ref C13) (pin 1)) + (node (ref C15) (pin 1)) + (node (ref C9) (pin 2)) + (node (ref C3) (pin 2)) + (node (ref R5) (pin 1)) + (node (ref C12) (pin 1)) + (node (ref J5) (pin 1)) + (node (ref J3) (pin 1)) + (node (ref R1) (pin 2)) + (node (ref C1) (pin 2)) + (node (ref J7) (pin 1)) + (node (ref U7) (pin 8)) + (node (ref U7) (pin 47)) + (node (ref U7) (pin 35)) + (node (ref U7) (pin 23)) + (node (ref U2) (pin 3)) + (node (ref P1) (pin 4)) + (node (ref P1) (pin 5)) + (node (ref C8) (pin 2)) + (node (ref U1) (pin 2)) + (node (ref R13) (pin 2)) + (node (ref U8) (pin 3)) + (node (ref U6) (pin 3)) + (node (ref U5) (pin 3)) + (node (ref J1) (pin 1)) + (node (ref C11) (pin 2)) + (node (ref C10) (pin 2)) + (node (ref R18) (pin 1))) + (net (code 3) (name +3V3) + (node (ref R20) (pin 1)) + (node (ref U7) (pin 24)) + (node (ref U7) (pin 36)) + (node (ref U7) (pin 48)) + (node (ref U7) (pin 9)) + (node (ref R16) (pin 1)) + (node (ref U7) (pin 1)) + (node (ref SW2) (pin 2)) + (node (ref C2) (pin 2)) + (node (ref C7) (pin 2)) + (node (ref R10) (pin 2)) + (node (ref Q2) (pin 2)) + (node (ref U4) (pin 4)) + (node (ref R2) (pin 2)) + (node (ref R14) (pin 2)) + (node (ref U4) (pin 2)) + (node (ref C12) (pin 2)) + (node (ref C13) (pin 2)) + (node (ref U3) (pin 5)) + (node (ref C14) (pin 2)) + (node (ref R9) (pin 2)) + (node (ref U3) (pin 4)) + (node (ref C15) (pin 2)) + (node (ref R12) (pin 1)) + (node (ref R8) (pin 2)) + (node (ref C9) (pin 1)) + (node (ref C5) (pin 2))) + (net (code 4) (name "Net-(J5-Pad2)") + (node (ref J5) (pin 2)) + (node (ref R15) (pin 1)) + (node (ref U6) (pin 2))) + (net (code 5) (name "Net-(R14-Pad1)") + (node (ref R15) (pin 2)) + (node (ref U6) (pin 1)) + (node (ref R14) (pin 1))) + (net (code 6) (name "Net-(J3-Pad2)") + (node (ref U5) (pin 2)) + (node (ref R11) (pin 1)) + (node (ref J3) (pin 2))) + (net (code 7) (name "Net-(R10-Pad1)") + (node (ref R10) (pin 1)) + (node (ref R11) (pin 2)) + (node (ref U5) (pin 1))) + (net (code 8) (name /TRIG2) + (node (ref U7) (pin 14)) + (node (ref U8) (pin 4)) + (node (ref R20) (pin 2))) + (net (code 9) (name "Net-(R17-Pad2)") + (node (ref U8) (pin 1)) + (node (ref R17) (pin 2)) + (node (ref R19) (pin 2))) + (net (code 10) (name "Net-(J6-Pad2)") + (node (ref J6) (pin 2)) + (node (ref R17) (pin 1))) + (net (code 11) (name "Net-(J6-Pad1)") + (node (ref J6) (pin 1)) + (node (ref U8) (pin 2)) + (node (ref R19) (pin 1))) + (net (code 12) (name "Net-(J1-Pad2)") + (node (ref J1) (pin 2)) + (node (ref Q1) (pin 3))) + (net (code 13) (name "Net-(Q2-Pad3)") + (node (ref Q2) (pin 3)) + (node (ref R6) (pin 1))) + (net (code 14) (name /USB_PU) + (node (ref U7) (pin 38)) + (node (ref Q2) (pin 1))) + (net (code 15) (name /OSC_OUT) + (node (ref U7) (pin 6)) + (node (ref Y1) (pin 2)) + (node (ref C11) (pin 1))) + (net (code 16) (name /TRIG0) + (node (ref U7) (pin 34)) + (node (ref R12) (pin 2)) + (node (ref U5) (pin 4))) + (net (code 17) (name /PPS) + (node (ref R18) (pin 2)) + (node (ref U3) (pin 6)) + (node (ref U7) (pin 11))) + (net (code 18) (name "Net-(U3-Pad9)") + (node (ref U3) (pin 9))) + (net (code 19) (name "Net-(U3-Pad8)") + (node (ref U3) (pin 8))) + (net (code 20) (name "Net-(U3-Pad7)") + (node (ref U3) (pin 7))) + (net (code 21) (name "Net-(U3-Pad11)") + (node (ref U3) (pin 11))) + (net (code 22) (name "Net-(U3-Pad10)") + (node (ref U3) (pin 10))) + (net (code 23) (name "Net-(U7-Pad15)") + (node (ref U7) (pin 15))) + (net (code 24) (name "Net-(U7-Pad16)") + (node (ref U7) (pin 16))) + (net (code 25) (name "Net-(U7-Pad41)") + (node (ref U7) (pin 41))) + (net (code 26) (name "Net-(U7-Pad42)") + (node (ref U7) (pin 42))) + (net (code 27) (name "Net-(U7-Pad43)") + (node (ref U7) (pin 43))) + (net (code 28) (name "Net-(U7-Pad40)") + (node (ref U7) (pin 40))) + (net (code 29) (name "Net-(D1-Pad2)") + (node (ref Q1) (pin 1)) + (node (ref D1) (pin 2)) + (node (ref R5) (pin 2))) + (net (code 30) (name "Net-(D2-Pad2)") + (node (ref P1) (pin 1)) + (node (ref U1) (pin 5)) + (node (ref D2) (pin 2))) + (net (code 31) (name "Net-(U7-Pad10)") + (node (ref U7) (pin 10))) + (net (code 32) (name "Net-(U7-Pad17)") + (node (ref U7) (pin 17))) + (net (code 33) (name "Net-(U7-Pad39)") + (node (ref U7) (pin 39))) + (net (code 34) (name "Net-(U7-Pad19)") + (node (ref U7) (pin 19))) + (net (code 35) (name "Net-(U7-Pad18)") + (node (ref U7) (pin 18))) + (net (code 36) (name "Net-(J2-Pad1)") + (node (ref J2) (pin 1)) + (node (ref R7) (pin 1))) + (net (code 37) (name "Net-(D3-Pad1)") + (node (ref U2) (pin 2)) + (node (ref L1) (pin 2)) + (node (ref D3) (pin 1))) + (net (code 38) (name /U1Tx) + (node (ref J7) (pin 2)) + (node (ref U7) (pin 30))) + (net (code 39) (name "Net-(U7-Pad28)") + (node (ref U7) (pin 28))) + (net (code 40) (name "Net-(U7-Pad2)") + (node (ref U7) (pin 2))) + (net (code 41) (name "Net-(U7-Pad3)") + (node (ref U7) (pin 3))) + (net (code 42) (name "Net-(U7-Pad4)") + (node (ref U7) (pin 4))) + (net (code 43) (name "Net-(U7-Pad27)") + (node (ref U7) (pin 27))) + (net (code 44) (name /U1Rx) + (node (ref J7) (pin 3)) + (node (ref U7) (pin 31))) + (net (code 45) (name /U2Tx) + (node (ref J4) (pin 1)) + (node (ref U7) (pin 21))) + (net (code 46) (name /U2Rx) + (node (ref J4) (pin 2)) + (node (ref U7) (pin 22))) + (net (code 47) (name "Net-(U7-Pad29)") + (node (ref U7) (pin 29))) + (net (code 48) (name "Net-(U7-Pad26)") + (node (ref U7) (pin 26))) + (net (code 49) (name "Net-(U7-Pad25)") + (node (ref U7) (pin 25))) + (net (code 50) (name "Net-(C3-Pad1)") + (node (ref Q1) (pin 2)) + (node (ref U2) (pin 1)) + (node (ref D1) (pin 1)) + (node (ref C4) (pin 1)) + (node (ref C3) (pin 1))) + (net (code 51) (name /LED0) + (node (ref D4) (pin 1)) + (node (ref U7) (pin 45))) + (net (code 52) (name /LED1) + (node (ref U7) (pin 46)) + (node (ref D5) (pin 1))) + (net (code 53) (name /U3Rx) + (node (ref U3) (pin 2)) + (node (ref U7) (pin 13))) + (net (code 54) (name /U3Tx) + (node (ref U7) (pin 12)) + (node (ref U3) (pin 1))) + (net (code 55) (name /NRST) + (node (ref U7) (pin 7)) + (node (ref SW1) (pin 1)) + (node (ref R2) (pin 1)) + (node (ref C1) (pin 1))) + (net (code 56) (name /OSC_IN) + (node (ref Y1) (pin 1)) + (node (ref U7) (pin 5)) + (node (ref C10) (pin 1))) + (net (code 57) (name "Net-(P1-Pad2)") + (node (ref R6) (pin 2)) + (node (ref U1) (pin 4)) + (node (ref P1) (pin 2))) + (net (code 58) (name +5V) + (node (ref U4) (pin 3)) + (node (ref U2) (pin 4)) + (node (ref C6) (pin 1)) + (node (ref L1) (pin 1)) + (node (ref D2) (pin 1)) + (node (ref C8) (pin 1)) + (node (ref J4) (pin 4)) + (node (ref R7) (pin 2))) + (net (code 59) (name "Net-(P1-Pad3)") + (node (ref P1) (pin 3)) + (node (ref U1) (pin 6))) + (net (code 60) (name "Net-(R3-Pad1)") + (node (ref U1) (pin 1)) + (node (ref R3) (pin 1))) + (net (code 61) (name "Net-(R4-Pad1)") + (node (ref U1) (pin 3)) + (node (ref R4) (pin 1))) + (net (code 62) (name "Net-(R13-Pad1)") + (node (ref R13) (pin 1)) + (node (ref U7) (pin 20))) + (net (code 63) (name /USBDM) + (node (ref R4) (pin 2)) + (node (ref U7) (pin 32))) + (net (code 64) (name /USBDP) + (node (ref U7) (pin 33)) + (node (ref R3) (pin 2))) + (net (code 65) (name "Net-(D5-Pad2)") + (node (ref R9) (pin 1)) + (node (ref D5) (pin 2))) + (net (code 66) (name "Net-(D4-Pad2)") + (node (ref R8) (pin 1)) + (node (ref D4) (pin 2))) + (net (code 67) (name /BOOT0) + (node (ref C2) (pin 1)) + (node (ref R1) (pin 1)) + (node (ref U7) (pin 44)) + (node (ref SW2) (pin 1))))) \ No newline at end of file diff --git a/F1-nolib/chronometer/kicad/chrono/chrono.pretty/L80-R.kicad_mod b/F1-nolib/chronometer/kicad/chrono/chrono.pretty/L80-R.kicad_mod new file mode 100644 index 0000000..e65455d --- /dev/null +++ b/F1-nolib/chronometer/kicad/chrono/chrono.pretty/L80-R.kicad_mod @@ -0,0 +1,38 @@ +(module L80-R (layer F.Cu) (tedit 5D1478E8) + (fp_text reference REF** (at 0 4) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text value L80-R (at 0 -8) (layer F.Fab) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_line (start -8 -14) (end -8 3) (layer F.SilkS) (width 0.15)) + (fp_line (start -8 3) (end 8 3) (layer F.SilkS) (width 0.15)) + (fp_line (start 8 3) (end 8 -14) (layer F.SilkS) (width 0.15)) + (fp_line (start 8 -14) (end -8 -14) (layer F.SilkS) (width 0.15)) + (fp_text user 1 (at 10 3) (layer F.SilkS) + (effects (font (size 2.5 2.5) (thickness 0.15))) + ) + (fp_line (start -4 3) (end -4 1) (layer F.SilkS) (width 0.15)) + (fp_line (start -4 1) (end -8 1) (layer F.SilkS) (width 0.15)) + (fp_line (start 8 2) (end 7 3) (layer F.SilkS) (width 0.15)) + (fp_text user Keepout (at -0.05 -8.65) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text user area (at 0 -4.5) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (pad 1 smd rect (at 8 0) (size 4 2) (layers F.Cu F.Paste F.Mask)) + (pad 2 smd rect (at 8 -2.54) (size 4 2) (layers F.Cu F.Paste F.Mask)) + (pad 3 smd rect (at 8 -5.08) (size 4 2) (layers F.Cu F.Paste F.Mask)) + (pad 4 smd rect (at 8 -7.62) (size 4 2) (layers F.Cu F.Paste F.Mask)) + (pad 5 smd rect (at 8 -10.16) (size 4 2) (layers F.Cu F.Paste F.Mask)) + (pad 6 smd rect (at 8 -12.7) (size 4 2) (layers F.Cu F.Paste F.Mask)) + (pad 12 smd rect (at -8 0) (size 4 2) (layers F.Cu F.Paste F.Mask)) + (pad 11 smd rect (at -8 -2.54) (size 4 2) (layers F.Cu F.Paste F.Mask)) + (pad 10 smd rect (at -8 -5.08) (size 4 2) (layers F.Cu F.Paste F.Mask)) + (pad 9 smd rect (at -8 -7.62) (size 4 2) (layers F.Cu F.Paste F.Mask)) + (pad 8 smd rect (at -8 -10.16) (size 4 2) (layers F.Cu F.Paste F.Mask)) + (pad 7 smd rect (at -8 -12.7) (size 4 2) (layers F.Cu F.Paste F.Mask)) + (pad 13 smd circle (at 0 -6.35) (size 2.5 2.5) (layers *.SilkS) + (solder_mask_margin 1.5) (solder_paste_margin 1.5) (clearance 1.3) (zone_connect 0)) +) diff --git a/F1-nolib/chronometer/kicad/chrono/chrono.pro b/F1-nolib/chronometer/kicad/chrono/chrono.pro new file mode 100644 index 0000000..01ecec4 --- /dev/null +++ b/F1-nolib/chronometer/kicad/chrono/chrono.pro @@ -0,0 +1,65 @@ +update=Чт 27 июн 2019 14:51:04 +version=1 +last_client=kicad +[general] +version=1 +RootSch= +BoardNm= +[cvpcb] +version=1 +NetIExt=net +[eeschema] +version=1 +LibDir= +[eeschema/libraries] +[pcbnew] +version=1 +PageLayoutDescrFile= +LastNetListRead=chrono.net +CopperLayerCount=2 +BoardThickness=1.6 +AllowMicroVias=0 +AllowBlindVias=0 +RequireCourtyardDefinitions=0 +ProhibitOverlappingCourtyards=1 +MinTrackWidth=0.2 +MinViaDiameter=0.4 +MinViaDrill=0.3 +MinMicroViaDiameter=0.2 +MinMicroViaDrill=0.09999999999999999 +MinHoleToHole=0.25 +TrackWidth1=0.25 +TrackWidth2=0.5 +TrackWidth3=1 +TrackWidth4=2 +ViaDiameter1=1.5 +ViaDrill1=0.6 +ViaDiameter2=2.5 +ViaDrill2=0.8 +dPairWidth1=0.2 +dPairGap1=0.25 +dPairViaGap1=0.25 +SilkLineWidth=0.12 +SilkTextSizeV=1 +SilkTextSizeH=1 +SilkTextSizeThickness=0.15 +SilkTextItalic=0 +SilkTextUpright=1 +CopperLineWidth=0.2 +CopperTextSizeV=1.5 +CopperTextSizeH=1.5 +CopperTextThickness=0.3 +CopperTextItalic=0 +CopperTextUpright=1 +EdgeCutLineWidth=0.05 +CourtyardLineWidth=0.05 +OthersLineWidth=0.15 +OthersTextSizeV=1 +OthersTextSizeH=1 +OthersTextSizeThickness=0.15 +OthersTextItalic=0 +OthersTextUpright=1 +SolderMaskClearance=0.051 +SolderMaskMinWidth=0.25 +SolderPasteClearance=0 +SolderPasteRatio=-0 diff --git a/F1-nolib/chronometer/kicad/chrono/chrono.sch b/F1-nolib/chronometer/kicad/chrono/chrono.sch new file mode 100644 index 0000000..f4f0f4a --- /dev/null +++ b/F1-nolib/chronometer/kicad/chrono/chrono.sch @@ -0,0 +1,1662 @@ +EESchema Schematic File Version 4 +LIBS:stm32-cache +EELAYER 29 0 +EELAYER END +$Descr A4 11693 8268 +encoding utf-8 +Sheet 1 1 +Title "" +Date "" +Rev "" +Comp "" +Comment1 "" +Comment2 "" +Comment3 "" +Comment4 "" +$EndDescr +$Comp +L MCU_ST_STM32F1:STM32F103C6Tx U7 +U 1 1 5D13BBBF +P 9325 2425 +F 0 "U7" H 9325 2600 50 0000 C CNN +F 1 "STM32F103C6Tx" H 9325 2400 50 0000 C CNN +F 2 "Package_QFP:LQFP-48_7x7mm_P0.5mm" H 8725 1025 50 0001 R CNN +F 3 "http://www.st.com/st-web-ui/static/active/en/resource/technical/document/datasheet/CD00210843.pdf" H 9325 2425 50 0001 C CNN + 1 9325 2425 + 1 0 0 -1 +$EndComp +$Comp +L Connector:Conn_01x03_Female J7 +U 1 1 5D14396C +P 10500 3125 +F 0 "J7" H 10350 2950 50 0000 L CNN +F 1 "USART1" H 10200 3325 50 0000 L CNN +F 2 "Connector_PinSocket_2.54mm:PinSocket_1x03_P2.54mm_Vertical" H 10500 3125 50 0001 C CNN +F 3 "~" H 10500 3125 50 0001 C CNN + 1 10500 3125 + 1 0 0 -1 +$EndComp +$Comp +L Connector_Generic:Conn_01x02 J3 +U 1 1 5D1444DC +P 6975 6000 +F 0 "J3" H 6975 6100 50 0000 C CNN +F 1 "Ext_trig0" H 6975 6175 50 0000 C CNN +F 2 "TerminalBlock_Phoenix:TerminalBlock_Phoenix_MKDS-1,5-2-5.08_1x02_P5.08mm_Horizontal" H 6975 6000 50 0001 C CNN +F 3 "~" H 6975 6000 50 0001 C CNN + 1 6975 6000 + -1 0 0 1 +$EndComp +Text Notes 675 4050 0 60 ~ 0 +Bootloader init +Text Label 975 5100 2 60 ~ 0 +NRST +Text Label 975 4200 0 60 ~ 0 +BOOT0 +$Comp +L stm32-rescue:R R1 +U 1 1 5D347863 +P 975 4500 +F 0 "R1" V 1055 4500 50 0000 C CNN +F 1 "10k" V 975 4500 50 0000 C CNN +F 2 "Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder" V 905 4500 50 0001 C CNN +F 3 "" H 975 4500 50 0000 C CNN + 1 975 4500 + 1 0 0 -1 +$EndComp +$Comp +L stm32-rescue:R R2 +U 1 1 590D3334 +P 975 5350 +F 0 "R2" V 1055 5350 50 0000 C CNN +F 1 "10k" V 975 5350 50 0000 C CNN +F 2 "Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder" V 905 5350 50 0001 C CNN +F 3 "" H 975 5350 50 0000 C CNN + 1 975 5350 + 1 0 0 -1 +$EndComp +$Comp +L stm32-rescue:C C2 +U 1 1 590D4150 +P 1575 4500 +F 0 "C2" H 1600 4600 50 0000 L CNN +F 1 "0.1" H 1600 4400 50 0000 L CNN +F 2 "Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder" H 1613 4350 50 0001 C CNN +F 3 "" H 1575 4500 50 0000 C CNN + 1 1575 4500 + 1 0 0 -1 +$EndComp +$Comp +L stm32-rescue:C C1 +U 1 1 5D4AE2B9 +P 1525 5350 +F 0 "C1" H 1550 5450 50 0000 L CNN +F 1 "0.1" H 1550 5250 50 0000 L CNN +F 2 "Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder" H 1563 5200 50 0001 C CNN +F 3 "" H 1525 5350 50 0000 C CNN + 1 1525 5350 + 1 0 0 -1 +$EndComp +$Comp +L Switch:SW_Push SW2 +U 1 1 5D34785A +P 1275 4500 +F 0 "SW2" H 1325 4600 50 0000 L CNN +F 1 "Boot" H 1275 4440 50 0000 C CNN +F 2 "Buttons_Switches_SMD:SW_SPST_FSMSM" H 1275 4700 50 0001 C CNN +F 3 "" H 1275 4700 50 0000 C CNN + 1 1275 4500 + 0 1 1 0 +$EndComp +$Comp +L Switch:SW_Push SW1 +U 1 1 5D34785B +P 1225 5350 +F 0 "SW1" H 1275 5450 50 0000 L CNN +F 1 "Reset" H 1225 5290 50 0000 C CNN +F 2 "Buttons_Switches_SMD:SW_SPST_FSMSM" H 1225 5550 50 0001 C CNN +F 3 "" H 1225 5550 50 0000 C CNN + 1 1225 5350 + 0 1 1 0 +$EndComp +$Comp +L stm32-rescue:GND #PWR02 +U 1 1 5D34785C +P 975 4700 +F 0 "#PWR02" H 975 4450 50 0001 C CNN +F 1 "GND" H 975 4550 50 0000 C CNN +F 2 "" H 975 4700 50 0000 C CNN +F 3 "" H 975 4700 50 0000 C CNN + 1 975 4700 + 1 0 0 -1 +$EndComp +$Comp +L stm32-rescue:+3.3V #PWR06 +U 1 1 5D34785D +P 1425 4750 +F 0 "#PWR06" H 1425 4600 50 0001 C CNN +F 1 "+3.3V" H 1425 4890 50 0000 C CNN +F 2 "" H 1425 4750 50 0000 C CNN +F 3 "" H 1425 4750 50 0000 C CNN + 1 1425 4750 + -1 0 0 1 +$EndComp +$Comp +L stm32-rescue:+3.3V #PWR03 +U 1 1 5D34785E +P 975 5600 +F 0 "#PWR03" H 975 5450 50 0001 C CNN +F 1 "+3.3V" H 975 5740 50 0000 C CNN +F 2 "" H 975 5600 50 0000 C CNN +F 3 "" H 975 5600 50 0000 C CNN + 1 975 5600 + -1 0 0 1 +$EndComp +$Comp +L stm32-rescue:GND #PWR05 +U 1 1 5D34785F +P 1375 5600 +F 0 "#PWR05" H 1375 5350 50 0001 C CNN +F 1 "GND" H 1375 5450 50 0000 C CNN +F 2 "" H 1375 5600 50 0000 C CNN +F 3 "" H 1375 5600 50 0000 C CNN + 1 1375 5600 + 1 0 0 -1 +$EndComp +Wire Wire Line + 975 4700 975 4650 +Wire Wire Line + 975 4200 975 4300 +Wire Wire Line + 1575 4300 1575 4350 +Wire Wire Line + 975 4300 1275 4300 +Connection ~ 1275 4300 +Connection ~ 975 4300 +Wire Wire Line + 1275 4700 1425 4700 +Wire Wire Line + 1575 4700 1575 4650 +Wire Wire Line + 1425 4750 1425 4700 +Connection ~ 1425 4700 +Wire Wire Line + 975 5100 975 5150 +Wire Wire Line + 975 5600 975 5500 +Wire Wire Line + 975 5150 1225 5150 +Connection ~ 975 5150 +Wire Wire Line + 1525 5150 1525 5200 +Connection ~ 1225 5150 +Wire Wire Line + 1225 5550 1375 5550 +Wire Wire Line + 1525 5550 1525 5500 +Wire Wire Line + 1375 5600 1375 5550 +Connection ~ 1375 5550 +Wire Notes Line + 575 3900 575 5850 +Wire Notes Line + 575 5850 1925 5850 +Wire Notes Line + 1925 5850 1925 3900 +Wire Notes Line + 1925 3900 575 3900 +Wire Wire Line + 1275 4300 1575 4300 +Wire Wire Line + 975 4300 975 4350 +Wire Wire Line + 1425 4700 1575 4700 +Wire Wire Line + 975 5150 975 5200 +Wire Wire Line + 1225 5150 1525 5150 +Wire Wire Line + 1375 5550 1525 5550 +$Comp +L Connector_Generic:Conn_01x02 J5 +U 1 1 5D145441 +P 8350 6000 +F 0 "J5" H 8350 6100 50 0000 C CNN +F 1 "Ext_trig1" H 8325 6175 50 0000 C CNN +F 2 "TerminalBlock_Phoenix:TerminalBlock_Phoenix_MKDS-1,5-2-5.08_1x02_P5.08mm_Horizontal" H 8350 6000 50 0001 C CNN +F 3 "~" H 8350 6000 50 0001 C CNN + 1 8350 6000 + -1 0 0 1 +$EndComp +$Comp +L Connector_Generic:Conn_01x02 J6 +U 1 1 5D1457FF +P 9700 5700 +F 0 "J6" H 9700 5800 50 0000 C CNN +F 1 "Ext_trig2" H 9700 5875 50 0000 C CNN +F 2 "TerminalBlock_Phoenix:TerminalBlock_Phoenix_MKDS-1,5-2-5.08_1x02_P5.08mm_Horizontal" H 9700 5700 50 0001 C CNN +F 3 "~" H 9700 5700 50 0001 C CNN + 1 9700 5700 + -1 0 0 1 +$EndComp +$Comp +L stm32-rescue:C C12 +U 1 1 58C42D39 +P 8825 4225 +F 0 "C12" H 8850 4325 50 0000 L CNN +F 1 "0.1" H 8850 4125 50 0000 L CNN +F 2 "Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder" H 8863 4075 50 0001 C CNN +F 3 "" H 8825 4225 50 0000 C CNN + 1 8825 4225 + 1 0 0 -1 +$EndComp +$Comp +L stm32-rescue:LM2576HV U2 +U 1 1 58C43093 +P 2875 975 +F 0 "U2" H 2525 1225 60 0000 C CNN +F 1 "LM2576HV" H 3125 1225 60 0000 C CNN +F 2 "TO_SOT_Packages_THT:TO-220-5_P3.4x3.7mm_StaggerEven_Lead3.8mm_Vertical" H 2875 975 60 0001 C CNN +F 3 "" H 2875 975 60 0001 C CNN +F 4 "Texas Instruments" H 2875 1325 60 0001 C CNN "Manufacturer" + 1 2875 975 + 1 0 0 -1 +$EndComp +$Comp +L stm32-rescue:LM1117-3.3-RESCUE-stm32 U4 +U 1 1 58C431FC +P 5300 1000 +F 0 "U4" H 5400 750 50 0000 C CNN +F 1 "LM1117-3.3" H 5300 1250 50 0000 C CNN +F 2 "TO_SOT_Packages_SMD:SOT-223" H 5300 1000 50 0001 C CNN +F 3 "" H 5300 1000 50 0000 C CNN + 1 5300 1000 + 1 0 0 -1 +$EndComp +$Comp +L stm32-rescue:D D3 +U 1 1 58C43816 +P 3575 1225 +F 0 "D3" H 3575 1325 50 0000 C CNN +F 1 "1n5822" H 3575 1125 50 0000 C CNN +F 2 "Diode_THT:D_DO-201_P12.70mm_Horizontal" H 3575 1225 50 0001 C CNN +F 3 "" H 3575 1225 50 0000 C CNN + 1 3575 1225 + 0 1 1 0 +$EndComp +$Comp +L stm32-rescue:L L1 +U 1 1 58C43929 +P 3775 1075 +F 0 "L1" V 3725 1075 50 0000 C CNN +F 1 "100u" V 3850 1075 50 0000 C CNN +F 2 "Inductor_SMD:L_12x12mm_H4.5mm" H 3775 1075 50 0001 C CNN +F 3 "" H 3775 1075 50 0000 C CNN + 1 3775 1075 + 0 1 1 0 +$EndComp +$Comp +L stm32-rescue:CP C6 +U 1 1 58C4396A +P 3925 1275 +F 0 "C6" H 3950 1375 50 0000 L CNN +F 1 "100u" H 3950 1175 50 0000 L CNN +F 2 "Capacitor_THT:CP_Radial_D8.0mm_P3.50mm" H 3963 1125 50 0001 C CNN +F 3 "" H 3925 1275 50 0000 C CNN + 1 3925 1275 + 1 0 0 -1 +$EndComp +$Comp +L stm32-rescue:GND #PWR013 +U 1 1 58C43A03 +P 3575 1425 +F 0 "#PWR013" H 3575 1175 50 0001 C CNN +F 1 "GND" H 3575 1275 50 0000 C CNN +F 2 "" H 3575 1425 50 0000 C CNN +F 3 "" H 3575 1425 50 0000 C CNN + 1 3575 1425 + 1 0 0 -1 +$EndComp +$Comp +L stm32-rescue:CP C4 +U 1 1 58C43A3B +P 2075 1025 +F 0 "C4" H 2100 1125 50 0000 L CNN +F 1 "47u" H 2100 925 50 0000 L CNN +F 2 "Capacitor_Tantalum_SMD:CP_EIA-3216-18_Kemet-A_Pad1.58x1.35mm_HandSolder" H 2113 875 50 0001 C CNN +F 3 "" H 2075 1025 50 0000 C CNN + 1 2075 1025 + 1 0 0 -1 +$EndComp +$Comp +L stm32-rescue:GND #PWR08 +U 1 1 58C43B9F +P 2075 1225 +F 0 "#PWR08" H 2075 975 50 0001 C CNN +F 1 "GND" H 2075 1075 50 0000 C CNN +F 2 "" H 2075 1225 50 0000 C CNN +F 3 "" H 2075 1225 50 0000 C CNN + 1 2075 1225 + 1 0 0 -1 +$EndComp +$Comp +L stm32-rescue:GND #PWR015 +U 1 1 58C44105 +P 3925 1475 +F 0 "#PWR015" H 3925 1225 50 0001 C CNN +F 1 "GND" H 3925 1325 50 0000 C CNN +F 2 "" H 3925 1475 50 0000 C CNN +F 3 "" H 3925 1475 50 0000 C CNN + 1 3925 1475 + 1 0 0 -1 +$EndComp +$Comp +L stm32-rescue:GND #PWR012 +U 1 1 58C44225 +P 2975 1525 +F 0 "#PWR012" H 2975 1275 50 0001 C CNN +F 1 "GND" H 2975 1375 50 0000 C CNN +F 2 "" H 2975 1525 50 0000 C CNN +F 3 "" H 2975 1525 50 0000 C CNN + 1 2975 1525 + 1 0 0 -1 +$EndComp +Text Notes 1675 675 0 60 ~ 0 +5V power source +$Comp +L stm32-rescue:+5V #PWR019 +U 1 1 5D4AE2B3 +P 5000 1000 +F 0 "#PWR019" H 5000 850 50 0001 C CNN +F 1 "+5V" H 5000 1140 50 0000 C CNN +F 2 "" H 5000 1000 50 0000 C CNN +F 3 "" H 5000 1000 50 0000 C CNN + 1 5000 1000 + 1 0 0 -1 +$EndComp +$Comp +L stm32-rescue:GND #PWR020 +U 1 1 5D4AE2B4 +P 5300 1350 +F 0 "#PWR020" H 5300 1100 50 0001 C CNN +F 1 "GND" H 5300 1200 50 0000 C CNN +F 2 "" H 5300 1350 50 0000 C CNN +F 3 "" H 5300 1350 50 0000 C CNN + 1 5300 1350 + 1 0 0 -1 +$EndComp +$Comp +L stm32-rescue:CP C9 +U 1 1 5D4AE2B5 +P 5700 1150 +F 0 "C9" H 5725 1250 50 0000 L CNN +F 1 "47u" H 5725 1050 50 0000 L CNN +F 2 "Capacitor_Tantalum_SMD:CP_EIA-3216-18_Kemet-A_Pad1.58x1.35mm_HandSolder" H 5738 1000 50 0001 C CNN +F 3 "" H 5700 1150 50 0000 C CNN + 1 5700 1150 + 1 0 0 -1 +$EndComp +$Comp +L stm32-rescue:+3.3V #PWR022 +U 1 1 58C455CB +P 5700 1000 +F 0 "#PWR022" H 5700 850 50 0001 C CNN +F 1 "+3.3V" H 5700 1140 50 0000 C CNN +F 2 "" H 5700 1000 50 0000 C CNN +F 3 "" H 5700 1000 50 0000 C CNN + 1 5700 1000 + 1 0 0 -1 +$EndComp +Text Label 6325 900 2 60 ~ 0 +LED0 +Text Label 6325 1200 2 60 ~ 0 +LED1 +$Comp +L stm32-rescue:LED-RESCUE-stm32 D4 +U 1 1 5908EA64 +P 6625 900 +F 0 "D4" H 6625 1000 50 0000 C CNN +F 1 "LED0" H 6625 800 50 0000 C CNN +F 2 "LED_THT:LED_D5.0mm" H 6625 900 50 0001 C CNN +F 3 "" H 6625 900 50 0000 C CNN + 1 6625 900 + 1 0 0 -1 +$EndComp +$Comp +L stm32-rescue:R R8 +U 1 1 5908EB17 +P 7025 900 +F 0 "R8" V 7105 900 50 0000 C CNN +F 1 "330" V 7025 900 50 0000 C CNN +F 2 "Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder" V 6955 900 50 0001 C CNN +F 3 "" H 7025 900 50 0000 C CNN + 1 7025 900 + 0 -1 -1 0 +$EndComp +$Comp +L stm32-rescue:+3.3V #PWR027 +U 1 1 5908F9F4 +P 7325 900 +F 0 "#PWR027" H 7325 750 50 0001 C CNN +F 1 "+3.3V" H 7325 1040 50 0000 C CNN +F 2 "" H 7325 900 50 0000 C CNN +F 3 "" H 7325 900 50 0000 C CNN + 1 7325 900 + 1 0 0 -1 +$EndComp +$Comp +L stm32-rescue:C C13 +U 1 1 590935EA +P 9125 4225 +F 0 "C13" H 9150 4325 50 0000 L CNN +F 1 "0.1" H 9150 4125 50 0000 L CNN +F 2 "Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder" H 9163 4075 50 0001 C CNN +F 3 "" H 9125 4225 50 0000 C CNN + 1 9125 4225 + 1 0 0 -1 +$EndComp +$Comp +L stm32-rescue:C C14 +U 1 1 59093675 +P 9425 4225 +F 0 "C14" H 9450 4325 50 0000 L CNN +F 1 "0.1" H 9450 4125 50 0000 L CNN +F 2 "Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder" H 9463 4075 50 0001 C CNN +F 3 "" H 9425 4225 50 0000 C CNN + 1 9425 4225 + 1 0 0 -1 +$EndComp +$Comp +L stm32-rescue:LED-RESCUE-stm32 D5 +U 1 1 5909AF9A +P 6625 1200 +F 0 "D5" H 6625 1300 50 0000 C CNN +F 1 "LED1" H 6625 1100 50 0000 C CNN +F 2 "LED_THT:LED_D5.0mm" H 6625 1200 50 0001 C CNN +F 3 "" H 6625 1200 50 0000 C CNN + 1 6625 1200 + 1 0 0 -1 +$EndComp +$Comp +L stm32-rescue:R R9 +U 1 1 5909AFA0 +P 7025 1200 +F 0 "R9" V 7105 1200 50 0000 C CNN +F 1 "330" V 7025 1200 50 0000 C CNN +F 2 "Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder" V 6955 1200 50 0001 C CNN +F 3 "" H 7025 1200 50 0000 C CNN + 1 7025 1200 + 0 -1 -1 0 +$EndComp +$Comp +L stm32-rescue:+3.3V #PWR028 +U 1 1 5909AFA6 +P 7325 1200 +F 0 "#PWR028" H 7325 1050 50 0001 C CNN +F 1 "+3.3V" H 7325 1340 50 0000 C CNN +F 2 "" H 7325 1200 50 0000 C CNN +F 3 "" H 7325 1200 50 0000 C CNN + 1 7325 1200 + 1 0 0 -1 +$EndComp +Text Notes 6175 650 0 60 ~ 0 +LED indicators +Text Notes 4800 675 0 60 ~ 0 +3.3V MCU power source +$Comp +L stm32-rescue:+3.3V #PWR040 +U 1 1 590A0C2D +P 10125 4375 +F 0 "#PWR040" H 10125 4225 50 0001 C CNN +F 1 "+3.3V" H 10125 4515 50 0000 C CNN +F 2 "" H 10125 4375 50 0000 C CNN +F 3 "" H 10125 4375 50 0000 C CNN + 1 10125 4375 + 1 0 0 -1 +$EndComp +$Comp +L stm32-rescue:GND #PWR034 +U 1 1 590A1958 +P 8475 4075 +F 0 "#PWR034" H 8475 3825 50 0001 C CNN +F 1 "GND" H 8475 3925 50 0000 C CNN +F 2 "" H 8475 4075 50 0000 C CNN +F 3 "" H 8475 4075 50 0000 C CNN + 1 8475 4075 + 1 0 0 -1 +$EndComp +$Comp +L stm32-rescue:C C15 +U 1 1 590A8102 +P 9725 4225 +F 0 "C15" H 9750 4325 50 0000 L CNN +F 1 "0.1" H 9750 4125 50 0000 L CNN +F 2 "Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder" H 9763 4075 50 0001 C CNN +F 3 "" H 9725 4225 50 0000 C CNN + 1 9725 4225 + 1 0 0 -1 +$EndComp +$Comp +L stm32-rescue:Q_PMOS_GSD Q1 +U 1 1 5910E2F2 +P 1375 975 +F 0 "Q1" V 1700 925 50 0000 L CNN +F 1 "AO3407" V 1600 825 50 0000 L CNN +F 2 "TO_SOT_Packages_SMD:SOT-23_Handsoldering" H 1575 1075 50 0001 C CNN +F 3 "" H 1375 975 50 0000 C CNN + 1 1375 975 + 0 -1 -1 0 +$EndComp +$Comp +L stm32-rescue:PWR_FLAG #FLG02 +U 1 1 590C1070 +P 1825 875 +F 0 "#FLG02" H 1825 970 50 0001 C CNN +F 1 "PWR_FLAG" H 1825 1055 50 0001 C CNN +F 2 "" H 1825 875 50 0000 C CNN +F 3 "" H 1825 875 50 0000 C CNN + 1 1825 875 + 1 0 0 -1 +$EndComp +$Comp +L stm32-rescue:PWR_FLAG #FLG04 +U 1 1 590C813A +P 3925 875 +F 0 "#FLG04" H 3925 970 50 0001 C CNN +F 1 "PWR_FLAG" H 3925 1055 50 0001 C CNN +F 2 "" H 3925 875 50 0000 C CNN +F 3 "" H 3925 875 50 0000 C CNN + 1 3925 875 + 1 0 0 -1 +$EndComp +$Comp +L stm32-rescue:C C3 +U 1 1 596772D4 +P 1825 1075 +F 0 "C3" H 1850 1175 50 0000 L CNN +F 1 "0.1" H 1850 975 50 0000 L CNN +F 2 "Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder" H 1863 925 50 0001 C CNN +F 3 "" H 1825 1075 50 0000 C CNN + 1 1825 1075 + 1 0 0 -1 +$EndComp +Text Notes 3650 1000 0 60 ~ 0 +1.5A! +Wire Wire Line + 3575 1375 3575 1425 +Wire Wire Line + 2075 1225 2075 1175 +Wire Wire Line + 3925 875 3925 1075 +Connection ~ 3925 1075 +Wire Wire Line + 3925 1475 3925 1425 +Connection ~ 3925 875 +Wire Wire Line + 5300 1350 5300 1300 +Wire Wire Line + 5600 1000 5700 1000 +Wire Wire Line + 9125 4075 9125 3925 +Wire Wire Line + 6325 900 6475 900 +Wire Wire Line + 6775 900 6875 900 +Wire Wire Line + 7175 900 7325 900 +Wire Wire Line + 6325 1200 6475 1200 +Wire Wire Line + 6775 1200 6875 1200 +Wire Wire Line + 7175 1200 7325 1200 +Wire Notes Line + 6025 550 6025 1350 +Wire Notes Line + 6025 1350 7525 1350 +Wire Notes Line + 7525 1350 7525 550 +Wire Notes Line + 7525 550 6025 550 +Connection ~ 9125 4075 +Wire Wire Line + 1825 925 1825 875 +Connection ~ 1825 875 +Wire Wire Line + 1825 1225 2075 1225 +$Comp +L stm32-rescue:C C8 +U 1 1 5A4FA4E4 +P 4225 1275 +F 0 "C8" H 4350 1275 50 0000 L CNN +F 1 "0.1" H 4250 1175 50 0000 L CNN +F 2 "Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder" H 4263 1125 50 0001 C CNN +F 3 "" H 4225 1275 50 0000 C CNN + 1 4225 1275 + 1 0 0 -1 +$EndComp +Wire Wire Line + 4225 1425 4225 1475 +Wire Wire Line + 4225 1475 3925 1475 +Wire Wire Line + 3925 1075 4225 1075 +Wire Wire Line + 4225 1075 4225 1125 +Wire Wire Line + 5600 950 5600 1000 +Connection ~ 5600 1000 +Wire Wire Line + 3925 1075 3925 1125 +Wire Wire Line + 5600 1000 5600 1050 +Wire Wire Line + 5300 1300 5700 1300 +$Comp +L stm32-rescue:R R5 +U 1 1 5D16EDDD +P 1125 1175 +F 0 "R5" V 1025 1175 50 0000 C CNN +F 1 "10k" V 1125 1175 50 0000 C CNN +F 2 "Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder" V 1055 1175 50 0001 C CNN +F 3 "" H 1125 1175 50 0000 C CNN + 1 1125 1175 + 0 -1 -1 0 +$EndComp +$Comp +L Device:D_Zener D1 +U 1 1 5D1735CA +P 1575 1025 +F 0 "D1" V 1700 1025 50 0000 L CNN +F 1 "MM3Z7V5" V 1775 850 50 0000 L CNN +F 2 "Diode_SMD:D_0805_2012Metric_Pad1.15x1.40mm_HandSolder" H 1575 1025 50 0001 C CNN +F 3 "~" H 1575 1025 50 0001 C CNN + 1 1575 1025 + 0 1 1 0 +$EndComp +$Comp +L stm32-rescue:GND #PWR01 +U 1 1 5D39DCF5 +P 975 1175 +F 0 "#PWR01" H 975 925 50 0001 C CNN +F 1 "GND" H 975 1025 50 0000 C CNN +F 2 "" H 975 1175 50 0000 C CNN +F 3 "" H 975 1175 50 0000 C CNN + 1 975 1175 + 1 0 0 -1 +$EndComp +$Comp +L stm32-rescue:USB_A-RESCUE-stm32 P1 +U 1 1 5CEABE76 +P 2525 2625 +F 0 "P1" V 2725 2575 50 0000 C CNN +F 1 "USB_B" V 2225 2625 50 0000 C CNN +F 2 "Connectors_USB:USB_B_OST_USB-B1HSxx_Horizontal" V 2475 2525 50 0001 C CNN +F 3 "" V 2475 2525 50 0000 C CNN + 1 2525 2625 + 0 1 -1 0 +$EndComp +$Comp +L stm32-rescue:GND #PWR04 +U 1 1 5CEABE82 +P 1000 2675 +F 0 "#PWR04" H 1000 2425 50 0001 C CNN +F 1 "GND" H 1000 2525 50 0000 C CNN +F 2 "" H 1000 2675 50 0000 C CNN +F 3 "" H 1000 2675 50 0000 C CNN + 1 1000 2675 + 1 0 0 -1 +$EndComp +$Comp +L stm32-rescue:R R3 +U 1 1 5CEABEA6 +P 1025 2150 +F 0 "R3" V 1105 2150 50 0000 C CNN +F 1 "22" V 1025 2150 50 0000 C CNN +F 2 "Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder" V 955 2150 50 0001 C CNN +F 3 "" H 1025 2150 50 0001 C CNN + 1 1025 2150 + 0 1 1 0 +$EndComp +$Comp +L stm32-rescue:R R4 +U 1 1 5CEABEAC +P 1025 3150 +F 0 "R4" V 1105 3150 50 0000 C CNN +F 1 "22" V 1025 3150 50 0000 C CNN +F 2 "Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder" V 955 3150 50 0001 C CNN +F 3 "" H 1025 3150 50 0001 C CNN + 1 1025 3150 + 0 1 1 0 +$EndComp +Wire Wire Line + 2625 2275 2625 2325 +Wire Wire Line + 1175 2150 1400 2150 +Wire Wire Line + 1175 3150 1400 3150 +Wire Wire Line + 1000 2675 1000 2650 +Wire Wire Line + 2225 2275 2225 2525 +$Comp +L stm32-rescue:+5V #PWR010 +U 1 1 5CFE3C1B +P 2525 3050 +F 0 "#PWR010" H 2525 2900 50 0001 C CNN +F 1 "+5V" H 2525 3190 50 0000 C CNN +F 2 "" H 2525 3050 50 0000 C CNN +F 3 "" H 2525 3050 50 0000 C CNN + 1 2525 3050 + 0 1 -1 0 +$EndComp +Wire Wire Line + 1600 2150 2125 2150 +Wire Wire Line + 2125 2150 2125 2625 +Wire Wire Line + 2125 2725 2225 2725 +Wire Wire Line + 2125 2625 2225 2625 +$Comp +L Power_Protection:USBLC6-2SC6 U1 +U 1 1 5CED0250 +P 1500 2650 +F 0 "U1" V 2075 2600 50 0000 L CNN +F 1 "USBLC6-2SC6" V 900 2375 50 0000 L CNN +F 2 "TO_SOT_Packages_SMD:SOT-23-6_Handsoldering" H 750 3050 50 0001 C CNN +F 3 "http://www2.st.com/resource/en/datasheet/CD00050750.pdf" H 1700 3000 50 0001 C CNN + 1 1500 2650 + 0 1 1 0 +$EndComp +$Comp +L stm32-rescue:R R13 +U 1 1 5D1076F1 +P 8375 2425 +F 0 "R13" V 8455 2425 50 0000 C CNN +F 1 "100k" V 8375 2425 50 0000 C CNN +F 2 "Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder" V 8305 2425 50 0001 C CNN +F 3 "" H 8375 2425 50 0000 C CNN + 1 8375 2425 + 0 1 1 0 +$EndComp +Wire Wire Line + 8525 2425 8625 2425 +$Comp +L stm32-rescue:GND #PWR031 +U 1 1 5D1293D9 +P 8175 2425 +F 0 "#PWR031" H 8175 2175 50 0001 C CNN +F 1 "GND" H 8175 2275 50 0000 C CNN +F 2 "" H 8175 2425 50 0000 C CNN +F 3 "" H 8175 2425 50 0000 C CNN + 1 8175 2425 + 1 0 0 -1 +$EndComp +Wire Wire Line + 8175 2425 8225 2425 +Text Label 6425 1950 2 50 ~ 0 +OSC_IN +Text Label 6875 1950 0 50 ~ 0 +OSC_OUT +$Comp +L Device:Crystal Y1 +U 1 1 5D1F4994 +P 6650 1950 +F 0 "Y1" H 6650 2218 50 0000 C CNN +F 1 "8MHz" H 6650 2127 50 0000 C CNN +F 2 "Crystal:Crystal_HC49-U_Vertical" H 6650 1950 50 0001 C CNN +F 3 "~" H 6650 1950 50 0001 C CNN + 1 6650 1950 + 1 0 0 -1 +$EndComp +$Comp +L stm32-rescue:C C11 +U 1 1 5D1F64B1 +P 6875 2100 +F 0 "C11" H 6900 2200 50 0000 L CNN +F 1 "12" H 6900 2000 50 0000 L CNN +F 2 "Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder" H 6913 1950 50 0001 C CNN +F 3 "" H 6875 2100 50 0000 C CNN + 1 6875 2100 + 1 0 0 -1 +$EndComp +$Comp +L stm32-rescue:C C10 +U 1 1 5D1F7471 +P 6425 2100 +F 0 "C10" H 6450 2200 50 0000 L CNN +F 1 "12" H 6450 2000 50 0000 L CNN +F 2 "Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder" H 6463 1950 50 0001 C CNN +F 3 "" H 6425 2100 50 0000 C CNN + 1 6425 2100 + -1 0 0 -1 +$EndComp +Wire Wire Line + 6425 1950 6500 1950 +Wire Wire Line + 6875 1950 6800 1950 +$Comp +L stm32-rescue:GND #PWR023 +U 1 1 5D21553E +P 6425 2250 +F 0 "#PWR023" H 6425 2000 50 0001 C CNN +F 1 "GND" H 6425 2100 50 0000 C CNN +F 2 "" H 6425 2250 50 0000 C CNN +F 3 "" H 6425 2250 50 0000 C CNN + 1 6425 2250 + 1 0 0 -1 +$EndComp +$Comp +L stm32-rescue:GND #PWR024 +U 1 1 5D215991 +P 6875 2250 +F 0 "#PWR024" H 6875 2000 50 0001 C CNN +F 1 "GND" H 6875 2100 50 0000 C CNN +F 2 "" H 6875 2250 50 0000 C CNN +F 3 "" H 6875 2250 50 0000 C CNN + 1 6875 2250 + 1 0 0 -1 +$EndComp +Text Notes 6175 1625 0 50 ~ 0 +Crystal +Wire Notes Line + 6025 1475 6025 2525 +Wire Notes Line + 6025 2525 7250 2525 +Wire Notes Line + 7250 2525 7250 1475 +Wire Notes Line + 7250 1475 6025 1475 +$Comp +L Transistor_BJT:DTA114Y Q2 +U 1 1 5D5EB488 +P 2025 3350 +F 0 "Q2" H 2213 3396 50 0000 L CNN +F 1 "DTA114Y" H 2213 3305 50 0000 L CNN +F 2 "TO_SOT_Packages_SMD:SOT-323_SC-70_Handsoldering" H 2025 3350 50 0001 L CNN +F 3 "" H 2025 3350 50 0001 L CNN + 1 2025 3350 + 1 0 0 -1 +$EndComp +Text Label 1775 3350 2 50 ~ 0 +USB_PU +$Comp +L stm32-rescue:+3.3V #PWR09 +U 1 1 5D77910C +P 2125 3550 +F 0 "#PWR09" H 2125 3400 50 0001 C CNN +F 1 "+3.3V" H 2125 3690 50 0000 C CNN +F 2 "" H 2125 3550 50 0000 C CNN +F 3 "" H 2125 3550 50 0000 C CNN + 1 2125 3550 + -1 0 0 1 +$EndComp +Text Label 8625 1325 2 60 ~ 0 +BOOT0 +Text Label 8625 1125 2 60 ~ 0 +NRST +Wire Wire Line + 9125 925 9225 925 +Wire Wire Line + 9225 925 9325 925 +Connection ~ 9225 925 +Wire Wire Line + 9325 925 9425 925 +Connection ~ 9325 925 +Wire Wire Line + 9525 925 9425 925 +Connection ~ 9425 925 +Wire Wire Line + 9325 925 9325 850 +$Comp +L power:+3.3V #PWR039 +U 1 1 5D5B1F88 +P 9325 850 +F 0 "#PWR039" H 9325 700 50 0001 C CNN +F 1 "+3.3V" H 9340 1023 50 0000 C CNN +F 2 "" H 9325 850 50 0001 C CNN +F 3 "" H 9325 850 50 0001 C CNN + 1 9325 850 + 1 0 0 -1 +$EndComp +Wire Wire Line + 9125 3925 9225 3925 +Connection ~ 9125 3925 +Wire Wire Line + 9225 3925 9325 3925 +Connection ~ 9225 3925 +Wire Wire Line + 9325 3925 9425 3925 +Connection ~ 9325 3925 +Text Label 8625 1525 2 50 ~ 0 +OSC_IN +Text Label 8625 1625 2 50 ~ 0 +OSC_OUT +Text Label 9925 3325 0 50 ~ 0 +USBDM +Text Label 9925 3425 0 50 ~ 0 +USBDP +Text Label 875 3150 2 50 ~ 0 +USBDM +Text Label 875 2150 2 50 ~ 0 +USBDP +$Comp +L stm32-rescue:R R18 +U 1 1 5D650328 +P 10200 2325 +F 0 "R18" V 10280 2325 50 0000 C CNN +F 1 "100k" V 10200 2325 50 0000 C CNN +F 2 "Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder" V 10130 2325 50 0001 C CNN +F 3 "" H 10200 2325 50 0000 C CNN + 1 10200 2325 + 0 1 1 0 +$EndComp +$Comp +L stm32-rescue:GND #PWR042 +U 1 1 5D666ED6 +P 10350 2325 +F 0 "#PWR042" H 10350 2075 50 0001 C CNN +F 1 "GND" H 10350 2175 50 0000 C CNN +F 2 "" H 10350 2325 50 0000 C CNN +F 3 "" H 10350 2325 50 0000 C CNN + 1 10350 2325 + 1 0 0 -1 +$EndComp +Wire Wire Line + 10050 2325 9925 2325 +Text Label 9925 2325 0 50 ~ 0 +PPS +Text Label 9925 3725 0 50 ~ 0 +USB_PU +$Comp +L Isolator:PC817 U5 +U 1 1 5D68F125 +P 7600 5800 +F 0 "U5" H 7600 6125 50 0000 C CNN +F 1 "PC817" H 7600 6034 50 0000 C CNN +F 2 "Package_DIP:DIP-4_W7.62mm" H 7400 5600 50 0001 L CIN +F 3 "http://www.soselectronic.cz/a_info/resource/d/pc817.pdf" H 7600 5800 50 0001 L CNN + 1 7600 5800 + 1 0 0 -1 +$EndComp +$Comp +L Device:R R12 +U 1 1 5D6934BF +P 7900 5500 +F 0 "R12" H 7970 5546 50 0000 L CNN +F 1 "4k7" H 7970 5455 50 0000 L CNN +F 2 "Resistor_SMD:R_0805_2012Metric_Pad1.15x1.40mm_HandSolder" V 7830 5500 50 0001 C CNN +F 3 "~" H 7900 5500 50 0001 C CNN + 1 7900 5500 + 1 0 0 -1 +$EndComp +Wire Wire Line + 7900 5650 7900 5700 +$Comp +L power:+3.3V #PWR029 +U 1 1 5D6AC121 +P 7900 5350 +F 0 "#PWR029" H 7900 5200 50 0001 C CNN +F 1 "+3.3V" H 7915 5523 50 0000 C CNN +F 2 "" H 7900 5350 50 0001 C CNN +F 3 "" H 7900 5350 50 0001 C CNN + 1 7900 5350 + 1 0 0 -1 +$EndComp +Text Label 7900 5700 0 50 ~ 0 +TRIG0 +$Comp +L Device:R R10 +U 1 1 5D6BDDB4 +P 7225 5450 +F 0 "R10" H 7156 5404 50 0000 R CNN +F 1 "330" H 7156 5495 50 0000 R CNN +F 2 "Resistor_SMD:R_0805_2012Metric_Pad1.15x1.40mm_HandSolder" V 7155 5450 50 0001 C CNN +F 3 "~" H 7225 5450 50 0001 C CNN + 1 7225 5450 + 1 0 0 1 +$EndComp +$Comp +L power:+3.3V #PWR025 +U 1 1 5D6CF631 +P 7225 5300 +F 0 "#PWR025" H 7225 5150 50 0001 C CNN +F 1 "+3.3V" H 7240 5473 50 0000 C CNN +F 2 "" H 7225 5300 50 0001 C CNN +F 3 "" H 7225 5300 50 0001 C CNN + 1 7225 5300 + 1 0 0 -1 +$EndComp +$Comp +L Device:R R11 +U 1 1 5D6D432A +P 7225 5750 +F 0 "R11" H 7155 5704 50 0000 R CNN +F 1 "4k7" H 7155 5795 50 0000 R CNN +F 2 "Resistor_SMD:R_0805_2012Metric_Pad1.15x1.40mm_HandSolder" V 7155 5750 50 0001 C CNN +F 3 "~" H 7225 5750 50 0001 C CNN + 1 7225 5750 + 1 0 0 1 +$EndComp +Wire Wire Line + 7300 5700 7300 5600 +Wire Wire Line + 7300 5600 7225 5600 +Connection ~ 7225 5600 +Wire Wire Line + 7225 5900 7300 5900 +Wire Wire Line + 7175 5900 7225 5900 +Connection ~ 7225 5900 +Wire Wire Line + 7175 6000 7225 6000 +$Comp +L Isolator:PC817 U6 +U 1 1 5D710D2A +P 8975 5800 +F 0 "U6" H 8975 6125 50 0000 C CNN +F 1 "PC817" H 8975 6034 50 0000 C CNN +F 2 "Package_DIP:DIP-4_W7.62mm" H 8775 5600 50 0001 L CIN +F 3 "http://www.soselectronic.cz/a_info/resource/d/pc817.pdf" H 8975 5800 50 0001 L CNN + 1 8975 5800 + 1 0 0 -1 +$EndComp +$Comp +L Device:R R16 +U 1 1 5D710D30 +P 9275 5500 +F 0 "R16" H 9345 5546 50 0000 L CNN +F 1 "4k7" H 9345 5455 50 0000 L CNN +F 2 "Resistor_SMD:R_0805_2012Metric_Pad1.15x1.40mm_HandSolder" V 9205 5500 50 0001 C CNN +F 3 "~" H 9275 5500 50 0001 C CNN + 1 9275 5500 + 1 0 0 -1 +$EndComp +Wire Wire Line + 9275 5650 9275 5700 +$Comp +L power:+3.3V #PWR037 +U 1 1 5D710D3D +P 9275 5350 +F 0 "#PWR037" H 9275 5200 50 0001 C CNN +F 1 "+3.3V" H 9290 5523 50 0000 C CNN +F 2 "" H 9275 5350 50 0001 C CNN +F 3 "" H 9275 5350 50 0001 C CNN + 1 9275 5350 + 1 0 0 -1 +$EndComp +Text Label 9275 5700 0 50 ~ 0 +TRIG1 +$Comp +L Device:R R14 +U 1 1 5D710D44 +P 8600 5450 +F 0 "R14" H 8531 5404 50 0000 R CNN +F 1 "330" H 8531 5495 50 0000 R CNN +F 2 "Resistor_SMD:R_0805_2012Metric_Pad1.15x1.40mm_HandSolder" V 8530 5450 50 0001 C CNN +F 3 "~" H 8600 5450 50 0001 C CNN + 1 8600 5450 + 1 0 0 1 +$EndComp +$Comp +L power:+3.3V #PWR035 +U 1 1 5D710D4A +P 8600 5300 +F 0 "#PWR035" H 8600 5150 50 0001 C CNN +F 1 "+3.3V" H 8615 5473 50 0000 C CNN +F 2 "" H 8600 5300 50 0001 C CNN +F 3 "" H 8600 5300 50 0001 C CNN + 1 8600 5300 + 1 0 0 -1 +$EndComp +$Comp +L Device:R R15 +U 1 1 5D710D50 +P 8600 5750 +F 0 "R15" H 8530 5704 50 0000 R CNN +F 1 "4k7" H 8530 5795 50 0000 R CNN +F 2 "Resistor_SMD:R_0805_2012Metric_Pad1.15x1.40mm_HandSolder" V 8530 5750 50 0001 C CNN +F 3 "~" H 8600 5750 50 0001 C CNN + 1 8600 5750 + 1 0 0 1 +$EndComp +Wire Wire Line + 8675 5700 8675 5600 +Wire Wire Line + 8675 5600 8600 5600 +Connection ~ 8600 5600 +Wire Wire Line + 8600 5900 8675 5900 +Wire Wire Line + 8550 5900 8600 5900 +Connection ~ 8600 5900 +Wire Wire Line + 8550 6000 8600 6000 +$Comp +L Isolator:PC817 U8 +U 1 1 5D72A0B8 +P 10575 5800 +F 0 "U8" H 10575 6125 50 0000 C CNN +F 1 "PC817" H 10575 6034 50 0000 C CNN +F 2 "Package_DIP:DIP-4_W7.62mm" H 10375 5600 50 0001 L CIN +F 3 "http://www.soselectronic.cz/a_info/resource/d/pc817.pdf" H 10575 5800 50 0001 L CNN + 1 10575 5800 + 1 0 0 -1 +$EndComp +$Comp +L Device:R R20 +U 1 1 5D72A0BE +P 10875 5500 +F 0 "R20" H 10945 5546 50 0000 L CNN +F 1 "4k7" H 10945 5455 50 0000 L CNN +F 2 "Resistor_SMD:R_0805_2012Metric_Pad1.15x1.40mm_HandSolder" V 10805 5500 50 0001 C CNN +F 3 "~" H 10875 5500 50 0001 C CNN + 1 10875 5500 + 1 0 0 -1 +$EndComp +Wire Wire Line + 10875 5650 10875 5700 +$Comp +L power:+3.3V #PWR043 +U 1 1 5D72A0CB +P 10875 5350 +F 0 "#PWR043" H 10875 5200 50 0001 C CNN +F 1 "+3.3V" H 10890 5523 50 0000 C CNN +F 2 "" H 10875 5350 50 0001 C CNN +F 3 "" H 10875 5350 50 0001 C CNN + 1 10875 5350 + 1 0 0 -1 +$EndComp +Text Label 10875 5700 0 50 ~ 0 +TRIG2 +$Comp +L Device:R R19 +U 1 1 5D72A0DE +P 10200 5750 +F 0 "R19" H 10130 5704 50 0000 R CNN +F 1 "4k7" H 10130 5795 50 0000 R CNN +F 2 "Resistor_SMD:R_0805_2012Metric_Pad1.15x1.40mm_HandSolder" V 10130 5750 50 0001 C CNN +F 3 "~" H 10200 5750 50 0001 C CNN + 1 10200 5750 + 1 0 0 1 +$EndComp +Wire Wire Line + 10275 5700 10275 5600 +Wire Wire Line + 10275 5600 10200 5600 +Wire Wire Line + 10200 5900 10275 5900 +Connection ~ 10200 5900 +Text Notes 7200 6400 0 118 ~ 0 +Button +Text Notes 8125 6400 0 118 ~ 0 +Open collector +Text Notes 10000 6375 0 118 ~ 0 +Ext. 12V +$Comp +L Device:R R17 +U 1 1 5D74F6B4 +P 10050 5600 +F 0 "R17" V 9950 5600 50 0000 C CNN +F 1 "2k2" V 10050 5600 50 0000 C CNN +F 2 "Resistor_SMD:R_0805_2012Metric_Pad1.15x1.40mm_HandSolder" V 9980 5600 50 0001 C CNN +F 3 "~" H 10050 5600 50 0001 C CNN + 1 10050 5600 + 0 -1 1 0 +$EndComp +Connection ~ 10200 5600 +Wire Wire Line + 9900 5700 9900 5900 +Wire Wire Line + 9900 5900 10200 5900 +Wire Notes Line + 6775 6425 11125 6425 +Wire Notes Line + 11125 6425 11125 5075 +Wire Notes Line + 11125 5075 6775 5075 +Wire Notes Line + 6775 5075 6775 6425 +Text Label 8625 3025 2 60 ~ 0 +LED0 +Text Label 8625 3125 2 60 ~ 0 +LED1 +$Comp +L Connector_Generic:Conn_01x02 J1 +U 1 1 5D79C13C +P 775 975 +F 0 "J1" H 775 1075 50 0000 C CNN +F 1 "Power 12V" H 775 750 50 0000 C CNN +F 2 "TerminalBlock_Phoenix:TerminalBlock_Phoenix_MKDS-1,5-2-5.08_1x02_P5.08mm_Horizontal" H 775 975 50 0001 C CNN +F 3 "~" H 775 975 50 0001 C CNN + 1 775 975 + -1 0 0 1 +$EndComp +Wire Wire Line + 975 975 975 1175 +Wire Wire Line + 2775 1525 2975 1525 +Wire Wire Line + 3575 1075 3625 1075 +Wire Wire Line + 1575 875 1825 875 +$Comp +L Device:D_Schottky D2 +U 1 1 5D89B9B8 +P 2375 3050 +F 0 "D2" H 2350 2875 50 0000 C CNN +F 1 "SS14" H 2375 2950 50 0000 C CNN +F 2 "Diode_SMD:D_SMA_Handsoldering" H 2375 3050 50 0001 C CNN +F 3 "~" H 2375 3050 50 0001 C CNN + 1 2375 3050 + -1 0 0 -1 +$EndComp +$Comp +L stm32-rescue:+5V #PWR014 +U 1 1 5D8AA2D8 +P 3775 875 +F 0 "#PWR014" H 3775 725 50 0001 C CNN +F 1 "+5V" H 3775 1015 50 0000 C CNN +F 2 "" H 3775 875 50 0000 C CNN +F 3 "" H 3775 875 50 0000 C CNN + 1 3775 875 + 1 0 0 -1 +$EndComp +$Comp +L stm32-rescue:R R6 +U 1 1 5D5EA0B2 +P 2125 3000 +F 0 "R6" V 2205 3000 50 0000 C CNN +F 1 "1k5" V 2125 3000 50 0000 C CNN +F 2 "Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder" V 2055 3000 50 0001 C CNN +F 3 "" H 2125 3000 50 0001 C CNN + 1 2125 3000 + -1 0 0 1 +$EndComp +Wire Wire Line + 1600 3150 1950 3150 +Wire Wire Line + 1950 3150 1950 2850 +Wire Wire Line + 1950 2850 2125 2850 +Wire Wire Line + 2125 2725 2125 2850 +Wire Notes Line + 575 1950 575 3750 +Wire Notes Line + 575 3750 2800 3750 +Wire Notes Line + 2800 3750 2800 1950 +Wire Notes Line + 2800 1950 575 1950 +$Comp +L Connector:Conn_01x04_Female J4 +U 1 1 5D927958 +P 8175 3325 +F 0 "J4" H 8025 3075 50 0000 L CNN +F 1 "LIDAR" H 7975 3525 50 0000 L CNN +F 2 "Connector_PinSocket_2.54mm:PinSocket_1x04_P2.54mm_Vertical" H 8175 3325 50 0001 C CNN +F 3 "~" H 8175 3325 50 0001 C CNN + 1 8175 3325 + -1 0 0 -1 +$EndComp +Text Notes 8125 3550 2 59 ~ 0 +LIDAR:\nRx\nTx\nGnd\n+5V +Text Notes 10525 3250 0 59 ~ 0 +USB<>TTL:\nGnd\nRx\nTx +$Comp +L Connector_Generic:Conn_01x02 J2 +U 1 1 5D93AD09 +P 4525 875 +F 0 "J2" H 4525 975 50 0000 C CNN +F 1 "+5Vout" H 4525 1050 50 0000 C CNN +F 2 "TerminalBlock_Phoenix:TerminalBlock_Phoenix_MKDS-1,5-2-5.08_1x02_P5.08mm_Horizontal" H 4525 875 50 0001 C CNN +F 3 "~" H 4525 875 50 0001 C CNN + 1 4525 875 + 1 0 0 -1 +$EndComp +$Comp +L stm32-rescue:GND #PWR018 +U 1 1 5D93E82A +P 4325 975 +F 0 "#PWR018" H 4325 725 50 0001 C CNN +F 1 "GND" H 4325 825 50 0000 C CNN +F 2 "" H 4325 975 50 0000 C CNN +F 3 "" H 4325 975 50 0000 C CNN + 1 4325 975 + 1 0 0 -1 +$EndComp +$Comp +L Device:R R7 +U 1 1 5D93EDCC +P 4075 875 +F 0 "R7" V 3975 875 50 0000 C CNN +F 1 "22" V 4075 875 50 0000 C CNN +F 2 "Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder" V 4005 875 50 0001 C CNN +F 3 "~" H 4075 875 50 0001 C CNN + 1 4075 875 + 0 1 1 0 +$EndComp +Wire Wire Line + 4225 875 4325 875 +Wire Notes Line + 550 550 550 1775 +Wire Notes Line + 550 1775 4700 1775 +Wire Notes Line + 4700 1775 4700 550 +Wire Notes Line + 4700 550 550 550 +Wire Notes Line + 4775 550 4775 1550 +Wire Notes Line + 4775 1550 5925 1550 +Wire Notes Line + 5925 1550 5925 550 +Wire Notes Line + 5925 550 4775 550 +Wire Wire Line + 9925 3225 10300 3225 +Wire Wire Line + 9925 3125 10300 3125 +$Comp +L stm32-rescue:GND #PWR041 +U 1 1 5D9BD709 +P 10300 3025 +F 0 "#PWR041" H 10300 2775 50 0001 C CNN +F 1 "GND" H 10300 2875 50 0000 C CNN +F 2 "" H 10300 3025 50 0000 C CNN +F 3 "" H 10300 3025 50 0000 C CNN + 1 10300 3025 + 0 1 1 0 +$EndComp +Wire Wire Line + 8625 3225 8375 3225 +Wire Wire Line + 8375 3325 8625 3325 +$Comp +L stm32-rescue:GND #PWR033 +U 1 1 5D9DBF9E +P 8475 3450 +F 0 "#PWR033" H 8475 3200 50 0001 C CNN +F 1 "GND" H 8500 3300 50 0000 C CNN +F 2 "" H 8475 3450 50 0000 C CNN +F 3 "" H 8475 3450 50 0000 C CNN + 1 8475 3450 + 1 0 0 -1 +$EndComp +Wire Wire Line + 8375 3425 8475 3425 +Wire Wire Line + 8475 3425 8475 3450 +$Comp +L stm32-rescue:+5V #PWR032 +U 1 1 5D9E3357 +P 8375 3525 +F 0 "#PWR032" H 8375 3375 50 0001 C CNN +F 1 "+5V" H 8400 3675 50 0000 C CNN +F 2 "" H 8375 3525 50 0000 C CNN +F 3 "" H 8375 3525 50 0000 C CNN + 1 8375 3525 + -1 0 0 1 +$EndComp +NoConn ~ 8625 3425 +NoConn ~ 8625 3525 +NoConn ~ 8625 3625 +NoConn ~ 8625 3725 +NoConn ~ 8625 1825 +NoConn ~ 8625 1925 +NoConn ~ 8625 2025 +Text Label 9925 2425 0 50 ~ 0 +U3Tx +Text Label 9925 2525 0 50 ~ 0 +U3Rx +Text Label 4325 3450 2 50 ~ 0 +U3Tx +Text Label 4325 3550 2 50 ~ 0 +U3Rx +Text Label 9925 3125 0 50 ~ 0 +U1Tx +Text Label 9925 3225 0 50 ~ 0 +U1Rx +Text Label 8625 3225 2 50 ~ 0 +U2Tx +Text Label 8625 3325 2 50 ~ 0 +U2Rx +Text Label 9925 2625 0 50 ~ 0 +TRIG2 +Text Label 9925 3525 0 50 ~ 0 +TRIG0 +Text Label 9925 3625 0 50 ~ 0 +TRIG1 +NoConn ~ 9925 3025 +NoConn ~ 9925 2925 +NoConn ~ 9925 2825 +NoConn ~ 9925 2725 +$Comp +L Chrono:L80-R U3 +U 1 1 5D13B322 +P 4775 3700 +F 0 "U3" H 4775 4215 50 0000 C CNN +F 1 "L80-R" H 4775 4124 50 0000 C CNN +F 2 "chrono:L80-R" H 4775 3700 50 0001 C CNN +F 3 "" H 4225 3650 50 0001 C CNN + 1 4775 3700 + 1 0 0 -1 +$EndComp +$Comp +L Device:C C5 +U 1 1 5DB80168 +P 3700 3750 +F 0 "C5" H 3525 3850 50 0000 L CNN +F 1 "10u" H 3500 3675 50 0000 L CNN +F 2 "Capacitor_SMD:C_1206_3216Metric_Pad1.42x1.75mm_HandSolder" H 3738 3600 50 0001 C CNN +F 3 "~" H 3700 3750 50 0001 C CNN + 1 3700 3750 + 1 0 0 -1 +$EndComp +$Comp +L stm32-rescue:C C7 +U 1 1 5DB8A65B +P 3925 3750 +F 0 "C7" H 3950 3850 50 0000 L CNN +F 1 "0.1" H 3950 3650 50 0000 L CNN +F 2 "Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder" H 3963 3600 50 0001 C CNN +F 3 "" H 3925 3750 50 0000 C CNN + 1 3925 3750 + 1 0 0 -1 +$EndComp +Wire Wire Line + 4325 3650 4150 3650 +Wire Wire Line + 4100 3650 4100 3600 +Wire Wire Line + 4150 3900 4150 3850 +Wire Wire Line + 4150 3850 4325 3850 +Wire Wire Line + 4325 3850 4325 3750 +Connection ~ 4325 3850 +$Comp +L power:GND #PWR017 +U 1 1 5DBA6FD4 +P 4150 3650 +F 0 "#PWR017" H 4150 3400 50 0001 C CNN +F 1 "GND" H 4150 3500 50 0000 C CNN +F 2 "" H 4150 3650 50 0001 C CNN +F 3 "" H 4150 3650 50 0001 C CNN + 1 4150 3650 + 1 0 0 -1 +$EndComp +Connection ~ 4150 3650 +Wire Wire Line + 4150 3650 4100 3650 +$Comp +L stm32-rescue:+3.3V #PWR016 +U 1 1 5DBAA731 +P 3925 3900 +F 0 "#PWR016" H 3925 3750 50 0001 C CNN +F 1 "+3.3V" H 3925 4040 50 0000 C CNN +F 2 "" H 3925 3900 50 0000 C CNN +F 3 "" H 3925 3900 50 0000 C CNN + 1 3925 3900 + -1 0 0 1 +$EndComp +Text Label 4325 3950 2 50 ~ 0 +PPS +NoConn ~ 5225 3950 +NoConn ~ 5225 3850 +NoConn ~ 5225 3750 +NoConn ~ 5225 3550 +NoConn ~ 5225 3650 +$Comp +L power:GND #PWR021 +U 1 1 5DBD6831 +P 5350 3450 +F 0 "#PWR021" H 5350 3200 50 0001 C CNN +F 1 "GND" H 5350 3300 50 0000 C CNN +F 2 "" H 5350 3450 50 0001 C CNN +F 3 "" H 5350 3450 50 0001 C CNN + 1 5350 3450 + 1 0 0 -1 +$EndComp +Wire Wire Line + 5225 3450 5350 3450 +Wire Notes Line + 3475 3050 3475 4125 +Wire Notes Line + 3475 4125 5450 4125 +Wire Notes Line + 5450 4125 5450 3050 +Wire Notes Line + 5450 3050 3475 3050 +Text Notes 3625 3250 0 60 ~ 0 +GPS module +Text Notes 2300 2075 0 61 ~ 0 +USB +Text Notes 9650 5200 0 61 ~ 0 +External triggers +NoConn ~ 8625 2225 +NoConn ~ 8625 2325 +NoConn ~ 8625 2525 +NoConn ~ 8625 2625 +NoConn ~ 8625 2725 +NoConn ~ 8625 2825 +NoConn ~ 8625 2925 +$Comp +L stm32-rescue:PWR_FLAG #FLG0101 +U 1 1 5DC59BA7 +P 2225 2925 +F 0 "#FLG0101" H 2225 3020 50 0001 C CNN +F 1 "PWR_FLAG" H 2225 3105 50 0001 C CNN +F 2 "" H 2225 2925 50 0000 C CNN +F 3 "" H 2225 2925 50 0000 C CNN + 1 2225 2925 + 0 1 -1 0 +$EndComp +Wire Wire Line + 2225 2275 2625 2275 +$Comp +L stm32-rescue:PWR_FLAG #FLG0102 +U 1 1 5DC73174 +P 975 1175 +F 0 "#FLG0102" H 975 1270 50 0001 C CNN +F 1 "PWR_FLAG" H 975 1355 50 0001 C CNN +F 2 "" H 975 1175 50 0000 C CNN +F 3 "" H 975 1175 50 0000 C CNN + 1 975 1175 + 0 -1 -1 0 +$EndComp +Wire Wire Line + 975 875 1175 875 +Wire Wire Line + 2225 2775 2000 2775 +Wire Wire Line + 2000 2775 2000 2650 +NoConn ~ 9925 2225 +Wire Wire Line + 8475 4075 9125 4075 +Wire Wire Line + 1825 875 2175 875 +Wire Wire Line + 3575 875 3925 875 +Wire Wire Line + 9125 4075 9725 4075 +Wire Wire Line + 1275 1175 1575 1175 +Wire Wire Line + 3700 3900 4150 3900 +Wire Wire Line + 3700 3600 4100 3600 +Wire Wire Line + 2225 2775 2225 3050 +Wire Wire Line + 8825 4375 10125 4375 +$Comp +L power:GND #PWR? +U 1 1 5DD979BE +P 8600 6000 +F 0 "#PWR?" H 8600 5750 50 0001 C CNN +F 1 "GND" H 8605 5827 50 0000 C CNN +F 2 "" H 8600 6000 50 0001 C CNN +F 3 "" H 8600 6000 50 0001 C CNN + 1 8600 6000 + 1 0 0 -1 +$EndComp +$Comp +L power:GND #PWR? +U 1 1 5DD97F2E +P 9275 5900 +F 0 "#PWR?" H 9275 5650 50 0001 C CNN +F 1 "GND" H 9280 5727 50 0000 C CNN +F 2 "" H 9275 5900 50 0001 C CNN +F 3 "" H 9275 5900 50 0001 C CNN + 1 9275 5900 + 1 0 0 -1 +$EndComp +$Comp +L power:GND #PWR? +U 1 1 5DD98BA6 +P 7900 5900 +F 0 "#PWR?" H 7900 5650 50 0001 C CNN +F 1 "GND" H 7905 5727 50 0000 C CNN +F 2 "" H 7900 5900 50 0001 C CNN +F 3 "" H 7900 5900 50 0001 C CNN + 1 7900 5900 + 1 0 0 -1 +$EndComp +$Comp +L power:GND #PWR? +U 1 1 5DD99058 +P 7225 6000 +F 0 "#PWR?" H 7225 5750 50 0001 C CNN +F 1 "GND" H 7230 5827 50 0000 C CNN +F 2 "" H 7225 6000 50 0001 C CNN +F 3 "" H 7225 6000 50 0001 C CNN + 1 7225 6000 + 1 0 0 -1 +$EndComp +$Comp +L power:GND #PWR? +U 1 1 5DD9B67F +P 10875 5900 +F 0 "#PWR?" H 10875 5650 50 0001 C CNN +F 1 "GND" H 10880 5727 50 0000 C CNN +F 2 "" H 10875 5900 50 0001 C CNN +F 3 "" H 10875 5900 50 0001 C CNN + 1 10875 5900 + 1 0 0 -1 +$EndComp +$Comp +L power:GND #PWR? +U 1 1 5DDACF17 +P 2625 2325 +F 0 "#PWR?" H 2625 2075 50 0001 C CNN +F 1 "GND" H 2630 2152 50 0000 C CNN +F 2 "" H 2625 2325 50 0001 C CNN +F 3 "" H 2625 2325 50 0001 C CNN + 1 2625 2325 + 1 0 0 -1 +$EndComp +$EndSCHEMATC diff --git a/F1-nolib/chronometer/kicad/chrono/fp-info-cache b/F1-nolib/chronometer/kicad/chrono/fp-info-cache new file mode 100644 index 0000000..fb05de9 --- /dev/null +++ b/F1-nolib/chronometer/kicad/chrono/fp-info-cache @@ -0,0 +1,22940 @@ +5011622174385028 +Buttons_Switches_SMD +Nidec_Copal_SH-7010A +4-bit rotary coded switch, J-hook, https://www.nidec-copal-electronics.com/e/catalog/switch/sh-7000.pdf +rotary switch bcd +0 +6 +5 +Buttons_Switches_SMD +Nidec_Copal_SH-7010B +4-bit rotary coded switch, gull wing, https://www.nidec-copal-electronics.com/e/catalog/switch/sh-7000.pdf +rotary switch bcd +0 +6 +5 +Buttons_Switches_SMD +Nidec_Copal_SH-7040B +4-bit rotary coded switch, gull wing, Gray code, https://www.nidec-copal-electronics.com/e/catalog/switch/sh-7000.pdf +rotary switch bcd +0 +5 +5 +Buttons_Switches_SMD +Panasonic_EVQPUJ_EVQPUA +http://industrial.panasonic.com/cdbs/www-data/pdf/ATV0000/ATV0000CE5.pdf +SMD SMT SPST EVQPUJ EVQPUA +0 +4 +2 +Buttons_Switches_SMD +Panasonic_EVQPUK_EVQPUB +http://industrial.panasonic.com/cdbs/www-data/pdf/ATV0000/ATV0000CE5.pdf +SMD SMT SPST EVQPUK EVQPUB +0 +4 +2 +Buttons_Switches_SMD +Panasonic_EVQPUL_EVQPUC +http://industrial.panasonic.com/cdbs/www-data/pdf/ATV0000/ATV0000CE5.pdf +SMD SMT SPST EVQPUL EVQPUC +0 +4 +2 +Buttons_Switches_SMD +Panasonic_EVQPUM_EVQPUD +http://industrial.panasonic.com/cdbs/www-data/pdf/ATV0000/ATV0000CE5.pdf +SMD SMT SPST EVQPUM EVQPUD +0 +4 +2 +Buttons_Switches_SMD +SW_DIP_SPSTx01_Slide_6.7x4.1mm_W6.73mm_P2.54mm_LowProfile_JPin +SMD 1x-dip-switch SPST , Slide, row spacing 6.73 mm (264 mils), body size 6.7x4.1mm (see e.g. https://www.ctscorp.com/wp-content/uploads/219.pdf), SMD, LowProfile, JPin +SMD DIP Switch SPST Slide 6.73mm 264mil SMD LowProfile JPin +0 +2 +2 +Buttons_Switches_SMD +SW_DIP_SPSTx01_Slide_6.7x4.1mm_W8.61mm_P2.54mm_LowProfile +SMD 1x-dip-switch SPST , Slide, row spacing 8.61 mm (338 mils), body size 6.7x4.1mm (see e.g. https://www.ctscorp.com/wp-content/uploads/219.pdf), SMD, LowProfile +SMD DIP Switch SPST Slide 8.61mm 338mil SMD LowProfile +0 +2 +2 +Buttons_Switches_SMD +SW_DIP_SPSTx01_Slide_9.78x4.72mm_W8.61mm_P2.54mm +SMD 1x-dip-switch SPST , Slide, row spacing 8.61 mm (338 mils), body size 9.78x4.72mm (see e.g. https://www.ctscorp.com/wp-content/uploads/204.pdf), SMD +SMD DIP Switch SPST Slide 8.61mm 338mil SMD +0 +2 +2 +Buttons_Switches_SMD +SW_DIP_SPSTx01_Slide_Copal_CHS-01A_W5.08mm_P1.27mm_JPin +SMD 1x-dip-switch SPST Copal_CHS-01A, Slide, row spacing 5.08 mm (200 mils), body size (see http://www.nidec-copal-electronics.com/e/catalog/switch/chs.pdf), SMD, JPin +SMD DIP Switch SPST Slide 5.08mm 200mil SMD JPin +0 +2 +2 +Buttons_Switches_SMD +SW_DIP_SPSTx01_Slide_Copal_CHS-01B_W7.62mm_P1.27mm +SMD 1x-dip-switch SPST Copal_CHS-01B, Slide, row spacing 7.62 mm (300 mils), body size (see http://www.nidec-copal-electronics.com/e/catalog/switch/chs.pdf), SMD +SMD DIP Switch SPST Slide 7.62mm 300mil SMD +0 +2 +2 +Buttons_Switches_SMD +SW_DIP_SPSTx01_Slide_Copal_CVS-01xB_W5.9mm_P1mm +SMD 1x-dip-switch SPST Copal_CVS-01xB, Slide, row spacing 5.9 mm (232 mils), body size (see http://www.nidec-copal-electronics.com/e/catalog/switch/cvs.pdf) +SMD DIP Switch SPST Slide 5.9mm 232mil +0 +6 +3 +Buttons_Switches_SMD +SW_DIP_SPSTx01_Slide_Omron_A6S-110x_W8.9mm_P2.54mm +SMD 1x-dip-switch SPST Omron_A6S-110x, Slide, row spacing 8.9 mm (350 mils), body size (see http://omronfs.omron.com/en_US/ecb/products/pdf/en-a6s.pdf) +SMD DIP Switch SPST Slide 8.9mm 350mil +0 +2 +2 +Buttons_Switches_SMD +SW_DIP_SPSTx02_Slide_6.7x6.64mm_W6.73mm_P2.54mm_LowProfile_JPin +SMD 2x-dip-switch SPST , Slide, row spacing 6.73 mm (264 mils), body size 6.7x6.64mm (see e.g. https://www.ctscorp.com/wp-content/uploads/219.pdf), SMD, LowProfile, JPin +SMD DIP Switch SPST Slide 6.73mm 264mil SMD LowProfile JPin +0 +4 +4 +Buttons_Switches_SMD +SW_DIP_SPSTx02_Slide_6.7x6.64mm_W8.61mm_P2.54mm_LowProfile +SMD 2x-dip-switch SPST , Slide, row spacing 8.61 mm (338 mils), body size 6.7x6.64mm (see e.g. https://www.ctscorp.com/wp-content/uploads/219.pdf), SMD, LowProfile +SMD DIP Switch SPST Slide 8.61mm 338mil SMD LowProfile +0 +4 +4 +Buttons_Switches_SMD +SW_DIP_SPSTx02_Slide_9.78x7.26mm_W8.61mm_P2.54mm +SMD 2x-dip-switch SPST , Slide, row spacing 8.61 mm (338 mils), body size 9.78x7.26mm (see e.g. https://www.ctscorp.com/wp-content/uploads/204.pdf), SMD +SMD DIP Switch SPST Slide 8.61mm 338mil SMD +0 +4 +4 +Buttons_Switches_SMD +SW_DIP_SPSTx02_Slide_Copal_CHS-02A_W5.08mm_P1.27mm_JPin +SMD 2x-dip-switch SPST Copal_CHS-02A, Slide, row spacing 5.08 mm (200 mils), body size (see http://www.nidec-copal-electronics.com/e/catalog/switch/chs.pdf), SMD, JPin +SMD DIP Switch SPST Slide 5.08mm 200mil SMD JPin +0 +4 +4 +Buttons_Switches_SMD +SW_DIP_SPSTx02_Slide_Copal_CHS-02B_W7.62mm_P1.27mm +SMD 2x-dip-switch SPST Copal_CHS-02B, Slide, row spacing 7.62 mm (300 mils), body size (see http://www.nidec-copal-electronics.com/e/catalog/switch/chs.pdf), SMD +SMD DIP Switch SPST Slide 7.62mm 300mil SMD +0 +4 +4 +Buttons_Switches_SMD +SW_DIP_SPSTx02_Slide_Copal_CVS-02xB_W5.9mm_P1mm +SMD 2x-dip-switch SPST Copal_CVS-02xB, Slide, row spacing 5.9 mm (232 mils), body size (see http://www.nidec-copal-electronics.com/e/catalog/switch/cvs.pdf) +SMD DIP Switch SPST Slide 5.9mm 232mil +0 +8 +5 +Buttons_Switches_SMD +SW_DIP_SPSTx02_Slide_KingTek_DSHP02TJ_W5.25mm_P1.27mm_JPin +SMD 2x-dip-switch SPST KingTek_DSHP02TJ, Slide, row spacing 5.25 mm (206 mils), body size (see http://www.kingtek.net.cn/pic/201601201446313350.pdf), JPin +SMD DIP Switch SPST Slide 5.25mm 206mil JPin +0 +4 +4 +Buttons_Switches_SMD +SW_DIP_SPSTx02_Slide_KingTek_DSHP02TS_W7.62mm_P1.27mm +SMD 2x-dip-switch SPST KingTek_DSHP02TS, Slide, row spacing 7.62 mm (300 mils), body size (see http://www.kingtek.net.cn/pic/201601201417455112.pdf) +SMD DIP Switch SPST Slide 7.62mm 300mil +0 +4 +4 +Buttons_Switches_SMD +SW_DIP_SPSTx02_Slide_Omron_A6H-2101_W6.15mm_P1.27mm +SMD 2x-dip-switch SPST Omron_A6H-2101, Slide, row spacing 6.15 mm (242 mils), body size (see https://www.omron.com/ecb/products/pdf/en-a6h.pdf) +SMD DIP Switch SPST Slide 6.15mm 242mil +0 +4 +4 +Buttons_Switches_SMD +SW_DIP_SPSTx02_Slide_Omron_A6S-210x_W8.9mm_P2.54mm +SMD 2x-dip-switch SPST Omron_A6S-210x, Slide, row spacing 8.9 mm (350 mils), body size (see http://omronfs.omron.com/en_US/ecb/products/pdf/en-a6s.pdf) +SMD DIP Switch SPST Slide 8.9mm 350mil +0 +4 +4 +Buttons_Switches_SMD +SW_DIP_SPSTx03_Slide_6.7x9.18mm_W6.73mm_P2.54mm_LowProfile_JPin +SMD 3x-dip-switch SPST , Slide, row spacing 6.73 mm (264 mils), body size 6.7x9.18mm (see e.g. https://www.ctscorp.com/wp-content/uploads/219.pdf), SMD, LowProfile, JPin +SMD DIP Switch SPST Slide 6.73mm 264mil SMD LowProfile JPin +0 +6 +6 +Buttons_Switches_SMD +SW_DIP_SPSTx03_Slide_6.7x9.18mm_W8.61mm_P2.54mm_LowProfile +SMD 3x-dip-switch SPST , Slide, row spacing 8.61 mm (338 mils), body size 6.7x9.18mm (see e.g. https://www.ctscorp.com/wp-content/uploads/219.pdf), SMD, LowProfile +SMD DIP Switch SPST Slide 8.61mm 338mil SMD LowProfile +0 +6 +6 +Buttons_Switches_SMD +SW_DIP_SPSTx03_Slide_9.78x9.8mm_W8.61mm_P2.54mm +SMD 3x-dip-switch SPST , Slide, row spacing 8.61 mm (338 mils), body size 9.78x9.8mm (see e.g. https://www.ctscorp.com/wp-content/uploads/204.pdf), SMD +SMD DIP Switch SPST Slide 8.61mm 338mil SMD +0 +6 +6 +Buttons_Switches_SMD +SW_DIP_SPSTx03_Slide_Copal_CVS-03xB_W5.9mm_P1mm +SMD 3x-dip-switch SPST Copal_CVS-03xB, Slide, row spacing 5.9 mm (232 mils), body size (see http://www.nidec-copal-electronics.com/e/catalog/switch/cvs.pdf) +SMD DIP Switch SPST Slide 5.9mm 232mil +0 +10 +7 +Buttons_Switches_SMD +SW_DIP_SPSTx03_Slide_KingTek_DSHP03TJ_W5.25mm_P1.27mm_JPin +SMD 3x-dip-switch SPST KingTek_DSHP03TJ, Slide, row spacing 5.25 mm (206 mils), body size (see http://www.kingtek.net.cn/pic/201601201446313350.pdf), JPin +SMD DIP Switch SPST Slide 5.25mm 206mil JPin +0 +6 +6 +Buttons_Switches_SMD +SW_DIP_SPSTx03_Slide_KingTek_DSHP03TS_W7.62mm_P1.27mm +SMD 3x-dip-switch SPST KingTek_DSHP03TS, Slide, row spacing 7.62 mm (300 mils), body size (see http://www.kingtek.net.cn/pic/201601201417455112.pdf) +SMD DIP Switch SPST Slide 7.62mm 300mil +0 +6 +6 +Buttons_Switches_SMD +SW_DIP_SPSTx03_Slide_Omron_A6S-310x_W8.9mm_P2.54mm +SMD 3x-dip-switch SPST Omron_A6S-310x, Slide, row spacing 8.9 mm (350 mils), body size (see http://omronfs.omron.com/en_US/ecb/products/pdf/en-a6s.pdf) +SMD DIP Switch SPST Slide 8.9mm 350mil +0 +6 +6 +Buttons_Switches_SMD +SW_DIP_SPSTx04_Slide_6.7x11.72mm_W6.73mm_P2.54mm_LowProfile_JPin +SMD 4x-dip-switch SPST , Slide, row spacing 6.73 mm (264 mils), body size 6.7x11.72mm (see e.g. https://www.ctscorp.com/wp-content/uploads/219.pdf), SMD, LowProfile, JPin +SMD DIP Switch SPST Slide 6.73mm 264mil SMD LowProfile JPin +0 +8 +8 +Buttons_Switches_SMD +SW_DIP_SPSTx04_Slide_6.7x11.72mm_W8.61mm_P2.54mm_LowProfile +SMD 4x-dip-switch SPST , Slide, row spacing 8.61 mm (338 mils), body size 6.7x11.72mm (see e.g. https://www.ctscorp.com/wp-content/uploads/219.pdf), SMD, LowProfile +SMD DIP Switch SPST Slide 8.61mm 338mil SMD LowProfile +0 +8 +8 +Buttons_Switches_SMD +SW_DIP_SPSTx04_Slide_9.78x12.34mm_W8.61mm_P2.54mm +SMD 4x-dip-switch SPST , Slide, row spacing 8.61 mm (338 mils), body size 9.78x12.34mm (see e.g. https://www.ctscorp.com/wp-content/uploads/204.pdf), SMD +SMD DIP Switch SPST Slide 8.61mm 338mil SMD +0 +8 +8 +Buttons_Switches_SMD +SW_DIP_SPSTx04_Slide_Copal_CHS-04A_W5.08mm_P1.27mm_JPin +SMD 4x-dip-switch SPST Copal_CHS-04A, Slide, row spacing 5.08 mm (200 mils), body size (see http://www.nidec-copal-electronics.com/e/catalog/switch/chs.pdf), SMD, JPin +SMD DIP Switch SPST Slide 5.08mm 200mil SMD JPin +0 +8 +8 +Buttons_Switches_SMD +SW_DIP_SPSTx04_Slide_Copal_CHS-04B_W7.62mm_P1.27mm +SMD 4x-dip-switch SPST Copal_CHS-04B, Slide, row spacing 7.62 mm (300 mils), body size (see http://www.nidec-copal-electronics.com/e/catalog/switch/chs.pdf), SMD +SMD DIP Switch SPST Slide 7.62mm 300mil SMD +0 +8 +8 +Buttons_Switches_SMD +SW_DIP_SPSTx04_Slide_Copal_CVS-04xB_W5.9mm_P1mm +SMD 4x-dip-switch SPST Copal_CVS-04xB, Slide, row spacing 5.9 mm (232 mils), body size (see http://www.nidec-copal-electronics.com/e/catalog/switch/cvs.pdf) +SMD DIP Switch SPST Slide 5.9mm 232mil +0 +12 +9 +Buttons_Switches_SMD +SW_DIP_SPSTx04_Slide_KingTek_DSHP04TJ_W5.25mm_P1.27mm_JPin +SMD 4x-dip-switch SPST KingTek_DSHP04TJ, Slide, row spacing 5.25 mm (206 mils), body size (see http://www.kingtek.net.cn/pic/201601201446313350.pdf), JPin +SMD DIP Switch SPST Slide 5.25mm 206mil JPin +0 +8 +8 +Buttons_Switches_SMD +SW_DIP_SPSTx04_Slide_KingTek_DSHP04TS_W7.62mm_P1.27mm +SMD 4x-dip-switch SPST KingTek_DSHP04TS, Slide, row spacing 7.62 mm (300 mils), body size (see http://www.kingtek.net.cn/pic/201601201417455112.pdf) +SMD DIP Switch SPST Slide 7.62mm 300mil +0 +8 +8 +Buttons_Switches_SMD +SW_DIP_SPSTx04_Slide_Omron_A6H-4101_W6.15mm_P1.27mm +SMD 4x-dip-switch SPST Omron_A6H-4101, Slide, row spacing 6.15 mm (242 mils), body size (see https://www.omron.com/ecb/products/pdf/en-a6h.pdf) +SMD DIP Switch SPST Slide 6.15mm 242mil +0 +8 +8 +Buttons_Switches_SMD +SW_DIP_SPSTx04_Slide_Omron_A6S-410x_W8.9mm_P2.54mm +SMD 4x-dip-switch SPST Omron_A6S-410x, Slide, row spacing 8.9 mm (350 mils), body size (see http://omronfs.omron.com/en_US/ecb/products/pdf/en-a6s.pdf) +SMD DIP Switch SPST Slide 8.9mm 350mil +0 +8 +8 +Buttons_Switches_SMD +SW_DIP_SPSTx05_Slide_6.7x14.26mm_W6.73mm_P2.54mm_LowProfile_JPin +SMD 5x-dip-switch SPST , Slide, row spacing 6.73 mm (264 mils), body size 6.7x14.26mm (see e.g. https://www.ctscorp.com/wp-content/uploads/219.pdf), SMD, LowProfile, JPin +SMD DIP Switch SPST Slide 6.73mm 264mil SMD LowProfile JPin +0 +10 +10 +Buttons_Switches_SMD +SW_DIP_SPSTx05_Slide_6.7x14.26mm_W8.61mm_P2.54mm_LowProfile +SMD 5x-dip-switch SPST , Slide, row spacing 8.61 mm (338 mils), body size 6.7x14.26mm (see e.g. https://www.ctscorp.com/wp-content/uploads/219.pdf), SMD, LowProfile +SMD DIP Switch SPST Slide 8.61mm 338mil SMD LowProfile +0 +10 +10 +Buttons_Switches_SMD +SW_DIP_SPSTx05_Slide_9.78x14.88mm_W8.61mm_P2.54mm +SMD 5x-dip-switch SPST , Slide, row spacing 8.61 mm (338 mils), body size 9.78x14.88mm (see e.g. https://www.ctscorp.com/wp-content/uploads/204.pdf), SMD +SMD DIP Switch SPST Slide 8.61mm 338mil SMD +0 +10 +10 +Buttons_Switches_SMD +SW_DIP_SPSTx05_Slide_KingTek_DSHP05TJ_W5.25mm_P1.27mm_JPin +SMD 5x-dip-switch SPST KingTek_DSHP05TJ, Slide, row spacing 5.25 mm (206 mils), body size (see http://www.kingtek.net.cn/pic/201601201446313350.pdf), JPin +SMD DIP Switch SPST Slide 5.25mm 206mil JPin +0 +10 +10 +Buttons_Switches_SMD +SW_DIP_SPSTx05_Slide_KingTek_DSHP05TS_W7.62mm_P1.27mm +SMD 5x-dip-switch SPST KingTek_DSHP05TS, Slide, row spacing 7.62 mm (300 mils), body size (see http://www.kingtek.net.cn/pic/201601201417455112.pdf) +SMD DIP Switch SPST Slide 7.62mm 300mil +0 +10 +10 +Buttons_Switches_SMD +SW_DIP_SPSTx05_Slide_Omron_A6S-510x_W8.9mm_P2.54mm +SMD 5x-dip-switch SPST Omron_A6S-510x, Slide, row spacing 8.9 mm (350 mils), body size (see http://omronfs.omron.com/en_US/ecb/products/pdf/en-a6s.pdf) +SMD DIP Switch SPST Slide 8.9mm 350mil +0 +10 +10 +Buttons_Switches_SMD +SW_DIP_SPSTx06_Slide_6.7x16.8mm_W6.73mm_P2.54mm_LowProfile_JPin +SMD 6x-dip-switch SPST , Slide, row spacing 6.73 mm (264 mils), body size 6.7x16.8mm (see e.g. https://www.ctscorp.com/wp-content/uploads/219.pdf), SMD, LowProfile, JPin +SMD DIP Switch SPST Slide 6.73mm 264mil SMD LowProfile JPin +0 +12 +12 +Buttons_Switches_SMD +SW_DIP_SPSTx06_Slide_6.7x16.8mm_W8.61mm_P2.54mm_LowProfile +SMD 6x-dip-switch SPST , Slide, row spacing 8.61 mm (338 mils), body size 6.7x16.8mm (see e.g. https://www.ctscorp.com/wp-content/uploads/219.pdf), SMD, LowProfile +SMD DIP Switch SPST Slide 8.61mm 338mil SMD LowProfile +0 +12 +12 +Buttons_Switches_SMD +SW_DIP_SPSTx06_Slide_9.78x17.42mm_W8.61mm_P2.54mm +SMD 6x-dip-switch SPST , Slide, row spacing 8.61 mm (338 mils), body size 9.78x17.42mm (see e.g. https://www.ctscorp.com/wp-content/uploads/204.pdf), SMD +SMD DIP Switch SPST Slide 8.61mm 338mil SMD +0 +12 +12 +Buttons_Switches_SMD +SW_DIP_SPSTx06_Slide_Copal_CHS-06A_W5.08mm_P1.27mm_JPin +SMD 6x-dip-switch SPST Copal_CHS-06A, Slide, row spacing 5.08 mm (200 mils), body size (see http://www.nidec-copal-electronics.com/e/catalog/switch/chs.pdf), SMD, JPin +SMD DIP Switch SPST Slide 5.08mm 200mil SMD JPin +0 +12 +12 +Buttons_Switches_SMD +SW_DIP_SPSTx06_Slide_Copal_CHS-06B_W7.62mm_P1.27mm +SMD 6x-dip-switch SPST Copal_CHS-06B, Slide, row spacing 7.62 mm (300 mils), body size (see http://www.nidec-copal-electronics.com/e/catalog/switch/chs.pdf), SMD +SMD DIP Switch SPST Slide 7.62mm 300mil SMD +0 +12 +12 +Buttons_Switches_SMD +SW_DIP_SPSTx06_Slide_KingTek_DSHP06TJ_W5.25mm_P1.27mm_JPin +SMD 6x-dip-switch SPST KingTek_DSHP06TJ, Slide, row spacing 5.25 mm (206 mils), body size (see http://www.kingtek.net.cn/pic/201601201446313350.pdf), JPin +SMD DIP Switch SPST Slide 5.25mm 206mil JPin +0 +12 +12 +Buttons_Switches_SMD +SW_DIP_SPSTx06_Slide_KingTek_DSHP06TS_W7.62mm_P1.27mm +SMD 6x-dip-switch SPST KingTek_DSHP06TS, Slide, row spacing 7.62 mm (300 mils), body size (see http://www.kingtek.net.cn/pic/201601201417455112.pdf) +SMD DIP Switch SPST Slide 7.62mm 300mil +0 +12 +12 +Buttons_Switches_SMD +SW_DIP_SPSTx06_Slide_Omron_A6H-6101_W6.15mm_P1.27mm +SMD 6x-dip-switch SPST Omron_A6H-6101, Slide, row spacing 6.15 mm (242 mils), body size (see https://www.omron.com/ecb/products/pdf/en-a6h.pdf) +SMD DIP Switch SPST Slide 6.15mm 242mil +0 +12 +12 +Buttons_Switches_SMD +SW_DIP_SPSTx06_Slide_Omron_A6S-610x_W8.9mm_P2.54mm +SMD 6x-dip-switch SPST Omron_A6S-610x, Slide, row spacing 8.9 mm (350 mils), body size (see http://omronfs.omron.com/en_US/ecb/products/pdf/en-a6s.pdf) +SMD DIP Switch SPST Slide 8.9mm 350mil +0 +12 +12 +Buttons_Switches_SMD +SW_DIP_SPSTx07_Slide_6.7x19.34mm_W6.73mm_P2.54mm_LowProfile_JPin +SMD 7x-dip-switch SPST , Slide, row spacing 6.73 mm (264 mils), body size 6.7x19.34mm (see e.g. https://www.ctscorp.com/wp-content/uploads/219.pdf), SMD, LowProfile, JPin +SMD DIP Switch SPST Slide 6.73mm 264mil SMD LowProfile JPin +0 +14 +14 +Buttons_Switches_SMD +SW_DIP_SPSTx07_Slide_6.7x19.34mm_W8.61mm_P2.54mm_LowProfile +SMD 7x-dip-switch SPST , Slide, row spacing 8.61 mm (338 mils), body size 6.7x19.34mm (see e.g. https://www.ctscorp.com/wp-content/uploads/219.pdf), SMD, LowProfile +SMD DIP Switch SPST Slide 8.61mm 338mil SMD LowProfile +0 +14 +14 +Buttons_Switches_SMD +SW_DIP_SPSTx07_Slide_9.78x19.96mm_W8.61mm_P2.54mm +SMD 7x-dip-switch SPST , Slide, row spacing 8.61 mm (338 mils), body size 9.78x19.96mm (see e.g. https://www.ctscorp.com/wp-content/uploads/204.pdf), SMD +SMD DIP Switch SPST Slide 8.61mm 338mil SMD +0 +14 +14 +Buttons_Switches_SMD +SW_DIP_SPSTx07_Slide_KingTek_DSHP07TJ_W5.25mm_P1.27mm_JPin +SMD 7x-dip-switch SPST KingTek_DSHP07TJ, Slide, row spacing 5.25 mm (206 mils), body size (see http://www.kingtek.net.cn/pic/201601201446313350.pdf), JPin +SMD DIP Switch SPST Slide 5.25mm 206mil JPin +0 +14 +14 +Buttons_Switches_SMD +SW_DIP_SPSTx07_Slide_KingTek_DSHP07TS_W7.62mm_P1.27mm +SMD 7x-dip-switch SPST KingTek_DSHP07TS, Slide, row spacing 7.62 mm (300 mils), body size (see http://www.kingtek.net.cn/pic/201601201417455112.pdf) +SMD DIP Switch SPST Slide 7.62mm 300mil +0 +14 +14 +Buttons_Switches_SMD +SW_DIP_SPSTx07_Slide_Omron_A6S-710x_W8.9mm_P2.54mm +SMD 7x-dip-switch SPST Omron_A6S-710x, Slide, row spacing 8.9 mm (350 mils), body size (see http://omronfs.omron.com/en_US/ecb/products/pdf/en-a6s.pdf) +SMD DIP Switch SPST Slide 8.9mm 350mil +0 +14 +14 +Buttons_Switches_SMD +SW_DIP_SPSTx08_Slide_6.7x21.88mm_W6.73mm_P2.54mm_LowProfile_JPin +SMD 8x-dip-switch SPST , Slide, row spacing 6.73 mm (264 mils), body size 6.7x21.88mm (see e.g. https://www.ctscorp.com/wp-content/uploads/219.pdf), SMD, LowProfile, JPin +SMD DIP Switch SPST Slide 6.73mm 264mil SMD LowProfile JPin +0 +16 +16 +Buttons_Switches_SMD +SW_DIP_SPSTx08_Slide_6.7x21.88mm_W8.61mm_P2.54mm_LowProfile +SMD 8x-dip-switch SPST , Slide, row spacing 8.61 mm (338 mils), body size 6.7x21.88mm (see e.g. https://www.ctscorp.com/wp-content/uploads/219.pdf), SMD, LowProfile +SMD DIP Switch SPST Slide 8.61mm 338mil SMD LowProfile +0 +16 +16 +Buttons_Switches_SMD +SW_DIP_SPSTx08_Slide_9.78x22.5mm_W8.61mm_P2.54mm +SMD 8x-dip-switch SPST , Slide, row spacing 8.61 mm (338 mils), body size 9.78x22.5mm (see e.g. https://www.ctscorp.com/wp-content/uploads/204.pdf), SMD +SMD DIP Switch SPST Slide 8.61mm 338mil SMD +0 +16 +16 +Buttons_Switches_SMD +SW_DIP_SPSTx08_Slide_Copal_CHS-08A_W5.08mm_P1.27mm_JPin +SMD 8x-dip-switch SPST Copal_CHS-08A, Slide, row spacing 5.08 mm (200 mils), body size (see http://www.nidec-copal-electronics.com/e/catalog/switch/chs.pdf), SMD, JPin +SMD DIP Switch SPST Slide 5.08mm 200mil SMD JPin +0 +16 +16 +Buttons_Switches_SMD +SW_DIP_SPSTx08_Slide_Copal_CHS-08B_W7.62mm_P1.27mm +SMD 8x-dip-switch SPST Copal_CHS-08B, Slide, row spacing 7.62 mm (300 mils), body size (see http://www.nidec-copal-electronics.com/e/catalog/switch/chs.pdf), SMD +SMD DIP Switch SPST Slide 7.62mm 300mil SMD +0 +16 +16 +Buttons_Switches_SMD +SW_DIP_SPSTx08_Slide_Copal_CVS-08xB_W5.9mm_P1mm +SMD 8x-dip-switch SPST Copal_CVS-08xB, Slide, row spacing 5.9 mm (232 mils), body size (see http://www.nidec-copal-electronics.com/e/catalog/switch/cvs.pdf) +SMD DIP Switch SPST Slide 5.9mm 232mil +0 +20 +17 +Buttons_Switches_SMD +SW_DIP_SPSTx08_Slide_KingTek_DSHP08TJ_W5.25mm_P1.27mm_JPin +SMD 8x-dip-switch SPST KingTek_DSHP08TJ, Slide, row spacing 5.25 mm (206 mils), body size (see http://www.kingtek.net.cn/pic/201601201446313350.pdf), JPin +SMD DIP Switch SPST Slide 5.25mm 206mil JPin +0 +16 +16 +Buttons_Switches_SMD +SW_DIP_SPSTx08_Slide_KingTek_DSHP08TS_W7.62mm_P1.27mm +SMD 8x-dip-switch SPST KingTek_DSHP08TS, Slide, row spacing 7.62 mm (300 mils), body size (see http://www.kingtek.net.cn/pic/201601201417455112.pdf) +SMD DIP Switch SPST Slide 7.62mm 300mil +0 +16 +16 +Buttons_Switches_SMD +SW_DIP_SPSTx08_Slide_Omron_A6H-8101_W6.15mm_P1.27mm +SMD 8x-dip-switch SPST Omron_A6H-8101, Slide, row spacing 6.15 mm (242 mils), body size (see https://www.omron.com/ecb/products/pdf/en-a6h.pdf) +SMD DIP Switch SPST Slide 6.15mm 242mil +0 +16 +16 +Buttons_Switches_SMD +SW_DIP_SPSTx08_Slide_Omron_A6S-810x_W8.9mm_P2.54mm +SMD 8x-dip-switch SPST Omron_A6S-810x, Slide, row spacing 8.9 mm (350 mils), body size (see http://omronfs.omron.com/en_US/ecb/products/pdf/en-a6s.pdf) +SMD DIP Switch SPST Slide 8.9mm 350mil +0 +16 +16 +Buttons_Switches_SMD +SW_DIP_SPSTx09_Slide_6.7x24.42mm_W6.73mm_P2.54mm_LowProfile_JPin +SMD 9x-dip-switch SPST , Slide, row spacing 6.73 mm (264 mils), body size 6.7x24.42mm (see e.g. https://www.ctscorp.com/wp-content/uploads/219.pdf), SMD, LowProfile, JPin +SMD DIP Switch SPST Slide 6.73mm 264mil SMD LowProfile JPin +0 +18 +18 +Buttons_Switches_SMD +SW_DIP_SPSTx09_Slide_6.7x24.42mm_W8.61mm_P2.54mm_LowProfile +SMD 9x-dip-switch SPST , Slide, row spacing 8.61 mm (338 mils), body size 6.7x24.42mm (see e.g. https://www.ctscorp.com/wp-content/uploads/219.pdf), SMD, LowProfile +SMD DIP Switch SPST Slide 8.61mm 338mil SMD LowProfile +0 +18 +18 +Buttons_Switches_SMD +SW_DIP_SPSTx09_Slide_9.78x25.04mm_W8.61mm_P2.54mm +SMD 9x-dip-switch SPST , Slide, row spacing 8.61 mm (338 mils), body size 9.78x25.04mm (see e.g. https://www.ctscorp.com/wp-content/uploads/204.pdf), SMD +SMD DIP Switch SPST Slide 8.61mm 338mil SMD +0 +18 +18 +Buttons_Switches_SMD +SW_DIP_SPSTx09_Slide_KingTek_DSHP09TJ_W5.25mm_P1.27mm_JPin +SMD 9x-dip-switch SPST KingTek_DSHP09TJ, Slide, row spacing 5.25 mm (206 mils), body size (see http://www.kingtek.net.cn/pic/201601201446313350.pdf), JPin +SMD DIP Switch SPST Slide 5.25mm 206mil JPin +0 +18 +18 +Buttons_Switches_SMD +SW_DIP_SPSTx09_Slide_KingTek_DSHP09TS_W7.62mm_P1.27mm +SMD 9x-dip-switch SPST KingTek_DSHP09TS, Slide, row spacing 7.62 mm (300 mils), body size (see http://www.kingtek.net.cn/pic/201601201417455112.pdf) +SMD DIP Switch SPST Slide 7.62mm 300mil +0 +18 +18 +Buttons_Switches_SMD +SW_DIP_SPSTx09_Slide_Omron_A6S-910x_W8.9mm_P2.54mm +SMD 9x-dip-switch SPST Omron_A6S-910x, Slide, row spacing 8.9 mm (350 mils), body size (see http://omronfs.omron.com/en_US/ecb/products/pdf/en-a6s.pdf) +SMD DIP Switch SPST Slide 8.9mm 350mil +0 +18 +18 +Buttons_Switches_SMD +SW_DIP_SPSTx10_Slide_6.7x26.96mm_W6.73mm_P2.54mm_LowProfile_JPin +SMD 10x-dip-switch SPST , Slide, row spacing 6.73 mm (264 mils), body size 6.7x26.96mm (see e.g. https://www.ctscorp.com/wp-content/uploads/219.pdf), SMD, LowProfile, JPin +SMD DIP Switch SPST Slide 6.73mm 264mil SMD LowProfile JPin +0 +20 +20 +Buttons_Switches_SMD +SW_DIP_SPSTx10_Slide_6.7x26.96mm_W8.61mm_P2.54mm_LowProfile +SMD 10x-dip-switch SPST , Slide, row spacing 8.61 mm (338 mils), body size 6.7x26.96mm (see e.g. https://www.ctscorp.com/wp-content/uploads/219.pdf), SMD, LowProfile +SMD DIP Switch SPST Slide 8.61mm 338mil SMD LowProfile +0 +20 +20 +Buttons_Switches_SMD +SW_DIP_SPSTx10_Slide_9.78x27.58mm_W8.61mm_P2.54mm +SMD 10x-dip-switch SPST , Slide, row spacing 8.61 mm (338 mils), body size 9.78x27.58mm (see e.g. https://www.ctscorp.com/wp-content/uploads/204.pdf), SMD +SMD DIP Switch SPST Slide 8.61mm 338mil SMD +0 +20 +20 +Buttons_Switches_SMD +SW_DIP_SPSTx10_Slide_Copal_CHS-10A_W5.08mm_P1.27mm_JPin +SMD 10x-dip-switch SPST Copal_CHS-10A, Slide, row spacing 5.08 mm (200 mils), body size (see http://www.nidec-copal-electronics.com/e/catalog/switch/chs.pdf), SMD, JPin +SMD DIP Switch SPST Slide 5.08mm 200mil SMD JPin +0 +20 +20 +Buttons_Switches_SMD +SW_DIP_SPSTx10_Slide_Copal_CHS-10B_W7.62mm_P1.27mm +SMD 10x-dip-switch SPST Copal_CHS-10B, Slide, row spacing 7.62 mm (300 mils), body size (see http://www.nidec-copal-electronics.com/e/catalog/switch/chs.pdf), SMD +SMD DIP Switch SPST Slide 7.62mm 300mil SMD +0 +20 +20 +Buttons_Switches_SMD +SW_DIP_SPSTx10_Slide_KingTek_DSHP10TJ_W5.25mm_P1.27mm_JPin +SMD 10x-dip-switch SPST KingTek_DSHP10TJ, Slide, row spacing 5.25 mm (206 mils), body size (see http://www.kingtek.net.cn/pic/201601201446313350.pdf), JPin +SMD DIP Switch SPST Slide 5.25mm 206mil JPin +0 +20 +20 +Buttons_Switches_SMD +SW_DIP_SPSTx10_Slide_KingTek_DSHP10TS_W7.62mm_P1.27mm +SMD 10x-dip-switch SPST KingTek_DSHP10TS, Slide, row spacing 7.62 mm (300 mils), body size (see http://www.kingtek.net.cn/pic/201601201417455112.pdf) +SMD DIP Switch SPST Slide 7.62mm 300mil +0 +20 +20 +Buttons_Switches_SMD +SW_DIP_SPSTx10_Slide_Omron_A6H-10101_W6.15mm_P1.27mm +SMD 10x-dip-switch SPST Omron_A6H-10101, Slide, row spacing 6.15 mm (242 mils), body size (see https://www.omron.com/ecb/products/pdf/en-a6h.pdf) +SMD DIP Switch SPST Slide 6.15mm 242mil +0 +20 +20 +Buttons_Switches_SMD +SW_DIP_SPSTx10_Slide_Omron_A6S-1010x_W8.9mm_P2.54mm +SMD 10x-dip-switch SPST Omron_A6S-1010x, Slide, row spacing 8.9 mm (350 mils), body size (see http://omronfs.omron.com/en_US/ecb/products/pdf/en-a6s.pdf) +SMD DIP Switch SPST Slide 8.9mm 350mil +0 +20 +20 +Buttons_Switches_SMD +SW_DIP_SPSTx11_Slide_6.7x29.5mm_W6.73mm_P2.54mm_LowProfile_JPin +SMD 11x-dip-switch SPST , Slide, row spacing 6.73 mm (264 mils), body size 6.7x29.5mm (see e.g. https://www.ctscorp.com/wp-content/uploads/219.pdf), SMD, LowProfile, JPin +SMD DIP Switch SPST Slide 6.73mm 264mil SMD LowProfile JPin +0 +22 +22 +Buttons_Switches_SMD +SW_DIP_SPSTx11_Slide_6.7x29.5mm_W8.61mm_P2.54mm_LowProfile +SMD 11x-dip-switch SPST , Slide, row spacing 8.61 mm (338 mils), body size 6.7x29.5mm (see e.g. https://www.ctscorp.com/wp-content/uploads/219.pdf), SMD, LowProfile +SMD DIP Switch SPST Slide 8.61mm 338mil SMD LowProfile +0 +22 +22 +Buttons_Switches_SMD +SW_DIP_SPSTx11_Slide_9.78x30.12mm_W8.61mm_P2.54mm +SMD 11x-dip-switch SPST , Slide, row spacing 8.61 mm (338 mils), body size 9.78x30.12mm (see e.g. https://www.ctscorp.com/wp-content/uploads/204.pdf), SMD +SMD DIP Switch SPST Slide 8.61mm 338mil SMD +0 +22 +22 +Buttons_Switches_SMD +SW_DIP_SPSTx12_Slide_6.7x32.04mm_W6.73mm_P2.54mm_LowProfile_JPin +SMD 12x-dip-switch SPST , Slide, row spacing 6.73 mm (264 mils), body size 6.7x32.04mm (see e.g. https://www.ctscorp.com/wp-content/uploads/219.pdf), SMD, LowProfile, JPin +SMD DIP Switch SPST Slide 6.73mm 264mil SMD LowProfile JPin +0 +24 +24 +Buttons_Switches_SMD +SW_DIP_SPSTx12_Slide_6.7x32.04mm_W8.61mm_P2.54mm_LowProfile +SMD 12x-dip-switch SPST , Slide, row spacing 8.61 mm (338 mils), body size 6.7x32.04mm (see e.g. https://www.ctscorp.com/wp-content/uploads/219.pdf), SMD, LowProfile +SMD DIP Switch SPST Slide 8.61mm 338mil SMD LowProfile +0 +24 +24 +Buttons_Switches_SMD +SW_DIP_SPSTx12_Slide_9.78x32.66mm_W8.61mm_P2.54mm +SMD 12x-dip-switch SPST , Slide, row spacing 8.61 mm (338 mils), body size 9.78x32.66mm (see e.g. https://www.ctscorp.com/wp-content/uploads/204.pdf), SMD +SMD DIP Switch SPST Slide 8.61mm 338mil SMD +0 +24 +24 +Buttons_Switches_SMD +SW_MEC_5GSH9 +MEC 5G single pole normally-open tactile switch +switch normally-open pushbutton push-button +0 +4 +4 +Buttons_Switches_SMD +SW_Push_1P1T_NO_CK_KMR2 +CK components KMR2 tactile switch http://www.ckswitches.com/media/1479/kmr2.pdf +tactile switch kmr2 +0 +4 +2 +Buttons_Switches_SMD +SW_Push_1P1T_NO_CK_KSC6xxJ +CK components KSC6 tactile switch https://www.ckswitches.com/media/1972/ksc6.pdf +tactile switch ksc6 +0 +4 +2 +Buttons_Switches_SMD +SW_Push_1P1T_NO_CK_KSC7xxJ +CK components KSC7 tactile switch https://www.ckswitches.com/media/1973/ksc7.pdf +tactile switch ksc7 +0 +4 +2 +Buttons_Switches_SMD +SW_Push_SPST_NO_Alps_SKRK +http://www.alps.com/prod/info/E/HTML/Tact/SurfaceMount/SKRK/SKRKAHE020.html +SMD SMT button +0 +2 +2 +Buttons_Switches_SMD +SW_SP3T_PCM13 +Ultraminiature Surface Mount Slide Switch + +0 +8 +4 +Buttons_Switches_SMD +SW_SPDT_CK-JS102011SAQN +http://www.ckswitches.com/media/1422/js.pdf +switch spdt +0 +3 +3 +Buttons_Switches_SMD +SW_SPDT_PCM12 +Ultraminiature Surface Mount Slide Switch + +0 +7 +3 +Buttons_Switches_SMD +SW_SPST_B3S-1000 +Surface Mount Tactile Switch for High-Density Packaging +Tactile Switch +0 +4 +2 +Buttons_Switches_SMD +SW_SPST_B3S-1100 +Surface Mount Tactile Switch for High-Density Packaging with Ground Terminal +Tactile Switch +0 +5 +3 +Buttons_Switches_SMD +SW_SPST_B3SL-1002P +Middle Stroke Tactile Switch, B3SL +Middle Stroke Tactile Switch +0 +4 +2 +Buttons_Switches_SMD +SW_SPST_B3SL-1022P +Middle Stroke Tactile Switch, B3SL +Middle Stroke Tactile Switch +0 +4 +2 +Buttons_Switches_SMD +SW_SPST_B3U-1000P +Ultra-small-sized Tactile Switch with High Contact Reliability, Top-actuated Model, without Ground Terminal, without Boss +Tactile Switch +0 +2 +2 +Buttons_Switches_SMD +SW_SPST_B3U-1000P-B +Ultra-small-sized Tactile Switch with High Contact Reliability, Top-actuated Model, without Ground Terminal, with Boss +Tactile Switch +0 +2 +2 +Buttons_Switches_SMD +SW_SPST_B3U-1100P +Ultra-small-sized Tactile Switch with High Contact Reliability, Top-actuated Model, with Ground Terminal, without Boss +Tactile Switch +0 +3 +3 +Buttons_Switches_SMD +SW_SPST_B3U-1100P-B +Ultra-small-sized Tactile Switch with High Contact Reliability, Top-actuated Model, with Ground Terminal, with Boss +Tactile Switch +0 +3 +3 +Buttons_Switches_SMD +SW_SPST_B3U-3000P +Ultra-small-sized Tactile Switch with High Contact Reliability, Side-actuated Model, without Ground Terminal, without Boss +Tactile Switch +0 +2 +2 +Buttons_Switches_SMD +SW_SPST_B3U-3000P-B +Ultra-small-sized Tactile Switch with High Contact Reliability, Side-actuated Model, without Ground Terminal, with Boss +Tactile Switch +0 +2 +2 +Buttons_Switches_SMD +SW_SPST_B3U-3100P +Ultra-small-sized Tactile Switch with High Contact Reliability, Side-actuated Model, with Ground Terminal, without Boss +Tactile Switch +0 +3 +3 +Buttons_Switches_SMD +SW_SPST_B3U-3100P-B +Ultra-small-sized Tactile Switch with High Contact Reliability, Side-actuated Model, with Ground Terminal, with Boss +Tactile Switch +0 +3 +3 +Buttons_Switches_SMD +SW_SPST_CK_KXT3 +https://www.ckswitches.com/media/1465/kxt3.pdf +Switch SPST KXT3 +0 +2 +2 +Buttons_Switches_SMD +SW_SPST_CK_RS282G05A3 +https://www.mouser.com/ds/2/60/RS-282G05A-SM_RT-1159762.pdf +SPST button tactile switch +0 +2 +2 +Buttons_Switches_SMD +SW_SPST_EVPBF +Light Touch Switch + +0 +4 +2 +Buttons_Switches_SMD +SW_SPST_EVQP0 +Light Touch Switch, https://industrial.panasonic.com/cdbs/www-data/pdf/ATK0000/ATK0000CE28.pdf + +0 +4 +2 +Buttons_Switches_SMD +SW_SPST_EVQP2 +Light Touch Switch + +0 +4 +2 +Buttons_Switches_SMD +SW_SPST_EVQP7A +Light Touch Switch,https://industrial.panasonic.com/cdbs/www-data/pdf/ATK0000/ATK0000CE20.pdf + +0 +4 +2 +Buttons_Switches_SMD +SW_SPST_EVQP7C +Light Touch Switch + +0 +4 +2 +Buttons_Switches_SMD +SW_SPST_EVQPE1 +Light Touch Switch, https://industrial.panasonic.com/cdbs/www-data/pdf/ATK0000/ATK0000CE7.pdf + +0 +2 +2 +Buttons_Switches_SMD +SW_SPST_EVQQ2 +Light Touch Switch, https://industrial.panasonic.com/cdbs/www-data/pdf/ATK0000/ATK0000CE28.pdf + +0 +4 +2 +Buttons_Switches_SMD +SW_SPST_FSMSM +http://www.te.com/commerce/DocumentDelivery/DDEController?Action=srchrtrv&DocNm=1437566-3&DocType=Customer+Drawing&DocLang=English +SPST button tactile switch +0 +2 +2 +Buttons_Switches_SMD +SW_SPST_Panasonic_EVQPL_3PL_5PL_PT_A08 +Light Touch Switch, http://industrial.panasonic.com/cdbs/www-data/pdf/ATK0000/ATK0000CE3.pdf +SMD SMT SPST EVQPL EVQPT +0 +6 +3 +Buttons_Switches_SMD +SW_SPST_Panasonic_EVQPL_3PL_5PL_PT_A15 +Light Touch Switch, http://industrial.panasonic.com/cdbs/www-data/pdf/ATK0000/ATK0000CE3.pdf +SMD SMT SPST EVQPL EVQPT +0 +6 +3 +Buttons_Switches_SMD +SW_SPST_PTS645 +C&K Components SPST SMD PTS645 Series 6mm Tact Switch +SPST Button Switch +0 +4 +2 +Buttons_Switches_SMD +SW_SPST_PTS810 +C&K Components, PTS 810 Series, Microminiature SMT Top Actuated, http://www.ckswitches.com/media/1476/pts810.pdf +SPST Button Switch +0 +4 +2 +Buttons_Switches_SMD +SW_SPST_REED_CT05-XXXX-G1 +Coto Technologies SPST Reed Switch CT05-XXXX-G1 +Coto Reed SPST Switch +0 +2 +2 +Buttons_Switches_SMD +SW_SPST_REED_CT05-XXXX-J1 +Coto Technologies SPST Reed Switch CT05-XXXX-J1 +Coto Reed SPST Switch +0 +2 +2 +Buttons_Switches_SMD +SW_SPST_REED_CT10-XXXX-G1 +Coto Technologies SPST Reed Switch CT10-XXXX-G1 +Coto Reed SPST Switch +0 +2 +2 +Buttons_Switches_SMD +SW_SPST_REED_CT10-XXXX-G2 +Coto Technologies SPST Reed Switch CT10-XXXX-G2 +Coto Reed SPST Switch +0 +2 +2 +Buttons_Switches_SMD +SW_SPST_REED_CT10-XXXX-G4 +Coto Technologies SPST Reed Switch CT10-XXXX-G4 +Coto Reed SPST Switch +0 +2 +2 +Buttons_Switches_SMD +SW_SPST_SKQG_WithoutStem +ALPS 5.2mm Square Low-profile Type (Surface Mount) SKQG Series, Without stem, http://www.alps.com/prod/info/E/HTML/Tact/SurfaceMount/SKQG/SKQGAEE010.html +SPST Button Switch +0 +4 +2 +Buttons_Switches_SMD +SW_SPST_SKQG_WithStem +ALPS 5.2mm Square Low-profile Type (Surface Mount) SKQG Series, With stem, http://www.alps.com/prod/info/E/HTML/Tact/SurfaceMount/SKQG/SKQGAFE010.html +SPST Button Switch +0 +4 +2 +Buttons_Switches_SMD +SW_SPST_TL3305A +https://www.e-switch.com/system/asset/product_line/data_sheet/213/TL3305.pdf +TL3305 Series Tact Switch +0 +4 +2 +Buttons_Switches_SMD +SW_SPST_TL3305B +https://www.e-switch.com/system/asset/product_line/data_sheet/213/TL3305.pdf +TL3305 Series Tact Switch +0 +4 +2 +Buttons_Switches_SMD +SW_SPST_TL3305C +https://www.e-switch.com/system/asset/product_line/data_sheet/213/TL3305.pdf +TL3305 Series Tact Switch +0 +4 +2 +Buttons_Switches_SMD +SW_SPST_TL3342 +Low-profile SMD Tactile Switch, https://www.e-switch.com/system/asset/product_line/data_sheet/165/TL3342.pdf +SPST Tactile Switch +0 +4 +2 +Button_Switch_THT +KSA_Tactile_SPST +KSA http://www.ckswitches.com/media/1457/ksa_ksl.pdf +SWITCH SMD KSA SW +0 +5 +5 +Button_Switch_THT +Nidec_Copal_SH-7010C +4-bit rotary coded switch, through-hole, https://www.nidec-copal-electronics.com/e/catalog/switch/sh-7000.pdf +rotary switch bcd +0 +6 +5 +Button_Switch_THT +Push_E-Switch_KS01Q01 +E-Switch KS01Q01 http://spec_sheets.e-switch.com/specs/29-KS01Q01.pdf +Push Button +0 +4 +4 +Button_Switch_THT +SW_CuK_JS202011AQN_DPDT_Angled +CuK sub miniature slide switch, JS series, DPDT, right angle, http://www.ckswitches.com/media/1422/js.pdf +switch DPDT +0 +6 +6 +Button_Switch_THT +SW_CuK_JS202011CQN_DPDT_Straight +CuK sub miniature slide switch, JS series, DPDT, right angle, http://www.ckswitches.com/media/1422/js.pdf +switch DPDT +0 +6 +6 +Button_Switch_THT +SW_CuK_OS102011MA1QN1_SPDT_Angled +CuK miniature slide switch, OS series, SPDT, right angle, http://www.ckswitches.com/media/1428/os.pdf +switch SPDT +0 +5 +3 +Button_Switch_THT +SW_CW_GPTS203211B +SPST Off-On Pushbutton, 1A, 30V, CW Industries P/N GPTS203211B, http://switches-connectors-custom.cwind.com/Asset/GPTS203211BR2.pdf +SPST button switch Off-On +0 +2 +2 +Button_Switch_THT +SW_DIP_SPSTx01_Piano_10.8x4.1mm_W7.62mm_P2.54mm +1x-dip-switch SPST , Piano, row spacing 7.62 mm (300 mils), body size 10.8x4.1mm +DIP Switch SPST Piano 7.62mm 300mil +0 +2 +2 +Button_Switch_THT +SW_DIP_SPSTx01_Slide_6.7x4.1mm_W7.62mm_P2.54mm_LowProfile +1x-dip-switch SPST , Slide, row spacing 7.62 mm (300 mils), body size 6.7x4.1mm (see e.g. https://www.ctscorp.com/wp-content/uploads/209-210.pdf), LowProfile +DIP Switch SPST Slide 7.62mm 300mil LowProfile +0 +2 +2 +Button_Switch_THT +SW_DIP_SPSTx01_Slide_9.78x4.72mm_W7.62mm_P2.54mm +1x-dip-switch SPST , Slide, row spacing 7.62 mm (300 mils), body size 9.78x4.72mm (see e.g. https://www.ctscorp.com/wp-content/uploads/206-208.pdf) +DIP Switch SPST Slide 7.62mm 300mil +0 +2 +2 +Button_Switch_THT +SW_DIP_SPSTx02_Piano_10.8x6.64mm_W7.62mm_P2.54mm +2x-dip-switch SPST , Piano, row spacing 7.62 mm (300 mils), body size 10.8x6.64mm +DIP Switch SPST Piano 7.62mm 300mil +0 +4 +4 +Button_Switch_THT +SW_DIP_SPSTx02_Piano_CTS_Series194-2MSTN_W7.62mm_P2.54mm +2x-dip-switch SPST CTS_Series194-2MSTN, Piano, row spacing 7.62 mm (300 mils), body size (see https://www.ctscorp.com/wp-content/uploads/194-195.pdf) +DIP Switch SPST Piano 7.62mm 300mil +0 +4 +4 +Button_Switch_THT +SW_DIP_SPSTx02_Slide_6.7x6.64mm_W7.62mm_P2.54mm_LowProfile +2x-dip-switch SPST , Slide, row spacing 7.62 mm (300 mils), body size 6.7x6.64mm (see e.g. https://www.ctscorp.com/wp-content/uploads/209-210.pdf), LowProfile +DIP Switch SPST Slide 7.62mm 300mil LowProfile +0 +4 +4 +Button_Switch_THT +SW_DIP_SPSTx02_Slide_9.78x7.26mm_W7.62mm_P2.54mm +2x-dip-switch SPST , Slide, row spacing 7.62 mm (300 mils), body size 9.78x7.26mm (see e.g. https://www.ctscorp.com/wp-content/uploads/206-208.pdf) +DIP Switch SPST Slide 7.62mm 300mil +0 +4 +4 +Button_Switch_THT +SW_DIP_SPSTx03_Piano_10.8x9.18mm_W7.62mm_P2.54mm +3x-dip-switch SPST , Piano, row spacing 7.62 mm (300 mils), body size 10.8x9.18mm +DIP Switch SPST Piano 7.62mm 300mil +0 +6 +6 +Button_Switch_THT +SW_DIP_SPSTx03_Piano_CTS_Series194-3MSTN_W7.62mm_P2.54mm +3x-dip-switch SPST CTS_Series194-3MSTN, Piano, row spacing 7.62 mm (300 mils), body size (see https://www.ctscorp.com/wp-content/uploads/194-195.pdf) +DIP Switch SPST Piano 7.62mm 300mil +0 +6 +6 +Button_Switch_THT +SW_DIP_SPSTx03_Slide_6.7x9.18mm_W7.62mm_P2.54mm_LowProfile +3x-dip-switch SPST , Slide, row spacing 7.62 mm (300 mils), body size 6.7x9.18mm (see e.g. https://www.ctscorp.com/wp-content/uploads/209-210.pdf), LowProfile +DIP Switch SPST Slide 7.62mm 300mil LowProfile +0 +6 +6 +Button_Switch_THT +SW_DIP_SPSTx03_Slide_9.78x9.8mm_W7.62mm_P2.54mm +3x-dip-switch SPST , Slide, row spacing 7.62 mm (300 mils), body size 9.78x9.8mm (see e.g. https://www.ctscorp.com/wp-content/uploads/206-208.pdf) +DIP Switch SPST Slide 7.62mm 300mil +0 +6 +6 +Button_Switch_THT +SW_DIP_SPSTx04_Piano_10.8x11.72mm_W7.62mm_P2.54mm +4x-dip-switch SPST , Piano, row spacing 7.62 mm (300 mils), body size 10.8x11.72mm +DIP Switch SPST Piano 7.62mm 300mil +0 +8 +8 +Button_Switch_THT +SW_DIP_SPSTx04_Piano_CTS_Series194-4MSTN_W7.62mm_P2.54mm +4x-dip-switch SPST CTS_Series194-4MSTN, Piano, row spacing 7.62 mm (300 mils), body size (see https://www.ctscorp.com/wp-content/uploads/194-195.pdf) +DIP Switch SPST Piano 7.62mm 300mil +0 +8 +8 +Button_Switch_THT +SW_DIP_SPSTx04_Slide_6.7x11.72mm_W7.62mm_P2.54mm_LowProfile +4x-dip-switch SPST , Slide, row spacing 7.62 mm (300 mils), body size 6.7x11.72mm (see e.g. https://www.ctscorp.com/wp-content/uploads/209-210.pdf), LowProfile +DIP Switch SPST Slide 7.62mm 300mil LowProfile +0 +8 +8 +Button_Switch_THT +SW_DIP_SPSTx04_Slide_9.78x12.34mm_W7.62mm_P2.54mm +4x-dip-switch SPST , Slide, row spacing 7.62 mm (300 mils), body size 9.78x12.34mm (see e.g. https://www.ctscorp.com/wp-content/uploads/206-208.pdf) +DIP Switch SPST Slide 7.62mm 300mil +0 +8 +8 +Button_Switch_THT +SW_DIP_SPSTx05_Piano_10.8x14.26mm_W7.62mm_P2.54mm +5x-dip-switch SPST , Piano, row spacing 7.62 mm (300 mils), body size 10.8x14.26mm +DIP Switch SPST Piano 7.62mm 300mil +0 +10 +10 +Button_Switch_THT +SW_DIP_SPSTx05_Piano_CTS_Series194-5MSTN_W7.62mm_P2.54mm +5x-dip-switch SPST CTS_Series194-5MSTN, Piano, row spacing 7.62 mm (300 mils), body size (see https://www.ctscorp.com/wp-content/uploads/194-195.pdf) +DIP Switch SPST Piano 7.62mm 300mil +0 +10 +10 +Button_Switch_THT +SW_DIP_SPSTx05_Slide_6.7x14.26mm_W7.62mm_P2.54mm_LowProfile +5x-dip-switch SPST , Slide, row spacing 7.62 mm (300 mils), body size 6.7x14.26mm (see e.g. https://www.ctscorp.com/wp-content/uploads/209-210.pdf), LowProfile +DIP Switch SPST Slide 7.62mm 300mil LowProfile +0 +10 +10 +Button_Switch_THT +SW_DIP_SPSTx05_Slide_9.78x14.88mm_W7.62mm_P2.54mm +5x-dip-switch SPST , Slide, row spacing 7.62 mm (300 mils), body size 9.78x14.88mm (see e.g. https://www.ctscorp.com/wp-content/uploads/206-208.pdf) +DIP Switch SPST Slide 7.62mm 300mil +0 +10 +10 +Button_Switch_THT +SW_DIP_SPSTx06_Piano_10.8x16.8mm_W7.62mm_P2.54mm +6x-dip-switch SPST , Piano, row spacing 7.62 mm (300 mils), body size 10.8x16.8mm +DIP Switch SPST Piano 7.62mm 300mil +0 +12 +12 +Button_Switch_THT +SW_DIP_SPSTx06_Piano_CTS_Series194-6MSTN_W7.62mm_P2.54mm +6x-dip-switch SPST CTS_Series194-6MSTN, Piano, row spacing 7.62 mm (300 mils), body size (see https://www.ctscorp.com/wp-content/uploads/194-195.pdf) +DIP Switch SPST Piano 7.62mm 300mil +0 +12 +12 +Button_Switch_THT +SW_DIP_SPSTx06_Slide_6.7x16.8mm_W7.62mm_P2.54mm_LowProfile +6x-dip-switch SPST , Slide, row spacing 7.62 mm (300 mils), body size 6.7x16.8mm (see e.g. https://www.ctscorp.com/wp-content/uploads/209-210.pdf), LowProfile +DIP Switch SPST Slide 7.62mm 300mil LowProfile +0 +12 +12 +Button_Switch_THT +SW_DIP_SPSTx06_Slide_9.78x17.42mm_W7.62mm_P2.54mm +6x-dip-switch SPST , Slide, row spacing 7.62 mm (300 mils), body size 9.78x17.42mm (see e.g. https://www.ctscorp.com/wp-content/uploads/206-208.pdf) +DIP Switch SPST Slide 7.62mm 300mil +0 +12 +12 +Button_Switch_THT +SW_DIP_SPSTx07_Piano_10.8x19.34mm_W7.62mm_P2.54mm +7x-dip-switch SPST , Piano, row spacing 7.62 mm (300 mils), body size 10.8x19.34mm +DIP Switch SPST Piano 7.62mm 300mil +0 +14 +14 +Button_Switch_THT +SW_DIP_SPSTx07_Piano_CTS_Series194-7MSTN_W7.62mm_P2.54mm +7x-dip-switch SPST CTS_Series194-7MSTN, Piano, row spacing 7.62 mm (300 mils), body size (see https://www.ctscorp.com/wp-content/uploads/194-195.pdf) +DIP Switch SPST Piano 7.62mm 300mil +0 +14 +14 +Button_Switch_THT +SW_DIP_SPSTx07_Slide_6.7x19.34mm_W7.62mm_P2.54mm_LowProfile +7x-dip-switch SPST , Slide, row spacing 7.62 mm (300 mils), body size 6.7x19.34mm (see e.g. https://www.ctscorp.com/wp-content/uploads/209-210.pdf), LowProfile +DIP Switch SPST Slide 7.62mm 300mil LowProfile +0 +14 +14 +Button_Switch_THT +SW_DIP_SPSTx07_Slide_9.78x19.96mm_W7.62mm_P2.54mm +7x-dip-switch SPST , Slide, row spacing 7.62 mm (300 mils), body size 9.78x19.96mm (see e.g. https://www.ctscorp.com/wp-content/uploads/206-208.pdf) +DIP Switch SPST Slide 7.62mm 300mil +0 +14 +14 +Button_Switch_THT +SW_DIP_SPSTx08_Piano_10.8x21.88mm_W7.62mm_P2.54mm +8x-dip-switch SPST , Piano, row spacing 7.62 mm (300 mils), body size 10.8x21.88mm +DIP Switch SPST Piano 7.62mm 300mil +0 +16 +16 +Button_Switch_THT +SW_DIP_SPSTx08_Piano_CTS_Series194-8MSTN_W7.62mm_P2.54mm +8x-dip-switch SPST CTS_Series194-8MSTN, Piano, row spacing 7.62 mm (300 mils), body size (see https://www.ctscorp.com/wp-content/uploads/194-195.pdf) +DIP Switch SPST Piano 7.62mm 300mil +0 +16 +16 +Button_Switch_THT +SW_DIP_SPSTx08_Slide_6.7x21.88mm_W7.62mm_P2.54mm_LowProfile +8x-dip-switch SPST , Slide, row spacing 7.62 mm (300 mils), body size 6.7x21.88mm (see e.g. https://www.ctscorp.com/wp-content/uploads/209-210.pdf), LowProfile +DIP Switch SPST Slide 7.62mm 300mil LowProfile +0 +16 +16 +Button_Switch_THT +SW_DIP_SPSTx08_Slide_9.78x22.5mm_W7.62mm_P2.54mm +8x-dip-switch SPST , Slide, row spacing 7.62 mm (300 mils), body size 9.78x22.5mm (see e.g. https://www.ctscorp.com/wp-content/uploads/206-208.pdf) +DIP Switch SPST Slide 7.62mm 300mil +0 +16 +16 +Button_Switch_THT +SW_DIP_SPSTx09_Piano_10.8x24.42mm_W7.62mm_P2.54mm +9x-dip-switch SPST , Piano, row spacing 7.62 mm (300 mils), body size 10.8x24.42mm +DIP Switch SPST Piano 7.62mm 300mil +0 +18 +18 +Button_Switch_THT +SW_DIP_SPSTx09_Piano_CTS_Series194-9MSTN_W7.62mm_P2.54mm +9x-dip-switch SPST CTS_Series194-9MSTN, Piano, row spacing 7.62 mm (300 mils), body size (see https://www.ctscorp.com/wp-content/uploads/194-195.pdf) +DIP Switch SPST Piano 7.62mm 300mil +0 +18 +18 +Button_Switch_THT +SW_DIP_SPSTx09_Slide_6.7x24.42mm_W7.62mm_P2.54mm_LowProfile +9x-dip-switch SPST , Slide, row spacing 7.62 mm (300 mils), body size 6.7x24.42mm (see e.g. https://www.ctscorp.com/wp-content/uploads/209-210.pdf), LowProfile +DIP Switch SPST Slide 7.62mm 300mil LowProfile +0 +18 +18 +Button_Switch_THT +SW_DIP_SPSTx09_Slide_9.78x25.04mm_W7.62mm_P2.54mm +9x-dip-switch SPST , Slide, row spacing 7.62 mm (300 mils), body size 9.78x25.04mm (see e.g. https://www.ctscorp.com/wp-content/uploads/206-208.pdf) +DIP Switch SPST Slide 7.62mm 300mil +0 +18 +18 +Button_Switch_THT +SW_DIP_SPSTx10_Piano_10.8x26.96mm_W7.62mm_P2.54mm +10x-dip-switch SPST , Piano, row spacing 7.62 mm (300 mils), body size 10.8x26.96mm +DIP Switch SPST Piano 7.62mm 300mil +0 +20 +20 +Button_Switch_THT +SW_DIP_SPSTx10_Piano_CTS_Series194-10MSTN_W7.62mm_P2.54mm +10x-dip-switch SPST CTS_Series194-10MSTN, Piano, row spacing 7.62 mm (300 mils), body size (see https://www.ctscorp.com/wp-content/uploads/194-195.pdf) +DIP Switch SPST Piano 7.62mm 300mil +0 +20 +20 +Button_Switch_THT +SW_DIP_SPSTx10_Slide_6.7x26.96mm_W7.62mm_P2.54mm_LowProfile +10x-dip-switch SPST , Slide, row spacing 7.62 mm (300 mils), body size 6.7x26.96mm (see e.g. https://www.ctscorp.com/wp-content/uploads/209-210.pdf), LowProfile +DIP Switch SPST Slide 7.62mm 300mil LowProfile +0 +20 +20 +Button_Switch_THT +SW_DIP_SPSTx10_Slide_9.78x27.58mm_W7.62mm_P2.54mm +10x-dip-switch SPST , Slide, row spacing 7.62 mm (300 mils), body size 9.78x27.58mm (see e.g. https://www.ctscorp.com/wp-content/uploads/206-208.pdf) +DIP Switch SPST Slide 7.62mm 300mil +0 +20 +20 +Button_Switch_THT +SW_DIP_SPSTx11_Piano_10.8x29.5mm_W7.62mm_P2.54mm +11x-dip-switch SPST , Piano, row spacing 7.62 mm (300 mils), body size 10.8x29.5mm +DIP Switch SPST Piano 7.62mm 300mil +0 +22 +22 +Button_Switch_THT +SW_DIP_SPSTx11_Piano_CTS_Series194-11MSTN_W7.62mm_P2.54mm +11x-dip-switch SPST CTS_Series194-11MSTN, Piano, row spacing 7.62 mm (300 mils), body size (see https://www.ctscorp.com/wp-content/uploads/194-195.pdf) +DIP Switch SPST Piano 7.62mm 300mil +0 +22 +22 +Button_Switch_THT +SW_DIP_SPSTx11_Slide_6.7x29.5mm_W7.62mm_P2.54mm_LowProfile +11x-dip-switch SPST , Slide, row spacing 7.62 mm (300 mils), body size 6.7x29.5mm (see e.g. https://www.ctscorp.com/wp-content/uploads/209-210.pdf), LowProfile +DIP Switch SPST Slide 7.62mm 300mil LowProfile +0 +22 +22 +Button_Switch_THT +SW_DIP_SPSTx11_Slide_9.78x30.12mm_W7.62mm_P2.54mm +11x-dip-switch SPST , Slide, row spacing 7.62 mm (300 mils), body size 9.78x30.12mm (see e.g. https://www.ctscorp.com/wp-content/uploads/206-208.pdf) +DIP Switch SPST Slide 7.62mm 300mil +0 +22 +22 +Button_Switch_THT +SW_DIP_SPSTx12_Piano_10.8x32.04mm_W7.62mm_P2.54mm +12x-dip-switch SPST , Piano, row spacing 7.62 mm (300 mils), body size 10.8x32.04mm +DIP Switch SPST Piano 7.62mm 300mil +0 +24 +24 +Button_Switch_THT +SW_DIP_SPSTx12_Piano_CTS_Series194-12MSTN_W7.62mm_P2.54mm +12x-dip-switch SPST CTS_Series194-12MSTN, Piano, row spacing 7.62 mm (300 mils), body size (see https://www.ctscorp.com/wp-content/uploads/194-195.pdf) +DIP Switch SPST Piano 7.62mm 300mil +0 +24 +24 +Button_Switch_THT +SW_DIP_SPSTx12_Slide_6.7x32.04mm_W7.62mm_P2.54mm_LowProfile +12x-dip-switch SPST , Slide, row spacing 7.62 mm (300 mils), body size 6.7x32.04mm (see e.g. https://www.ctscorp.com/wp-content/uploads/209-210.pdf), LowProfile +DIP Switch SPST Slide 7.62mm 300mil LowProfile +0 +24 +24 +Button_Switch_THT +SW_DIP_SPSTx12_Slide_9.78x32.66mm_W7.62mm_P2.54mm +12x-dip-switch SPST , Slide, row spacing 7.62 mm (300 mils), body size 9.78x32.66mm (see e.g. https://www.ctscorp.com/wp-content/uploads/206-208.pdf) +DIP Switch SPST Slide 7.62mm 300mil +0 +24 +24 +Button_Switch_THT +SW_E-Switch_EG1224_SPDT_Angled +E-Switch slide switch, EG series, SPDT, right angle, http://spec_sheets.e-switch.com/specs/P040042.pdf +switch SPDT +0 +7 +3 +Button_Switch_THT +SW_E-Switch_EG1271_DPDT +E-Switch sub miniature slide switch, EG series, DPDT, http://spec_sheets.e-switch.com/specs/P040047.pdf +switch DPDT +0 +6 +6 +Button_Switch_THT +SW_E-Switch_EG2219_DPDT_Angled +E-Switch slide switch, EG series, DPDT, right angle, http://spec_sheets.e-switch.com/specs/P040170.pdf +switch DPDT +0 +10 +6 +Button_Switch_THT +SW_Lever_1P2T_NKK_GW12LxH +Switch, single pole double throw, right angle, http://www.nkkswitches.com/pdf/GW.pdf +switch single-pole double-throw spdt ON-ON horizontal +0 +5 +3 +Button_Switch_THT +SW_MEC_5GTH9 +MEC 5G single pole normally-open tactile switch https://cdn.sos.sk/productdata/80/f6/aabf7be6/5gth9358222.pdf +switch normally-open pushbutton push-button +0 +4 +2 +Button_Switch_THT +SW_NKK_BB15AH +https://www.nkkswitches.com/pdf/Bpushbuttons-1.pdf +Pushbutton Right-angle +0 +5 +3 +Button_Switch_THT +SW_NKK_G1xJP +Switch NKK G1xJP http://www.nkkswitches.com/pdf/gwillum.pdf +SWITCH TOGGLE ILLUM SPDT NKK +0 +6 +6 +Button_Switch_THT +SW_NKK_GW12LJP +Switch, single pole double throw, illuminated paddle, http://www.nkkswitches.com/pdf/gwillum.pdf +switch single-pole double-throw spdt ON-ON illuminated LED +0 +6 +6 +Button_Switch_THT +SW_PUSH-12mm +SW PUSH 12mm https://www.e-switch.com/system/asset/product_line/data_sheet/143/TL1100.pdf +tact sw push 12mm +0 +4 +2 +Button_Switch_THT +SW_PUSH-12mm_Wuerth-430476085716 +SW PUSH 12mm http://katalog.we-online.de/em/datasheet/430476085716.pdf +tact sw push 12mm +0 +4 +2 +Button_Switch_THT +SW_PUSH_6mm +https://www.omron.com/ecb/products/pdf/en-b3f.pdf +tact sw push 6mm +0 +4 +2 +Button_Switch_THT +SW_PUSH_6mm_H4.3mm +tactile push button, 6x6mm e.g. PHAP33xx series, height=4.3mm +tact sw push 6mm +0 +4 +2 +Button_Switch_THT +SW_PUSH_6mm_H5mm +tactile push button, 6x6mm e.g. PHAP33xx series, height=5mm +tact sw push 6mm +0 +4 +2 +Button_Switch_THT +SW_PUSH_6mm_H7.3mm +tactile push button, 6x6mm e.g. PHAP33xx series, height=7.3mm +tact sw push 6mm +0 +4 +2 +Button_Switch_THT +SW_PUSH_6mm_H8.5mm +tactile push button, 6x6mm e.g. PHAP33xx series, height=8.5mm +tact sw push 6mm +0 +4 +2 +Button_Switch_THT +SW_PUSH_6mm_H8mm +tactile push button, 6x6mm e.g. PHAP33xx series, height=8mm +tact sw push 6mm +0 +4 +2 +Button_Switch_THT +SW_PUSH_6mm_H9.5mm +tactile push button, 6x6mm e.g. PHAP33xx series, height=9.5mm +tact sw push 6mm +0 +4 +2 +Button_Switch_THT +SW_PUSH_6mm_H13mm +tactile push button, 6x6mm e.g. PHAP33xx series, height=13mm +tact sw push 6mm +0 +4 +2 +Button_Switch_THT +SW_PUSH_E-Switch_FS5700DP_DPDT +FS5700 series pushbutton footswitch, DPDT, https://www.e-switch.com/system/asset/product_line/data_sheet/226/FS5700.pdf +switch DPDT footswitch +0 +6 +6 +Button_Switch_THT +SW_PUSH_LCD_E3_SAxxxx +Switch with LCD screen E3 SAxxxx +switch normally-open pushbutton push-button LCD +0 +6 +6 +Button_Switch_THT +SW_PUSH_LCD_E3_SAxxxx_SocketPins +Switch with LCD screen E3 SAxxxx +switch normally-open pushbutton push-button LCD +0 +6 +6 +Button_Switch_THT +SW_Slide_1P2T_CK_OS102011MS2Q +CuK miniature slide switch, OS series, SPDT, https://www.ckswitches.com/media/1428/os.pdf +switch SPDT +0 +5 +3 +Button_Switch_THT +SW_Tactile_SKHH_Angled +tactile switch 6mm ALPS SKHH right angle http://www.alps.com/prod/info/E/HTML/Tact/SnapIn/SKHH/SKHHLUA010.html +tactile switch 6mm ALPS SKHH right angle +0 +4 +2 +Button_Switch_THT +SW_Tactile_SPST_Angled_PTS645Vx31-2LFS +tactile switch SPST right angle, PTS645VL31-2 LFS +tactile switch SPST angled PTS645VL31-2 LFS C&K Button +0 +4 +2 +Button_Switch_THT +SW_Tactile_SPST_Angled_PTS645Vx39-2LFS +tactile switch SPST right angle, PTS645VL39-2 LFS +tactile switch SPST angled PTS645VL39-2 LFS C&K Button +0 +4 +2 +Button_Switch_THT +SW_Tactile_SPST_Angled_PTS645Vx58-2LFS +tactile switch SPST right angle, PTS645VL58-2 LFS +tactile switch SPST angled PTS645VL58-2 LFS C&K Button +0 +4 +2 +Button_Switch_THT +SW_Tactile_SPST_Angled_PTS645Vx83-2LFS +tactile switch SPST right angle, PTS645VL83-2 LFS +tactile switch SPST angled PTS645VL83-2 LFS C&K Button +0 +4 +2 +Button_Switch_THT +SW_Tactile_Straight_KSA0Axx1LFTR +SW PUSH SMALL http://www.ckswitches.com/media/1457/ksa_ksl.pdf +SW PUSH SMALL Tactile C&K +0 +4 +2 +Button_Switch_THT +SW_Tactile_Straight_KSL0Axx1LFTR +SW PUSH SMALL http://www.ckswitches.com/media/1457/ksa_ksl.pdf +SW PUSH SMALL Tactile C&K +0 +4 +2 +Button_Switch_THT +SW_TH_Tactile_Omron_B3F-10xx +SW_TH_Tactile_Omron_B3F-10xx_https://www.omron.com/ecb/products/pdf/en-b3f.pdf +Omron B3F-10xx +0 +4 +4 +Buzzer_Beeper +Buzzer_12x9.5RM7.6 +Generic Buzzer, D12mm height 9.5mm with RM7.6mm +buzzer +0 +2 +2 +Buzzer_Beeper +Buzzer_15x7.5RM7.6 +Generic Buzzer, D15mm height 7.5mm with RM7.6mm +buzzer +0 +2 +2 +Buzzer_Beeper +Buzzer_CUI_CPT-9019S-SMT +https://www.cui.com/product/resource/cpt-9019s-smt.pdf +buzzer piezo +0 +2 +2 +Buzzer_Beeper +Buzzer_Murata_PKMCS0909E4000-R1 +Murata Buzzer http://www.murata.com/en-us/api/pdfdownloadapi?cate=&partno=PKMCS0909E4000-R1 +Murata Buzzer Beeper +0 +2 +2 +Buzzer_Beeper +Buzzer_TDK_PS1240P02BT_D12.2mm_H6.5mm +Buzzer, D12.2mm height 6.5mm, https://product.tdk.com/info/en/catalog/datasheets/piezoelectronic_buzzer_ps_en.pdf +buzzer +0 +2 +2 +Buzzer_Beeper +MagneticBuzzer_CUI_CST-931RP-A +CST-931RP-A, http://www.cui.com/product/resource/cst-931rp-a.pdf +CST-931RP-A +0 +2 +2 +Buzzer_Beeper +MagneticBuzzer_Kingstate_KCG0601 +Buzzer, Elektromagnetic Beeper, Summer, +Kingstate KCG0601 +0 +2 +2 +Buzzer_Beeper +MagneticBuzzer_Kobitone_254-EMB84Q-RO +MagneticBuzzer Kobitone 254-EMB84Q-RO https://www.mouser.es/datasheet/2/209/KT-400385-1171904.pdf +MagneticBuzzer Kobitone 254-EMB84Q-RO +0 +3 +3 +Buzzer_Beeper +MagneticBuzzer_ProjectsUnlimited_AI-4228-TWT-R +Buzzer, Elektromagnetic Beeper, Summer, 3-28V-DC, https://www.kynix.com/uploadfiles/pdf/AI-4228-TWT-R.pdf +Projects Unlimited AI-4228-TWT-R +0 +2 +2 +Buzzer_Beeper +MagneticBuzzer_ProSignal_ABI-009-RC +Buzzer, Elektromagnetic Beeper, Summer, 6V-DC, +Pro Signal ABI-009-RC +0 +2 +2 +Buzzer_Beeper +MagneticBuzzer_ProSignal_ABI-010-RC +Buzzer, Elektromagnetic Beeper, Summer, 12V-DC, +Pro Signal ABI-010-RC +0 +2 +2 +Buzzer_Beeper +MagneticBuzzer_ProSignal_ABT-410-RC +Buzzer, Elektromagnetic Beeper, Summer, 1,5V-DC, +Pro Signal ABT-410-RC +0 +2 +2 +Buzzer_Beeper +MagneticBuzzer_StarMicronics_HMB-06_HMB-12 +Buzzer, Elektromagnetic Beeper, Summer, +Star Micronics HMB-06 HMB-12 +0 +2 +2 +Buzzer_Beeper +PUIAudio_SMT_0825_S_4_R +SMD 8540, http://www.puiaudio.com/product-detail.aspx?partnumber=SMT-0825-S-4-R +SMD 8540 +0 +4 +4 +Capacitor_SMD +CP_Elec_3x5.3 +SMT capacitor, aluminium electrolytic, 3x5.3, Cornell Dubilier Electronics +Capacitor Electrolytic +0 +2 +2 +Capacitor_SMD +CP_Elec_3x5.4 +SMD capacitor, aluminum electrolytic, Nichicon, 3.0x5.4mm +capacitor electrolytic +0 +2 +2 +Capacitor_SMD +CP_Elec_4x3 +SMD capacitor, aluminum electrolytic, Nichicon, 4.0x3mm +capacitor electrolytic +0 +2 +2 +Capacitor_SMD +CP_Elec_4x3.9 +SMD capacitor, aluminum electrolytic, Nichicon, 4.0x3.9mm +capacitor electrolytic +0 +2 +2 +Capacitor_SMD +CP_Elec_4x4.5 +SMD capacitor, aluminum electrolytic, Nichicon, 4.0x4.5mm +capacitor electrolytic +0 +2 +2 +Capacitor_SMD +CP_Elec_4x5.3 +SMD capacitor, aluminum electrolytic, Vishay, 4.0x5.3mm +capacitor electrolytic +0 +2 +2 +Capacitor_SMD +CP_Elec_4x5.4 +SMD capacitor, aluminum electrolytic, Panasonic A5 / Nichicon, 4.0x5.4mm +capacitor electrolytic +0 +2 +2 +Capacitor_SMD +CP_Elec_4x5.7 +SMD capacitor, aluminum electrolytic, United Chemi-Con, 4.0x5.7mm +capacitor electrolytic +0 +2 +2 +Capacitor_SMD +CP_Elec_4x5.8 +SMD capacitor, aluminum electrolytic, Panasonic, 4.0x5.8mm +capacitor electrolytic +0 +2 +2 +Capacitor_SMD +CP_Elec_5x3 +SMD capacitor, aluminum electrolytic, Nichicon, 5.0x3.0mm +capacitor electrolytic +0 +2 +2 +Capacitor_SMD +CP_Elec_5x3.9 +SMD capacitor, aluminum electrolytic, Nichicon, 5.0x3.9mm +capacitor electrolytic +0 +2 +2 +Capacitor_SMD +CP_Elec_5x4.4 +SMD capacitor, aluminum electrolytic, Panasonic B45, 5.0x4.4mm +capacitor electrolytic +0 +2 +2 +Capacitor_SMD +CP_Elec_5x4.5 +SMD capacitor, aluminum electrolytic, Nichicon, 5.0x4.5mm +capacitor electrolytic +0 +2 +2 +Capacitor_SMD +CP_Elec_5x5.3 +SMD capacitor, aluminum electrolytic, Nichicon, 5.0x5.3mm +capacitor electrolytic +0 +2 +2 +Capacitor_SMD +CP_Elec_5x5.4 +SMD capacitor, aluminum electrolytic, Nichicon, 5.0x5.4mm +capacitor electrolytic +0 +2 +2 +Capacitor_SMD +CP_Elec_5x5.7 +SMD capacitor, aluminum electrolytic, United Chemi-Con, 5.0x5.7mm +capacitor electrolytic +0 +2 +2 +Capacitor_SMD +CP_Elec_5x5.8 +SMD capacitor, aluminum electrolytic, Panasonic, 5.0x5.8mm +capacitor electrolytic +0 +2 +2 +Capacitor_SMD +CP_Elec_5x5.9 +SMD capacitor, aluminum electrolytic, Panasonic B6, 5.0x5.9mm +capacitor electrolytic +0 +2 +2 +Capacitor_SMD +CP_Elec_6.3x3 +SMD capacitor, aluminum electrolytic, Nichicon, 6.3x3.0mm +capacitor electrolytic +0 +2 +2 +Capacitor_SMD +CP_Elec_6.3x3.9 +SMD capacitor, aluminum electrolytic, Nichicon, 6.3x3.9mm +capacitor electrolytic +0 +2 +2 +Capacitor_SMD +CP_Elec_6.3x4.5 +SMD capacitor, aluminum electrolytic, Nichicon, 6.3x4.5mm +capacitor electrolytic +0 +2 +2 +Capacitor_SMD +CP_Elec_6.3x4.9 +SMD capacitor, aluminum electrolytic, Panasonic C5, 6.3x4.9mm +capacitor electrolytic +0 +2 +2 +Capacitor_SMD +CP_Elec_6.3x5.2 +SMD capacitor, aluminum electrolytic, United Chemi-Con, 6.3x5.2mm +capacitor electrolytic +0 +2 +2 +Capacitor_SMD +CP_Elec_6.3x5.3 +SMD capacitor, aluminum electrolytic, Cornell Dubilier, 6.3x5.3mm +capacitor electrolytic +0 +2 +2 +Capacitor_SMD +CP_Elec_6.3x5.4 +SMD capacitor, aluminum electrolytic, Panasonic C55, 6.3x5.4mm +capacitor electrolytic +0 +2 +2 +Capacitor_SMD +CP_Elec_6.3x5.4_Nichicon +SMD capacitor, aluminum electrolytic, Nichicon, 6.3x5.4mm +capacitor electrolytic +0 +2 +2 +Capacitor_SMD +CP_Elec_6.3x5.7 +SMD capacitor, aluminum electrolytic, United Chemi-Con, 6.3x5.7mm +capacitor electrolytic +0 +2 +2 +Capacitor_SMD +CP_Elec_6.3x5.8 +SMD capacitor, aluminum electrolytic, Nichicon, 6.3x5.8mm +capacitor electrolytic +0 +2 +2 +Capacitor_SMD +CP_Elec_6.3x5.9 +SMD capacitor, aluminum electrolytic, Panasonic C6, 6.3x5.9mm +capacitor electrolytic +0 +2 +2 +Capacitor_SMD +CP_Elec_6.3x7.7 +SMD capacitor, aluminum electrolytic, Nichicon, 6.3x7.7mm +capacitor electrolytic +0 +2 +2 +Capacitor_SMD +CP_Elec_6.3x9.9 +SMD capacitor, aluminum electrolytic, Panasonic C10, 6.3x9.9mm +capacitor electrolytic +0 +2 +2 +Capacitor_SMD +CP_Elec_8x5.4 +SMD capacitor, aluminum electrolytic, Nichicon, 8.0x5.4mm +capacitor electrolytic +0 +2 +2 +Capacitor_SMD +CP_Elec_8x6.2 +SMD capacitor, aluminum electrolytic, Nichicon, 8.0x6.2mm +capacitor electrolytic +0 +2 +2 +Capacitor_SMD +CP_Elec_8x6.5 +SMD capacitor, aluminum electrolytic, Rubycon, 8.0x6.5mm +capacitor electrolytic +0 +2 +2 +Capacitor_SMD +CP_Elec_8x6.7 +SMD capacitor, aluminum electrolytic, United Chemi-Con, 8.0x6.7mm +capacitor electrolytic +0 +2 +2 +Capacitor_SMD +CP_Elec_8x6.9 +SMD capacitor, aluminum electrolytic, Panasonic E7, 8.0x6.9mm +capacitor electrolytic +0 +2 +2 +Capacitor_SMD +CP_Elec_8x10 +SMD capacitor, aluminum electrolytic, Nichicon, 8.0x10mm +capacitor electrolytic +0 +2 +2 +Capacitor_SMD +CP_Elec_8x10.5 +SMD capacitor, aluminum electrolytic, Vishay 0810, 8.0x10.5mm, http://www.vishay.com/docs/28395/150crz.pdf +capacitor electrolytic +0 +2 +2 +Capacitor_SMD +CP_Elec_8x11.9 +SMD capacitor, aluminum electrolytic, Panasonic E12, 8.0x11.9mm +capacitor electrolytic +0 +2 +2 +Capacitor_SMD +CP_Elec_10x7.7 +SMD capacitor, aluminum electrolytic, Nichicon, 10.0x7.7mm +capacitor electrolytic +0 +2 +2 +Capacitor_SMD +CP_Elec_10x7.9 +SMD capacitor, aluminum electrolytic, Panasonic F8, 10.0x7.9mm +capacitor electrolytic +0 +2 +2 +Capacitor_SMD +CP_Elec_10x10 +SMD capacitor, aluminum electrolytic, Nichicon, 10.0x10.0mm +capacitor electrolytic +0 +2 +2 +Capacitor_SMD +CP_Elec_10x10.5 +SMD capacitor, aluminum electrolytic, Vishay 1010, 10.0x10.5mm, http://www.vishay.com/docs/28395/150crz.pdf +capacitor electrolytic +0 +2 +2 +Capacitor_SMD +CP_Elec_10x12.5 +SMD capacitor, aluminum electrolytic, Vishay 1012, 10.0x12.5mm, http://www.vishay.com/docs/28395/150crz.pdf +capacitor electrolytic +0 +2 +2 +Capacitor_SMD +CP_Elec_10x12.6 +SMD capacitor, aluminum electrolytic, Panasonic F12, 10.0x12.6mm +capacitor electrolytic +0 +2 +2 +Capacitor_SMD +CP_Elec_10x14.3 +SMD capacitor, aluminum electrolytic, Vishay 1014, 10.0x14.3mm, http://www.vishay.com/docs/28395/150crz.pdf +capacitor electrolytic +0 +2 +2 +Capacitor_SMD +CP_Elec_16x17.5 +SMD capacitor, aluminum electrolytic, Vishay 1616, 16.0x17.5mm, http://www.vishay.com/docs/28395/150crz.pdf +capacitor electrolytic +0 +2 +2 +Capacitor_SMD +CP_Elec_16x22 +SMD capacitor, aluminum electrolytic, Vishay 1621, 16.0x22.0mm, http://www.vishay.com/docs/28395/150crz.pdf +capacitor electrolytic +0 +2 +2 +Capacitor_SMD +CP_Elec_18x17.5 +SMD capacitor, aluminum electrolytic, Vishay 1816, 18.0x17.5mm, http://www.vishay.com/docs/28395/150crz.pdf +capacitor electrolytic +0 +2 +2 +Capacitor_SMD +CP_Elec_18x22 +SMD capacitor, aluminum electrolytic, Vishay 1821, 18.0x22.0mm, http://www.vishay.com/docs/28395/150crz.pdf +capacitor electrolytic +0 +2 +2 +Capacitor_SMD +C_0201_0603Metric +Capacitor SMD 0201 (0603 Metric), square (rectangular) end terminal, IPC_7351 nominal, (Body size source: https://www.vishay.com/docs/20052/crcw0201e3.pdf), generated with kicad-footprint-generator +capacitor +0 +4 +2 +Capacitor_SMD +C_0402_1005Metric +Capacitor SMD 0402 (1005 Metric), square (rectangular) end terminal, IPC_7351 nominal, (Body size source: http://www.tortai-tech.com/upload/download/2011102023233369053.pdf), generated with kicad-footprint-generator +capacitor +0 +2 +2 +Capacitor_SMD +C_0603_1608Metric +Capacitor SMD 0603 (1608 Metric), square (rectangular) end terminal, IPC_7351 nominal, (Body size source: http://www.tortai-tech.com/upload/download/2011102023233369053.pdf), generated with kicad-footprint-generator +capacitor +0 +2 +2 +Capacitor_SMD +C_0603_1608Metric_Pad1.05x0.95mm_HandSolder +Capacitor SMD 0603 (1608 Metric), square (rectangular) end terminal, IPC_7351 nominal with elongated pad for handsoldering. (Body size source: http://www.tortai-tech.com/upload/download/2011102023233369053.pdf), generated with kicad-footprint-generator +capacitor handsolder +0 +2 +2 +Capacitor_SMD +C_0805_2012Metric +Capacitor SMD 0805 (2012 Metric), square (rectangular) end terminal, IPC_7351 nominal, (Body size source: https://docs.google.com/spreadsheets/d/1BsfQQcO9C6DZCsRaXUlFlo91Tg2WpOkGARC1WS5S8t0/edit?usp=sharing), generated with kicad-footprint-generator +capacitor +0 +2 +2 +Capacitor_SMD +C_0805_2012Metric_Pad1.15x1.40mm_HandSolder +Capacitor SMD 0805 (2012 Metric), square (rectangular) end terminal, IPC_7351 nominal with elongated pad for handsoldering. (Body size source: https://docs.google.com/spreadsheets/d/1BsfQQcO9C6DZCsRaXUlFlo91Tg2WpOkGARC1WS5S8t0/edit?usp=sharing), generated with kicad-footprint-generator +capacitor handsolder +0 +2 +2 +Capacitor_SMD +C_01005_0402Metric +Capacitor SMD 01005 (0402 Metric), square (rectangular) end terminal, IPC_7351 nominal, (Body size source: http://www.vishay.com/docs/20056/crcw01005e3.pdf), generated with kicad-footprint-generator +capacitor +0 +4 +2 +Capacitor_SMD +C_1206_3216Metric +Capacitor SMD 1206 (3216 Metric), square (rectangular) end terminal, IPC_7351 nominal, (Body size source: http://www.tortai-tech.com/upload/download/2011102023233369053.pdf), generated with kicad-footprint-generator +capacitor +0 +2 +2 +Capacitor_SMD +C_1206_3216Metric_Pad1.42x1.75mm_HandSolder +Capacitor SMD 1206 (3216 Metric), square (rectangular) end terminal, IPC_7351 nominal with elongated pad for handsoldering. (Body size source: http://www.tortai-tech.com/upload/download/2011102023233369053.pdf), generated with kicad-footprint-generator +capacitor handsolder +0 +2 +2 +Capacitor_SMD +C_1210_3225Metric +Capacitor SMD 1210 (3225 Metric), square (rectangular) end terminal, IPC_7351 nominal, (Body size source: http://www.tortai-tech.com/upload/download/2011102023233369053.pdf), generated with kicad-footprint-generator +capacitor +0 +2 +2 +Capacitor_SMD +C_1210_3225Metric_Pad1.42x2.65mm_HandSolder +Capacitor SMD 1210 (3225 Metric), square (rectangular) end terminal, IPC_7351 nominal with elongated pad for handsoldering. (Body size source: http://www.tortai-tech.com/upload/download/2011102023233369053.pdf), generated with kicad-footprint-generator +capacitor handsolder +0 +2 +2 +Capacitor_SMD +C_1806_4516Metric +Capacitor SMD 1806 (4516 Metric), square (rectangular) end terminal, IPC_7351 nominal, (Body size source: https://www.modelithics.com/models/Vendor/MuRata/BLM41P.pdf), generated with kicad-footprint-generator +capacitor +0 +2 +2 +Capacitor_SMD +C_1806_4516Metric_Pad1.57x1.80mm_HandSolder +Capacitor SMD 1806 (4516 Metric), square (rectangular) end terminal, IPC_7351 nominal with elongated pad for handsoldering. (Body size source: https://www.modelithics.com/models/Vendor/MuRata/BLM41P.pdf), generated with kicad-footprint-generator +capacitor handsolder +0 +2 +2 +Capacitor_SMD +C_1812_4532Metric +Capacitor SMD 1812 (4532 Metric), square (rectangular) end terminal, IPC_7351 nominal, (Body size source: https://www.nikhef.nl/pub/departments/mt/projects/detectorR_D/dtddice/ERJ2G.pdf), generated with kicad-footprint-generator +capacitor +0 +2 +2 +Capacitor_SMD +C_1812_4532Metric_Pad1.30x3.40mm_HandSolder +Capacitor SMD 1812 (4532 Metric), square (rectangular) end terminal, IPC_7351 nominal with elongated pad for handsoldering. (Body size source: https://www.nikhef.nl/pub/departments/mt/projects/detectorR_D/dtddice/ERJ2G.pdf), generated with kicad-footprint-generator +capacitor handsolder +0 +2 +2 +Capacitor_SMD +C_1825_4564Metric +Capacitor SMD 1825 (4564 Metric), square (rectangular) end terminal, IPC_7351 nominal, (Body size from: http://datasheets.avx.com/AVX-HV_MLCC.pdf), generated with kicad-footprint-generator +capacitor +0 +2 +2 +Capacitor_SMD +C_1825_4564Metric_Pad1.88x6.70mm_HandSolder +Capacitor SMD 1825 (4564 Metric), square (rectangular) end terminal, IPC_7351 nominal with elongated pad for handsoldering. (Body size from: http://datasheets.avx.com/AVX-HV_MLCC.pdf), generated with kicad-footprint-generator +capacitor handsolder +0 +2 +2 +Capacitor_SMD +C_2010_5025Metric +Capacitor SMD 2010 (5025 Metric), square (rectangular) end terminal, IPC_7351 nominal, (Body size source: http://www.tortai-tech.com/upload/download/2011102023233369053.pdf), generated with kicad-footprint-generator +capacitor +0 +2 +2 +Capacitor_SMD +C_2010_5025Metric_Pad1.52x2.65mm_HandSolder +Capacitor SMD 2010 (5025 Metric), square (rectangular) end terminal, IPC_7351 nominal with elongated pad for handsoldering. (Body size source: http://www.tortai-tech.com/upload/download/2011102023233369053.pdf), generated with kicad-footprint-generator +capacitor handsolder +0 +2 +2 +Capacitor_SMD +C_2220_5650Metric +Capacitor SMD 2220 (5650 Metric), square (rectangular) end terminal, IPC_7351 nominal, (Body size from: http://datasheets.avx.com/AVX-HV_MLCC.pdf), generated with kicad-footprint-generator +capacitor +0 +2 +2 +Capacitor_SMD +C_2220_5650Metric_Pad1.97x5.40mm_HandSolder +Capacitor SMD 2220 (5650 Metric), square (rectangular) end terminal, IPC_7351 nominal with elongated pad for handsoldering. (Body size from: http://datasheets.avx.com/AVX-HV_MLCC.pdf), generated with kicad-footprint-generator +capacitor handsolder +0 +2 +2 +Capacitor_SMD +C_2225_5664Metric +Capacitor SMD 2225 (5664 Metric), square (rectangular) end terminal, IPC_7351 nominal, (Body size from: http://datasheets.avx.com/AVX-HV_MLCC.pdf), generated with kicad-footprint-generator +capacitor +0 +2 +2 +Capacitor_SMD +C_2225_5664Metric_Pad1.80x6.60mm_HandSolder +Capacitor SMD 2225 (5664 Metric), square (rectangular) end terminal, IPC_7351 nominal with elongated pad for handsoldering. (Body size from: http://datasheets.avx.com/AVX-HV_MLCC.pdf), generated with kicad-footprint-generator +capacitor handsolder +0 +2 +2 +Capacitor_SMD +C_2512_6332Metric +Capacitor SMD 2512 (6332 Metric), square (rectangular) end terminal, IPC_7351 nominal, (Body size source: http://www.tortai-tech.com/upload/download/2011102023233369053.pdf), generated with kicad-footprint-generator +capacitor +0 +2 +2 +Capacitor_SMD +C_2512_6332Metric_Pad1.52x3.35mm_HandSolder +Capacitor SMD 2512 (6332 Metric), square (rectangular) end terminal, IPC_7351 nominal with elongated pad for handsoldering. (Body size source: http://www.tortai-tech.com/upload/download/2011102023233369053.pdf), generated with kicad-footprint-generator +capacitor handsolder +0 +2 +2 +Capacitor_SMD +C_2816_7142Metric +Capacitor SMD 2816 (7142 Metric), square (rectangular) end terminal, IPC_7351 nominal, (Body size from: https://www.vishay.com/docs/30100/wsl.pdf), generated with kicad-footprint-generator +capacitor +0 +2 +2 +Capacitor_SMD +C_2816_7142Metric_Pad3.20x4.45mm_HandSolder +Capacitor SMD 2816 (7142 Metric), square (rectangular) end terminal, IPC_7351 nominal with elongated pad for handsoldering. (Body size from: https://www.vishay.com/docs/30100/wsl.pdf), generated with kicad-footprint-generator +capacitor handsolder +0 +2 +2 +Capacitor_SMD +C_3640_9110Metric +Capacitor SMD 3640 (9110 Metric), square (rectangular) end terminal, IPC_7351 nominal, (Body size from: http://datasheets.avx.com/AVX-HV_MLCC.pdf), generated with kicad-footprint-generator +capacitor +0 +2 +2 +Capacitor_SMD +C_3640_9110Metric_Pad2.10x10.45mm_HandSolder +Capacitor SMD 3640 (9110 Metric), square (rectangular) end terminal, IPC_7351 nominal with elongated pad for handsoldering. (Body size from: http://datasheets.avx.com/AVX-HV_MLCC.pdf), generated with kicad-footprint-generator +capacitor handsolder +0 +2 +2 +Capacitor_SMD +C_Elec_3x5.4 +SMD capacitor, aluminum electrolytic nonpolar, 3.0x5.4mm +capacitor electrolyic nonpolar +0 +2 +2 +Capacitor_SMD +C_Elec_4x5.4 +SMD capacitor, aluminum electrolytic nonpolar, 4.0x5.4mm +capacitor electrolyic nonpolar +0 +2 +2 +Capacitor_SMD +C_Elec_4x5.8 +SMD capacitor, aluminum electrolytic nonpolar, 4.0x5.8mm +capacitor electrolyic nonpolar +0 +2 +2 +Capacitor_SMD +C_Elec_5x5.4 +SMD capacitor, aluminum electrolytic nonpolar, 5.0x5.4mm +capacitor electrolyic nonpolar +0 +2 +2 +Capacitor_SMD +C_Elec_5x5.8 +SMD capacitor, aluminum electrolytic nonpolar, 5.0x5.8mm +capacitor electrolyic nonpolar +0 +2 +2 +Capacitor_SMD +C_Elec_6.3x5.4 +SMD capacitor, aluminum electrolytic nonpolar, 6.3x5.4mm +capacitor electrolyic nonpolar +0 +2 +2 +Capacitor_SMD +C_Elec_6.3x5.8 +SMD capacitor, aluminum electrolytic nonpolar, 6.3x5.8mm +capacitor electrolyic nonpolar +0 +2 +2 +Capacitor_SMD +C_Elec_6.3x7.7 +SMD capacitor, aluminum electrolytic nonpolar, 6.3x7.7mm +capacitor electrolyic nonpolar +0 +2 +2 +Capacitor_SMD +C_Elec_8x5.4 +SMD capacitor, aluminum electrolytic nonpolar, 8.0x5.4mm +capacitor electrolyic nonpolar +0 +2 +2 +Capacitor_SMD +C_Elec_8x6.2 +SMD capacitor, aluminum electrolytic nonpolar, 8.0x6.2mm +capacitor electrolyic nonpolar +0 +2 +2 +Capacitor_SMD +C_Elec_8x10.2 +SMD capacitor, aluminum electrolytic nonpolar, 8.0x10.2mm +capacitor electrolyic nonpolar +0 +2 +2 +Capacitor_SMD +C_Elec_10x10.2 +SMD capacitor, aluminum electrolytic nonpolar, 10.0x10.2mm +capacitor electrolyic nonpolar +0 +2 +2 +Capacitor_SMD +C_Trimmer_Murata_TZB4-A +trimmer capacitor SMD horizontal, http://www.murata.com/~/media/webrenewal/support/library/catalog/products/capacitor/trimmer/t13e.ashx?la=en-gb + Murata TZB4 TZB4-A +0 +2 +2 +Capacitor_SMD +C_Trimmer_Murata_TZB4-B +trimmer capacitor SMD horizontal, http://www.murata.com/~/media/webrenewal/support/library/catalog/products/capacitor/trimmer/t13e.ashx?la=en-gb + Murata TZB4 TZB4-A +0 +2 +2 +Capacitor_SMD +C_Trimmer_Murata_TZC3 +trimmer capacitor SMD horizontal, http://www.murata.com/~/media/webrenewal/support/library/catalog/products/capacitor/trimmer/t13e.ashx?la=en-gb + Murata TZC3 +0 +2 +2 +Capacitor_SMD +C_Trimmer_Murata_TZR1 +trimmer capacitor SMD horizontal, http://www.murata.com/~/media/webrenewal/support/library/catalog/products/capacitor/trimmer/t13e.ashx?la=en-gb + Murata TZR1 +0 +2 +2 +Capacitor_SMD +C_Trimmer_Murata_TZW4 +trimmer capacitor SMD horizontal, http://www.murata.com/~/media/webrenewal/support/library/catalog/products/capacitor/trimmer/t13e.ashx?la=en-gb + Murata TZW4 +0 +2 +2 +Capacitor_SMD +C_Trimmer_Murata_TZY2 +trimmer capacitor SMD horizontal, http://www.murata.com/~/media/webrenewal/support/library/catalog/products/capacitor/trimmer/t13e.ashx?la=en-gb + Murata TZY2 +0 +2 +2 +Capacitor_SMD +C_Trimmer_Sprague-Goodman_SGC3 +trimmer capacitor SMD horizontal, http://media.wix.com/ugd/d86717_38d9821e12823a7aa9cef38c6c2a73cc.pdf + Sprague Goodman SGC3 +0 +2 +2 +Capacitor_SMD +C_Trimmer_Voltronics_JN +trimmer capacitor SMD horizontal, http://www.knowlescapacitors.com/File%20Library/Voltronics/English/GlobalNavigation/Products/Trimmer%20Capacitors/CerChipTrimCap.pdf + Voltronics JN +0 +2 +2 +Capacitor_SMD +C_Trimmer_Voltronics_JQ +trimmer capacitor SMD horizontal, http://www.knowlescapacitors.com/File%20Library/Voltronics/English/GlobalNavigation/Products/Trimmer%20Capacitors/CerChipTrimCap.pdf + Voltronics JQ +0 +2 +2 +Capacitor_SMD +C_Trimmer_Voltronics_JR +trimmer capacitor SMD horizontal, http://www.knowlescapacitors.com/File%20Library/Voltronics/English/GlobalNavigation/Products/Trimmer%20Capacitors/CerChipTrimCap.pdf + Voltronics JR +0 +2 +2 +Capacitor_SMD +C_Trimmer_Voltronics_JV +trimmer capacitor SMD horizontal, http://www.knowlescapacitors.com/File%20Library/Voltronics/English/GlobalNavigation/Products/Trimmer%20Capacitors/CerChipTrimCap.pdf + Voltronics JV +0 +2 +2 +Capacitor_SMD +C_Trimmer_Voltronics_JZ +trimmer capacitor SMD horizontal, http://www.knowlescapacitors.com/File%20Library/Voltronics/English/GlobalNavigation/Products/Trimmer%20Capacitors/CerChipTrimCap.pdf + Voltronics JR +0 +2 +2 +Capacitor_Tantalum_SMD +CP_EIA-1608-08_AVX-J +Tantalum Capacitor SMD AVX-J (1608-08 Metric), IPC_7351 nominal, (Body size from: https://www.vishay.com/docs/48064/_t58_vmn_pt0471_1601.pdf), generated with kicad-footprint-generator +capacitor tantalum +0 +2 +2 +Capacitor_Tantalum_SMD +CP_EIA-1608-08_AVX-J_Pad1.25x1.05mm_HandSolder +Tantalum Capacitor SMD AVX-J (1608-08 Metric), IPC_7351 nominal, (Body size from: https://www.vishay.com/docs/48064/_t58_vmn_pt0471_1601.pdf), generated with kicad-footprint-generator +capacitor tantalum +0 +2 +2 +Capacitor_Tantalum_SMD +CP_EIA-1608-10_AVX-L +Tantalum Capacitor SMD AVX-L (1608-10 Metric), IPC_7351 nominal, (Body size from: https://www.vishay.com/docs/48064/_t58_vmn_pt0471_1601.pdf), generated with kicad-footprint-generator +capacitor tantalum +0 +2 +2 +Capacitor_Tantalum_SMD +CP_EIA-1608-10_AVX-L_Pad1.25x1.05mm_HandSolder +Tantalum Capacitor SMD AVX-L (1608-10 Metric), IPC_7351 nominal, (Body size from: https://www.vishay.com/docs/48064/_t58_vmn_pt0471_1601.pdf), generated with kicad-footprint-generator +capacitor tantalum +0 +2 +2 +Capacitor_Tantalum_SMD +CP_EIA-2012-12_Kemet-R +Tantalum Capacitor SMD Kemet-R (2012-12 Metric), IPC_7351 nominal, (Body size from: https://www.vishay.com/docs/40182/tmch.pdf), generated with kicad-footprint-generator +capacitor tantalum +0 +2 +2 +Capacitor_Tantalum_SMD +CP_EIA-2012-12_Kemet-R_Pad1.30x1.05mm_HandSolder +Tantalum Capacitor SMD Kemet-R (2012-12 Metric), IPC_7351 nominal, (Body size from: https://www.vishay.com/docs/40182/tmch.pdf), generated with kicad-footprint-generator +capacitor tantalum +0 +2 +2 +Capacitor_Tantalum_SMD +CP_EIA-2012-15_AVX-P +Tantalum Capacitor SMD AVX-P (2012-15 Metric), IPC_7351 nominal, (Body size from: https://www.vishay.com/docs/40182/tmch.pdf), generated with kicad-footprint-generator +capacitor tantalum +0 +2 +2 +Capacitor_Tantalum_SMD +CP_EIA-2012-15_AVX-P_Pad1.30x1.05mm_HandSolder +Tantalum Capacitor SMD AVX-P (2012-15 Metric), IPC_7351 nominal, (Body size from: https://www.vishay.com/docs/40182/tmch.pdf), generated with kicad-footprint-generator +capacitor tantalum +0 +2 +2 +Capacitor_Tantalum_SMD +CP_EIA-3216-10_Kemet-I +Tantalum Capacitor SMD Kemet-I (3216-10 Metric), IPC_7351 nominal, (Body size from: http://www.kemet.com/Lists/ProductCatalog/Attachments/253/KEM_TC101_STD.pdf), generated with kicad-footprint-generator +capacitor tantalum +0 +2 +2 +Capacitor_Tantalum_SMD +CP_EIA-3216-10_Kemet-I_Pad1.58x1.35mm_HandSolder +Tantalum Capacitor SMD Kemet-I (3216-10 Metric), IPC_7351 nominal, (Body size from: http://www.kemet.com/Lists/ProductCatalog/Attachments/253/KEM_TC101_STD.pdf), generated with kicad-footprint-generator +capacitor tantalum +0 +2 +2 +Capacitor_Tantalum_SMD +CP_EIA-3216-12_Kemet-S +Tantalum Capacitor SMD Kemet-S (3216-12 Metric), IPC_7351 nominal, (Body size from: http://www.kemet.com/Lists/ProductCatalog/Attachments/253/KEM_TC101_STD.pdf), generated with kicad-footprint-generator +capacitor tantalum +0 +2 +2 +Capacitor_Tantalum_SMD +CP_EIA-3216-12_Kemet-S_Pad1.58x1.35mm_HandSolder +Tantalum Capacitor SMD Kemet-S (3216-12 Metric), IPC_7351 nominal, (Body size from: http://www.kemet.com/Lists/ProductCatalog/Attachments/253/KEM_TC101_STD.pdf), generated with kicad-footprint-generator +capacitor tantalum +0 +2 +2 +Capacitor_Tantalum_SMD +CP_EIA-3216-18_Kemet-A +Tantalum Capacitor SMD Kemet-A (3216-18 Metric), IPC_7351 nominal, (Body size from: http://www.kemet.com/Lists/ProductCatalog/Attachments/253/KEM_TC101_STD.pdf), generated with kicad-footprint-generator +capacitor tantalum +0 +2 +2 +Capacitor_Tantalum_SMD +CP_EIA-3216-18_Kemet-A_Pad1.58x1.35mm_HandSolder +Tantalum Capacitor SMD Kemet-A (3216-18 Metric), IPC_7351 nominal, (Body size from: http://www.kemet.com/Lists/ProductCatalog/Attachments/253/KEM_TC101_STD.pdf), generated with kicad-footprint-generator +capacitor tantalum +0 +2 +2 +Capacitor_Tantalum_SMD +CP_EIA-3528-12_Kemet-T +Tantalum Capacitor SMD Kemet-T (3528-12 Metric), IPC_7351 nominal, (Body size from: http://www.kemet.com/Lists/ProductCatalog/Attachments/253/KEM_TC101_STD.pdf), generated with kicad-footprint-generator +capacitor tantalum +0 +2 +2 +Capacitor_Tantalum_SMD +CP_EIA-3528-12_Kemet-T_Pad1.50x2.35mm_HandSolder +Tantalum Capacitor SMD Kemet-T (3528-12 Metric), IPC_7351 nominal, (Body size from: http://www.kemet.com/Lists/ProductCatalog/Attachments/253/KEM_TC101_STD.pdf), generated with kicad-footprint-generator +capacitor tantalum +0 +2 +2 +Capacitor_Tantalum_SMD +CP_EIA-3528-15_AVX-H +Tantalum Capacitor SMD AVX-H (3528-15 Metric), IPC_7351 nominal, (Body size from: http://www.kemet.com/Lists/ProductCatalog/Attachments/253/KEM_TC101_STD.pdf), generated with kicad-footprint-generator +capacitor tantalum +0 +2 +2 +Capacitor_Tantalum_SMD +CP_EIA-3528-15_AVX-H_Pad1.50x2.35mm_HandSolder +Tantalum Capacitor SMD AVX-H (3528-15 Metric), IPC_7351 nominal, (Body size from: http://www.kemet.com/Lists/ProductCatalog/Attachments/253/KEM_TC101_STD.pdf), generated with kicad-footprint-generator +capacitor tantalum +0 +2 +2 +Capacitor_Tantalum_SMD +CP_EIA-3528-21_Kemet-B +Tantalum Capacitor SMD Kemet-B (3528-21 Metric), IPC_7351 nominal, (Body size from: http://www.kemet.com/Lists/ProductCatalog/Attachments/253/KEM_TC101_STD.pdf), generated with kicad-footprint-generator +capacitor tantalum +0 +2 +2 +Capacitor_Tantalum_SMD +CP_EIA-3528-21_Kemet-B_Pad1.50x2.35mm_HandSolder +Tantalum Capacitor SMD Kemet-B (3528-21 Metric), IPC_7351 nominal, (Body size from: http://www.kemet.com/Lists/ProductCatalog/Attachments/253/KEM_TC101_STD.pdf), generated with kicad-footprint-generator +capacitor tantalum +0 +2 +2 +Capacitor_Tantalum_SMD +CP_EIA-6032-15_Kemet-U +Tantalum Capacitor SMD Kemet-U (6032-15 Metric), IPC_7351 nominal, (Body size from: http://www.kemet.com/Lists/ProductCatalog/Attachments/253/KEM_TC101_STD.pdf), generated with kicad-footprint-generator +capacitor tantalum +0 +2 +2 +Capacitor_Tantalum_SMD +CP_EIA-6032-15_Kemet-U_Pad2.25x2.35mm_HandSolder +Tantalum Capacitor SMD Kemet-U (6032-15 Metric), IPC_7351 nominal, (Body size from: http://www.kemet.com/Lists/ProductCatalog/Attachments/253/KEM_TC101_STD.pdf), generated with kicad-footprint-generator +capacitor tantalum +0 +2 +2 +Capacitor_Tantalum_SMD +CP_EIA-6032-20_AVX-F +Tantalum Capacitor SMD AVX-F (6032-20 Metric), IPC_7351 nominal, (Body size from: http://www.kemet.com/Lists/ProductCatalog/Attachments/253/KEM_TC101_STD.pdf), generated with kicad-footprint-generator +capacitor tantalum +0 +2 +2 +Capacitor_Tantalum_SMD +CP_EIA-6032-20_AVX-F_Pad2.25x2.35mm_HandSolder +Tantalum Capacitor SMD AVX-F (6032-20 Metric), IPC_7351 nominal, (Body size from: http://www.kemet.com/Lists/ProductCatalog/Attachments/253/KEM_TC101_STD.pdf), generated with kicad-footprint-generator +capacitor tantalum +0 +2 +2 +Capacitor_Tantalum_SMD +CP_EIA-6032-28_Kemet-C +Tantalum Capacitor SMD Kemet-C (6032-28 Metric), IPC_7351 nominal, (Body size from: http://www.kemet.com/Lists/ProductCatalog/Attachments/253/KEM_TC101_STD.pdf), generated with kicad-footprint-generator +capacitor tantalum +0 +2 +2 +Capacitor_Tantalum_SMD +CP_EIA-6032-28_Kemet-C_Pad2.25x2.35mm_HandSolder +Tantalum Capacitor SMD Kemet-C (6032-28 Metric), IPC_7351 nominal, (Body size from: http://www.kemet.com/Lists/ProductCatalog/Attachments/253/KEM_TC101_STD.pdf), generated with kicad-footprint-generator +capacitor tantalum +0 +2 +2 +Capacitor_Tantalum_SMD +CP_EIA-7343-15_Kemet-W +Tantalum Capacitor SMD Kemet-W (7343-15 Metric), IPC_7351 nominal, (Body size from: http://www.kemet.com/Lists/ProductCatalog/Attachments/253/KEM_TC101_STD.pdf), generated with kicad-footprint-generator +capacitor tantalum +0 +2 +2 +Capacitor_Tantalum_SMD +CP_EIA-7343-15_Kemet-W_Pad2.25x2.55mm_HandSolder +Tantalum Capacitor SMD Kemet-W (7343-15 Metric), IPC_7351 nominal, (Body size from: http://www.kemet.com/Lists/ProductCatalog/Attachments/253/KEM_TC101_STD.pdf), generated with kicad-footprint-generator +capacitor tantalum +0 +2 +2 +Capacitor_Tantalum_SMD +CP_EIA-7343-20_Kemet-V +Tantalum Capacitor SMD Kemet-V (7343-20 Metric), IPC_7351 nominal, (Body size from: http://www.kemet.com/Lists/ProductCatalog/Attachments/253/KEM_TC101_STD.pdf), generated with kicad-footprint-generator +capacitor tantalum +0 +2 +2 +Capacitor_Tantalum_SMD +CP_EIA-7343-20_Kemet-V_Pad2.25x2.55mm_HandSolder +Tantalum Capacitor SMD Kemet-V (7343-20 Metric), IPC_7351 nominal, (Body size from: http://www.kemet.com/Lists/ProductCatalog/Attachments/253/KEM_TC101_STD.pdf), generated with kicad-footprint-generator +capacitor tantalum +0 +2 +2 +Capacitor_Tantalum_SMD +CP_EIA-7343-30_AVX-N +Tantalum Capacitor SMD AVX-N (7343-30 Metric), IPC_7351 nominal, (Body size from: http://www.kemet.com/Lists/ProductCatalog/Attachments/253/KEM_TC101_STD.pdf), generated with kicad-footprint-generator +capacitor tantalum +0 +2 +2 +Capacitor_Tantalum_SMD +CP_EIA-7343-30_AVX-N_Pad2.25x2.55mm_HandSolder +Tantalum Capacitor SMD AVX-N (7343-30 Metric), IPC_7351 nominal, (Body size from: http://www.kemet.com/Lists/ProductCatalog/Attachments/253/KEM_TC101_STD.pdf), generated with kicad-footprint-generator +capacitor tantalum +0 +2 +2 +Capacitor_Tantalum_SMD +CP_EIA-7343-31_Kemet-D +Tantalum Capacitor SMD Kemet-D (7343-31 Metric), IPC_7351 nominal, (Body size from: http://www.kemet.com/Lists/ProductCatalog/Attachments/253/KEM_TC101_STD.pdf), generated with kicad-footprint-generator +capacitor tantalum +0 +2 +2 +Capacitor_Tantalum_SMD +CP_EIA-7343-31_Kemet-D_Pad2.25x2.55mm_HandSolder +Tantalum Capacitor SMD Kemet-D (7343-31 Metric), IPC_7351 nominal, (Body size from: http://www.kemet.com/Lists/ProductCatalog/Attachments/253/KEM_TC101_STD.pdf), generated with kicad-footprint-generator +capacitor tantalum +0 +2 +2 +Capacitor_Tantalum_SMD +CP_EIA-7343-40_Kemet-Y +Tantalum Capacitor SMD Kemet-Y (7343-40 Metric), IPC_7351 nominal, (Body size from: http://www.kemet.com/Lists/ProductCatalog/Attachments/253/KEM_TC101_STD.pdf), generated with kicad-footprint-generator +capacitor tantalum +0 +2 +2 +Capacitor_Tantalum_SMD +CP_EIA-7343-40_Kemet-Y_Pad2.25x2.55mm_HandSolder +Tantalum Capacitor SMD Kemet-Y (7343-40 Metric), IPC_7351 nominal, (Body size from: http://www.kemet.com/Lists/ProductCatalog/Attachments/253/KEM_TC101_STD.pdf), generated with kicad-footprint-generator +capacitor tantalum +0 +2 +2 +Capacitor_Tantalum_SMD +CP_EIA-7343-43_Kemet-X +Tantalum Capacitor SMD Kemet-X (7343-43 Metric), IPC_7351 nominal, (Body size from: http://www.kemet.com/Lists/ProductCatalog/Attachments/253/KEM_TC101_STD.pdf), generated with kicad-footprint-generator +capacitor tantalum +0 +2 +2 +Capacitor_Tantalum_SMD +CP_EIA-7343-43_Kemet-X_Pad2.25x2.55mm_HandSolder +Tantalum Capacitor SMD Kemet-X (7343-43 Metric), IPC_7351 nominal, (Body size from: http://www.kemet.com/Lists/ProductCatalog/Attachments/253/KEM_TC101_STD.pdf), generated with kicad-footprint-generator +capacitor tantalum +0 +2 +2 +Capacitor_Tantalum_SMD +CP_EIA-7360-38_Kemet-E +Tantalum Capacitor SMD Kemet-E (7360-38 Metric), IPC_7351 nominal, (Body size from: http://www.kemet.com/Lists/ProductCatalog/Attachments/253/KEM_TC101_STD.pdf), generated with kicad-footprint-generator +capacitor tantalum +0 +2 +2 +Capacitor_Tantalum_SMD +CP_EIA-7360-38_Kemet-E_Pad2.25x4.25mm_HandSolder +Tantalum Capacitor SMD Kemet-E (7360-38 Metric), IPC_7351 nominal, (Body size from: http://www.kemet.com/Lists/ProductCatalog/Attachments/253/KEM_TC101_STD.pdf), generated with kicad-footprint-generator +capacitor tantalum +0 +2 +2 +Capacitor_Tantalum_SMD +CP_EIA-7361-38_AVX-V +Tantalum Capacitor SMD AVX-V (7361-38 Metric), IPC_7351 nominal, (Body size from: http://datasheets.avx.com/NOS.pdf), generated with kicad-footprint-generator +capacitor tantalum +0 +2 +2 +Capacitor_Tantalum_SMD +CP_EIA-7361-38_AVX-V_Pad2.18x3.30mm_HandSolder +Tantalum Capacitor SMD AVX-V (7361-38 Metric), IPC_7351 nominal, (Body size from: http://datasheets.avx.com/NOS.pdf), generated with kicad-footprint-generator +capacitor tantalum +0 +2 +2 +Capacitor_Tantalum_SMD +CP_EIA-7361-438_AVX-U +Tantalum Capacitor SMD AVX-U (7361-438 Metric), IPC_7351 nominal, (Body size from: http://datasheets.avx.com/NOS.pdf), generated with kicad-footprint-generator +capacitor tantalum +0 +2 +2 +Capacitor_Tantalum_SMD +CP_EIA-7361-438_AVX-U_Pad2.18x3.30mm_HandSolder +Tantalum Capacitor SMD AVX-U (7361-438 Metric), IPC_7351 nominal, (Body size from: http://datasheets.avx.com/NOS.pdf), generated with kicad-footprint-generator +capacitor tantalum +0 +2 +2 +Capacitor_THT +CP_Axial_L10.0mm_D4.5mm_P15.00mm_Horizontal +CP, Axial series, Axial, Horizontal, pin pitch=15mm, , length*diameter=10*4.5mm^2, Electrolytic Capacitor, , http://www.vishay.com/docs/28325/021asm.pdf +CP Axial series Axial Horizontal pin pitch 15mm length 10mm diameter 4.5mm Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +CP_Axial_L10.0mm_D6.0mm_P15.00mm_Horizontal +CP, Axial series, Axial, Horizontal, pin pitch=15mm, , length*diameter=10*6mm^2, Electrolytic Capacitor, , http://www.vishay.com/docs/28325/021asm.pdf +CP Axial series Axial Horizontal pin pitch 15mm length 10mm diameter 6mm Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +CP_Axial_L11.0mm_D5.0mm_P18.00mm_Horizontal +CP, Axial series, Axial, Horizontal, pin pitch=18mm, , length*diameter=11*5mm^2, Electrolytic Capacitor +CP Axial series Axial Horizontal pin pitch 18mm length 11mm diameter 5mm Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +CP_Axial_L11.0mm_D6.0mm_P18.00mm_Horizontal +CP, Axial series, Axial, Horizontal, pin pitch=18mm, , length*diameter=11*6mm^2, Electrolytic Capacitor +CP Axial series Axial Horizontal pin pitch 18mm length 11mm diameter 6mm Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +CP_Axial_L11.0mm_D8.0mm_P15.00mm_Horizontal +CP, Axial series, Axial, Horizontal, pin pitch=15mm, , length*diameter=11*8mm^2, Electrolytic Capacitor, , http://www.vishay.com/docs/28325/021asm.pdf +CP Axial series Axial Horizontal pin pitch 15mm length 11mm diameter 8mm Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +CP_Axial_L18.0mm_D6.5mm_P25.00mm_Horizontal +CP, Axial series, Axial, Horizontal, pin pitch=25mm, , length*diameter=18*6.5mm^2, Electrolytic Capacitor, , http://www.vishay.com/docs/28325/021asm.pdf +CP Axial series Axial Horizontal pin pitch 25mm length 18mm diameter 6.5mm Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +CP_Axial_L18.0mm_D8.0mm_P25.00mm_Horizontal +CP, Axial series, Axial, Horizontal, pin pitch=25mm, , length*diameter=18*8mm^2, Electrolytic Capacitor, , http://www.vishay.com/docs/28325/021asm.pdf +CP Axial series Axial Horizontal pin pitch 25mm length 18mm diameter 8mm Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +CP_Axial_L18.0mm_D10.0mm_P25.00mm_Horizontal +CP, Axial series, Axial, Horizontal, pin pitch=25mm, , length*diameter=18*10mm^2, Electrolytic Capacitor, , http://www.vishay.com/docs/28325/021asm.pdf +CP Axial series Axial Horizontal pin pitch 25mm length 18mm diameter 10mm Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +CP_Axial_L20.0mm_D10.0mm_P26.00mm_Horizontal +CP, Axial series, Axial, Horizontal, pin pitch=26mm, , length*diameter=20*10mm^2, Electrolytic Capacitor, , http://www.kemet.com/Lists/ProductCatalog/Attachments/424/KEM_AC102.pdf +CP Axial series Axial Horizontal pin pitch 26mm length 20mm diameter 10mm Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +CP_Axial_L20.0mm_D13.0mm_P26.00mm_Horizontal +CP, Axial series, Axial, Horizontal, pin pitch=26mm, , length*diameter=20*13mm^2, Electrolytic Capacitor, , http://www.kemet.com/Lists/ProductCatalog/Attachments/424/KEM_AC102.pdf +CP Axial series Axial Horizontal pin pitch 26mm length 20mm diameter 13mm Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +CP_Axial_L21.0mm_D8.0mm_P28.00mm_Horizontal +CP, Axial series, Axial, Horizontal, pin pitch=28mm, , length*diameter=21*8mm^2, Electrolytic Capacitor +CP Axial series Axial Horizontal pin pitch 28mm length 21mm diameter 8mm Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +CP_Axial_L25.0mm_D10.0mm_P30.00mm_Horizontal +CP, Axial series, Axial, Horizontal, pin pitch=30mm, , length*diameter=25*10mm^2, Electrolytic Capacitor, , http://www.vishay.com/docs/28325/021asm.pdf +CP Axial series Axial Horizontal pin pitch 30mm length 25mm diameter 10mm Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +CP_Axial_L26.5mm_D20.0mm_P33.00mm_Horizontal +CP, Axial series, Axial, Horizontal, pin pitch=33mm, , length*diameter=26.5*20mm^2, Electrolytic Capacitor, , http://www.kemet.com/Lists/ProductCatalog/Attachments/424/KEM_AC102.pdf +CP Axial series Axial Horizontal pin pitch 33mm length 26.5mm diameter 20mm Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +CP_Axial_L29.0mm_D10.0mm_P35.00mm_Horizontal +CP, Axial series, Axial, Horizontal, pin pitch=35mm, , length*diameter=29*10mm^2, Electrolytic Capacitor, , http://www.kemet.com/Lists/ProductCatalog/Attachments/424/KEM_AC102.pdf +CP Axial series Axial Horizontal pin pitch 35mm length 29mm diameter 10mm Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +CP_Axial_L29.0mm_D13.0mm_P35.00mm_Horizontal +CP, Axial series, Axial, Horizontal, pin pitch=35mm, , length*diameter=29*13mm^2, Electrolytic Capacitor, , http://www.kemet.com/Lists/ProductCatalog/Attachments/424/KEM_AC102.pdf +CP Axial series Axial Horizontal pin pitch 35mm length 29mm diameter 13mm Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +CP_Axial_L29.0mm_D16.0mm_P35.00mm_Horizontal +CP, Axial series, Axial, Horizontal, pin pitch=35mm, , length*diameter=29*16mm^2, Electrolytic Capacitor, , http://www.kemet.com/Lists/ProductCatalog/Attachments/424/KEM_AC102.pdf +CP Axial series Axial Horizontal pin pitch 35mm length 29mm diameter 16mm Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +CP_Axial_L29.0mm_D20.0mm_P35.00mm_Horizontal +CP, Axial series, Axial, Horizontal, pin pitch=35mm, , length*diameter=29*20mm^2, Electrolytic Capacitor, , http://www.kemet.com/Lists/ProductCatalog/Attachments/424/KEM_AC102.pdf +CP Axial series Axial Horizontal pin pitch 35mm length 29mm diameter 20mm Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +CP_Axial_L30.0mm_D10.0mm_P35.00mm_Horizontal +CP, Axial series, Axial, Horizontal, pin pitch=35mm, , length*diameter=30*10mm^2, Electrolytic Capacitor, , http://www.vishay.com/docs/28325/021asm.pdf +CP Axial series Axial Horizontal pin pitch 35mm length 30mm diameter 10mm Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +CP_Axial_L30.0mm_D12.5mm_P35.00mm_Horizontal +CP, Axial series, Axial, Horizontal, pin pitch=35mm, , length*diameter=30*12.5mm^2, Electrolytic Capacitor, , http://www.vishay.com/docs/28325/021asm.pdf +CP Axial series Axial Horizontal pin pitch 35mm length 30mm diameter 12.5mm Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +CP_Axial_L30.0mm_D15.0mm_P35.00mm_Horizontal +CP, Axial series, Axial, Horizontal, pin pitch=35mm, , length*diameter=30*15mm^2, Electrolytic Capacitor, , http://www.vishay.com/docs/28325/021asm.pdf +CP Axial series Axial Horizontal pin pitch 35mm length 30mm diameter 15mm Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +CP_Axial_L30.0mm_D18.0mm_P35.00mm_Horizontal +CP, Axial series, Axial, Horizontal, pin pitch=35mm, , length*diameter=30*18mm^2, Electrolytic Capacitor, , http://www.vishay.com/docs/28325/021asm.pdf +CP Axial series Axial Horizontal pin pitch 35mm length 30mm diameter 18mm Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +CP_Axial_L34.5mm_D20.0mm_P41.00mm_Horizontal +CP, Axial series, Axial, Horizontal, pin pitch=41mm, , length*diameter=34.5*20mm^2, Electrolytic Capacitor, , http://www.kemet.com/Lists/ProductCatalog/Attachments/424/KEM_AC102.pdf +CP Axial series Axial Horizontal pin pitch 41mm length 34.5mm diameter 20mm Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +CP_Axial_L37.0mm_D13.0mm_P43.00mm_Horizontal +CP, Axial series, Axial, Horizontal, pin pitch=43mm, , length*diameter=37*13mm^2, Electrolytic Capacitor, , http://www.kemet.com/Lists/ProductCatalog/Attachments/424/KEM_AC102.pdf +CP Axial series Axial Horizontal pin pitch 43mm length 37mm diameter 13mm Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +CP_Axial_L37.0mm_D16.0mm_P43.00mm_Horizontal +CP, Axial series, Axial, Horizontal, pin pitch=43mm, , length*diameter=37*16mm^2, Electrolytic Capacitor, , http://www.kemet.com/Lists/ProductCatalog/Attachments/424/KEM_AC102.pdf +CP Axial series Axial Horizontal pin pitch 43mm length 37mm diameter 16mm Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +CP_Axial_L37.0mm_D20.0mm_P43.00mm_Horizontal +CP, Axial series, Axial, Horizontal, pin pitch=43mm, , length*diameter=37*20mm^2, Electrolytic Capacitor, , http://www.kemet.com/Lists/ProductCatalog/Attachments/424/KEM_AC102.pdf +CP Axial series Axial Horizontal pin pitch 43mm length 37mm diameter 20mm Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +CP_Axial_L38.0mm_D18.0mm_P44.00mm_Horizontal +CP, Axial series, Axial, Horizontal, pin pitch=44mm, , length*diameter=38*18mm^2, Electrolytic Capacitor, , http://www.vishay.com/docs/28325/021asm.pdf +CP Axial series Axial Horizontal pin pitch 44mm length 38mm diameter 18mm Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +CP_Axial_L38.0mm_D21.0mm_P44.00mm_Horizontal +CP, Axial series, Axial, Horizontal, pin pitch=44mm, , length*diameter=38*21mm^2, Electrolytic Capacitor, , http://www.vishay.com/docs/28325/021asm.pdf +CP Axial series Axial Horizontal pin pitch 44mm length 38mm diameter 21mm Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +CP_Axial_L40.0mm_D16.0mm_P48.00mm_Horizontal +CP, Axial series, Axial, Horizontal, pin pitch=48mm, , length*diameter=40*16mm^2, Electrolytic Capacitor +CP Axial series Axial Horizontal pin pitch 48mm length 40mm diameter 16mm Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +CP_Axial_L42.0mm_D23.0mm_P45.00mm_Horizontal +CP, Axial series, Axial, Horizontal, pin pitch=45mm, , length*diameter=42*23.0mm^2, Electrolytic Capacitor, , http://www.vishay.com/docs/42037/53d.pdf +CP Axial series Axial Horizontal pin pitch 45mm length 42mm diameter 23.0mm Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +CP_Axial_L42.0mm_D26.0mm_P45.00mm_Horizontal +CP, Axial series, Axial, Horizontal, pin pitch=45mm, , length*diameter=42*26mm^2, Electrolytic Capacitor, , http://www.vishay.com/docs/42037/53d.pdf +CP Axial series Axial Horizontal pin pitch 45mm length 42mm diameter 26mm Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +CP_Axial_L42.0mm_D29.0mm_P45.00mm_Horizontal +CP, Axial series, Axial, Horizontal, pin pitch=45mm, , length*diameter=42*29.0mm^2, Electrolytic Capacitor, , http://www.vishay.com/docs/42037/53d.pdf +CP Axial series Axial Horizontal pin pitch 45mm length 42mm diameter 29.0mm Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +CP_Axial_L42.0mm_D32.0mm_P45.00mm_Horizontal +CP, Axial series, Axial, Horizontal, pin pitch=45mm, , length*diameter=42*32.0mm^2, Electrolytic Capacitor, , http://www.vishay.com/docs/42037/53d.pdf +CP Axial series Axial Horizontal pin pitch 45mm length 42mm diameter 32.0mm Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +CP_Axial_L42.0mm_D35.0mm_P45.00mm_Horizontal +CP, Axial series, Axial, Horizontal, pin pitch=45mm, , length*diameter=42*35.0mm^2, Electrolytic Capacitor, , http://www.vishay.com/docs/42037/53d.pdf +CP Axial series Axial Horizontal pin pitch 45mm length 42mm diameter 35.0mm Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +CP_Axial_L42.5mm_D20.0mm_P49.00mm_Horizontal +CP, Axial series, Axial, Horizontal, pin pitch=49mm, , length*diameter=42.5*20mm^2, Electrolytic Capacitor +CP Axial series Axial Horizontal pin pitch 49mm length 42.5mm diameter 20mm Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +CP_Axial_L46.0mm_D20.0mm_P52.00mm_Horizontal +CP, Axial series, Axial, Horizontal, pin pitch=52mm, , length*diameter=46*20mm^2, Electrolytic Capacitor +CP Axial series Axial Horizontal pin pitch 52mm length 46mm diameter 20mm Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +CP_Axial_L55.0mm_D23.0mm_P60.00mm_Horizontal +CP, Axial series, Axial, Horizontal, pin pitch=60mm, , length*diameter=55*23.0mm^2, Electrolytic Capacitor, , http://www.vishay.com/docs/42037/53d.pdf +CP Axial series Axial Horizontal pin pitch 60mm length 55mm diameter 23.0mm Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +CP_Axial_L55.0mm_D26.0mm_P60.00mm_Horizontal +CP, Axial series, Axial, Horizontal, pin pitch=60mm, , length*diameter=55*26mm^2, Electrolytic Capacitor, , http://www.vishay.com/docs/42037/53d.pdf +CP Axial series Axial Horizontal pin pitch 60mm length 55mm diameter 26mm Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +CP_Axial_L55.0mm_D29.0mm_P60.00mm_Horizontal +CP, Axial series, Axial, Horizontal, pin pitch=60mm, , length*diameter=55*29.0mm^2, Electrolytic Capacitor, , http://www.vishay.com/docs/42037/53d.pdf +CP Axial series Axial Horizontal pin pitch 60mm length 55mm diameter 29.0mm Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +CP_Axial_L55.0mm_D32.0mm_P60.00mm_Horizontal +CP, Axial series, Axial, Horizontal, pin pitch=60mm, , length*diameter=55*32.0mm^2, Electrolytic Capacitor, , http://www.vishay.com/docs/42037/53d.pdf +CP Axial series Axial Horizontal pin pitch 60mm length 55mm diameter 32.0mm Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +CP_Axial_L55.0mm_D35.0mm_P60.00mm_Horizontal +CP, Axial series, Axial, Horizontal, pin pitch=60mm, , length*diameter=55*35.0mm^2, Electrolytic Capacitor, , http://www.vishay.com/docs/42037/53d.pdf +CP Axial series Axial Horizontal pin pitch 60mm length 55mm diameter 35.0mm Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +CP_Axial_L67.0mm_D23.0mm_P75.00mm_Horizontal +CP, Axial series, Axial, Horizontal, pin pitch=75mm, , length*diameter=67*23.0mm^2, Electrolytic Capacitor, , http://www.vishay.com/docs/42037/53d.pdf +CP Axial series Axial Horizontal pin pitch 75mm length 67mm diameter 23.0mm Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +CP_Axial_L67.0mm_D26.0mm_P75.00mm_Horizontal +CP, Axial series, Axial, Horizontal, pin pitch=75mm, , length*diameter=67*26mm^2, Electrolytic Capacitor, , http://www.vishay.com/docs/42037/53d.pdf +CP Axial series Axial Horizontal pin pitch 75mm length 67mm diameter 26mm Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +CP_Axial_L67.0mm_D29.0mm_P75.00mm_Horizontal +CP, Axial series, Axial, Horizontal, pin pitch=75mm, , length*diameter=67*29.0mm^2, Electrolytic Capacitor, , http://www.vishay.com/docs/42037/53d.pdf +CP Axial series Axial Horizontal pin pitch 75mm length 67mm diameter 29.0mm Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +CP_Axial_L67.0mm_D32.0mm_P75.00mm_Horizontal +CP, Axial series, Axial, Horizontal, pin pitch=75mm, , length*diameter=67*32.0mm^2, Electrolytic Capacitor, , http://www.vishay.com/docs/42037/53d.pdf +CP Axial series Axial Horizontal pin pitch 75mm length 67mm diameter 32.0mm Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +CP_Axial_L67.0mm_D35.0mm_P75.00mm_Horizontal +CP, Axial series, Axial, Horizontal, pin pitch=75mm, , length*diameter=67*35.0mm^2, Electrolytic Capacitor, , http://www.vishay.com/docs/42037/53d.pdf +CP Axial series Axial Horizontal pin pitch 75mm length 67mm diameter 35.0mm Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +CP_Axial_L80.0mm_D23.0mm_P85.00mm_Horizontal +CP, Axial series, Axial, Horizontal, pin pitch=85mm, , length*diameter=80*23.0mm^2, Electrolytic Capacitor, , http://www.vishay.com/docs/42037/53d.pdf +CP Axial series Axial Horizontal pin pitch 85mm length 80mm diameter 23.0mm Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +CP_Axial_L80.0mm_D26.0mm_P85.00mm_Horizontal +CP, Axial series, Axial, Horizontal, pin pitch=85mm, , length*diameter=80*26mm^2, Electrolytic Capacitor, , http://www.vishay.com/docs/42037/53d.pdf +CP Axial series Axial Horizontal pin pitch 85mm length 80mm diameter 26mm Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +CP_Axial_L80.0mm_D29.0mm_P85.00mm_Horizontal +CP, Axial series, Axial, Horizontal, pin pitch=85mm, , length*diameter=80*29.0mm^2, Electrolytic Capacitor, , http://www.vishay.com/docs/42037/53d.pdf +CP Axial series Axial Horizontal pin pitch 85mm length 80mm diameter 29.0mm Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +CP_Axial_L80.0mm_D32.0mm_P85.00mm_Horizontal +CP, Axial series, Axial, Horizontal, pin pitch=85mm, , length*diameter=80*32.0mm^2, Electrolytic Capacitor, , http://www.vishay.com/docs/42037/53d.pdf +CP Axial series Axial Horizontal pin pitch 85mm length 80mm diameter 32.0mm Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +CP_Axial_L80.0mm_D35.0mm_P85.00mm_Horizontal +CP, Axial series, Axial, Horizontal, pin pitch=85mm, , length*diameter=80*35.0mm^2, Electrolytic Capacitor, , http://www.vishay.com/docs/42037/53d.pdf +CP Axial series Axial Horizontal pin pitch 85mm length 80mm diameter 35.0mm Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +CP_Axial_L93.0mm_D23.0mm_P100.00mm_Horizontal +CP, Axial series, Axial, Horizontal, pin pitch=100mm, , length*diameter=93*23.0mm^2, Electrolytic Capacitor, , http://www.vishay.com/docs/42037/53d.pdf +CP Axial series Axial Horizontal pin pitch 100mm length 93mm diameter 23.0mm Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +CP_Axial_L93.0mm_D26.0mm_P100.00mm_Horizontal +CP, Axial series, Axial, Horizontal, pin pitch=100mm, , length*diameter=93*26mm^2, Electrolytic Capacitor, , http://www.vishay.com/docs/42037/53d.pdf +CP Axial series Axial Horizontal pin pitch 100mm length 93mm diameter 26mm Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +CP_Axial_L93.0mm_D29.0mm_P100.00mm_Horizontal +CP, Axial series, Axial, Horizontal, pin pitch=100mm, , length*diameter=93*29.0mm^2, Electrolytic Capacitor, , http://www.vishay.com/docs/42037/53d.pdf +CP Axial series Axial Horizontal pin pitch 100mm length 93mm diameter 29.0mm Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +CP_Axial_L93.0mm_D32.0mm_P100.00mm_Horizontal +CP, Axial series, Axial, Horizontal, pin pitch=100mm, , length*diameter=93*32.0mm^2, Electrolytic Capacitor, , http://www.vishay.com/docs/42037/53d.pdf +CP Axial series Axial Horizontal pin pitch 100mm length 93mm diameter 32.0mm Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +CP_Axial_L93.0mm_D35.0mm_P100.00mm_Horizontal +CP, Axial series, Axial, Horizontal, pin pitch=100mm, , length*diameter=93*35.0mm^2, Electrolytic Capacitor, , http://www.vishay.com/docs/42037/53d.pdf +CP Axial series Axial Horizontal pin pitch 100mm length 93mm diameter 35.0mm Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +CP_Radial_D4.0mm_P1.50mm +CP, Radial series, Radial, pin pitch=1.50mm, , diameter=4mm, Electrolytic Capacitor +CP Radial series Radial pin pitch 1.50mm diameter 4mm Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +CP_Radial_D4.0mm_P2.00mm +CP, Radial series, Radial, pin pitch=2.00mm, , diameter=4mm, Electrolytic Capacitor +CP Radial series Radial pin pitch 2.00mm diameter 4mm Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +CP_Radial_D5.0mm_P2.00mm +CP, Radial series, Radial, pin pitch=2.00mm, , diameter=5mm, Electrolytic Capacitor +CP Radial series Radial pin pitch 2.00mm diameter 5mm Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +CP_Radial_D5.0mm_P2.50mm +CP, Radial series, Radial, pin pitch=2.50mm, , diameter=5mm, Electrolytic Capacitor +CP Radial series Radial pin pitch 2.50mm diameter 5mm Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +CP_Radial_D6.3mm_P2.50mm +CP, Radial series, Radial, pin pitch=2.50mm, , diameter=6.3mm, Electrolytic Capacitor +CP Radial series Radial pin pitch 2.50mm diameter 6.3mm Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +CP_Radial_D7.5mm_P2.50mm +CP, Radial series, Radial, pin pitch=2.50mm, , diameter=7.5mm, Electrolytic Capacitor +CP Radial series Radial pin pitch 2.50mm diameter 7.5mm Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +CP_Radial_D8.0mm_P2.50mm +CP, Radial series, Radial, pin pitch=2.50mm, , diameter=8mm, Electrolytic Capacitor +CP Radial series Radial pin pitch 2.50mm diameter 8mm Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +CP_Radial_D8.0mm_P3.50mm +CP, Radial series, Radial, pin pitch=3.50mm, , diameter=8mm, Electrolytic Capacitor +CP Radial series Radial pin pitch 3.50mm diameter 8mm Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +CP_Radial_D8.0mm_P3.80mm +CP, Radial series, Radial, pin pitch=3.80mm, , diameter=8mm, Electrolytic Capacitor +CP Radial series Radial pin pitch 3.80mm diameter 8mm Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +CP_Radial_D8.0mm_P5.00mm +CP, Radial series, Radial, pin pitch=5.00mm, , diameter=8mm, Electrolytic Capacitor +CP Radial series Radial pin pitch 5.00mm diameter 8mm Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +CP_Radial_D10.0mm_P2.50mm +CP, Radial series, Radial, pin pitch=2.50mm, , diameter=10mm, Electrolytic Capacitor +CP Radial series Radial pin pitch 2.50mm diameter 10mm Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +CP_Radial_D10.0mm_P2.50mm_P5.00mm +CP, Radial series, Radial, pin pitch=2.50mm 5.00mm, , diameter=10mm, Electrolytic Capacitor +CP Radial series Radial pin pitch 2.50mm 5.00mm diameter 10mm Electrolytic Capacitor +0 +4 +2 +Capacitor_THT +CP_Radial_D10.0mm_P3.50mm +CP, Radial series, Radial, pin pitch=3.50mm, , diameter=10mm, Electrolytic Capacitor +CP Radial series Radial pin pitch 3.50mm diameter 10mm Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +CP_Radial_D10.0mm_P3.80mm +CP, Radial series, Radial, pin pitch=3.80mm, , diameter=10mm, Electrolytic Capacitor +CP Radial series Radial pin pitch 3.80mm diameter 10mm Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +CP_Radial_D10.0mm_P5.00mm +CP, Radial series, Radial, pin pitch=5.00mm, , diameter=10mm, Electrolytic Capacitor +CP Radial series Radial pin pitch 5.00mm diameter 10mm Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +CP_Radial_D10.0mm_P5.00mm_P7.50mm +CP, Radial series, Radial, pin pitch=5.00mm 7.50mm, , diameter=10mm, Electrolytic Capacitor +CP Radial series Radial pin pitch 5.00mm 7.50mm diameter 10mm Electrolytic Capacitor +0 +4 +2 +Capacitor_THT +CP_Radial_D10.0mm_P7.50mm +CP, Radial series, Radial, pin pitch=7.50mm, , diameter=10mm, Electrolytic Capacitor +CP Radial series Radial pin pitch 7.50mm diameter 10mm Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +CP_Radial_D12.5mm_P2.50mm +CP, Radial series, Radial, pin pitch=2.50mm, , diameter=12.5mm, Electrolytic Capacitor +CP Radial series Radial pin pitch 2.50mm diameter 12.5mm Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +CP_Radial_D12.5mm_P5.00mm +CP, Radial series, Radial, pin pitch=5.00mm, , diameter=12.5mm, Electrolytic Capacitor +CP Radial series Radial pin pitch 5.00mm diameter 12.5mm Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +CP_Radial_D12.5mm_P7.50mm +CP, Radial series, Radial, pin pitch=7.50mm, , diameter=12.5mm, Electrolytic Capacitor +CP Radial series Radial pin pitch 7.50mm diameter 12.5mm Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +CP_Radial_D13.0mm_P2.50mm +CP, Radial series, Radial, pin pitch=2.50mm, , diameter=13mm, Electrolytic Capacitor +CP Radial series Radial pin pitch 2.50mm diameter 13mm Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +CP_Radial_D13.0mm_P5.00mm +CP, Radial series, Radial, pin pitch=5.00mm, , diameter=13mm, Electrolytic Capacitor +CP Radial series Radial pin pitch 5.00mm diameter 13mm Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +CP_Radial_D13.0mm_P7.50mm +CP, Radial series, Radial, pin pitch=7.50mm, , diameter=13mm, Electrolytic Capacitor +CP Radial series Radial pin pitch 7.50mm diameter 13mm Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +CP_Radial_D14.0mm_P5.00mm +CP, Radial series, Radial, pin pitch=5.00mm, , diameter=14mm, Electrolytic Capacitor +CP Radial series Radial pin pitch 5.00mm diameter 14mm Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +CP_Radial_D14.0mm_P7.50mm +CP, Radial series, Radial, pin pitch=7.50mm, , diameter=14mm, Electrolytic Capacitor +CP Radial series Radial pin pitch 7.50mm diameter 14mm Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +CP_Radial_D16.0mm_P7.50mm +CP, Radial series, Radial, pin pitch=7.50mm, , diameter=16mm, Electrolytic Capacitor +CP Radial series Radial pin pitch 7.50mm diameter 16mm Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +CP_Radial_D17.0mm_P7.50mm +CP, Radial series, Radial, pin pitch=7.50mm, , diameter=17mm, Electrolytic Capacitor +CP Radial series Radial pin pitch 7.50mm diameter 17mm Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +CP_Radial_D18.0mm_P7.50mm +CP, Radial series, Radial, pin pitch=7.50mm, , diameter=18mm, Electrolytic Capacitor +CP Radial series Radial pin pitch 7.50mm diameter 18mm Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +CP_Radial_D22.0mm_P10.00mm_3pin_SnapIn +CP, Radial series, Radial, pin pitch=10.00mm, , diameter=22mm, Electrolytic Capacitor, , http://www.vishay.com/docs/28342/058059pll-si.pdf +CP Radial series Radial pin pitch 10.00mm diameter 22mm Electrolytic Capacitor +0 +3 +2 +Capacitor_THT +CP_Radial_D22.0mm_P10.00mm_SnapIn +CP, Radial series, Radial, pin pitch=10.00mm, , diameter=22mm, Electrolytic Capacitor, , http://www.vishay.com/docs/28342/058059pll-si.pdf +CP Radial series Radial pin pitch 10.00mm diameter 22mm Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +CP_Radial_D24.0mm_P10.00mm_3pin_SnapIn +CP, Radial series, Radial, pin pitch=10.00mm, , diameter=24mm, Electrolytic Capacitor, , http://www.vishay.com/docs/28342/058059pll-si.pdf +CP Radial series Radial pin pitch 10.00mm diameter 24mm Electrolytic Capacitor +0 +3 +2 +Capacitor_THT +CP_Radial_D24.0mm_P10.00mm_SnapIn +CP, Radial series, Radial, pin pitch=10.00mm, , diameter=24mm, Electrolytic Capacitor, , http://www.vishay.com/docs/28342/058059pll-si.pdf +CP Radial series Radial pin pitch 10.00mm diameter 24mm Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +CP_Radial_D25.0mm_P10.00mm_3pin_SnapIn +CP, Radial series, Radial, pin pitch=10.00mm, , diameter=25mm, Electrolytic Capacitor, , http://www.vishay.com/docs/28342/058059pll-si.pdf +CP Radial series Radial pin pitch 10.00mm diameter 25mm Electrolytic Capacitor +0 +3 +2 +Capacitor_THT +CP_Radial_D25.0mm_P10.00mm_SnapIn +CP, Radial series, Radial, pin pitch=10.00mm, , diameter=25mm, Electrolytic Capacitor, , http://www.vishay.com/docs/28342/058059pll-si.pdf +CP Radial series Radial pin pitch 10.00mm diameter 25mm Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +CP_Radial_D26.0mm_P10.00mm_3pin_SnapIn +CP, Radial series, Radial, pin pitch=10.00mm, , diameter=26mm, Electrolytic Capacitor, , http://www.vishay.com/docs/28342/058059pll-si.pdf +CP Radial series Radial pin pitch 10.00mm diameter 26mm Electrolytic Capacitor +0 +3 +2 +Capacitor_THT +CP_Radial_D26.0mm_P10.00mm_SnapIn +CP, Radial series, Radial, pin pitch=10.00mm, , diameter=26mm, Electrolytic Capacitor, , http://www.vishay.com/docs/28342/058059pll-si.pdf +CP Radial series Radial pin pitch 10.00mm diameter 26mm Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +CP_Radial_D30.0mm_P10.00mm_3pin_SnapIn +CP, Radial series, Radial, pin pitch=10.00mm, , diameter=30mm, Electrolytic Capacitor, , http://www.vishay.com/docs/28342/058059pll-si.pdf +CP Radial series Radial pin pitch 10.00mm diameter 30mm Electrolytic Capacitor +0 +3 +2 +Capacitor_THT +CP_Radial_D30.0mm_P10.00mm_SnapIn +CP, Radial series, Radial, pin pitch=10.00mm, , diameter=30mm, Electrolytic Capacitor, , http://www.vishay.com/docs/28342/058059pll-si.pdf +CP Radial series Radial pin pitch 10.00mm diameter 30mm Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +CP_Radial_D35.0mm_P10.00mm_3pin_SnapIn +CP, Radial series, Radial, pin pitch=10.00mm, , diameter=35mm, Electrolytic Capacitor, , http://www.vishay.com/docs/28342/058059pll-si.pdf +CP Radial series Radial pin pitch 10.00mm diameter 35mm Electrolytic Capacitor +0 +3 +2 +Capacitor_THT +CP_Radial_D35.0mm_P10.00mm_SnapIn +CP, Radial series, Radial, pin pitch=10.00mm, , diameter=35mm, Electrolytic Capacitor, , http://www.vishay.com/docs/28342/058059pll-si.pdf +CP Radial series Radial pin pitch 10.00mm diameter 35mm Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +CP_Radial_D40.0mm_P10.00mm_3pin_SnapIn +CP, Radial series, Radial, pin pitch=10.00mm, , diameter=40mm, Electrolytic Capacitor, , http://www.vishay.com/docs/28342/058059pll-si.pdf +CP Radial series Radial pin pitch 10.00mm diameter 40mm Electrolytic Capacitor +0 +3 +2 +Capacitor_THT +CP_Radial_D40.0mm_P10.00mm_SnapIn +CP, Radial series, Radial, pin pitch=10.00mm, , diameter=40mm, Electrolytic Capacitor, , http://www.vishay.com/docs/28342/058059pll-si.pdf +CP Radial series Radial pin pitch 10.00mm diameter 40mm Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +CP_Radial_Tantal_D4.5mm_P2.50mm +CP, Radial_Tantal series, Radial, pin pitch=2.50mm, , diameter=4.5mm, Tantal Electrolytic Capacitor, http://cdn-reichelt.de/documents/datenblatt/B300/TANTAL-TB-Serie%23.pdf +CP Radial_Tantal series Radial pin pitch 2.50mm diameter 4.5mm Tantal Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +CP_Radial_Tantal_D4.5mm_P5.00mm +CP, Radial_Tantal series, Radial, pin pitch=5.00mm, , diameter=4.5mm, Tantal Electrolytic Capacitor, http://cdn-reichelt.de/documents/datenblatt/B300/TANTAL-TB-Serie%23.pdf +CP Radial_Tantal series Radial pin pitch 5.00mm diameter 4.5mm Tantal Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +CP_Radial_Tantal_D5.0mm_P2.50mm +CP, Radial_Tantal series, Radial, pin pitch=2.50mm, , diameter=5.0mm, Tantal Electrolytic Capacitor, http://cdn-reichelt.de/documents/datenblatt/B300/TANTAL-TB-Serie%23.pdf +CP Radial_Tantal series Radial pin pitch 2.50mm diameter 5.0mm Tantal Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +CP_Radial_Tantal_D5.0mm_P5.00mm +CP, Radial_Tantal series, Radial, pin pitch=5.00mm, , diameter=5.0mm, Tantal Electrolytic Capacitor, http://cdn-reichelt.de/documents/datenblatt/B300/TANTAL-TB-Serie%23.pdf +CP Radial_Tantal series Radial pin pitch 5.00mm diameter 5.0mm Tantal Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +CP_Radial_Tantal_D5.5mm_P2.50mm +CP, Radial_Tantal series, Radial, pin pitch=2.50mm, , diameter=5.5mm, Tantal Electrolytic Capacitor, http://cdn-reichelt.de/documents/datenblatt/B300/TANTAL-TB-Serie%23.pdf +CP Radial_Tantal series Radial pin pitch 2.50mm diameter 5.5mm Tantal Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +CP_Radial_Tantal_D5.5mm_P5.00mm +CP, Radial_Tantal series, Radial, pin pitch=5.00mm, , diameter=5.5mm, Tantal Electrolytic Capacitor, http://cdn-reichelt.de/documents/datenblatt/B300/TANTAL-TB-Serie%23.pdf +CP Radial_Tantal series Radial pin pitch 5.00mm diameter 5.5mm Tantal Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +CP_Radial_Tantal_D6.0mm_P2.50mm +CP, Radial_Tantal series, Radial, pin pitch=2.50mm, , diameter=6.0mm, Tantal Electrolytic Capacitor, http://cdn-reichelt.de/documents/datenblatt/B300/TANTAL-TB-Serie%23.pdf +CP Radial_Tantal series Radial pin pitch 2.50mm diameter 6.0mm Tantal Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +CP_Radial_Tantal_D6.0mm_P5.00mm +CP, Radial_Tantal series, Radial, pin pitch=5.00mm, , diameter=6.0mm, Tantal Electrolytic Capacitor, http://cdn-reichelt.de/documents/datenblatt/B300/TANTAL-TB-Serie%23.pdf +CP Radial_Tantal series Radial pin pitch 5.00mm diameter 6.0mm Tantal Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +CP_Radial_Tantal_D7.0mm_P2.50mm +CP, Radial_Tantal series, Radial, pin pitch=2.50mm, , diameter=7.0mm, Tantal Electrolytic Capacitor, http://cdn-reichelt.de/documents/datenblatt/B300/TANTAL-TB-Serie%23.pdf +CP Radial_Tantal series Radial pin pitch 2.50mm diameter 7.0mm Tantal Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +CP_Radial_Tantal_D7.0mm_P5.00mm +CP, Radial_Tantal series, Radial, pin pitch=5.00mm, , diameter=7.0mm, Tantal Electrolytic Capacitor, http://cdn-reichelt.de/documents/datenblatt/B300/TANTAL-TB-Serie%23.pdf +CP Radial_Tantal series Radial pin pitch 5.00mm diameter 7.0mm Tantal Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +CP_Radial_Tantal_D8.0mm_P2.50mm +CP, Radial_Tantal series, Radial, pin pitch=2.50mm, , diameter=8.0mm, Tantal Electrolytic Capacitor, http://cdn-reichelt.de/documents/datenblatt/B300/TANTAL-TB-Serie%23.pdf +CP Radial_Tantal series Radial pin pitch 2.50mm diameter 8.0mm Tantal Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +CP_Radial_Tantal_D8.0mm_P5.00mm +CP, Radial_Tantal series, Radial, pin pitch=5.00mm, , diameter=8.0mm, Tantal Electrolytic Capacitor, http://cdn-reichelt.de/documents/datenblatt/B300/TANTAL-TB-Serie%23.pdf +CP Radial_Tantal series Radial pin pitch 5.00mm diameter 8.0mm Tantal Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +CP_Radial_Tantal_D9.0mm_P2.50mm +CP, Radial_Tantal series, Radial, pin pitch=2.50mm, , diameter=9.0mm, Tantal Electrolytic Capacitor, http://cdn-reichelt.de/documents/datenblatt/B300/TANTAL-TB-Serie%23.pdf +CP Radial_Tantal series Radial pin pitch 2.50mm diameter 9.0mm Tantal Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +CP_Radial_Tantal_D9.0mm_P5.00mm +CP, Radial_Tantal series, Radial, pin pitch=5.00mm, , diameter=9.0mm, Tantal Electrolytic Capacitor, http://cdn-reichelt.de/documents/datenblatt/B300/TANTAL-TB-Serie%23.pdf +CP Radial_Tantal series Radial pin pitch 5.00mm diameter 9.0mm Tantal Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +CP_Radial_Tantal_D10.5mm_P2.50mm +CP, Radial_Tantal series, Radial, pin pitch=2.50mm, , diameter=10.5mm, Tantal Electrolytic Capacitor, http://cdn-reichelt.de/documents/datenblatt/B300/TANTAL-TB-Serie%23.pdf +CP Radial_Tantal series Radial pin pitch 2.50mm diameter 10.5mm Tantal Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +CP_Radial_Tantal_D10.5mm_P5.00mm +CP, Radial_Tantal series, Radial, pin pitch=5.00mm, , diameter=10.5mm, Tantal Electrolytic Capacitor, http://cdn-reichelt.de/documents/datenblatt/B300/TANTAL-TB-Serie%23.pdf +CP Radial_Tantal series Radial pin pitch 5.00mm diameter 10.5mm Tantal Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +C_Axial_L3.8mm_D2.6mm_P7.50mm_Horizontal +C, Axial series, Axial, Horizontal, pin pitch=7.5mm, , length*diameter=3.8*2.6mm^2, http://www.vishay.com/docs/45231/arseries.pdf +C Axial series Axial Horizontal pin pitch 7.5mm length 3.8mm diameter 2.6mm +0 +2 +2 +Capacitor_THT +C_Axial_L3.8mm_D2.6mm_P10.00mm_Horizontal +C, Axial series, Axial, Horizontal, pin pitch=10mm, , length*diameter=3.8*2.6mm^2, http://www.vishay.com/docs/45231/arseries.pdf +C Axial series Axial Horizontal pin pitch 10mm length 3.8mm diameter 2.6mm +0 +2 +2 +Capacitor_THT +C_Axial_L3.8mm_D2.6mm_P12.50mm_Horizontal +C, Axial series, Axial, Horizontal, pin pitch=12.5mm, , length*diameter=3.8*2.6mm^2, http://www.vishay.com/docs/45231/arseries.pdf +C Axial series Axial Horizontal pin pitch 12.5mm length 3.8mm diameter 2.6mm +0 +2 +2 +Capacitor_THT +C_Axial_L3.8mm_D2.6mm_P15.00mm_Horizontal +C, Axial series, Axial, Horizontal, pin pitch=15mm, , length*diameter=3.8*2.6mm^2, http://www.vishay.com/docs/45231/arseries.pdf +C Axial series Axial Horizontal pin pitch 15mm length 3.8mm diameter 2.6mm +0 +2 +2 +Capacitor_THT +C_Axial_L5.1mm_D3.1mm_P7.50mm_Horizontal +C, Axial series, Axial, Horizontal, pin pitch=7.5mm, , length*diameter=5.1*3.1mm^2, http://www.vishay.com/docs/45231/arseries.pdf +C Axial series Axial Horizontal pin pitch 7.5mm length 5.1mm diameter 3.1mm +0 +2 +2 +Capacitor_THT +C_Axial_L5.1mm_D3.1mm_P10.00mm_Horizontal +C, Axial series, Axial, Horizontal, pin pitch=10mm, , length*diameter=5.1*3.1mm^2, http://www.vishay.com/docs/45231/arseries.pdf +C Axial series Axial Horizontal pin pitch 10mm length 5.1mm diameter 3.1mm +0 +2 +2 +Capacitor_THT +C_Axial_L5.1mm_D3.1mm_P12.50mm_Horizontal +C, Axial series, Axial, Horizontal, pin pitch=12.5mm, , length*diameter=5.1*3.1mm^2, http://www.vishay.com/docs/45231/arseries.pdf +C Axial series Axial Horizontal pin pitch 12.5mm length 5.1mm diameter 3.1mm +0 +2 +2 +Capacitor_THT +C_Axial_L5.1mm_D3.1mm_P15.00mm_Horizontal +C, Axial series, Axial, Horizontal, pin pitch=15mm, , length*diameter=5.1*3.1mm^2, http://www.vishay.com/docs/45231/arseries.pdf +C Axial series Axial Horizontal pin pitch 15mm length 5.1mm diameter 3.1mm +0 +2 +2 +Capacitor_THT +C_Axial_L12.0mm_D6.5mm_P15.00mm_Horizontal +C, Axial series, Axial, Horizontal, pin pitch=15mm, , length*diameter=12*6.5mm^2, http://cdn-reichelt.de/documents/datenblatt/B300/STYROFLEX.pdf +C Axial series Axial Horizontal pin pitch 15mm length 12mm diameter 6.5mm +0 +2 +2 +Capacitor_THT +C_Axial_L12.0mm_D6.5mm_P20.00mm_Horizontal +C, Axial series, Axial, Horizontal, pin pitch=20mm, , length*diameter=12*6.5mm^2, http://cdn-reichelt.de/documents/datenblatt/B300/STYROFLEX.pdf +C Axial series Axial Horizontal pin pitch 20mm length 12mm diameter 6.5mm +0 +2 +2 +Capacitor_THT +C_Axial_L12.0mm_D7.5mm_P15.00mm_Horizontal +C, Axial series, Axial, Horizontal, pin pitch=15mm, , length*diameter=12*7.5mm^2, http://cdn-reichelt.de/documents/datenblatt/B300/STYROFLEX.pdf +C Axial series Axial Horizontal pin pitch 15mm length 12mm diameter 7.5mm +0 +2 +2 +Capacitor_THT +C_Axial_L12.0mm_D7.5mm_P20.00mm_Horizontal +C, Axial series, Axial, Horizontal, pin pitch=20mm, , length*diameter=12*7.5mm^2, http://cdn-reichelt.de/documents/datenblatt/B300/STYROFLEX.pdf +C Axial series Axial Horizontal pin pitch 20mm length 12mm diameter 7.5mm +0 +2 +2 +Capacitor_THT +C_Axial_L12.0mm_D8.5mm_P15.00mm_Horizontal +C, Axial series, Axial, Horizontal, pin pitch=15mm, , length*diameter=12*8.5mm^2, http://cdn-reichelt.de/documents/datenblatt/B300/STYROFLEX.pdf +C Axial series Axial Horizontal pin pitch 15mm length 12mm diameter 8.5mm +0 +2 +2 +Capacitor_THT +C_Axial_L12.0mm_D8.5mm_P20.00mm_Horizontal +C, Axial series, Axial, Horizontal, pin pitch=20mm, , length*diameter=12*8.5mm^2, http://cdn-reichelt.de/documents/datenblatt/B300/STYROFLEX.pdf +C Axial series Axial Horizontal pin pitch 20mm length 12mm diameter 8.5mm +0 +2 +2 +Capacitor_THT +C_Axial_L12.0mm_D9.5mm_P15.00mm_Horizontal +C, Axial series, Axial, Horizontal, pin pitch=15mm, , length*diameter=12*9.5mm^2, http://cdn-reichelt.de/documents/datenblatt/B300/STYROFLEX.pdf +C Axial series Axial Horizontal pin pitch 15mm length 12mm diameter 9.5mm +0 +2 +2 +Capacitor_THT +C_Axial_L12.0mm_D9.5mm_P20.00mm_Horizontal +C, Axial series, Axial, Horizontal, pin pitch=20mm, , length*diameter=12*9.5mm^2, http://cdn-reichelt.de/documents/datenblatt/B300/STYROFLEX.pdf +C Axial series Axial Horizontal pin pitch 20mm length 12mm diameter 9.5mm +0 +2 +2 +Capacitor_THT +C_Axial_L12.0mm_D10.5mm_P15.00mm_Horizontal +C, Axial series, Axial, Horizontal, pin pitch=15mm, , length*diameter=12*10.5mm^2, http://cdn-reichelt.de/documents/datenblatt/B300/STYROFLEX.pdf +C Axial series Axial Horizontal pin pitch 15mm length 12mm diameter 10.5mm +0 +2 +2 +Capacitor_THT +C_Axial_L12.0mm_D10.5mm_P20.00mm_Horizontal +C, Axial series, Axial, Horizontal, pin pitch=20mm, , length*diameter=12*10.5mm^2, http://cdn-reichelt.de/documents/datenblatt/B300/STYROFLEX.pdf +C Axial series Axial Horizontal pin pitch 20mm length 12mm diameter 10.5mm +0 +2 +2 +Capacitor_THT +C_Axial_L17.0mm_D6.5mm_P20.00mm_Horizontal +C, Axial series, Axial, Horizontal, pin pitch=20mm, , length*diameter=17*6.5mm^2, http://cdn-reichelt.de/documents/datenblatt/B300/STYROFLEX.pdf +C Axial series Axial Horizontal pin pitch 20mm length 17mm diameter 6.5mm +0 +2 +2 +Capacitor_THT +C_Axial_L17.0mm_D6.5mm_P25.00mm_Horizontal +C, Axial series, Axial, Horizontal, pin pitch=25mm, , length*diameter=17*6.5mm^2, http://cdn-reichelt.de/documents/datenblatt/B300/STYROFLEX.pdf +C Axial series Axial Horizontal pin pitch 25mm length 17mm diameter 6.5mm +0 +2 +2 +Capacitor_THT +C_Axial_L17.0mm_D7.0mm_P20.00mm_Horizontal +C, Axial series, Axial, Horizontal, pin pitch=20mm, , length*diameter=17*7.0mm^2, http://cdn-reichelt.de/documents/datenblatt/B300/STYROFLEX.pdf +C Axial series Axial Horizontal pin pitch 20mm length 17mm diameter 7.0mm +0 +2 +2 +Capacitor_THT +C_Axial_L17.0mm_D7.0mm_P25.00mm_Horizontal +C, Axial series, Axial, Horizontal, pin pitch=25mm, , length*diameter=17*7.0mm^2, http://cdn-reichelt.de/documents/datenblatt/B300/STYROFLEX.pdf +C Axial series Axial Horizontal pin pitch 25mm length 17mm diameter 7.0mm +0 +2 +2 +Capacitor_THT +C_Axial_L19.0mm_D7.5mm_P25.00mm_Horizontal +C, Axial series, Axial, Horizontal, pin pitch=25mm, , length*diameter=19*7.5mm^2, http://cdn-reichelt.de/documents/datenblatt/B300/STYROFLEX.pdf +C Axial series Axial Horizontal pin pitch 25mm length 19mm diameter 7.5mm +0 +2 +2 +Capacitor_THT +C_Axial_L19.0mm_D8.0mm_P25.00mm_Horizontal +C, Axial series, Axial, Horizontal, pin pitch=25mm, , length*diameter=19*8.0mm^2, http://cdn-reichelt.de/documents/datenblatt/B300/STYROFLEX.pdf +C Axial series Axial Horizontal pin pitch 25mm length 19mm diameter 8.0mm +0 +2 +2 +Capacitor_THT +C_Axial_L19.0mm_D9.0mm_P25.00mm_Horizontal +C, Axial series, Axial, Horizontal, pin pitch=25mm, , length*diameter=19*9mm^2, http://cdn-reichelt.de/documents/datenblatt/B300/STYROFLEX.pdf +C Axial series Axial Horizontal pin pitch 25mm length 19mm diameter 9mm +0 +2 +2 +Capacitor_THT +C_Axial_L19.0mm_D9.5mm_P25.00mm_Horizontal +C, Axial series, Axial, Horizontal, pin pitch=25mm, , length*diameter=19*9.5mm^2, http://cdn-reichelt.de/documents/datenblatt/B300/STYROFLEX.pdf +C Axial series Axial Horizontal pin pitch 25mm length 19mm diameter 9.5mm +0 +2 +2 +Capacitor_THT +C_Axial_L22.0mm_D9.5mm_P27.50mm_Horizontal +C, Axial series, Axial, Horizontal, pin pitch=27.5mm, , length*diameter=22*9.5mm^2, http://cdn-reichelt.de/documents/datenblatt/B300/STYROFLEX.pdf +C Axial series Axial Horizontal pin pitch 27.5mm length 22mm diameter 9.5mm +0 +2 +2 +Capacitor_THT +C_Axial_L22.0mm_D10.5mm_P27.50mm_Horizontal +C, Axial series, Axial, Horizontal, pin pitch=27.5mm, , length*diameter=22*10.5mm^2, http://cdn-reichelt.de/documents/datenblatt/B300/STYROFLEX.pdf +C Axial series Axial Horizontal pin pitch 27.5mm length 22mm diameter 10.5mm +0 +2 +2 +Capacitor_THT +C_Disc_D3.0mm_W1.6mm_P2.50mm +C, Disc series, Radial, pin pitch=2.50mm, , diameter*width=3.0*1.6mm^2, Capacitor, http://www.vishay.com/docs/45233/krseries.pdf +C Disc series Radial pin pitch 2.50mm diameter 3.0mm width 1.6mm Capacitor +0 +2 +2 +Capacitor_THT +C_Disc_D3.0mm_W2.0mm_P2.50mm +C, Disc series, Radial, pin pitch=2.50mm, , diameter*width=3*2mm^2, Capacitor +C Disc series Radial pin pitch 2.50mm diameter 3mm width 2mm Capacitor +0 +2 +2 +Capacitor_THT +C_Disc_D3.4mm_W2.1mm_P2.50mm +C, Disc series, Radial, pin pitch=2.50mm, , diameter*width=3.4*2.1mm^2, Capacitor, http://www.vishay.com/docs/45233/krseries.pdf +C Disc series Radial pin pitch 2.50mm diameter 3.4mm width 2.1mm Capacitor +0 +2 +2 +Capacitor_THT +C_Disc_D3.8mm_W2.6mm_P2.50mm +C, Disc series, Radial, pin pitch=2.50mm, , diameter*width=3.8*2.6mm^2, Capacitor, http://www.vishay.com/docs/45233/krseries.pdf +C Disc series Radial pin pitch 2.50mm diameter 3.8mm width 2.6mm Capacitor +0 +2 +2 +Capacitor_THT +C_Disc_D4.3mm_W1.9mm_P5.00mm +C, Disc series, Radial, pin pitch=5.00mm, , diameter*width=4.3*1.9mm^2, Capacitor, http://www.vishay.com/docs/45233/krseries.pdf +C Disc series Radial pin pitch 5.00mm diameter 4.3mm width 1.9mm Capacitor +0 +2 +2 +Capacitor_THT +C_Disc_D4.7mm_W2.5mm_P5.00mm +C, Disc series, Radial, pin pitch=5.00mm, , diameter*width=4.7*2.5mm^2, Capacitor, http://www.vishay.com/docs/45233/krseries.pdf +C Disc series Radial pin pitch 5.00mm diameter 4.7mm width 2.5mm Capacitor +0 +2 +2 +Capacitor_THT +C_Disc_D5.0mm_W2.5mm_P2.50mm +C, Disc series, Radial, pin pitch=2.50mm, , diameter*width=5*2.5mm^2, Capacitor, http://cdn-reichelt.de/documents/datenblatt/B300/DS_KERKO_TC.pdf +C Disc series Radial pin pitch 2.50mm diameter 5mm width 2.5mm Capacitor +0 +2 +2 +Capacitor_THT +C_Disc_D5.0mm_W2.5mm_P5.00mm +C, Disc series, Radial, pin pitch=5.00mm, , diameter*width=5*2.5mm^2, Capacitor, http://cdn-reichelt.de/documents/datenblatt/B300/DS_KERKO_TC.pdf +C Disc series Radial pin pitch 5.00mm diameter 5mm width 2.5mm Capacitor +0 +2 +2 +Capacitor_THT +C_Disc_D5.1mm_W3.2mm_P5.00mm +C, Disc series, Radial, pin pitch=5.00mm, , diameter*width=5.1*3.2mm^2, Capacitor, http://www.vishay.com/docs/45233/krseries.pdf +C Disc series Radial pin pitch 5.00mm diameter 5.1mm width 3.2mm Capacitor +0 +2 +2 +Capacitor_THT +C_Disc_D6.0mm_W2.5mm_P5.00mm +C, Disc series, Radial, pin pitch=5.00mm, , diameter*width=6*2.5mm^2, Capacitor, http://cdn-reichelt.de/documents/datenblatt/B300/DS_KERKO_TC.pdf +C Disc series Radial pin pitch 5.00mm diameter 6mm width 2.5mm Capacitor +0 +2 +2 +Capacitor_THT +C_Disc_D6.0mm_W4.4mm_P5.00mm +C, Disc series, Radial, pin pitch=5.00mm, , diameter*width=6*4.4mm^2, Capacitor +C Disc series Radial pin pitch 5.00mm diameter 6mm width 4.4mm Capacitor +0 +2 +2 +Capacitor_THT +C_Disc_D7.0mm_W2.5mm_P5.00mm +C, Disc series, Radial, pin pitch=5.00mm, , diameter*width=7*2.5mm^2, Capacitor, http://cdn-reichelt.de/documents/datenblatt/B300/DS_KERKO_TC.pdf +C Disc series Radial pin pitch 5.00mm diameter 7mm width 2.5mm Capacitor +0 +2 +2 +Capacitor_THT +C_Disc_D7.5mm_W2.5mm_P5.00mm +C, Disc series, Radial, pin pitch=5.00mm, , diameter*width=7.5*2.5mm^2, Capacitor, http://www.vishay.com/docs/28535/vy2series.pdf +C Disc series Radial pin pitch 5.00mm diameter 7.5mm width 2.5mm Capacitor +0 +2 +2 +Capacitor_THT +C_Disc_D7.5mm_W4.4mm_P5.00mm +C, Disc series, Radial, pin pitch=5.00mm, , diameter*width=7.5*4.4mm^2, Capacitor +C Disc series Radial pin pitch 5.00mm diameter 7.5mm width 4.4mm Capacitor +0 +2 +2 +Capacitor_THT +C_Disc_D7.5mm_W5.0mm_P5.00mm +C, Disc series, Radial, pin pitch=5.00mm, , diameter*width=7.5*5.0mm^2, Capacitor, http://www.vishay.com/docs/28535/vy2series.pdf +C Disc series Radial pin pitch 5.00mm diameter 7.5mm width 5.0mm Capacitor +0 +2 +2 +Capacitor_THT +C_Disc_D7.5mm_W5.0mm_P7.50mm +C, Disc series, Radial, pin pitch=7.50mm, , diameter*width=7.5*5.0mm^2, Capacitor, http://www.vishay.com/docs/28535/vy2series.pdf +C Disc series Radial pin pitch 7.50mm diameter 7.5mm width 5.0mm Capacitor +0 +2 +2 +Capacitor_THT +C_Disc_D7.5mm_W5.0mm_P10.00mm +C, Disc series, Radial, pin pitch=10.00mm, , diameter*width=7.5*5.0mm^2, Capacitor, http://www.vishay.com/docs/28535/vy2series.pdf +C Disc series Radial pin pitch 10.00mm diameter 7.5mm width 5.0mm Capacitor +0 +2 +2 +Capacitor_THT +C_Disc_D8.0mm_W2.5mm_P5.00mm +C, Disc series, Radial, pin pitch=5.00mm, , diameter*width=8*2.5mm^2, Capacitor, http://cdn-reichelt.de/documents/datenblatt/B300/DS_KERKO_TC.pdf +C Disc series Radial pin pitch 5.00mm diameter 8mm width 2.5mm Capacitor +0 +2 +2 +Capacitor_THT +C_Disc_D8.0mm_W5.0mm_P5.00mm +C, Disc series, Radial, pin pitch=5.00mm, , diameter*width=8*5.0mm^2, Capacitor, http://www.vishay.com/docs/28535/vy2series.pdf +C Disc series Radial pin pitch 5.00mm diameter 8mm width 5.0mm Capacitor +0 +2 +2 +Capacitor_THT +C_Disc_D8.0mm_W5.0mm_P7.50mm +C, Disc series, Radial, pin pitch=7.50mm, , diameter*width=8*5.0mm^2, Capacitor, http://www.vishay.com/docs/28535/vy2series.pdf +C Disc series Radial pin pitch 7.50mm diameter 8mm width 5.0mm Capacitor +0 +2 +2 +Capacitor_THT +C_Disc_D8.0mm_W5.0mm_P10.00mm +C, Disc series, Radial, pin pitch=10.00mm, , diameter*width=8*5.0mm^2, Capacitor, http://www.vishay.com/docs/28535/vy2series.pdf +C Disc series Radial pin pitch 10.00mm diameter 8mm width 5.0mm Capacitor +0 +2 +2 +Capacitor_THT +C_Disc_D9.0mm_W2.5mm_P5.00mm +C, Disc series, Radial, pin pitch=5.00mm, , diameter*width=9*2.5mm^2, Capacitor, http://cdn-reichelt.de/documents/datenblatt/B300/DS_KERKO_TC.pdf +C Disc series Radial pin pitch 5.00mm diameter 9mm width 2.5mm Capacitor +0 +2 +2 +Capacitor_THT +C_Disc_D9.0mm_W5.0mm_P5.00mm +C, Disc series, Radial, pin pitch=5.00mm, , diameter*width=9*5.0mm^2, Capacitor, http://www.vishay.com/docs/28535/vy2series.pdf +C Disc series Radial pin pitch 5.00mm diameter 9mm width 5.0mm Capacitor +0 +2 +2 +Capacitor_THT +C_Disc_D9.0mm_W5.0mm_P7.50mm +C, Disc series, Radial, pin pitch=7.50mm, , diameter*width=9*5.0mm^2, Capacitor, http://www.vishay.com/docs/28535/vy2series.pdf +C Disc series Radial pin pitch 7.50mm diameter 9mm width 5.0mm Capacitor +0 +2 +2 +Capacitor_THT +C_Disc_D9.0mm_W5.0mm_P10.00mm +C, Disc series, Radial, pin pitch=10.00mm, , diameter*width=9*5.0mm^2, Capacitor, http://www.vishay.com/docs/28535/vy2series.pdf +C Disc series Radial pin pitch 10.00mm diameter 9mm width 5.0mm Capacitor +0 +2 +2 +Capacitor_THT +C_Disc_D10.0mm_W2.5mm_P5.00mm +C, Disc series, Radial, pin pitch=5.00mm, , diameter*width=10*2.5mm^2, Capacitor, http://cdn-reichelt.de/documents/datenblatt/B300/DS_KERKO_TC.pdf +C Disc series Radial pin pitch 5.00mm diameter 10mm width 2.5mm Capacitor +0 +2 +2 +Capacitor_THT +C_Disc_D10.5mm_W5.0mm_P5.00mm +C, Disc series, Radial, pin pitch=5.00mm, , diameter*width=10.5*5.0mm^2, Capacitor, http://www.vishay.com/docs/28535/vy2series.pdf +C Disc series Radial pin pitch 5.00mm diameter 10.5mm width 5.0mm Capacitor +0 +2 +2 +Capacitor_THT +C_Disc_D10.5mm_W5.0mm_P7.50mm +C, Disc series, Radial, pin pitch=7.50mm, , diameter*width=10.5*5.0mm^2, Capacitor, http://www.vishay.com/docs/28535/vy2series.pdf +C Disc series Radial pin pitch 7.50mm diameter 10.5mm width 5.0mm Capacitor +0 +2 +2 +Capacitor_THT +C_Disc_D10.5mm_W5.0mm_P10.00mm +C, Disc series, Radial, pin pitch=10.00mm, , diameter*width=10.5*5.0mm^2, Capacitor, http://www.vishay.com/docs/28535/vy2series.pdf +C Disc series Radial pin pitch 10.00mm diameter 10.5mm width 5.0mm Capacitor +0 +2 +2 +Capacitor_THT +C_Disc_D11.0mm_W5.0mm_P5.00mm +C, Disc series, Radial, pin pitch=5.00mm, , diameter*width=11*5.0mm^2, Capacitor, http://www.vishay.com/docs/28535/vy2series.pdf +C Disc series Radial pin pitch 5.00mm diameter 11mm width 5.0mm Capacitor +0 +2 +2 +Capacitor_THT +C_Disc_D11.0mm_W5.0mm_P7.50mm +C, Disc series, Radial, pin pitch=7.50mm, , diameter*width=11*5.0mm^2, Capacitor, http://www.vishay.com/docs/28535/vy2series.pdf +C Disc series Radial pin pitch 7.50mm diameter 11mm width 5.0mm Capacitor +0 +2 +2 +Capacitor_THT +C_Disc_D11.0mm_W5.0mm_P10.00mm +C, Disc series, Radial, pin pitch=10.00mm, , diameter*width=11*5.0mm^2, Capacitor, http://www.vishay.com/docs/28535/vy2series.pdf +C Disc series Radial pin pitch 10.00mm diameter 11mm width 5.0mm Capacitor +0 +2 +2 +Capacitor_THT +C_Disc_D12.0mm_W4.4mm_P7.75mm +C, Disc series, Radial, pin pitch=7.75mm, , diameter*width=12*4.4mm^2, Capacitor +C Disc series Radial pin pitch 7.75mm diameter 12mm width 4.4mm Capacitor +0 +2 +2 +Capacitor_THT +C_Disc_D12.5mm_W5.0mm_P7.50mm +C, Disc series, Radial, pin pitch=7.50mm, , diameter*width=12.5*5.0mm^2, Capacitor, http://www.vishay.com/docs/28535/vy2series.pdf +C Disc series Radial pin pitch 7.50mm diameter 12.5mm width 5.0mm Capacitor +0 +2 +2 +Capacitor_THT +C_Disc_D12.5mm_W5.0mm_P10.00mm +C, Disc series, Radial, pin pitch=10.00mm, , diameter*width=12.5*5.0mm^2, Capacitor, http://www.vishay.com/docs/28535/vy2series.pdf +C Disc series Radial pin pitch 10.00mm diameter 12.5mm width 5.0mm Capacitor +0 +2 +2 +Capacitor_THT +C_Disc_D14.5mm_W5.0mm_P7.50mm +C, Disc series, Radial, pin pitch=7.50mm, , diameter*width=14.5*5.0mm^2, Capacitor, http://www.vishay.com/docs/28535/vy2series.pdf +C Disc series Radial pin pitch 7.50mm diameter 14.5mm width 5.0mm Capacitor +0 +2 +2 +Capacitor_THT +C_Disc_D14.5mm_W5.0mm_P10.00mm +C, Disc series, Radial, pin pitch=10.00mm, , diameter*width=14.5*5.0mm^2, Capacitor, http://www.vishay.com/docs/28535/vy2series.pdf +C Disc series Radial pin pitch 10.00mm diameter 14.5mm width 5.0mm Capacitor +0 +2 +2 +Capacitor_THT +C_Disc_D16.0mm_W5.0mm_P7.50mm +C, Disc series, Radial, pin pitch=7.50mm, , diameter*width=16.0*5.0mm^2, Capacitor, http://www.vishay.com/docs/28535/vy2series.pdf +C Disc series Radial pin pitch 7.50mm diameter 16.0mm width 5.0mm Capacitor +0 +2 +2 +Capacitor_THT +C_Disc_D16.0mm_W5.0mm_P10.00mm +C, Disc series, Radial, pin pitch=10.00mm, , diameter*width=16.0*5.0mm^2, Capacitor, http://www.vishay.com/docs/28535/vy2series.pdf +C Disc series Radial pin pitch 10.00mm diameter 16.0mm width 5.0mm Capacitor +0 +2 +2 +Capacitor_THT +C_Radial_D4.0mm_H5.0mm_P1.50mm +C, Radial series, Radial, pin pitch=1.50mm, diameter=4mm, height=5mm, Non-Polar Electrolytic Capacitor +C Radial series Radial pin pitch 1.50mm diameter 4mm height 5mm Non-Polar Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +C_Radial_D4.0mm_H7.0mm_P1.50mm +C, Radial series, Radial, pin pitch=1.50mm, diameter=4mm, height=7mm, Non-Polar Electrolytic Capacitor +C Radial series Radial pin pitch 1.50mm diameter 4mm height 7mm Non-Polar Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +C_Radial_D5.0mm_H5.0mm_P2.00mm +C, Radial series, Radial, pin pitch=2.00mm, diameter=5mm, height=5mm, Non-Polar Electrolytic Capacitor +C Radial series Radial pin pitch 2.00mm diameter 5mm height 5mm Non-Polar Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +C_Radial_D5.0mm_H7.0mm_P2.00mm +C, Radial series, Radial, pin pitch=2.00mm, diameter=5mm, height=7mm, Non-Polar Electrolytic Capacitor +C Radial series Radial pin pitch 2.00mm diameter 5mm height 7mm Non-Polar Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +C_Radial_D5.0mm_H11.0mm_P2.00mm +C, Radial series, Radial, pin pitch=2.00mm, diameter=5mm, height=11mm, Non-Polar Electrolytic Capacitor +C Radial series Radial pin pitch 2.00mm diameter 5mm height 11mm Non-Polar Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +C_Radial_D6.3mm_H5.0mm_P2.50mm +C, Radial series, Radial, pin pitch=2.50mm, diameter=6.3mm, height=5mm, Non-Polar Electrolytic Capacitor +C Radial series Radial pin pitch 2.50mm diameter 6.3mm height 5mm Non-Polar Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +C_Radial_D6.3mm_H7.0mm_P2.50mm +C, Radial series, Radial, pin pitch=2.50mm, diameter=6.3mm, height=7mm, Non-Polar Electrolytic Capacitor +C Radial series Radial pin pitch 2.50mm diameter 6.3mm height 7mm Non-Polar Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +C_Radial_D6.3mm_H11.0mm_P2.50mm +C, Radial series, Radial, pin pitch=2.50mm, diameter=6.3mm, height=11mm, Non-Polar Electrolytic Capacitor +C Radial series Radial pin pitch 2.50mm diameter 6.3mm height 11mm Non-Polar Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +C_Radial_D8.0mm_H7.0mm_P3.50mm +C, Radial series, Radial, pin pitch=3.50mm, diameter=8mm, height=7mm, Non-Polar Electrolytic Capacitor +C Radial series Radial pin pitch 3.50mm diameter 8mm height 7mm Non-Polar Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +C_Radial_D8.0mm_H11.5mm_P3.50mm +C, Radial series, Radial, pin pitch=3.50mm, diameter=8mm, height=11.5mm, Non-Polar Electrolytic Capacitor +C Radial series Radial pin pitch 3.50mm diameter 8mm height 11.5mm Non-Polar Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +C_Radial_D10.0mm_H12.5mm_P5.00mm +C, Radial series, Radial, pin pitch=5.00mm, diameter=10mm, height=12.5mm, Non-Polar Electrolytic Capacitor +C Radial series Radial pin pitch 5.00mm diameter 10mm height 12.5mm Non-Polar Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +C_Radial_D10.0mm_H16.0mm_P5.00mm +C, Radial series, Radial, pin pitch=5.00mm, diameter=10mm, height=16mm, Non-Polar Electrolytic Capacitor +C Radial series Radial pin pitch 5.00mm diameter 10mm height 16mm Non-Polar Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +C_Radial_D10.0mm_H20.0mm_P5.00mm +C, Radial series, Radial, pin pitch=5.00mm, diameter=10mm, height=20mm, Non-Polar Electrolytic Capacitor +C Radial series Radial pin pitch 5.00mm diameter 10mm height 20mm Non-Polar Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +C_Radial_D12.5mm_H20.0mm_P5.00mm +C, Radial series, Radial, pin pitch=5.00mm, diameter=12.5mm, height=20mm, Non-Polar Electrolytic Capacitor +C Radial series Radial pin pitch 5.00mm diameter 12.5mm height 20mm Non-Polar Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +C_Radial_D12.5mm_H25.0mm_P5.00mm +C, Radial series, Radial, pin pitch=5.00mm, diameter=12.5mm, height=25mm, Non-Polar Electrolytic Capacitor +C Radial series Radial pin pitch 5.00mm diameter 12.5mm height 25mm Non-Polar Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +C_Radial_D16.0mm_H25.0mm_P7.50mm +C, Radial series, Radial, pin pitch=7.50mm, diameter=16mm, height=25mm, Non-Polar Electrolytic Capacitor +C Radial series Radial pin pitch 7.50mm diameter 16mm height 25mm Non-Polar Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +C_Radial_D16.0mm_H31.5mm_P7.50mm +C, Radial series, Radial, pin pitch=7.50mm, diameter=16mm, height=31.5mm, Non-Polar Electrolytic Capacitor +C Radial series Radial pin pitch 7.50mm diameter 16mm height 31.5mm Non-Polar Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +C_Radial_D18.0mm_H35.5mm_P7.50mm +C, Radial series, Radial, pin pitch=7.50mm, diameter=18mm, height=35.5mm, Non-Polar Electrolytic Capacitor +C Radial series Radial pin pitch 7.50mm diameter 18mm height 35.5mm Non-Polar Electrolytic Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L4.0mm_W2.5mm_P2.50mm +C, Rect series, Radial, pin pitch=2.50mm, , length*width=4*2.5mm^2, Capacitor +C Rect series Radial pin pitch 2.50mm length 4mm width 2.5mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L4.6mm_W2.0mm_P2.50mm_MKS02_FKP02 +C, Rect series, Radial, pin pitch=2.50mm, , length*width=4.6*2mm^2, Capacitor, http://www.wima.de/DE/WIMA_MKS_02.pdf +C Rect series Radial pin pitch 2.50mm length 4.6mm width 2mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L4.6mm_W3.0mm_P2.50mm_MKS02_FKP02 +C, Rect series, Radial, pin pitch=2.50mm, , length*width=4.6*3.0mm^2, Capacitor, http://www.wima.de/DE/WIMA_MKS_02.pdf +C Rect series Radial pin pitch 2.50mm length 4.6mm width 3.0mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L4.6mm_W3.8mm_P2.50mm_MKS02_FKP02 +C, Rect series, Radial, pin pitch=2.50mm, , length*width=4.6*3.8mm^2, Capacitor, http://www.wima.de/DE/WIMA_MKS_02.pdf +C Rect series Radial pin pitch 2.50mm length 4.6mm width 3.8mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L4.6mm_W4.6mm_P2.50mm_MKS02_FKP02 +C, Rect series, Radial, pin pitch=2.50mm, , length*width=4.6*4.6mm^2, Capacitor, http://www.wima.de/DE/WIMA_MKS_02.pdf +C Rect series Radial pin pitch 2.50mm length 4.6mm width 4.6mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L4.6mm_W5.5mm_P2.50mm_MKS02_FKP02 +C, Rect series, Radial, pin pitch=2.50mm, , length*width=4.6*5.5mm^2, Capacitor, http://www.wima.de/DE/WIMA_MKS_02.pdf +C Rect series Radial pin pitch 2.50mm length 4.6mm width 5.5mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L7.0mm_W2.0mm_P5.00mm +C, Rect series, Radial, pin pitch=5.00mm, , length*width=7*2mm^2, Capacitor +C Rect series Radial pin pitch 5.00mm length 7mm width 2mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L7.0mm_W2.5mm_P5.00mm +C, Rect series, Radial, pin pitch=5.00mm, , length*width=7*2.5mm^2, Capacitor +C Rect series Radial pin pitch 5.00mm length 7mm width 2.5mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L7.0mm_W3.5mm_P2.50mm_P5.00mm +C, Rect series, Radial, pin pitch=2.50mm 5.00mm, , length*width=7*3.5mm^2, Capacitor +C Rect series Radial pin pitch 2.50mm 5.00mm length 7mm width 3.5mm Capacitor +0 +4 +2 +Capacitor_THT +C_Rect_L7.0mm_W3.5mm_P5.00mm +C, Rect series, Radial, pin pitch=5.00mm, , length*width=7*3.5mm^2, Capacitor +C Rect series Radial pin pitch 5.00mm length 7mm width 3.5mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L7.0mm_W4.5mm_P5.00mm +C, Rect series, Radial, pin pitch=5.00mm, , length*width=7*4.5mm^2, Capacitor +C Rect series Radial pin pitch 5.00mm length 7mm width 4.5mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L7.0mm_W6.0mm_P5.00mm +C, Rect series, Radial, pin pitch=5.00mm, , length*width=7*6mm^2, Capacitor +C Rect series Radial pin pitch 5.00mm length 7mm width 6mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L7.0mm_W6.5mm_P5.00mm +C, Rect series, Radial, pin pitch=5.00mm, , length*width=7*6.5mm^2, Capacitor +C Rect series Radial pin pitch 5.00mm length 7mm width 6.5mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L7.2mm_W2.5mm_P5.00mm_FKS2_FKP2_MKS2_MKP2 +C, Rect series, Radial, pin pitch=5.00mm, , length*width=7.2*2.5mm^2, Capacitor, http://www.wima.com/EN/WIMA_FKS_2.pdf +C Rect series Radial pin pitch 5.00mm length 7.2mm width 2.5mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L7.2mm_W3.0mm_P5.00mm_FKS2_FKP2_MKS2_MKP2 +C, Rect series, Radial, pin pitch=5.00mm, , length*width=7.2*3.0mm^2, Capacitor, http://www.wima.com/EN/WIMA_FKS_2.pdf +C Rect series Radial pin pitch 5.00mm length 7.2mm width 3.0mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L7.2mm_W3.5mm_P5.00mm_FKS2_FKP2_MKS2_MKP2 +C, Rect series, Radial, pin pitch=5.00mm, , length*width=7.2*3.5mm^2, Capacitor, http://www.wima.com/EN/WIMA_FKS_2.pdf +C Rect series Radial pin pitch 5.00mm length 7.2mm width 3.5mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L7.2mm_W4.5mm_P5.00mm_FKS2_FKP2_MKS2_MKP2 +C, Rect series, Radial, pin pitch=5.00mm, , length*width=7.2*4.5mm^2, Capacitor, http://www.wima.com/EN/WIMA_FKS_2.pdf +C Rect series Radial pin pitch 5.00mm length 7.2mm width 4.5mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L7.2mm_W5.5mm_P5.00mm_FKS2_FKP2_MKS2_MKP2 +C, Rect series, Radial, pin pitch=5.00mm, , length*width=7.2*5.5mm^2, Capacitor, http://www.wima.com/EN/WIMA_FKS_2.pdf +C Rect series Radial pin pitch 5.00mm length 7.2mm width 5.5mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L7.2mm_W7.2mm_P5.00mm_FKS2_FKP2_MKS2_MKP2 +C, Rect series, Radial, pin pitch=5.00mm, , length*width=7.2*7.2mm^2, Capacitor, http://www.wima.com/EN/WIMA_FKS_2.pdf +C Rect series Radial pin pitch 5.00mm length 7.2mm width 7.2mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L7.2mm_W8.5mm_P5.00mm_FKP2_FKP2_MKS2_MKP2 +C, Rect series, Radial, pin pitch=5.00mm, , length*width=7.2*8.5mm^2, Capacitor, http://www.wima.com/EN/WIMA_FKS_2.pdf +C Rect series Radial pin pitch 5.00mm length 7.2mm width 8.5mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L7.2mm_W11.0mm_P5.00mm_FKS2_FKP2_MKS2_MKP2 +C, Rect series, Radial, pin pitch=5.00mm, , length*width=7.2*11mm^2, Capacitor, http://www.wima.com/EN/WIMA_FKS_2.pdf +C Rect series Radial pin pitch 5.00mm length 7.2mm width 11mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L7.5mm_W6.5mm_P5.00mm +C, Rect series, Radial, pin pitch=5.00mm, , length*width=7.5*6.5mm^2, Capacitor +C Rect series Radial pin pitch 5.00mm length 7.5mm width 6.5mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L9.0mm_W2.5mm_P7.50mm_MKT +C, Rect series, Radial, pin pitch=7.50mm, , length*width=9*2.5mm^2, Capacitor, https://en.tdk.eu/inf/20/20/db/fc_2009/MKT_B32560_564.pdf +C Rect series Radial pin pitch 7.50mm length 9mm width 2.5mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L9.0mm_W2.6mm_P7.50mm_MKT +C, Rect series, Radial, pin pitch=7.50mm, , length*width=9*2.6mm^2, Capacitor, https://en.tdk.eu/inf/20/20/db/fc_2009/MKT_B32560_564.pdf +C Rect series Radial pin pitch 7.50mm length 9mm width 2.6mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L9.0mm_W2.7mm_P7.50mm_MKT +C, Rect series, Radial, pin pitch=7.50mm, , length*width=9*2.7mm^2, Capacitor, https://en.tdk.eu/inf/20/20/db/fc_2009/MKT_B32560_564.pdf +C Rect series Radial pin pitch 7.50mm length 9mm width 2.7mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L9.0mm_W3.2mm_P7.50mm_MKT +C, Rect series, Radial, pin pitch=7.50mm, , length*width=9*3.2mm^2, Capacitor, https://en.tdk.eu/inf/20/20/db/fc_2009/MKT_B32560_564.pdf +C Rect series Radial pin pitch 7.50mm length 9mm width 3.2mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L9.0mm_W3.3mm_P7.50mm_MKT +C, Rect series, Radial, pin pitch=7.50mm, , length*width=9*3.3mm^2, Capacitor, https://en.tdk.eu/inf/20/20/db/fc_2009/MKT_B32560_564.pdf +C Rect series Radial pin pitch 7.50mm length 9mm width 3.3mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L9.0mm_W3.4mm_P7.50mm_MKT +C, Rect series, Radial, pin pitch=7.50mm, , length*width=9*3.4mm^2, Capacitor, https://en.tdk.eu/inf/20/20/db/fc_2009/MKT_B32560_564.pdf +C Rect series Radial pin pitch 7.50mm length 9mm width 3.4mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L9.0mm_W3.6mm_P7.50mm_MKT +C, Rect series, Radial, pin pitch=7.50mm, , length*width=9*3.6mm^2, Capacitor, https://en.tdk.eu/inf/20/20/db/fc_2009/MKT_B32560_564.pdf +C Rect series Radial pin pitch 7.50mm length 9mm width 3.6mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L9.0mm_W3.8mm_P7.50mm_MKT +C, Rect series, Radial, pin pitch=7.50mm, , length*width=9*3.8mm^2, Capacitor, https://en.tdk.eu/inf/20/20/db/fc_2009/MKT_B32560_564.pdf +C Rect series Radial pin pitch 7.50mm length 9mm width 3.8mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L9.0mm_W3.9mm_P7.50mm_MKT +C, Rect series, Radial, pin pitch=7.50mm, , length*width=9*3.9mm^2, Capacitor, https://en.tdk.eu/inf/20/20/db/fc_2009/MKT_B32560_564.pdf +C Rect series Radial pin pitch 7.50mm length 9mm width 3.9mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L9.0mm_W4.0mm_P7.50mm_MKT +C, Rect series, Radial, pin pitch=7.50mm, , length*width=9*4.0mm^2, Capacitor, https://en.tdk.eu/inf/20/20/db/fc_2009/MKT_B32560_564.pdf +C Rect series Radial pin pitch 7.50mm length 9mm width 4.0mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L9.0mm_W4.2mm_P7.50mm_MKT +C, Rect series, Radial, pin pitch=7.50mm, , length*width=9*4.2mm^2, Capacitor, https://en.tdk.eu/inf/20/20/db/fc_2009/MKT_B32560_564.pdf +C Rect series Radial pin pitch 7.50mm length 9mm width 4.2mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L9.0mm_W4.9mm_P7.50mm_MKT +C, Rect series, Radial, pin pitch=7.50mm, , length*width=9*4.9mm^2, Capacitor, https://en.tdk.eu/inf/20/20/db/fc_2009/MKT_B32560_564.pdf +C Rect series Radial pin pitch 7.50mm length 9mm width 4.9mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L9.0mm_W5.1mm_P7.50mm_MKT +C, Rect series, Radial, pin pitch=7.50mm, , length*width=9*5.1mm^2, Capacitor, https://en.tdk.eu/inf/20/20/db/fc_2009/MKT_B32560_564.pdf +C Rect series Radial pin pitch 7.50mm length 9mm width 5.1mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L9.0mm_W5.7mm_P7.50mm_MKT +C, Rect series, Radial, pin pitch=7.50mm, , length*width=9*5.7mm^2, Capacitor, https://en.tdk.eu/inf/20/20/db/fc_2009/MKT_B32560_564.pdf +C Rect series Radial pin pitch 7.50mm length 9mm width 5.7mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L9.0mm_W6.4mm_P7.50mm_MKT +C, Rect series, Radial, pin pitch=7.50mm, , length*width=9*6.4mm^2, Capacitor, https://en.tdk.eu/inf/20/20/db/fc_2009/MKT_B32560_564.pdf +C Rect series Radial pin pitch 7.50mm length 9mm width 6.4mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L9.0mm_W6.7mm_P7.50mm_MKT +C, Rect series, Radial, pin pitch=7.50mm, , length*width=9*6.7mm^2, Capacitor, https://en.tdk.eu/inf/20/20/db/fc_2009/MKT_B32560_564.pdf +C Rect series Radial pin pitch 7.50mm length 9mm width 6.7mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L9.0mm_W7.7mm_P7.50mm_MKT +C, Rect series, Radial, pin pitch=7.50mm, , length*width=9*7.7mm^2, Capacitor, https://en.tdk.eu/inf/20/20/db/fc_2009/MKT_B32560_564.pdf +C Rect series Radial pin pitch 7.50mm length 9mm width 7.7mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L9.0mm_W8.5mm_P7.50mm_MKT +C, Rect series, Radial, pin pitch=7.50mm, , length*width=9*8.5mm^2, Capacitor, https://en.tdk.eu/inf/20/20/db/fc_2009/MKT_B32560_564.pdf +C Rect series Radial pin pitch 7.50mm length 9mm width 8.5mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L9.0mm_W9.5mm_P7.50mm_MKT +C, Rect series, Radial, pin pitch=7.50mm, , length*width=9*9.5mm^2, Capacitor, https://en.tdk.eu/inf/20/20/db/fc_2009/MKT_B32560_564.pdf +C Rect series Radial pin pitch 7.50mm length 9mm width 9.5mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L9.0mm_W9.8mm_P7.50mm_MKT +C, Rect series, Radial, pin pitch=7.50mm, , length*width=9*9.8mm^2, Capacitor, https://en.tdk.eu/inf/20/20/db/fc_2009/MKT_B32560_564.pdf +C Rect series Radial pin pitch 7.50mm length 9mm width 9.8mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L10.0mm_W2.5mm_P7.50mm_MKS4 +C, Rect series, Radial, pin pitch=7.50mm, , length*width=10*2.5mm^2, Capacitor, http://www.wima.com/EN/WIMA_MKS_4.pdf +C Rect series Radial pin pitch 7.50mm length 10mm width 2.5mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L10.0mm_W3.0mm_P7.50mm_FKS3_FKP3 +C, Rect series, Radial, pin pitch=7.50mm, , length*width=10*3mm^2, Capacitor, http://www.wima.com/EN/WIMA_FKS_3.pdf +C Rect series Radial pin pitch 7.50mm length 10mm width 3mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L10.0mm_W3.0mm_P7.50mm_MKS4 +C, Rect series, Radial, pin pitch=7.50mm, , length*width=10*3.0mm^2, Capacitor, http://www.wima.com/EN/WIMA_MKS_4.pdf +C Rect series Radial pin pitch 7.50mm length 10mm width 3.0mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L10.0mm_W4.0mm_P7.50mm_FKS3_FKP3 +C, Rect series, Radial, pin pitch=7.50mm, , length*width=10*4mm^2, Capacitor, http://www.wima.com/EN/WIMA_FKS_3.pdf +C Rect series Radial pin pitch 7.50mm length 10mm width 4mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L10.0mm_W4.0mm_P7.50mm_MKS4 +C, Rect series, Radial, pin pitch=7.50mm, , length*width=10*4.0mm^2, Capacitor, http://www.wima.com/EN/WIMA_MKS_4.pdf +C Rect series Radial pin pitch 7.50mm length 10mm width 4.0mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L10.0mm_W5.0mm_P5.00mm_P7.50mm +C, Rect series, Radial, pin pitch=5.00mm 7.50mm, , length*width=10*5mm^2, Capacitor +C Rect series Radial pin pitch 5.00mm 7.50mm length 10mm width 5mm Capacitor +0 +4 +2 +Capacitor_THT +C_Rect_L10.3mm_W4.5mm_P7.50mm_MKS4 +C, Rect series, Radial, pin pitch=7.50mm, , length*width=10.3*4.5mm^2, Capacitor, http://www.wima.com/EN/WIMA_MKS_4.pdf +C Rect series Radial pin pitch 7.50mm length 10.3mm width 4.5mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L10.3mm_W5.0mm_P7.50mm_MKS4 +C, Rect series, Radial, pin pitch=7.50mm, , length*width=10.3*5mm^2, Capacitor, http://www.wima.com/EN/WIMA_MKS_4.pdf +C Rect series Radial pin pitch 7.50mm length 10.3mm width 5mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L10.3mm_W5.7mm_P7.50mm_MKS4 +C, Rect series, Radial, pin pitch=7.50mm, , length*width=10.3*5.7mm^2, Capacitor, http://www.wima.com/EN/WIMA_MKS_4.pdf +C Rect series Radial pin pitch 7.50mm length 10.3mm width 5.7mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L10.3mm_W7.2mm_P7.50mm_MKS4 +C, Rect series, Radial, pin pitch=7.50mm, , length*width=10.3*7.2mm^2, Capacitor, http://www.wima.com/EN/WIMA_MKS_4.pdf +C Rect series Radial pin pitch 7.50mm length 10.3mm width 7.2mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L11.0mm_W2.8mm_P10.00mm_MKT +C, Rect series, Radial, pin pitch=10.00mm, , length*width=11.0*2.8mm^2, Capacitor, https://en.tdk.eu/inf/20/20/db/fc_2009/MKT_B32560_564.pdf +C Rect series Radial pin pitch 10.00mm length 11.0mm width 2.8mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L11.0mm_W3.4mm_P10.00mm_MKT +C, Rect series, Radial, pin pitch=10.00mm, , length*width=11.0*3.4mm^2, Capacitor, https://en.tdk.eu/inf/20/20/db/fc_2009/MKT_B32560_564.pdf +C Rect series Radial pin pitch 10.00mm length 11.0mm width 3.4mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L11.0mm_W3.5mm_P10.00mm_MKT +C, Rect series, Radial, pin pitch=10.00mm, , length*width=11.0*3.5mm^2, Capacitor, https://en.tdk.eu/inf/20/20/db/fc_2009/MKT_B32560_564.pdf +C Rect series Radial pin pitch 10.00mm length 11.0mm width 3.5mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L11.0mm_W4.2mm_P10.00mm_MKT +C, Rect series, Radial, pin pitch=10.00mm, , length*width=11.0*4.2mm^2, Capacitor, https://en.tdk.eu/inf/20/20/db/fc_2009/MKT_B32560_564.pdf +C Rect series Radial pin pitch 10.00mm length 11.0mm width 4.2mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L11.0mm_W4.3mm_P10.00mm_MKT +C, Rect series, Radial, pin pitch=10.00mm, , length*width=11.0*4.3mm^2, Capacitor, https://en.tdk.eu/inf/20/20/db/fc_2009/MKT_B32560_564.pdf +C Rect series Radial pin pitch 10.00mm length 11.0mm width 4.3mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L11.0mm_W5.1mm_P10.00mm_MKT +C, Rect series, Radial, pin pitch=10.00mm, , length*width=11.0*5.1mm^2, Capacitor, https://en.tdk.eu/inf/20/20/db/fc_2009/MKT_B32560_564.pdf +C Rect series Radial pin pitch 10.00mm length 11.0mm width 5.1mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L11.0mm_W5.3mm_P10.00mm_MKT +C, Rect series, Radial, pin pitch=10.00mm, , length*width=11.0*5.3mm^2, Capacitor, https://en.tdk.eu/inf/20/20/db/fc_2009/MKT_B32560_564.pdf +C Rect series Radial pin pitch 10.00mm length 11.0mm width 5.3mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L11.0mm_W6.3mm_P10.00mm_MKT +C, Rect series, Radial, pin pitch=10.00mm, , length*width=11.0*6.3mm^2, Capacitor, https://en.tdk.eu/inf/20/20/db/fc_2009/MKT_B32560_564.pdf +C Rect series Radial pin pitch 10.00mm length 11.0mm width 6.3mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L11.0mm_W6.4mm_P10.00mm_MKT +C, Rect series, Radial, pin pitch=10.00mm, , length*width=11.0*6.4mm^2, Capacitor, https://en.tdk.eu/inf/20/20/db/fc_2009/MKT_B32560_564.pdf +C Rect series Radial pin pitch 10.00mm length 11.0mm width 6.4mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L11.0mm_W7.3mm_P10.00mm_MKT +C, Rect series, Radial, pin pitch=10.00mm, , length*width=11.0*7.3mm^2, Capacitor, https://en.tdk.eu/inf/20/20/db/fc_2009/MKT_B32560_564.pdf +C Rect series Radial pin pitch 10.00mm length 11.0mm width 7.3mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L11.0mm_W8.8mm_P10.00mm_MKT +C, Rect series, Radial, pin pitch=10.00mm, , length*width=11.0*8.8mm^2, Capacitor, https://en.tdk.eu/inf/20/20/db/fc_2009/MKT_B32560_564.pdf +C Rect series Radial pin pitch 10.00mm length 11.0mm width 8.8mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L11.5mm_W2.0mm_P10.00mm_MKT +C, Rect series, Radial, pin pitch=10.00mm, , length*width=11.5*2mm^2, Capacitor, https://en.tdk.eu/inf/20/20/db/fc_2009/MKT_B32560_564.pdf +C Rect series Radial pin pitch 10.00mm length 11.5mm width 2mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L11.5mm_W2.6mm_P10.00mm_MKT +C, Rect series, Radial, pin pitch=10.00mm, , length*width=11.5*2.6mm^2, Capacitor, https://en.tdk.eu/inf/20/20/db/fc_2009/MKT_B32560_564.pdf +C Rect series Radial pin pitch 10.00mm length 11.5mm width 2.6mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L11.5mm_W2.8mm_P10.00mm_MKT +C, Rect series, Radial, pin pitch=10.00mm, , length*width=11.5*2.8mm^2, Capacitor, https://en.tdk.eu/inf/20/20/db/fc_2009/MKT_B32560_564.pdf +C Rect series Radial pin pitch 10.00mm length 11.5mm width 2.8mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L11.5mm_W3.2mm_P10.00mm_MKT +C, Rect series, Radial, pin pitch=10.00mm, , length*width=11.5*3.2mm^2, Capacitor, https://en.tdk.eu/inf/20/20/db/fc_2009/MKT_B32560_564.pdf +C Rect series Radial pin pitch 10.00mm length 11.5mm width 3.2mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L11.5mm_W3.5mm_P10.00mm_MKT +C, Rect series, Radial, pin pitch=10.00mm, , length*width=11.5*3.5mm^2, Capacitor, https://en.tdk.eu/inf/20/20/db/fc_2009/MKT_B32560_564.pdf +C Rect series Radial pin pitch 10.00mm length 11.5mm width 3.5mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L11.5mm_W3.6mm_P10.00mm_MKT +C, Rect series, Radial, pin pitch=10.00mm, , length*width=11.5*3.6mm^2, Capacitor, https://en.tdk.eu/inf/20/20/db/fc_2009/MKT_B32560_564.pdf +C Rect series Radial pin pitch 10.00mm length 11.5mm width 3.6mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L11.5mm_W4.0mm_P10.00mm_MKT +C, Rect series, Radial, pin pitch=10.00mm, , length*width=11.5*4.0mm^2, Capacitor, https://en.tdk.eu/inf/20/20/db/fc_2009/MKT_B32560_564.pdf +C Rect series Radial pin pitch 10.00mm length 11.5mm width 4.0mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L11.5mm_W4.3mm_P10.00mm_MKT +C, Rect series, Radial, pin pitch=10.00mm, , length*width=11.5*4.3mm^2, Capacitor, https://en.tdk.eu/inf/20/20/db/fc_2009/MKT_B32560_564.pdf +C Rect series Radial pin pitch 10.00mm length 11.5mm width 4.3mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L11.5mm_W4.5mm_P10.00mm_MKT +C, Rect series, Radial, pin pitch=10.00mm, , length*width=11.5*4.5mm^2, Capacitor, https://en.tdk.eu/inf/20/20/db/fc_2009/MKT_B32560_564.pdf +C Rect series Radial pin pitch 10.00mm length 11.5mm width 4.5mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L11.5mm_W5.0mm_P10.00mm_MKT +C, Rect series, Radial, pin pitch=10.00mm, , length*width=11.5*5mm^2, Capacitor, https://en.tdk.eu/inf/20/20/db/fc_2009/MKT_B32560_564.pdf +C Rect series Radial pin pitch 10.00mm length 11.5mm width 5mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L11.5mm_W5.1mm_P10.00mm_MKT +C, Rect series, Radial, pin pitch=10.00mm, , length*width=11.5*5.1mm^2, Capacitor, https://en.tdk.eu/inf/20/20/db/fc_2009/MKT_B32560_564.pdf +C Rect series Radial pin pitch 10.00mm length 11.5mm width 5.1mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L11.5mm_W5.2mm_P10.00mm_MKT +C, Rect series, Radial, pin pitch=10.00mm, , length*width=11.5*5.2mm^2, Capacitor, https://en.tdk.eu/inf/20/20/db/fc_2009/MKT_B32560_564.pdf +C Rect series Radial pin pitch 10.00mm length 11.5mm width 5.2mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L11.5mm_W5.6mm_P10.00mm_MKT +C, Rect series, Radial, pin pitch=10.00mm, , length*width=11.5*5.6mm^2, Capacitor, https://en.tdk.eu/inf/20/20/db/fc_2009/MKT_B32560_564.pdf +C Rect series Radial pin pitch 10.00mm length 11.5mm width 5.6mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L11.5mm_W6.4mm_P10.00mm_MKT +C, Rect series, Radial, pin pitch=10.00mm, , length*width=11.5*6.4mm^2, Capacitor, https://en.tdk.eu/inf/20/20/db/fc_2009/MKT_B32560_564.pdf +C Rect series Radial pin pitch 10.00mm length 11.5mm width 6.4mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L11.5mm_W6.6mm_P10.00mm_MKT +C, Rect series, Radial, pin pitch=10.00mm, , length*width=11.5*6.6mm^2, Capacitor, https://en.tdk.eu/inf/20/20/db/fc_2009/MKT_B32560_564.pdf +C Rect series Radial pin pitch 10.00mm length 11.5mm width 6.6mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L11.5mm_W6.9mm_P10.00mm_MKT +C, Rect series, Radial, pin pitch=10.00mm, , length*width=11.5*6.9mm^2, Capacitor, https://en.tdk.eu/inf/20/20/db/fc_2009/MKT_B32560_564.pdf +C Rect series Radial pin pitch 10.00mm length 11.5mm width 6.9mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L11.5mm_W7.3mm_P10.00mm_MKT +C, Rect series, Radial, pin pitch=10.00mm, , length*width=11.5*7.3mm^2, Capacitor, https://en.tdk.eu/inf/20/20/db/fc_2009/MKT_B32560_564.pdf +C Rect series Radial pin pitch 10.00mm length 11.5mm width 7.3mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L11.5mm_W7.5mm_P10.00mm_MKT +C, Rect series, Radial, pin pitch=10.00mm, , length*width=11.5*7.5mm^2, Capacitor, https://en.tdk.eu/inf/20/20/db/fc_2009/MKT_B32560_564.pdf +C Rect series Radial pin pitch 10.00mm length 11.5mm width 7.5mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L11.5mm_W7.8mm_P10.00mm_MKT +C, Rect series, Radial, pin pitch=10.00mm, , length*width=11.5*7.8mm^2, Capacitor, https://en.tdk.eu/inf/20/20/db/fc_2009/MKT_B32560_564.pdf +C Rect series Radial pin pitch 10.00mm length 11.5mm width 7.8mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L11.5mm_W8.0mm_P10.00mm_MKT +C, Rect series, Radial, pin pitch=10.00mm, , length*width=11.5*8.0mm^2, Capacitor, https://en.tdk.eu/inf/20/20/db/fc_2009/MKT_B32560_564.pdf +C Rect series Radial pin pitch 10.00mm length 11.5mm width 8.0mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L11.5mm_W8.8mm_P10.00mm_MKT +C, Rect series, Radial, pin pitch=10.00mm, , length*width=11.5*8.8mm^2, Capacitor, https://en.tdk.eu/inf/20/20/db/fc_2009/MKT_B32560_564.pdf +C Rect series Radial pin pitch 10.00mm length 11.5mm width 8.8mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L11.5mm_W9.5mm_P10.00mm_MKT +C, Rect series, Radial, pin pitch=10.00mm, , length*width=11.5*9.5mm^2, Capacitor, https://en.tdk.eu/inf/20/20/db/fc_2009/MKT_B32560_564.pdf +C Rect series Radial pin pitch 10.00mm length 11.5mm width 9.5mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L11.5mm_W9.8mm_P10.00mm_MKT +C, Rect series, Radial, pin pitch=10.00mm, , length*width=11.5*9.8mm^2, Capacitor, https://en.tdk.eu/inf/20/20/db/fc_2009/MKT_B32560_564.pdf +C Rect series Radial pin pitch 10.00mm length 11.5mm width 9.8mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L13.0mm_W3.0mm_P10.00mm_FKS3_FKP3_MKS4 +C, Rect series, Radial, pin pitch=10.00mm, , length*width=13*3mm^2, Capacitor, http://www.wima.com/EN/WIMA_FKS_3.pdf, http://www.wima.com/EN/WIMA_MKS_4.pdf +C Rect series Radial pin pitch 10.00mm length 13mm width 3mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L13.0mm_W4.0mm_P10.00mm_FKS3_FKP3_MKS4 +C, Rect series, Radial, pin pitch=10.00mm, , length*width=13*4mm^2, Capacitor, http://www.wima.com/EN/WIMA_FKS_3.pdf, http://www.wima.com/EN/WIMA_MKS_4.pdf +C Rect series Radial pin pitch 10.00mm length 13mm width 4mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L13.0mm_W5.0mm_P10.00mm_FKS3_FKP3_MKS4 +C, Rect series, Radial, pin pitch=10.00mm, , length*width=13*5mm^2, Capacitor, http://www.wima.com/EN/WIMA_FKS_3.pdf, http://www.wima.com/EN/WIMA_MKS_4.pdf +C Rect series Radial pin pitch 10.00mm length 13mm width 5mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L13.0mm_W6.0mm_P10.00mm_FKS3_FKP3_MKS4 +C, Rect series, Radial, pin pitch=10.00mm, , length*width=13*6mm^2, Capacitor, http://www.wima.com/EN/WIMA_FKS_3.pdf, http://www.wima.com/EN/WIMA_MKS_4.pdf +C Rect series Radial pin pitch 10.00mm length 13mm width 6mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L13.0mm_W6.5mm_P7.50mm_P10.00mm +C, Rect series, Radial, pin pitch=7.50mm 10.00mm, , length*width=13*6.5mm^2, Capacitor +C Rect series Radial pin pitch 7.50mm 10.00mm length 13mm width 6.5mm Capacitor +0 +4 +2 +Capacitor_THT +C_Rect_L13.0mm_W8.0mm_P10.00mm_FKS3_FKP3_MKS4 +C, Rect series, Radial, pin pitch=10.00mm, , length*width=13*8mm^2, Capacitor, http://www.wima.com/EN/WIMA_FKS_3.pdf, http://www.wima.com/EN/WIMA_MKS_4.pdf +C Rect series Radial pin pitch 10.00mm length 13mm width 8mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L13.5mm_W4.0mm_P10.00mm_FKS3_FKP3_MKS4 +C, Rect series, Radial, pin pitch=10.00mm, , length*width=13.5*4mm^2, Capacitor, http://www.wima.com/EN/WIMA_FKS_3.pdf, http://www.wima.com/EN/WIMA_MKS_4.pdf +C Rect series Radial pin pitch 10.00mm length 13.5mm width 4mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L13.5mm_W5.0mm_P10.00mm_FKS3_FKP3_MKS4 +C, Rect series, Radial, pin pitch=10.00mm, , length*width=13.5*5mm^2, Capacitor, http://www.wima.com/EN/WIMA_FKS_3.pdf, http://www.wima.com/EN/WIMA_MKS_4.pdf +C Rect series Radial pin pitch 10.00mm length 13.5mm width 5mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L16.5mm_W4.7mm_P15.00mm_MKT +C, Rect series, Radial, pin pitch=15.00mm, , length*width=16.5*4.7mm^2, Capacitor, https://en.tdk.eu/inf/20/20/db/fc_2009/MKT_B32560_564.pdf +C Rect series Radial pin pitch 15.00mm length 16.5mm width 4.7mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L16.5mm_W4.9mm_P15.00mm_MKT +C, Rect series, Radial, pin pitch=15.00mm, , length*width=16.5*4.9mm^2, Capacitor, https://en.tdk.eu/inf/20/20/db/fc_2009/MKT_B32560_564.pdf +C Rect series Radial pin pitch 15.00mm length 16.5mm width 4.9mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L16.5mm_W5.0mm_P15.00mm_MKT +C, Rect series, Radial, pin pitch=15.00mm, , length*width=16.5*5mm^2, Capacitor, https://en.tdk.eu/inf/20/20/db/fc_2009/MKT_B32560_564.pdf +C Rect series Radial pin pitch 15.00mm length 16.5mm width 5mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L16.5mm_W6.0mm_P15.00mm_MKT +C, Rect series, Radial, pin pitch=15.00mm, , length*width=16.5*6mm^2, Capacitor, https://en.tdk.eu/inf/20/20/db/fc_2009/MKT_B32560_564.pdf +C Rect series Radial pin pitch 15.00mm length 16.5mm width 6mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L16.5mm_W7.0mm_P15.00mm_MKT +C, Rect series, Radial, pin pitch=15.00mm, , length*width=16.5*7mm^2, Capacitor, https://en.tdk.eu/inf/20/20/db/fc_2009/MKT_B32560_564.pdf +C Rect series Radial pin pitch 15.00mm length 16.5mm width 7mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L16.5mm_W7.3mm_P15.00mm_MKT +C, Rect series, Radial, pin pitch=15.00mm, , length*width=16.5*7.3mm^2, Capacitor, https://en.tdk.eu/inf/20/20/db/fc_2009/MKT_B32560_564.pdf +C Rect series Radial pin pitch 15.00mm length 16.5mm width 7.3mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L16.5mm_W8.7mm_P15.00mm_MKT +C, Rect series, Radial, pin pitch=15.00mm, , length*width=16.5*8.7mm^2, Capacitor, https://en.tdk.eu/inf/20/20/db/fc_2009/MKT_B32560_564.pdf +C Rect series Radial pin pitch 15.00mm length 16.5mm width 8.7mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L16.5mm_W8.9mm_P15.00mm_MKT +C, Rect series, Radial, pin pitch=15.00mm, , length*width=16.5*8.9mm^2, Capacitor, https://en.tdk.eu/inf/20/20/db/fc_2009/MKT_B32560_564.pdf +C Rect series Radial pin pitch 15.00mm length 16.5mm width 8.9mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L16.5mm_W9.0mm_P15.00mm_MKT +C, Rect series, Radial, pin pitch=15.00mm, , length*width=16.5*9mm^2, Capacitor, https://en.tdk.eu/inf/20/20/db/fc_2009/MKT_B32560_564.pdf +C Rect series Radial pin pitch 15.00mm length 16.5mm width 9mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L16.5mm_W9.2mm_P15.00mm_MKT +C, Rect series, Radial, pin pitch=15.00mm, , length*width=16.5*9.2mm^2, Capacitor, https://en.tdk.eu/inf/20/20/db/fc_2009/MKT_B32560_564.pdf +C Rect series Radial pin pitch 15.00mm length 16.5mm width 9.2mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L16.5mm_W10.7mm_P15.00mm_MKT +C, Rect series, Radial, pin pitch=15.00mm, , length*width=16.5*10.7mm^2, Capacitor, https://en.tdk.eu/inf/20/20/db/fc_2009/MKT_B32560_564.pdf +C Rect series Radial pin pitch 15.00mm length 16.5mm width 10.7mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L16.5mm_W10.9mm_P15.00mm_MKT +C, Rect series, Radial, pin pitch=15.00mm, , length*width=16.5*10.9mm^2, Capacitor, https://en.tdk.eu/inf/20/20/db/fc_2009/MKT_B32560_564.pdf +C Rect series Radial pin pitch 15.00mm length 16.5mm width 10.9mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L16.5mm_W11.2mm_P15.00mm_MKT +C, Rect series, Radial, pin pitch=15.00mm, , length*width=16.5*11.2mm^2, Capacitor, https://en.tdk.eu/inf/20/20/db/fc_2009/MKT_B32560_564.pdf +C Rect series Radial pin pitch 15.00mm length 16.5mm width 11.2mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L16.5mm_W11.8mm_P15.00mm_MKT +C, Rect series, Radial, pin pitch=15.00mm, , length*width=16.5*11.8mm^2, Capacitor, https://en.tdk.eu/inf/20/20/db/fc_2009/MKT_B32560_564.pdf +C Rect series Radial pin pitch 15.00mm length 16.5mm width 11.8mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L16.5mm_W13.5mm_P15.00mm_MKT +C, Rect series, Radial, pin pitch=15.00mm, , length*width=16.5*13.5mm^2, Capacitor, https://en.tdk.eu/inf/20/20/db/fc_2009/MKT_B32560_564.pdf +C Rect series Radial pin pitch 15.00mm length 16.5mm width 13.5mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L16.5mm_W13.7mm_P15.00mm_MKT +C, Rect series, Radial, pin pitch=15.00mm, , length*width=16.5*13.7mm^2, Capacitor, https://en.tdk.eu/inf/20/20/db/fc_2009/MKT_B32560_564.pdf +C Rect series Radial pin pitch 15.00mm length 16.5mm width 13.7mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L16.5mm_W13.9mm_P15.00mm_MKT +C, Rect series, Radial, pin pitch=15.00mm, , length*width=16.5*13.9mm^2, Capacitor, https://en.tdk.eu/inf/20/20/db/fc_2009/MKT_B32560_564.pdf +C Rect series Radial pin pitch 15.00mm length 16.5mm width 13.9mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L18.0mm_W5.0mm_P15.00mm_FKS3_FKP3 +C, Rect series, Radial, pin pitch=15.00mm, , length*width=18*5mm^2, Capacitor, http://www.wima.com/EN/WIMA_FKS_3.pdf +C Rect series Radial pin pitch 15.00mm length 18mm width 5mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L18.0mm_W6.0mm_P15.00mm_FKS3_FKP3 +C, Rect series, Radial, pin pitch=15.00mm, , length*width=18*6mm^2, Capacitor, http://www.wima.com/EN/WIMA_FKS_3.pdf +C Rect series Radial pin pitch 15.00mm length 18mm width 6mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L18.0mm_W7.0mm_P15.00mm_FKS3_FKP3 +C, Rect series, Radial, pin pitch=15.00mm, , length*width=18*7mm^2, Capacitor, http://www.wima.com/EN/WIMA_FKS_3.pdf +C Rect series Radial pin pitch 15.00mm length 18mm width 7mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L18.0mm_W8.0mm_P15.00mm_FKS3_FKP3 +C, Rect series, Radial, pin pitch=15.00mm, , length*width=18*8mm^2, Capacitor, http://www.wima.com/EN/WIMA_FKS_3.pdf +C Rect series Radial pin pitch 15.00mm length 18mm width 8mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L18.0mm_W9.0mm_P15.00mm_FKS3_FKP3 +C, Rect series, Radial, pin pitch=15.00mm, , length*width=18*9mm^2, Capacitor, http://www.wima.com/EN/WIMA_FKS_3.pdf +C Rect series Radial pin pitch 15.00mm length 18mm width 9mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L18.0mm_W11.0mm_P15.00mm_FKS3_FKP3 +C, Rect series, Radial, pin pitch=15.00mm, , length*width=18*11mm^2, Capacitor, http://www.wima.com/EN/WIMA_FKS_3.pdf +C Rect series Radial pin pitch 15.00mm length 18mm width 11mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L19.0mm_W5.0mm_P15.00mm_MKS4 +C, Rect series, Radial, pin pitch=15.00mm, , length*width=19*5mm^2, Capacitor, http://www.wima.com/EN/WIMA_MKS_4.pdf +C Rect series Radial pin pitch 15.00mm length 19mm width 5mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L19.0mm_W6.0mm_P15.00mm_MKS4 +C, Rect series, Radial, pin pitch=15.00mm, , length*width=19*6mm^2, Capacitor, http://www.wima.com/EN/WIMA_MKS_4.pdf +C Rect series Radial pin pitch 15.00mm length 19mm width 6mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L19.0mm_W7.0mm_P15.00mm_MKS4 +C, Rect series, Radial, pin pitch=15.00mm, , length*width=19*7mm^2, Capacitor, http://www.wima.com/EN/WIMA_MKS_4.pdf +C Rect series Radial pin pitch 15.00mm length 19mm width 7mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L19.0mm_W8.0mm_P15.00mm_MKS4 +C, Rect series, Radial, pin pitch=15.00mm, , length*width=19*8mm^2, Capacitor, http://www.wima.com/EN/WIMA_MKS_4.pdf +C Rect series Radial pin pitch 15.00mm length 19mm width 8mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L19.0mm_W9.0mm_P15.00mm_MKS4 +C, Rect series, Radial, pin pitch=15.00mm, , length*width=19*9mm^2, Capacitor, http://www.wima.com/EN/WIMA_MKS_4.pdf +C Rect series Radial pin pitch 15.00mm length 19mm width 9mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L19.0mm_W11.0mm_P15.00mm_MKS4 +C, Rect series, Radial, pin pitch=15.00mm, , length*width=19*11mm^2, Capacitor, http://www.wima.com/EN/WIMA_MKS_4.pdf +C Rect series Radial pin pitch 15.00mm length 19mm width 11mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L24.0mm_W7.0mm_P22.50mm_MKT +C, Rect series, Radial, pin pitch=22.50mm, , length*width=24*7mm^2, Capacitor, https://en.tdk.eu/inf/20/20/db/fc_2009/MKT_B32560_564.pdf +C Rect series Radial pin pitch 22.50mm length 24mm width 7mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L24.0mm_W8.3mm_P22.50mm_MKT +C, Rect series, Radial, pin pitch=22.50mm, , length*width=24*8.3mm^2, Capacitor, https://en.tdk.eu/inf/20/20/db/fc_2009/MKT_B32560_564.pdf +C Rect series Radial pin pitch 22.50mm length 24mm width 8.3mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L24.0mm_W8.6mm_P22.50mm_MKT +C, Rect series, Radial, pin pitch=22.50mm, , length*width=24*8.6mm^2, Capacitor, https://en.tdk.eu/inf/20/20/db/fc_2009/MKT_B32560_564.pdf +C Rect series Radial pin pitch 22.50mm length 24mm width 8.6mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L24.0mm_W10.1mm_P22.50mm_MKT +C, Rect series, Radial, pin pitch=22.50mm, , length*width=24*10.1mm^2, Capacitor, https://en.tdk.eu/inf/20/20/db/fc_2009/MKT_B32560_564.pdf +C Rect series Radial pin pitch 22.50mm length 24mm width 10.1mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L24.0mm_W10.3mm_P22.50mm_MKT +C, Rect series, Radial, pin pitch=22.50mm, , length*width=24*10.3mm^2, Capacitor, https://en.tdk.eu/inf/20/20/db/fc_2009/MKT_B32560_564.pdf +C Rect series Radial pin pitch 22.50mm length 24mm width 10.3mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L24.0mm_W10.9mm_P22.50mm_MKT +C, Rect series, Radial, pin pitch=22.50mm, , length*width=24*10.9mm^2, Capacitor, https://en.tdk.eu/inf/20/20/db/fc_2009/MKT_B32560_564.pdf +C Rect series Radial pin pitch 22.50mm length 24mm width 10.9mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L24.0mm_W12.2mm_P22.50mm_MKT +C, Rect series, Radial, pin pitch=22.50mm, , length*width=24*12.2mm^2, Capacitor, https://en.tdk.eu/inf/20/20/db/fc_2009/MKT_B32560_564.pdf +C Rect series Radial pin pitch 22.50mm length 24mm width 12.2mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L24.0mm_W12.6mm_P22.50mm_MKT +C, Rect series, Radial, pin pitch=22.50mm, , length*width=24*12.6mm^2, Capacitor, https://en.tdk.eu/inf/20/20/db/fc_2009/MKT_B32560_564.pdf +C Rect series Radial pin pitch 22.50mm length 24mm width 12.6mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L24.0mm_W12.8mm_P22.50mm_MKT +C, Rect series, Radial, pin pitch=22.50mm, , length*width=24*12.8mm^2, Capacitor, https://en.tdk.eu/inf/20/20/db/fc_2009/MKT_B32560_564.pdf +C Rect series Radial pin pitch 22.50mm length 24mm width 12.8mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L26.5mm_W5.0mm_P22.50mm_MKS4 +C, Rect series, Radial, pin pitch=22.50mm, , length*width=26.5*5mm^2, Capacitor, http://www.wima.com/EN/WIMA_MKS_4.pdf +C Rect series Radial pin pitch 22.50mm length 26.5mm width 5mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L26.5mm_W6.0mm_P22.50mm_MKS4 +C, Rect series, Radial, pin pitch=22.50mm, , length*width=26.5*6mm^2, Capacitor, http://www.wima.com/EN/WIMA_MKS_4.pdf +C Rect series Radial pin pitch 22.50mm length 26.5mm width 6mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L26.5mm_W7.0mm_P22.50mm_MKS4 +C, Rect series, Radial, pin pitch=22.50mm, , length*width=26.5*7mm^2, Capacitor, http://www.wima.com/EN/WIMA_MKS_4.pdf +C Rect series Radial pin pitch 22.50mm length 26.5mm width 7mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L26.5mm_W8.5mm_P22.50mm_MKS4 +C, Rect series, Radial, pin pitch=22.50mm, , length*width=26.5*8.5mm^2, Capacitor, http://www.wima.com/EN/WIMA_MKS_4.pdf +C Rect series Radial pin pitch 22.50mm length 26.5mm width 8.5mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L26.5mm_W10.5mm_P22.50mm_MKS4 +C, Rect series, Radial, pin pitch=22.50mm, , length*width=26.5*10.5mm^2, Capacitor, http://www.wima.com/EN/WIMA_MKS_4.pdf +C Rect series Radial pin pitch 22.50mm length 26.5mm width 10.5mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L26.5mm_W11.5mm_P22.50mm_MKS4 +C, Rect series, Radial, pin pitch=22.50mm, , length*width=26.5*11.5mm^2, Capacitor, http://www.wima.com/EN/WIMA_MKS_4.pdf +C Rect series Radial pin pitch 22.50mm length 26.5mm width 11.5mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L27.0mm_W9.0mm_P22.00mm +C, Rect series, Radial, pin pitch=22.00mm, , length*width=27*9mm^2, Capacitor +C Rect series Radial pin pitch 22.00mm length 27mm width 9mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L27.0mm_W9.0mm_P23.00mm +C, Rect series, Radial, pin pitch=23.00mm, , length*width=27*9mm^2, Capacitor +C Rect series Radial pin pitch 23.00mm length 27mm width 9mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L27.0mm_W11.0mm_P22.00mm +C, Rect series, Radial, pin pitch=22.00mm, , length*width=27*11mm^2, Capacitor +C Rect series Radial pin pitch 22.00mm length 27mm width 11mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L28.0mm_W8.0mm_P22.50mm_MKS4 +C, Rect series, Radial, pin pitch=22.50mm, , length*width=28*8mm^2, Capacitor, http://www.wima.com/EN/WIMA_MKS_4.pdf +C Rect series Radial pin pitch 22.50mm length 28mm width 8mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L28.0mm_W10.0mm_P22.50mm_MKS4 +C, Rect series, Radial, pin pitch=22.50mm, , length*width=28*10mm^2, Capacitor, http://www.wima.com/EN/WIMA_MKS_4.pdf +C Rect series Radial pin pitch 22.50mm length 28mm width 10mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L28.0mm_W12.0mm_P22.50mm_MKS4 +C, Rect series, Radial, pin pitch=22.50mm, , length*width=28*12mm^2, Capacitor, http://www.wima.com/EN/WIMA_MKS_4.pdf +C Rect series Radial pin pitch 22.50mm length 28mm width 12mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L29.0mm_W7.6mm_P27.50mm_MKT +C, Rect series, Radial, pin pitch=27.50mm, , length*width=29*7.6mm^2, Capacitor, https://en.tdk.eu/inf/20/20/db/fc_2009/MKT_B32560_564.pdf +C Rect series Radial pin pitch 27.50mm length 29mm width 7.6mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L29.0mm_W7.8mm_P27.50mm_MKT +C, Rect series, Radial, pin pitch=27.50mm, , length*width=29*7.8mm^2, Capacitor, https://en.tdk.eu/inf/20/20/db/fc_2009/MKT_B32560_564.pdf +C Rect series Radial pin pitch 27.50mm length 29mm width 7.8mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L29.0mm_W7.9mm_P27.50mm_MKT +C, Rect series, Radial, pin pitch=27.50mm, , length*width=29*7.9mm^2, Capacitor, https://en.tdk.eu/inf/20/20/db/fc_2009/MKT_B32560_564.pdf +C Rect series Radial pin pitch 27.50mm length 29mm width 7.9mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L29.0mm_W9.1mm_P27.50mm_MKT +C, Rect series, Radial, pin pitch=27.50mm, , length*width=29*9.1mm^2, Capacitor, https://en.tdk.eu/inf/20/20/db/fc_2009/MKT_B32560_564.pdf +C Rect series Radial pin pitch 27.50mm length 29mm width 9.1mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L29.0mm_W9.6mm_P27.50mm_MKT +C, Rect series, Radial, pin pitch=27.50mm, , length*width=29*9.6mm^2, Capacitor, https://en.tdk.eu/inf/20/20/db/fc_2009/MKT_B32560_564.pdf +C Rect series Radial pin pitch 27.50mm length 29mm width 9.6mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L29.0mm_W11.0mm_P27.50mm_MKT +C, Rect series, Radial, pin pitch=27.50mm, , length*width=29*11mm^2, Capacitor, https://en.tdk.eu/inf/20/20/db/fc_2009/MKT_B32560_564.pdf +C Rect series Radial pin pitch 27.50mm length 29mm width 11mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L29.0mm_W11.9mm_P27.50mm_MKT +C, Rect series, Radial, pin pitch=27.50mm, , length*width=29*11.9mm^2, Capacitor, https://en.tdk.eu/inf/20/20/db/fc_2009/MKT_B32560_564.pdf +C Rect series Radial pin pitch 27.50mm length 29mm width 11.9mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L29.0mm_W12.2mm_P27.50mm_MKT +C, Rect series, Radial, pin pitch=27.50mm, , length*width=29*12.2mm^2, Capacitor, https://en.tdk.eu/inf/20/20/db/fc_2009/MKT_B32560_564.pdf +C Rect series Radial pin pitch 27.50mm length 29mm width 12.2mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L29.0mm_W13.0mm_P27.50mm_MKT +C, Rect series, Radial, pin pitch=27.50mm, , length*width=29*13mm^2, Capacitor, https://en.tdk.eu/inf/20/20/db/fc_2009/MKT_B32560_564.pdf +C Rect series Radial pin pitch 27.50mm length 29mm width 13mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L29.0mm_W13.8mm_P27.50mm_MKT +C, Rect series, Radial, pin pitch=27.50mm, , length*width=29*13.8mm^2, Capacitor, https://en.tdk.eu/inf/20/20/db/fc_2009/MKT_B32560_564.pdf +C Rect series Radial pin pitch 27.50mm length 29mm width 13.8mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L29.0mm_W14.2mm_P27.50mm_MKT +C, Rect series, Radial, pin pitch=27.50mm, , length*width=29*14.2mm^2, Capacitor, https://en.tdk.eu/inf/20/20/db/fc_2009/MKT_B32560_564.pdf +C Rect series Radial pin pitch 27.50mm length 29mm width 14.2mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L29.0mm_W16.0mm_P27.50mm_MKT +C, Rect series, Radial, pin pitch=27.50mm, , length*width=29*16mm^2, Capacitor, https://en.tdk.eu/inf/20/20/db/fc_2009/MKT_B32560_564.pdf +C Rect series Radial pin pitch 27.50mm length 29mm width 16mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L31.5mm_W9.0mm_P27.50mm_MKS4 +C, Rect series, Radial, pin pitch=27.50mm, , length*width=31.5*9mm^2, Capacitor, http://www.wima.com/EN/WIMA_MKS_4.pdf +C Rect series Radial pin pitch 27.50mm length 31.5mm width 9mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L31.5mm_W11.0mm_P27.50mm_MKS4 +C, Rect series, Radial, pin pitch=27.50mm, , length*width=31.5*11mm^2, Capacitor, http://www.wima.com/EN/WIMA_MKS_4.pdf +C Rect series Radial pin pitch 27.50mm length 31.5mm width 11mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L31.5mm_W13.0mm_P27.50mm_MKS4 +C, Rect series, Radial, pin pitch=27.50mm, , length*width=31.5*13mm^2, Capacitor, http://www.wima.com/EN/WIMA_MKS_4.pdf +C Rect series Radial pin pitch 27.50mm length 31.5mm width 13mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L31.5mm_W15.0mm_P27.50mm_MKS4 +C, Rect series, Radial, pin pitch=27.50mm, , length*width=31.5*15mm^2, Capacitor, http://www.wima.com/EN/WIMA_MKS_4.pdf +C Rect series Radial pin pitch 27.50mm length 31.5mm width 15mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L31.5mm_W17.0mm_P27.50mm_MKS4 +C, Rect series, Radial, pin pitch=27.50mm, , length*width=31.5*17mm^2, Capacitor, http://www.wima.com/EN/WIMA_MKS_4.pdf +C Rect series Radial pin pitch 27.50mm length 31.5mm width 17mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L31.5mm_W20.0mm_P27.50mm_MKS4 +C, Rect series, Radial, pin pitch=27.50mm, , length*width=31.5*20mm^2, Capacitor, http://www.wima.com/EN/WIMA_MKS_4.pdf +C Rect series Radial pin pitch 27.50mm length 31.5mm width 20mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L32.0mm_W15.0mm_P27.00mm +C, Rect series, Radial, pin pitch=27.00mm, , length*width=32*15mm^2, Capacitor +C Rect series Radial pin pitch 27.00mm length 32mm width 15mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L33.0mm_W13.0mm_P27.50mm_MKS4 +C, Rect series, Radial, pin pitch=27.50mm, , length*width=33*13mm^2, Capacitor, http://www.wima.com/EN/WIMA_MKS_4.pdf +C Rect series Radial pin pitch 27.50mm length 33mm width 13mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L33.0mm_W15.0mm_P27.50mm_MKS4 +C, Rect series, Radial, pin pitch=27.50mm, , length*width=33*15mm^2, Capacitor, http://www.wima.com/EN/WIMA_MKS_4.pdf +C Rect series Radial pin pitch 27.50mm length 33mm width 15mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L33.0mm_W20.0mm_P27.50mm_MKS4 +C, Rect series, Radial, pin pitch=27.50mm, , length*width=33*20mm^2, Capacitor, http://www.wima.com/EN/WIMA_MKS_4.pdf +C Rect series Radial pin pitch 27.50mm length 33mm width 20mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L41.5mm_W9.0mm_P37.50mm_MKS4 +C, Rect series, Radial, pin pitch=37.50mm, , length*width=41.5*9mm^2, Capacitor, http://www.wima.com/EN/WIMA_MKS_4.pdf +C Rect series Radial pin pitch 37.50mm length 41.5mm width 9mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L41.5mm_W11.0mm_P37.50mm_MKS4 +C, Rect series, Radial, pin pitch=37.50mm, , length*width=41.5*11mm^2, Capacitor, http://www.wima.com/EN/WIMA_MKS_4.pdf +C Rect series Radial pin pitch 37.50mm length 41.5mm width 11mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L41.5mm_W13.0mm_P37.50mm_MKS4 +C, Rect series, Radial, pin pitch=37.50mm, , length*width=41.5*13mm^2, Capacitor, http://www.wima.com/EN/WIMA_MKS_4.pdf +C Rect series Radial pin pitch 37.50mm length 41.5mm width 13mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L41.5mm_W15.0mm_P37.50mm_MKS4 +C, Rect series, Radial, pin pitch=37.50mm, , length*width=41.5*15mm^2, Capacitor, http://www.wima.com/EN/WIMA_MKS_4.pdf +C Rect series Radial pin pitch 37.50mm length 41.5mm width 15mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L41.5mm_W17.0mm_P37.50mm_MKS4 +C, Rect series, Radial, pin pitch=37.50mm, , length*width=41.5*17mm^2, Capacitor, http://www.wima.com/EN/WIMA_MKS_4.pdf +C Rect series Radial pin pitch 37.50mm length 41.5mm width 17mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L41.5mm_W19.0mm_P37.50mm_MKS4 +C, Rect series, Radial, pin pitch=37.50mm, , length*width=41.5*19mm^2, Capacitor, http://www.wima.com/EN/WIMA_MKS_4.pdf +C Rect series Radial pin pitch 37.50mm length 41.5mm width 19mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L41.5mm_W20.0mm_P37.50mm_MKS4 +C, Rect series, Radial, pin pitch=37.50mm, , length*width=41.5*20mm^2, Capacitor, http://www.wima.com/EN/WIMA_MKS_4.pdf +C Rect series Radial pin pitch 37.50mm length 41.5mm width 20mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L41.5mm_W24.0mm_P37.50mm_MKS4 +C, Rect series, Radial, pin pitch=37.50mm, , length*width=41.5*24mm^2, Capacitor, http://www.wima.com/EN/WIMA_MKS_4.pdf +C Rect series Radial pin pitch 37.50mm length 41.5mm width 24mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L41.5mm_W31.0mm_P37.50mm_MKS4 +C, Rect series, Radial, pin pitch=37.50mm, , length*width=41.5*31mm^2, Capacitor, http://www.wima.com/EN/WIMA_MKS_4.pdf +C Rect series Radial pin pitch 37.50mm length 41.5mm width 31mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L41.5mm_W35.0mm_P37.50mm_MKS4 +C, Rect series, Radial, pin pitch=37.50mm, , length*width=41.5*35mm^2, Capacitor, http://www.wima.com/EN/WIMA_MKS_4.pdf +C Rect series Radial pin pitch 37.50mm length 41.5mm width 35mm Capacitor +0 +2 +2 +Capacitor_THT +C_Rect_L41.5mm_W40.0mm_P37.50mm_MKS4 +C, Rect series, Radial, pin pitch=37.50mm, , length*width=41.5*40mm^2, Capacitor, http://www.wima.com/EN/WIMA_MKS_4.pdf +C Rect series Radial pin pitch 37.50mm length 41.5mm width 40mm Capacitor +0 +2 +2 +chrono +L80-R + + +0 +13 +12 +Connectors +Banana_Jack_1Pin +Single banana socket, footprint - 6mm drill +banana socket +0 +1 +1 +Connectors +Banana_Jack_2Pin +Dual banana socket, footprint - 2 x 6mm drills +banana socket +0 +2 +2 +Connectors +Banana_Jack_3Pin +Triple banana socket, footprint - 3 x 6mm drills +banana socket +0 +3 +3 +Connectors +CalTest_CT3151 +Right-angle standard banana jack, http://www.caltestelectronics.com/images/attachments/P315100rH_drawing.pdf +banana jack horizontal +0 +4 +1 +Connectors +CUI_PD-30 +3 pin connector, PD-30, http://www.cui.com/product/resource/pd-30.pdf +connector 3-pin PD-30 power DIN +0 +4 +4 +Connectors +DTF13-12Px +http://www.te.com/usa-en/product-DTF13-12PA-G003.html +DEUTSCH DT header 12 pin +0 +12 +12 +Connectors +FanPinHeader_1x03_P2.54mm_Vertical +3-pin CPU fan Through hole pin header, see http://www.formfactors.org/developer%5Cspecs%5Crev1_2_public.pdf +pin header 3-pin CPU fan +0 +3 +3 +Connectors +FanPinHeader_1x04_P2.54mm_Vertical +4-pin CPU fan Through hole pin header, e.g. for Wieson part number 2366C888-007 Molex 47053-1000, Foxconn HF27040-M1, Tyco 1470947-1 or equivalent, see http://www.formfactors.org/developer%5Cspecs%5Crev1_2_public.pdf +pin header 4-pin CPU fan +0 +4 +4 +Connectors +GB042-34S-H10 +http://www.lsmtron.com/pdf/Connector&Antenna_catalog.PDF +34pin SMD connector +0 +34 +34 +Connectors +IHI_B6A-PCB-45_Vertical +https://lugsdirect.com/PDF_Webprint/B6A-PCB-45-XX(-X).pdf +connector IHI B6A-PCB-45 +0 +49 +1 +Connectors +JWT_A3963_1x02_P3.96mm_Vertical +JWT A3963, 3.96mm pitch Pin head connector (http://www.jwt.com.tw/pro_pdf/A3963.pdf) +connector JWT A3963 pinhead +0 +2 +2 +Connectors +NS-Tech_Grove_1x04_P2mm_Vertical +https://statics3.seeedstudio.com/images/opl/datasheet/3470130P1.pdf +Grove-1x04 +0 +4 +4 +Connectors +Tag-Connect_TC2030-IDC-FP_2x03_P1.27mm_Vertical +Tag-Connect programming header; http://www.tag-connect.com/Materials/TC2030-IDC.pdf +tag connect programming header pogo pins +0 +6 +6 +Connectors +Tag-Connect_TC2030-IDC-NL_2x03_P1.27mm_Vertical +Tag-Connect programming header; http://www.tag-connect.com/Materials/TC2030-IDC-NL.pdf +tag connect programming header pogo pins +0 +6 +6 +Connectors +Tag-Connect_TC2050-IDC-FP_2x05_P1.27mm_Vertical +Tag-Connect programming header; http://www.tag-connect.com/Materials/TC2050-IDC-430%20Datasheet.pdf +tag connect programming header pogo pins +0 +10 +10 +Connectors +Tag-Connect_TC2050-IDC-NL_2x05_P1.27mm_Vertical +Tag-Connect programming header; http://www.tag-connect.com/Materials/TC2050-IDC-NL%20Datasheet.pdf +tag connect programming header pogo pins +0 +10 +10 +Connectors +Tag-Connect_TC2070-IDC-FP_2x07_P1.27mm_Vertical +Tag-Connect programming header; http://www.tag-connect.com/Materials/TC2070-IDC%20Datasheet.pdf +tag connect programming header pogo pins +0 +14 +14 +Connectors_USB +USB3_A_Molex_48393-001 +USB 3.0, type A, right angle (http://www.molex.com/pdm_docs/sd/483930003_sd.pdf) +USB 3.0 type A right angle +0 +13 +10 +Connectors_USB +USB3_A_Plug_Wuerth_692112030100_Horizontal +USB type A Plug, Horizontal, http://katalog.we-online.de/em/datasheet/692112030100.pdf +usb A plug horizontal +0 +11 +10 +Connectors_USB +USB_A_CNCTech_1001-011-01101_Horizontal +http://cnctech.us/pdfs/1001-011-01101.pdf +USB-A +0 +6 +5 +Connectors_USB +USB_A_Wuerth_61400826021_Horizontal_Stacked +Stacked USB A connector http://katalog.we-online.de/em/datasheet/61400826021.pdf +Wuerth stacked USB_A +0 +12 +9 +Connectors_USB +USB_B_Amphenol_MUSB-D511_Vertical_Rugged +A,phenol MUSB_D511, USB B female connector, straight, rugged, https://www.amphenolcanada.com/ProductSearch/drawings/AC/MUSBD511XX.pdf +USB_B_MUSB_Straight female connector straight rugged MUSB D511 +0 +6 +5 +Connectors_USB +USB_B_OST_USB-B1HSxx_Horizontal +USB B receptacle, Horizontal, through-hole, http://www.on-shore.com/wp-content/uploads/2015/09/usb-b1hsxx.pdf +USB-B receptacle horizontal through-hole +0 +6 +5 +Connectors_USB +USB_B_TE_5787834_Vertical +http://www.mouser.com/ds/2/418/NG_CD_5787834_A4-669110.pdf +USB_B USB B vertical female connector +0 +6 +5 +Connectors_USB +USB_C_Plug_Molex_105444 +Universal Serial Bus (USB) Shielded I/O Plug, Type C, Right Angle, Surface Mount, http://www.molex.com/pdm_docs/sd/1054440001_sd.pdf +USB Type-C Plug Edge Mount +0 +24 +23 +Connectors_USB +USB_C_Receptacle_Amphenol_12401548E4-2A +USB TYPE C, RA RCPT PCB, Hybrid, https://www.amphenolcanada.com/StockAvailabilityPrice.aspx?From=&PartNum=12401548E4%7e2A +USB C Type-C Receptacle Hybrid +0 +28 +25 +Connectors_USB +USB_C_Receptacle_Amphenol_12401548E4-2A_CircularHoles +USB TYPE C, RA RCPT PCB, Hybrid, https://www.amphenolcanada.com/StockAvailabilityPrice.aspx?From=&PartNum=12401548E4%7e2A +USB C Type-C Receptacle Hybrid +0 +28 +25 +Connectors_USB +USB_C_Receptacle_Amphenol_12401610E4-2A +USB TYPE C, RA RCPT PCB, SMT, https://www.amphenolcanada.com/StockAvailabilityPrice.aspx?From=&PartNum=12401610E4%7e2A +USB C Type-C Receptacle SMD +0 +28 +25 +Connectors_USB +USB_C_Receptacle_Amphenol_12401610E4-2A_CircularHoles +USB TYPE C, RA RCPT PCB, SMT, https://www.amphenolcanada.com/StockAvailabilityPrice.aspx?From=&PartNum=12401610E4%7e2A +USB C Type-C Receptacle SMD +0 +28 +25 +Connectors_USB +USB_C_Receptacle_GCT_USB4085 +USB 2.0 Type C Receptacle, https://gct.co/Files/Drawings/USB4085.pdf +USB Type-C Receptacle Through-hole Right angle +0 +20 +17 +Connectors_USB +USB_C_Receptacle_JAE_DX07S024WJ1R350 +http://www.jae.com/z-en/pdf_download_exec.cfm?param=SJ117219.pdf +USB C Type-C Receptacle SMD +0 +30 +25 +Connectors_USB +USB_C_Receptacle_JAE_DX07S024WJ3R400 +USB TYPE C, VERT RCPT PCB, SMT, http://www.jae.com/z-en/pdf_download_exec.cfm?param=SJ117928.pdf +USB C Type-C Receptacle SMD +0 +28 +25 +Connectors_USB +USB_Micro-B_Amphenol_10103594-0001LF_Horizontal +Micro USB Type B 10103594-0001LF, http://cdn.amphenol-icc.com/media/wysiwyg/files/drawing/10103594.pdf +USB USB_B USB_micro USB_OTG +0 +17 +6 +Connectors_USB +USB_Micro-B_GCT_USB3076-30-A +GCT Micro USB https://gct.co/files/drawings/usb3076.pdf +Micro-USB SMD Typ-B GCT +0 +11 +6 +Connectors_USB +USB_Micro-B_Molex-105017-0001 +http://www.molex.com/pdm_docs/sd/1050170001_sd.pdf +Micro-USB SMD Typ-B +0 +13 +6 +Connectors_USB +USB_Micro-B_Molex-105133-0001 +Molex Vertical Micro USB Typ-B (http://www.molex.com/pdm_docs/sd/1051330001_sd.pdf) +Micro-USB SMD Typ-B Vertical +0 +8 +6 +Connectors_USB +USB_Micro-B_Molex-105133-0031 +Molex Vertical Micro USB Typ-B (http://www.molex.com/pdm_docs/sd/1051330031_sd.pdf) +Micro-USB SMD Typ-B Vertical +0 +8 +6 +Connectors_USB +USB_Micro-B_Molex_47346-0001 +Micro USB B receptable with flange, bottom-mount, SMD, right-angle (http://www.molex.com/pdm_docs/sd/473460001_sd.pdf) +Micro B USB SMD +0 +11 +6 +Connectors_USB +USB_Micro-B_Wuerth_614105150721_Vertical +USB Micro-B receptacle, through-hole, vertical, http://katalog.we-online.de/em/datasheet/614105150721.pdf +usb micro receptacle vertical +0 +7 +6 +Connectors_USB +USB_Micro-B_Wuerth_614105150721_Vertical_CircularHoles +USB Micro-B receptacle, through-hole, vertical, http://katalog.we-online.de/em/datasheet/614105150721.pdf +usb micro receptacle vertical +0 +7 +6 +Connectors_USB +USB_Micro-B_Wuerth_629105150521 +USB Micro-B receptacle, http://www.mouser.com/ds/2/445/629105150521-469306.pdf +usb micro receptacle +0 +9 +6 +Connectors_USB +USB_Micro-B_Wuerth_629105150521_CircularHoles +USB Micro-B receptacle, http://www.mouser.com/ds/2/445/629105150521-469306.pdf +usb micro receptacle +0 +9 +6 +Connectors_USB +USB_Mini-B_AdamTech_MUSB-B5-S-VT-TSMT-1_SMD_Vertical +http://www.adam-tech.com/upload/MUSB-B5-S-VT-TSMT-1.pdf +USB Mini-B +0 +7 +6 +Connectors_USB +USB_Mini-B_Lumberg_2486_01_Horizontal +USB Mini-B 5-pin SMD connector, http://downloads.lumberg.com/datenblaetter/en/2486_01.pdf +USB USB_B USB_Mini connector +0 +9 +6 +Connectors_USB +USB_Mini-B_Tensility_54-00023_Vertical +http://www.tensility.com/pdffiles/54-00023.pdf +usb mini receptacle vertical +0 +7 +6 +Connectors_USB +USB_Mini-B_Tensility_54-00023_Vertical_CircularHoles +http://www.tensility.com/pdffiles/54-00023.pdf +usb mini receptacle vertical +0 +7 +6 +Connector_IDC +IDC-Header_2x03_P2.54mm_Horizontal +Through hole angled IDC box header, 2x03, 2.54mm pitch, double rows +Through hole IDC box header THT 2x03 2.54mm double row +0 +6 +6 +Connector_IDC +IDC-Header_2x03_P2.54mm_Vertical +Through hole straight IDC box header, 2x03, 2.54mm pitch, double rows +Through hole IDC box header THT 2x03 2.54mm double row +0 +6 +6 +Connector_IDC +IDC-Header_2x04_P2.54mm_Horizontal +Through hole angled IDC box header, 2x04, 2.54mm pitch, double rows +Through hole IDC box header THT 2x04 2.54mm double row +0 +8 +8 +Connector_IDC +IDC-Header_2x04_P2.54mm_Vertical +Through hole straight IDC box header, 2x04, 2.54mm pitch, double rows +Through hole IDC box header THT 2x04 2.54mm double row +0 +8 +8 +Connector_IDC +IDC-Header_2x05_P2.54mm_Horizontal +Through hole angled IDC box header, 2x05, 2.54mm pitch, double rows +Through hole IDC box header THT 2x05 2.54mm double row +0 +10 +10 +Connector_IDC +IDC-Header_2x05_P2.54mm_Horizontal_Lock +Connector IDC Locked, 10 contacts, compatible header: PANCON HE10 (Series 50, (https://www.reboul.fr/storage/00003af6.pdf) +connector idc locked +0 +12 +10 +Connector_IDC +IDC-Header_2x05_P2.54mm_Vertical +Through hole straight IDC box header, 2x05, 2.54mm pitch, double rows +Through hole IDC box header THT 2x05 2.54mm double row +0 +10 +10 +Connector_IDC +IDC-Header_2x05_P2.54mm_Vertical_Lock +Connector IDC Locked, 10 contacts, compatible header: PANCON HE10 (Series 50, (https://www.reboul.fr/storage/00003af6.pdf) +connector idc locked +0 +12 +10 +Connector_IDC +IDC-Header_2x06_P2.54mm_Horizontal +Through hole angled IDC box header, 2x06, 2.54mm pitch, double rows +Through hole IDC box header THT 2x06 2.54mm double row +0 +12 +12 +Connector_IDC +IDC-Header_2x06_P2.54mm_Vertical +Through hole straight IDC box header, 2x06, 2.54mm pitch, double rows +Through hole IDC box header THT 2x06 2.54mm double row +0 +12 +12 +Connector_IDC +IDC-Header_2x07_P2.54mm_Horizontal +Through hole angled IDC box header, 2x07, 2.54mm pitch, double rows +Through hole IDC box header THT 2x07 2.54mm double row +0 +14 +14 +Connector_IDC +IDC-Header_2x07_P2.54mm_Horizontal_Lock +Connector IDC Locked, 10 contacts, compatible header: PANCON HE10 (Series 50, (https://www.reboul.fr/storage/00003af6.pdf) +connector idc locked +0 +16 +14 +Connector_IDC +IDC-Header_2x07_P2.54mm_Vertical +Through hole straight IDC box header, 2x07, 2.54mm pitch, double rows +Through hole IDC box header THT 2x07 2.54mm double row +0 +14 +14 +Connector_IDC +IDC-Header_2x07_P2.54mm_Vertical_Lock +Connector IDC Locked, 10 contacts, compatible header: PANCON HE10 (Series 50, (https://www.reboul.fr/storage/00003af6.pdf) +connector idc locked +0 +16 +14 +Connector_IDC +IDC-Header_2x08_P2.54mm_Horizontal +Through hole angled IDC box header, 2x08, 2.54mm pitch, double rows +Through hole IDC box header THT 2x08 2.54mm double row +0 +16 +16 +Connector_IDC +IDC-Header_2x08_P2.54mm_Horizontal_Lock +Connector IDC Locked, 10 contacts, compatible header: PANCON HE10 (Series 50, (https://www.reboul.fr/storage/00003af6.pdf) +connector idc locked +0 +18 +16 +Connector_IDC +IDC-Header_2x08_P2.54mm_Vertical +Through hole straight IDC box header, 2x08, 2.54mm pitch, double rows +Through hole IDC box header THT 2x08 2.54mm double row +0 +16 +16 +Connector_IDC +IDC-Header_2x08_P2.54mm_Vertical_Lock +Connector IDC Locked, 10 contacts, compatible header: PANCON HE10 (Series 50, (https://www.reboul.fr/storage/00003af6.pdf) +connector idc locked +0 +18 +16 +Connector_IDC +IDC-Header_2x10_P2.54mm_Horizontal +Through hole angled IDC box header, 2x10, 2.54mm pitch, double rows +Through hole IDC box header THT 2x10 2.54mm double row +0 +20 +20 +Connector_IDC +IDC-Header_2x10_P2.54mm_Horizontal_Lock +Connector IDC Locked, 10 contacts, compatible header: PANCON HE10 (Series 50, (https://www.reboul.fr/storage/00003af6.pdf) +connector idc locked +0 +22 +20 +Connector_IDC +IDC-Header_2x10_P2.54mm_Vertical +Through hole straight IDC box header, 2x10, 2.54mm pitch, double rows +Through hole IDC box header THT 2x10 2.54mm double row +0 +20 +20 +Connector_IDC +IDC-Header_2x10_P2.54mm_Vertical_Lock +Connector IDC Locked, 10 contacts, compatible header: PANCON HE10 (Series 50, (https://www.reboul.fr/storage/00003af6.pdf) +connector idc locked +0 +22 +20 +Connector_IDC +IDC-Header_2x13_P2.54mm_Horizontal +Through hole angled IDC box header, 2x13, 2.54mm pitch, double rows +Through hole IDC box header THT 2x13 2.54mm double row +0 +26 +26 +Connector_IDC +IDC-Header_2x13_P2.54mm_Horizontal_Lock +Connector IDC Locked, 10 contacts, compatible header: PANCON HE10 (Series 50, (https://www.reboul.fr/storage/00003af6.pdf) +connector idc locked +0 +28 +26 +Connector_IDC +IDC-Header_2x13_P2.54mm_Vertical +Through hole straight IDC box header, 2x13, 2.54mm pitch, double rows +Through hole IDC box header THT 2x13 2.54mm double row +0 +26 +26 +Connector_IDC +IDC-Header_2x13_P2.54mm_Vertical_Lock +Connector IDC Locked, 10 contacts, compatible header: PANCON HE10 (Series 50, (https://www.reboul.fr/storage/00003af6.pdf) +connector idc locked +0 +28 +26 +Connector_IDC +IDC-Header_2x15_P2.54mm_Horizontal +Through hole angled IDC box header, 2x15, 2.54mm pitch, double rows +Through hole IDC box header THT 2x15 2.54mm double row +0 +30 +30 +Connector_IDC +IDC-Header_2x15_P2.54mm_Vertical +Through hole straight IDC box header, 2x15, 2.54mm pitch, double rows +Through hole IDC box header THT 2x15 2.54mm double row +0 +30 +30 +Connector_IDC +IDC-Header_2x17_P2.54mm_Horizontal +Through hole angled IDC box header, 2x17, 2.54mm pitch, double rows +Through hole IDC box header THT 2x17 2.54mm double row +0 +34 +34 +Connector_IDC +IDC-Header_2x17_P2.54mm_Horizontal_Lock +Connector IDC Locked, 10 contacts, compatible header: PANCON HE10 (Series 50, (https://www.reboul.fr/storage/00003af6.pdf) +connector idc locked +0 +36 +34 +Connector_IDC +IDC-Header_2x17_P2.54mm_Vertical +Through hole straight IDC box header, 2x17, 2.54mm pitch, double rows +Through hole IDC box header THT 2x17 2.54mm double row +0 +34 +34 +Connector_IDC +IDC-Header_2x17_P2.54mm_Vertical_Lock +Connector IDC Locked, 10 contacts, compatible header: PANCON HE10 (Series 50, (https://www.reboul.fr/storage/00003af6.pdf) +connector idc locked +0 +36 +34 +Connector_IDC +IDC-Header_2x20_P2.54mm_Horizontal +Through hole angled IDC box header, 2x20, 2.54mm pitch, double rows +Through hole IDC box header THT 2x20 2.54mm double row +0 +40 +40 +Connector_IDC +IDC-Header_2x20_P2.54mm_Horizontal_Lock +Connector IDC Locked, 10 contacts, compatible header: PANCON HE10 (Series 50, (https://www.reboul.fr/storage/00003af6.pdf) +connector idc locked +0 +42 +41 +Connector_IDC +IDC-Header_2x20_P2.54mm_Vertical +Through hole straight IDC box header, 2x20, 2.54mm pitch, double rows +Through hole IDC box header THT 2x20 2.54mm double row +0 +40 +40 +Connector_IDC +IDC-Header_2x20_P2.54mm_Vertical_Lock +Connector IDC Locked, 10 contacts, compatible header: PANCON HE10 (Series 50, (https://www.reboul.fr/storage/00003af6.pdf) +connector idc locked +0 +42 +40 +Connector_IDC +IDC-Header_2x25_P2.54mm_Horizontal +Through hole angled IDC box header, 2x25, 2.54mm pitch, double rows +Through hole IDC box header THT 2x25 2.54mm double row +0 +50 +50 +Connector_IDC +IDC-Header_2x25_P2.54mm_Vertical +Through hole straight IDC box header, 2x25, 2.54mm pitch, double rows +Through hole IDC box header THT 2x25 2.54mm double row +0 +50 +50 +Connector_IDC +IDC-Header_2x25_P2.54mm_Vertical_Lock +Connector IDC Locked, 10 contacts, compatible header: PANCON HE10 (Series 50, (https://www.reboul.fr/storage/00003af6.pdf) +connector idc locked +0 +52 +50 +Connector_IDC +IDC-Header_2x30_P2.54mm_Horizontal +Through hole angled IDC box header, 2x30, 2.54mm pitch, double rows +Through hole IDC box header THT 2x30 2.54mm double row +0 +60 +60 +Connector_IDC +IDC-Header_2x30_P2.54mm_Vertical +Through hole straight IDC box header, 2x30, 2.54mm pitch, double rows +Through hole IDC box header THT 2x30 2.54mm double row +0 +60 +60 +Connector_IDC +IDC-Header_2x30_P2.54mm_Vertical_Lock +Connector IDC Locked, 10 contacts, compatible header: PANCON HE10 (Series 50, (https://www.reboul.fr/storage/00003af6.pdf) +connector idc locked +0 +62 +60 +Connector_IDC +IDC-Header_2x32_P2.54mm_Horizontal +Through hole angled IDC box header, 2x32, 2.54mm pitch, double rows +Through hole IDC box header THT 2x32 2.54mm double row +0 +64 +64 +Connector_IDC +IDC-Header_2x32_P2.54mm_Vertical +Through hole straight IDC box header, 2x32, 2.54mm pitch, double rows +Through hole IDC box header THT 2x32 2.54mm double row +0 +64 +64 +Connector_IDC +IDC-Header_2x32_P2.54mm_Vertical_Lock +Connector IDC Locked, 10 contacts, compatible header: PANCON HE10 (Series 50, (https://www.reboul.fr/storage/00003af6.pdf) +connector idc locked +0 +66 +64 +Connector_PinHeader_2.54mm +PinHeader_1x01_P2.54mm_Horizontal +Through hole angled pin header, 1x01, 2.54mm pitch, 6mm pin length, single row +Through hole angled pin header THT 1x01 2.54mm single row +0 +1 +1 +Connector_PinHeader_2.54mm +PinHeader_1x01_P2.54mm_Vertical +Through hole straight pin header, 1x01, 2.54mm pitch, single row +Through hole pin header THT 1x01 2.54mm single row +0 +1 +1 +Connector_PinHeader_2.54mm +PinHeader_1x02_P2.54mm_Horizontal +Through hole angled pin header, 1x02, 2.54mm pitch, 6mm pin length, single row +Through hole angled pin header THT 1x02 2.54mm single row +0 +2 +2 +Connector_PinHeader_2.54mm +PinHeader_1x02_P2.54mm_Vertical +Through hole straight pin header, 1x02, 2.54mm pitch, single row +Through hole pin header THT 1x02 2.54mm single row +0 +2 +2 +Connector_PinHeader_2.54mm +PinHeader_1x02_P2.54mm_Vertical_SMD_Pin1Left +surface-mounted straight pin header, 1x02, 2.54mm pitch, single row, style 1 (pin 1 left) +Surface mounted pin header SMD 1x02 2.54mm single row style1 pin1 left +0 +2 +2 +Connector_PinHeader_2.54mm +PinHeader_1x02_P2.54mm_Vertical_SMD_Pin1Right +surface-mounted straight pin header, 1x02, 2.54mm pitch, single row, style 2 (pin 1 right) +Surface mounted pin header SMD 1x02 2.54mm single row style2 pin1 right +0 +2 +2 +Connector_PinHeader_2.54mm +PinHeader_1x03_P2.54mm_Horizontal +Through hole angled pin header, 1x03, 2.54mm pitch, 6mm pin length, single row +Through hole angled pin header THT 1x03 2.54mm single row +0 +3 +3 +Connector_PinHeader_2.54mm +PinHeader_1x03_P2.54mm_Vertical +Through hole straight pin header, 1x03, 2.54mm pitch, single row +Through hole pin header THT 1x03 2.54mm single row +0 +3 +3 +Connector_PinHeader_2.54mm +PinHeader_1x03_P2.54mm_Vertical_SMD_Pin1Left +surface-mounted straight pin header, 1x03, 2.54mm pitch, single row, style 1 (pin 1 left) +Surface mounted pin header SMD 1x03 2.54mm single row style1 pin1 left +0 +3 +3 +Connector_PinHeader_2.54mm +PinHeader_1x03_P2.54mm_Vertical_SMD_Pin1Right +surface-mounted straight pin header, 1x03, 2.54mm pitch, single row, style 2 (pin 1 right) +Surface mounted pin header SMD 1x03 2.54mm single row style2 pin1 right +0 +3 +3 +Connector_PinHeader_2.54mm +PinHeader_1x04_P2.54mm_Horizontal +Through hole angled pin header, 1x04, 2.54mm pitch, 6mm pin length, single row +Through hole angled pin header THT 1x04 2.54mm single row +0 +4 +4 +Connector_PinHeader_2.54mm +PinHeader_1x04_P2.54mm_Vertical +Through hole straight pin header, 1x04, 2.54mm pitch, single row +Through hole pin header THT 1x04 2.54mm single row +0 +4 +4 +Connector_PinHeader_2.54mm +PinHeader_1x04_P2.54mm_Vertical_SMD_Pin1Left +surface-mounted straight pin header, 1x04, 2.54mm pitch, single row, style 1 (pin 1 left) +Surface mounted pin header SMD 1x04 2.54mm single row style1 pin1 left +0 +4 +4 +Connector_PinHeader_2.54mm +PinHeader_1x04_P2.54mm_Vertical_SMD_Pin1Right +surface-mounted straight pin header, 1x04, 2.54mm pitch, single row, style 2 (pin 1 right) +Surface mounted pin header SMD 1x04 2.54mm single row style2 pin1 right +0 +4 +4 +Connector_PinHeader_2.54mm +PinHeader_1x05_P2.54mm_Horizontal +Through hole angled pin header, 1x05, 2.54mm pitch, 6mm pin length, single row +Through hole angled pin header THT 1x05 2.54mm single row +0 +5 +5 +Connector_PinHeader_2.54mm +PinHeader_1x05_P2.54mm_Vertical +Through hole straight pin header, 1x05, 2.54mm pitch, single row +Through hole pin header THT 1x05 2.54mm single row +0 +5 +5 +Connector_PinHeader_2.54mm +PinHeader_1x05_P2.54mm_Vertical_SMD_Pin1Left +surface-mounted straight pin header, 1x05, 2.54mm pitch, single row, style 1 (pin 1 left) +Surface mounted pin header SMD 1x05 2.54mm single row style1 pin1 left +0 +5 +5 +Connector_PinHeader_2.54mm +PinHeader_1x05_P2.54mm_Vertical_SMD_Pin1Right +surface-mounted straight pin header, 1x05, 2.54mm pitch, single row, style 2 (pin 1 right) +Surface mounted pin header SMD 1x05 2.54mm single row style2 pin1 right +0 +5 +5 +Connector_PinHeader_2.54mm +PinHeader_1x06_P2.54mm_Horizontal +Through hole angled pin header, 1x06, 2.54mm pitch, 6mm pin length, single row +Through hole angled pin header THT 1x06 2.54mm single row +0 +6 +6 +Connector_PinHeader_2.54mm +PinHeader_1x06_P2.54mm_Vertical +Through hole straight pin header, 1x06, 2.54mm pitch, single row +Through hole pin header THT 1x06 2.54mm single row +0 +6 +6 +Connector_PinHeader_2.54mm +PinHeader_1x06_P2.54mm_Vertical_SMD_Pin1Left +surface-mounted straight pin header, 1x06, 2.54mm pitch, single row, style 1 (pin 1 left) +Surface mounted pin header SMD 1x06 2.54mm single row style1 pin1 left +0 +6 +6 +Connector_PinHeader_2.54mm +PinHeader_1x06_P2.54mm_Vertical_SMD_Pin1Right +surface-mounted straight pin header, 1x06, 2.54mm pitch, single row, style 2 (pin 1 right) +Surface mounted pin header SMD 1x06 2.54mm single row style2 pin1 right +0 +6 +6 +Connector_PinHeader_2.54mm +PinHeader_1x07_P2.54mm_Horizontal +Through hole angled pin header, 1x07, 2.54mm pitch, 6mm pin length, single row +Through hole angled pin header THT 1x07 2.54mm single row +0 +7 +7 +Connector_PinHeader_2.54mm +PinHeader_1x07_P2.54mm_Vertical +Through hole straight pin header, 1x07, 2.54mm pitch, single row +Through hole pin header THT 1x07 2.54mm single row +0 +7 +7 +Connector_PinHeader_2.54mm +PinHeader_1x07_P2.54mm_Vertical_SMD_Pin1Left +surface-mounted straight pin header, 1x07, 2.54mm pitch, single row, style 1 (pin 1 left) +Surface mounted pin header SMD 1x07 2.54mm single row style1 pin1 left +0 +7 +7 +Connector_PinHeader_2.54mm +PinHeader_1x07_P2.54mm_Vertical_SMD_Pin1Right +surface-mounted straight pin header, 1x07, 2.54mm pitch, single row, style 2 (pin 1 right) +Surface mounted pin header SMD 1x07 2.54mm single row style2 pin1 right +0 +7 +7 +Connector_PinHeader_2.54mm +PinHeader_1x08_P2.54mm_Horizontal +Through hole angled pin header, 1x08, 2.54mm pitch, 6mm pin length, single row +Through hole angled pin header THT 1x08 2.54mm single row +0 +8 +8 +Connector_PinHeader_2.54mm +PinHeader_1x08_P2.54mm_Vertical +Through hole straight pin header, 1x08, 2.54mm pitch, single row +Through hole pin header THT 1x08 2.54mm single row +0 +8 +8 +Connector_PinHeader_2.54mm +PinHeader_1x08_P2.54mm_Vertical_SMD_Pin1Left +surface-mounted straight pin header, 1x08, 2.54mm pitch, single row, style 1 (pin 1 left) +Surface mounted pin header SMD 1x08 2.54mm single row style1 pin1 left +0 +8 +8 +Connector_PinHeader_2.54mm +PinHeader_1x08_P2.54mm_Vertical_SMD_Pin1Right +surface-mounted straight pin header, 1x08, 2.54mm pitch, single row, style 2 (pin 1 right) +Surface mounted pin header SMD 1x08 2.54mm single row style2 pin1 right +0 +8 +8 +Connector_PinHeader_2.54mm +PinHeader_1x09_P2.54mm_Horizontal +Through hole angled pin header, 1x09, 2.54mm pitch, 6mm pin length, single row +Through hole angled pin header THT 1x09 2.54mm single row +0 +9 +9 +Connector_PinHeader_2.54mm +PinHeader_1x09_P2.54mm_Vertical +Through hole straight pin header, 1x09, 2.54mm pitch, single row +Through hole pin header THT 1x09 2.54mm single row +0 +9 +9 +Connector_PinHeader_2.54mm +PinHeader_1x09_P2.54mm_Vertical_SMD_Pin1Left +surface-mounted straight pin header, 1x09, 2.54mm pitch, single row, style 1 (pin 1 left) +Surface mounted pin header SMD 1x09 2.54mm single row style1 pin1 left +0 +9 +9 +Connector_PinHeader_2.54mm +PinHeader_1x09_P2.54mm_Vertical_SMD_Pin1Right +surface-mounted straight pin header, 1x09, 2.54mm pitch, single row, style 2 (pin 1 right) +Surface mounted pin header SMD 1x09 2.54mm single row style2 pin1 right +0 +9 +9 +Connector_PinHeader_2.54mm +PinHeader_1x10_P2.54mm_Horizontal +Through hole angled pin header, 1x10, 2.54mm pitch, 6mm pin length, single row +Through hole angled pin header THT 1x10 2.54mm single row +0 +10 +10 +Connector_PinHeader_2.54mm +PinHeader_1x10_P2.54mm_Vertical +Through hole straight pin header, 1x10, 2.54mm pitch, single row +Through hole pin header THT 1x10 2.54mm single row +0 +10 +10 +Connector_PinHeader_2.54mm +PinHeader_1x10_P2.54mm_Vertical_SMD_Pin1Left +surface-mounted straight pin header, 1x10, 2.54mm pitch, single row, style 1 (pin 1 left) +Surface mounted pin header SMD 1x10 2.54mm single row style1 pin1 left +0 +10 +10 +Connector_PinHeader_2.54mm +PinHeader_1x10_P2.54mm_Vertical_SMD_Pin1Right +surface-mounted straight pin header, 1x10, 2.54mm pitch, single row, style 2 (pin 1 right) +Surface mounted pin header SMD 1x10 2.54mm single row style2 pin1 right +0 +10 +10 +Connector_PinHeader_2.54mm +PinHeader_1x11_P2.54mm_Horizontal +Through hole angled pin header, 1x11, 2.54mm pitch, 6mm pin length, single row +Through hole angled pin header THT 1x11 2.54mm single row +0 +11 +11 +Connector_PinHeader_2.54mm +PinHeader_1x11_P2.54mm_Vertical +Through hole straight pin header, 1x11, 2.54mm pitch, single row +Through hole pin header THT 1x11 2.54mm single row +0 +11 +11 +Connector_PinHeader_2.54mm +PinHeader_1x11_P2.54mm_Vertical_SMD_Pin1Left +surface-mounted straight pin header, 1x11, 2.54mm pitch, single row, style 1 (pin 1 left) +Surface mounted pin header SMD 1x11 2.54mm single row style1 pin1 left +0 +11 +11 +Connector_PinHeader_2.54mm +PinHeader_1x11_P2.54mm_Vertical_SMD_Pin1Right +surface-mounted straight pin header, 1x11, 2.54mm pitch, single row, style 2 (pin 1 right) +Surface mounted pin header SMD 1x11 2.54mm single row style2 pin1 right +0 +11 +11 +Connector_PinHeader_2.54mm +PinHeader_1x12_P2.54mm_Horizontal +Through hole angled pin header, 1x12, 2.54mm pitch, 6mm pin length, single row +Through hole angled pin header THT 1x12 2.54mm single row +0 +12 +12 +Connector_PinHeader_2.54mm +PinHeader_1x12_P2.54mm_Vertical +Through hole straight pin header, 1x12, 2.54mm pitch, single row +Through hole pin header THT 1x12 2.54mm single row +0 +12 +12 +Connector_PinHeader_2.54mm +PinHeader_1x12_P2.54mm_Vertical_SMD_Pin1Left +surface-mounted straight pin header, 1x12, 2.54mm pitch, single row, style 1 (pin 1 left) +Surface mounted pin header SMD 1x12 2.54mm single row style1 pin1 left +0 +12 +12 +Connector_PinHeader_2.54mm +PinHeader_1x12_P2.54mm_Vertical_SMD_Pin1Right +surface-mounted straight pin header, 1x12, 2.54mm pitch, single row, style 2 (pin 1 right) +Surface mounted pin header SMD 1x12 2.54mm single row style2 pin1 right +0 +12 +12 +Connector_PinHeader_2.54mm +PinHeader_1x13_P2.54mm_Horizontal +Through hole angled pin header, 1x13, 2.54mm pitch, 6mm pin length, single row +Through hole angled pin header THT 1x13 2.54mm single row +0 +13 +13 +Connector_PinHeader_2.54mm +PinHeader_1x13_P2.54mm_Vertical +Through hole straight pin header, 1x13, 2.54mm pitch, single row +Through hole pin header THT 1x13 2.54mm single row +0 +13 +13 +Connector_PinHeader_2.54mm +PinHeader_1x13_P2.54mm_Vertical_SMD_Pin1Left +surface-mounted straight pin header, 1x13, 2.54mm pitch, single row, style 1 (pin 1 left) +Surface mounted pin header SMD 1x13 2.54mm single row style1 pin1 left +0 +13 +13 +Connector_PinHeader_2.54mm +PinHeader_1x13_P2.54mm_Vertical_SMD_Pin1Right +surface-mounted straight pin header, 1x13, 2.54mm pitch, single row, style 2 (pin 1 right) +Surface mounted pin header SMD 1x13 2.54mm single row style2 pin1 right +0 +13 +13 +Connector_PinHeader_2.54mm +PinHeader_1x14_P2.54mm_Horizontal +Through hole angled pin header, 1x14, 2.54mm pitch, 6mm pin length, single row +Through hole angled pin header THT 1x14 2.54mm single row +0 +14 +14 +Connector_PinHeader_2.54mm +PinHeader_1x14_P2.54mm_Vertical +Through hole straight pin header, 1x14, 2.54mm pitch, single row +Through hole pin header THT 1x14 2.54mm single row +0 +14 +14 +Connector_PinHeader_2.54mm +PinHeader_1x14_P2.54mm_Vertical_SMD_Pin1Left +surface-mounted straight pin header, 1x14, 2.54mm pitch, single row, style 1 (pin 1 left) +Surface mounted pin header SMD 1x14 2.54mm single row style1 pin1 left +0 +14 +14 +Connector_PinHeader_2.54mm +PinHeader_1x14_P2.54mm_Vertical_SMD_Pin1Right +surface-mounted straight pin header, 1x14, 2.54mm pitch, single row, style 2 (pin 1 right) +Surface mounted pin header SMD 1x14 2.54mm single row style2 pin1 right +0 +14 +14 +Connector_PinHeader_2.54mm +PinHeader_1x15_P2.54mm_Horizontal +Through hole angled pin header, 1x15, 2.54mm pitch, 6mm pin length, single row +Through hole angled pin header THT 1x15 2.54mm single row +0 +15 +15 +Connector_PinHeader_2.54mm +PinHeader_1x15_P2.54mm_Vertical +Through hole straight pin header, 1x15, 2.54mm pitch, single row +Through hole pin header THT 1x15 2.54mm single row +0 +15 +15 +Connector_PinHeader_2.54mm +PinHeader_1x15_P2.54mm_Vertical_SMD_Pin1Left +surface-mounted straight pin header, 1x15, 2.54mm pitch, single row, style 1 (pin 1 left) +Surface mounted pin header SMD 1x15 2.54mm single row style1 pin1 left +0 +15 +15 +Connector_PinHeader_2.54mm +PinHeader_1x15_P2.54mm_Vertical_SMD_Pin1Right +surface-mounted straight pin header, 1x15, 2.54mm pitch, single row, style 2 (pin 1 right) +Surface mounted pin header SMD 1x15 2.54mm single row style2 pin1 right +0 +15 +15 +Connector_PinHeader_2.54mm +PinHeader_1x16_P2.54mm_Horizontal +Through hole angled pin header, 1x16, 2.54mm pitch, 6mm pin length, single row +Through hole angled pin header THT 1x16 2.54mm single row +0 +16 +16 +Connector_PinHeader_2.54mm +PinHeader_1x16_P2.54mm_Vertical +Through hole straight pin header, 1x16, 2.54mm pitch, single row +Through hole pin header THT 1x16 2.54mm single row +0 +16 +16 +Connector_PinHeader_2.54mm +PinHeader_1x16_P2.54mm_Vertical_SMD_Pin1Left +surface-mounted straight pin header, 1x16, 2.54mm pitch, single row, style 1 (pin 1 left) +Surface mounted pin header SMD 1x16 2.54mm single row style1 pin1 left +0 +16 +16 +Connector_PinHeader_2.54mm +PinHeader_1x16_P2.54mm_Vertical_SMD_Pin1Right +surface-mounted straight pin header, 1x16, 2.54mm pitch, single row, style 2 (pin 1 right) +Surface mounted pin header SMD 1x16 2.54mm single row style2 pin1 right +0 +16 +16 +Connector_PinHeader_2.54mm +PinHeader_1x17_P2.54mm_Horizontal +Through hole angled pin header, 1x17, 2.54mm pitch, 6mm pin length, single row +Through hole angled pin header THT 1x17 2.54mm single row +0 +17 +17 +Connector_PinHeader_2.54mm +PinHeader_1x17_P2.54mm_Vertical +Through hole straight pin header, 1x17, 2.54mm pitch, single row +Through hole pin header THT 1x17 2.54mm single row +0 +17 +17 +Connector_PinHeader_2.54mm +PinHeader_1x17_P2.54mm_Vertical_SMD_Pin1Left +surface-mounted straight pin header, 1x17, 2.54mm pitch, single row, style 1 (pin 1 left) +Surface mounted pin header SMD 1x17 2.54mm single row style1 pin1 left +0 +17 +17 +Connector_PinHeader_2.54mm +PinHeader_1x17_P2.54mm_Vertical_SMD_Pin1Right +surface-mounted straight pin header, 1x17, 2.54mm pitch, single row, style 2 (pin 1 right) +Surface mounted pin header SMD 1x17 2.54mm single row style2 pin1 right +0 +17 +17 +Connector_PinHeader_2.54mm +PinHeader_1x18_P2.54mm_Horizontal +Through hole angled pin header, 1x18, 2.54mm pitch, 6mm pin length, single row +Through hole angled pin header THT 1x18 2.54mm single row +0 +18 +18 +Connector_PinHeader_2.54mm +PinHeader_1x18_P2.54mm_Vertical +Through hole straight pin header, 1x18, 2.54mm pitch, single row +Through hole pin header THT 1x18 2.54mm single row +0 +18 +18 +Connector_PinHeader_2.54mm +PinHeader_1x18_P2.54mm_Vertical_SMD_Pin1Left +surface-mounted straight pin header, 1x18, 2.54mm pitch, single row, style 1 (pin 1 left) +Surface mounted pin header SMD 1x18 2.54mm single row style1 pin1 left +0 +18 +18 +Connector_PinHeader_2.54mm +PinHeader_1x18_P2.54mm_Vertical_SMD_Pin1Right +surface-mounted straight pin header, 1x18, 2.54mm pitch, single row, style 2 (pin 1 right) +Surface mounted pin header SMD 1x18 2.54mm single row style2 pin1 right +0 +18 +18 +Connector_PinHeader_2.54mm +PinHeader_1x19_P2.54mm_Horizontal +Through hole angled pin header, 1x19, 2.54mm pitch, 6mm pin length, single row +Through hole angled pin header THT 1x19 2.54mm single row +0 +19 +19 +Connector_PinHeader_2.54mm +PinHeader_1x19_P2.54mm_Vertical +Through hole straight pin header, 1x19, 2.54mm pitch, single row +Through hole pin header THT 1x19 2.54mm single row +0 +19 +19 +Connector_PinHeader_2.54mm +PinHeader_1x19_P2.54mm_Vertical_SMD_Pin1Left +surface-mounted straight pin header, 1x19, 2.54mm pitch, single row, style 1 (pin 1 left) +Surface mounted pin header SMD 1x19 2.54mm single row style1 pin1 left +0 +19 +19 +Connector_PinHeader_2.54mm +PinHeader_1x19_P2.54mm_Vertical_SMD_Pin1Right +surface-mounted straight pin header, 1x19, 2.54mm pitch, single row, style 2 (pin 1 right) +Surface mounted pin header SMD 1x19 2.54mm single row style2 pin1 right +0 +19 +19 +Connector_PinHeader_2.54mm +PinHeader_1x20_P2.54mm_Horizontal +Through hole angled pin header, 1x20, 2.54mm pitch, 6mm pin length, single row +Through hole angled pin header THT 1x20 2.54mm single row +0 +20 +20 +Connector_PinHeader_2.54mm +PinHeader_1x20_P2.54mm_Vertical +Through hole straight pin header, 1x20, 2.54mm pitch, single row +Through hole pin header THT 1x20 2.54mm single row +0 +20 +20 +Connector_PinHeader_2.54mm +PinHeader_1x20_P2.54mm_Vertical_SMD_Pin1Left +surface-mounted straight pin header, 1x20, 2.54mm pitch, single row, style 1 (pin 1 left) +Surface mounted pin header SMD 1x20 2.54mm single row style1 pin1 left +0 +20 +20 +Connector_PinHeader_2.54mm +PinHeader_1x20_P2.54mm_Vertical_SMD_Pin1Right +surface-mounted straight pin header, 1x20, 2.54mm pitch, single row, style 2 (pin 1 right) +Surface mounted pin header SMD 1x20 2.54mm single row style2 pin1 right +0 +20 +20 +Connector_PinHeader_2.54mm +PinHeader_1x21_P2.54mm_Horizontal +Through hole angled pin header, 1x21, 2.54mm pitch, 6mm pin length, single row +Through hole angled pin header THT 1x21 2.54mm single row +0 +21 +21 +Connector_PinHeader_2.54mm +PinHeader_1x21_P2.54mm_Vertical +Through hole straight pin header, 1x21, 2.54mm pitch, single row +Through hole pin header THT 1x21 2.54mm single row +0 +21 +21 +Connector_PinHeader_2.54mm +PinHeader_1x21_P2.54mm_Vertical_SMD_Pin1Left +surface-mounted straight pin header, 1x21, 2.54mm pitch, single row, style 1 (pin 1 left) +Surface mounted pin header SMD 1x21 2.54mm single row style1 pin1 left +0 +21 +21 +Connector_PinHeader_2.54mm +PinHeader_1x21_P2.54mm_Vertical_SMD_Pin1Right +surface-mounted straight pin header, 1x21, 2.54mm pitch, single row, style 2 (pin 1 right) +Surface mounted pin header SMD 1x21 2.54mm single row style2 pin1 right +0 +21 +21 +Connector_PinHeader_2.54mm +PinHeader_1x22_P2.54mm_Horizontal +Through hole angled pin header, 1x22, 2.54mm pitch, 6mm pin length, single row +Through hole angled pin header THT 1x22 2.54mm single row +0 +22 +22 +Connector_PinHeader_2.54mm +PinHeader_1x22_P2.54mm_Vertical +Through hole straight pin header, 1x22, 2.54mm pitch, single row +Through hole pin header THT 1x22 2.54mm single row +0 +22 +22 +Connector_PinHeader_2.54mm +PinHeader_1x22_P2.54mm_Vertical_SMD_Pin1Left +surface-mounted straight pin header, 1x22, 2.54mm pitch, single row, style 1 (pin 1 left) +Surface mounted pin header SMD 1x22 2.54mm single row style1 pin1 left +0 +22 +22 +Connector_PinHeader_2.54mm +PinHeader_1x22_P2.54mm_Vertical_SMD_Pin1Right +surface-mounted straight pin header, 1x22, 2.54mm pitch, single row, style 2 (pin 1 right) +Surface mounted pin header SMD 1x22 2.54mm single row style2 pin1 right +0 +22 +22 +Connector_PinHeader_2.54mm +PinHeader_1x23_P2.54mm_Horizontal +Through hole angled pin header, 1x23, 2.54mm pitch, 6mm pin length, single row +Through hole angled pin header THT 1x23 2.54mm single row +0 +23 +23 +Connector_PinHeader_2.54mm +PinHeader_1x23_P2.54mm_Vertical +Through hole straight pin header, 1x23, 2.54mm pitch, single row +Through hole pin header THT 1x23 2.54mm single row +0 +23 +23 +Connector_PinHeader_2.54mm +PinHeader_1x23_P2.54mm_Vertical_SMD_Pin1Left +surface-mounted straight pin header, 1x23, 2.54mm pitch, single row, style 1 (pin 1 left) +Surface mounted pin header SMD 1x23 2.54mm single row style1 pin1 left +0 +23 +23 +Connector_PinHeader_2.54mm +PinHeader_1x23_P2.54mm_Vertical_SMD_Pin1Right +surface-mounted straight pin header, 1x23, 2.54mm pitch, single row, style 2 (pin 1 right) +Surface mounted pin header SMD 1x23 2.54mm single row style2 pin1 right +0 +23 +23 +Connector_PinHeader_2.54mm +PinHeader_1x24_P2.54mm_Horizontal +Through hole angled pin header, 1x24, 2.54mm pitch, 6mm pin length, single row +Through hole angled pin header THT 1x24 2.54mm single row +0 +24 +24 +Connector_PinHeader_2.54mm +PinHeader_1x24_P2.54mm_Vertical +Through hole straight pin header, 1x24, 2.54mm pitch, single row +Through hole pin header THT 1x24 2.54mm single row +0 +24 +24 +Connector_PinHeader_2.54mm +PinHeader_1x24_P2.54mm_Vertical_SMD_Pin1Left +surface-mounted straight pin header, 1x24, 2.54mm pitch, single row, style 1 (pin 1 left) +Surface mounted pin header SMD 1x24 2.54mm single row style1 pin1 left +0 +24 +24 +Connector_PinHeader_2.54mm +PinHeader_1x24_P2.54mm_Vertical_SMD_Pin1Right +surface-mounted straight pin header, 1x24, 2.54mm pitch, single row, style 2 (pin 1 right) +Surface mounted pin header SMD 1x24 2.54mm single row style2 pin1 right +0 +24 +24 +Connector_PinHeader_2.54mm +PinHeader_1x25_P2.54mm_Horizontal +Through hole angled pin header, 1x25, 2.54mm pitch, 6mm pin length, single row +Through hole angled pin header THT 1x25 2.54mm single row +0 +25 +25 +Connector_PinHeader_2.54mm +PinHeader_1x25_P2.54mm_Vertical +Through hole straight pin header, 1x25, 2.54mm pitch, single row +Through hole pin header THT 1x25 2.54mm single row +0 +25 +25 +Connector_PinHeader_2.54mm +PinHeader_1x25_P2.54mm_Vertical_SMD_Pin1Left +surface-mounted straight pin header, 1x25, 2.54mm pitch, single row, style 1 (pin 1 left) +Surface mounted pin header SMD 1x25 2.54mm single row style1 pin1 left +0 +25 +25 +Connector_PinHeader_2.54mm +PinHeader_1x25_P2.54mm_Vertical_SMD_Pin1Right +surface-mounted straight pin header, 1x25, 2.54mm pitch, single row, style 2 (pin 1 right) +Surface mounted pin header SMD 1x25 2.54mm single row style2 pin1 right +0 +25 +25 +Connector_PinHeader_2.54mm +PinHeader_1x26_P2.54mm_Horizontal +Through hole angled pin header, 1x26, 2.54mm pitch, 6mm pin length, single row +Through hole angled pin header THT 1x26 2.54mm single row +0 +26 +26 +Connector_PinHeader_2.54mm +PinHeader_1x26_P2.54mm_Vertical +Through hole straight pin header, 1x26, 2.54mm pitch, single row +Through hole pin header THT 1x26 2.54mm single row +0 +26 +26 +Connector_PinHeader_2.54mm +PinHeader_1x26_P2.54mm_Vertical_SMD_Pin1Left +surface-mounted straight pin header, 1x26, 2.54mm pitch, single row, style 1 (pin 1 left) +Surface mounted pin header SMD 1x26 2.54mm single row style1 pin1 left +0 +26 +26 +Connector_PinHeader_2.54mm +PinHeader_1x26_P2.54mm_Vertical_SMD_Pin1Right +surface-mounted straight pin header, 1x26, 2.54mm pitch, single row, style 2 (pin 1 right) +Surface mounted pin header SMD 1x26 2.54mm single row style2 pin1 right +0 +26 +26 +Connector_PinHeader_2.54mm +PinHeader_1x27_P2.54mm_Horizontal +Through hole angled pin header, 1x27, 2.54mm pitch, 6mm pin length, single row +Through hole angled pin header THT 1x27 2.54mm single row +0 +27 +27 +Connector_PinHeader_2.54mm +PinHeader_1x27_P2.54mm_Vertical +Through hole straight pin header, 1x27, 2.54mm pitch, single row +Through hole pin header THT 1x27 2.54mm single row +0 +27 +27 +Connector_PinHeader_2.54mm +PinHeader_1x27_P2.54mm_Vertical_SMD_Pin1Left +surface-mounted straight pin header, 1x27, 2.54mm pitch, single row, style 1 (pin 1 left) +Surface mounted pin header SMD 1x27 2.54mm single row style1 pin1 left +0 +27 +27 +Connector_PinHeader_2.54mm +PinHeader_1x27_P2.54mm_Vertical_SMD_Pin1Right +surface-mounted straight pin header, 1x27, 2.54mm pitch, single row, style 2 (pin 1 right) +Surface mounted pin header SMD 1x27 2.54mm single row style2 pin1 right +0 +27 +27 +Connector_PinHeader_2.54mm +PinHeader_1x28_P2.54mm_Horizontal +Through hole angled pin header, 1x28, 2.54mm pitch, 6mm pin length, single row +Through hole angled pin header THT 1x28 2.54mm single row +0 +28 +28 +Connector_PinHeader_2.54mm +PinHeader_1x28_P2.54mm_Vertical +Through hole straight pin header, 1x28, 2.54mm pitch, single row +Through hole pin header THT 1x28 2.54mm single row +0 +28 +28 +Connector_PinHeader_2.54mm +PinHeader_1x28_P2.54mm_Vertical_SMD_Pin1Left +surface-mounted straight pin header, 1x28, 2.54mm pitch, single row, style 1 (pin 1 left) +Surface mounted pin header SMD 1x28 2.54mm single row style1 pin1 left +0 +28 +28 +Connector_PinHeader_2.54mm +PinHeader_1x28_P2.54mm_Vertical_SMD_Pin1Right +surface-mounted straight pin header, 1x28, 2.54mm pitch, single row, style 2 (pin 1 right) +Surface mounted pin header SMD 1x28 2.54mm single row style2 pin1 right +0 +28 +28 +Connector_PinHeader_2.54mm +PinHeader_1x29_P2.54mm_Horizontal +Through hole angled pin header, 1x29, 2.54mm pitch, 6mm pin length, single row +Through hole angled pin header THT 1x29 2.54mm single row +0 +29 +29 +Connector_PinHeader_2.54mm +PinHeader_1x29_P2.54mm_Vertical +Through hole straight pin header, 1x29, 2.54mm pitch, single row +Through hole pin header THT 1x29 2.54mm single row +0 +29 +29 +Connector_PinHeader_2.54mm +PinHeader_1x29_P2.54mm_Vertical_SMD_Pin1Left +surface-mounted straight pin header, 1x29, 2.54mm pitch, single row, style 1 (pin 1 left) +Surface mounted pin header SMD 1x29 2.54mm single row style1 pin1 left +0 +29 +29 +Connector_PinHeader_2.54mm +PinHeader_1x29_P2.54mm_Vertical_SMD_Pin1Right +surface-mounted straight pin header, 1x29, 2.54mm pitch, single row, style 2 (pin 1 right) +Surface mounted pin header SMD 1x29 2.54mm single row style2 pin1 right +0 +29 +29 +Connector_PinHeader_2.54mm +PinHeader_1x30_P2.54mm_Horizontal +Through hole angled pin header, 1x30, 2.54mm pitch, 6mm pin length, single row +Through hole angled pin header THT 1x30 2.54mm single row +0 +30 +30 +Connector_PinHeader_2.54mm +PinHeader_1x30_P2.54mm_Vertical +Through hole straight pin header, 1x30, 2.54mm pitch, single row +Through hole pin header THT 1x30 2.54mm single row +0 +30 +30 +Connector_PinHeader_2.54mm +PinHeader_1x30_P2.54mm_Vertical_SMD_Pin1Left +surface-mounted straight pin header, 1x30, 2.54mm pitch, single row, style 1 (pin 1 left) +Surface mounted pin header SMD 1x30 2.54mm single row style1 pin1 left +0 +30 +30 +Connector_PinHeader_2.54mm +PinHeader_1x30_P2.54mm_Vertical_SMD_Pin1Right +surface-mounted straight pin header, 1x30, 2.54mm pitch, single row, style 2 (pin 1 right) +Surface mounted pin header SMD 1x30 2.54mm single row style2 pin1 right +0 +30 +30 +Connector_PinHeader_2.54mm +PinHeader_1x31_P2.54mm_Horizontal +Through hole angled pin header, 1x31, 2.54mm pitch, 6mm pin length, single row +Through hole angled pin header THT 1x31 2.54mm single row +0 +31 +31 +Connector_PinHeader_2.54mm +PinHeader_1x31_P2.54mm_Vertical +Through hole straight pin header, 1x31, 2.54mm pitch, single row +Through hole pin header THT 1x31 2.54mm single row +0 +31 +31 +Connector_PinHeader_2.54mm +PinHeader_1x31_P2.54mm_Vertical_SMD_Pin1Left +surface-mounted straight pin header, 1x31, 2.54mm pitch, single row, style 1 (pin 1 left) +Surface mounted pin header SMD 1x31 2.54mm single row style1 pin1 left +0 +31 +31 +Connector_PinHeader_2.54mm +PinHeader_1x31_P2.54mm_Vertical_SMD_Pin1Right +surface-mounted straight pin header, 1x31, 2.54mm pitch, single row, style 2 (pin 1 right) +Surface mounted pin header SMD 1x31 2.54mm single row style2 pin1 right +0 +31 +31 +Connector_PinHeader_2.54mm +PinHeader_1x32_P2.54mm_Horizontal +Through hole angled pin header, 1x32, 2.54mm pitch, 6mm pin length, single row +Through hole angled pin header THT 1x32 2.54mm single row +0 +32 +32 +Connector_PinHeader_2.54mm +PinHeader_1x32_P2.54mm_Vertical +Through hole straight pin header, 1x32, 2.54mm pitch, single row +Through hole pin header THT 1x32 2.54mm single row +0 +32 +32 +Connector_PinHeader_2.54mm +PinHeader_1x32_P2.54mm_Vertical_SMD_Pin1Left +surface-mounted straight pin header, 1x32, 2.54mm pitch, single row, style 1 (pin 1 left) +Surface mounted pin header SMD 1x32 2.54mm single row style1 pin1 left +0 +32 +32 +Connector_PinHeader_2.54mm +PinHeader_1x32_P2.54mm_Vertical_SMD_Pin1Right +surface-mounted straight pin header, 1x32, 2.54mm pitch, single row, style 2 (pin 1 right) +Surface mounted pin header SMD 1x32 2.54mm single row style2 pin1 right +0 +32 +32 +Connector_PinHeader_2.54mm +PinHeader_1x33_P2.54mm_Horizontal +Through hole angled pin header, 1x33, 2.54mm pitch, 6mm pin length, single row +Through hole angled pin header THT 1x33 2.54mm single row +0 +33 +33 +Connector_PinHeader_2.54mm +PinHeader_1x33_P2.54mm_Vertical +Through hole straight pin header, 1x33, 2.54mm pitch, single row +Through hole pin header THT 1x33 2.54mm single row +0 +33 +33 +Connector_PinHeader_2.54mm +PinHeader_1x33_P2.54mm_Vertical_SMD_Pin1Left +surface-mounted straight pin header, 1x33, 2.54mm pitch, single row, style 1 (pin 1 left) +Surface mounted pin header SMD 1x33 2.54mm single row style1 pin1 left +0 +33 +33 +Connector_PinHeader_2.54mm +PinHeader_1x33_P2.54mm_Vertical_SMD_Pin1Right +surface-mounted straight pin header, 1x33, 2.54mm pitch, single row, style 2 (pin 1 right) +Surface mounted pin header SMD 1x33 2.54mm single row style2 pin1 right +0 +33 +33 +Connector_PinHeader_2.54mm +PinHeader_1x34_P2.54mm_Horizontal +Through hole angled pin header, 1x34, 2.54mm pitch, 6mm pin length, single row +Through hole angled pin header THT 1x34 2.54mm single row +0 +34 +34 +Connector_PinHeader_2.54mm +PinHeader_1x34_P2.54mm_Vertical +Through hole straight pin header, 1x34, 2.54mm pitch, single row +Through hole pin header THT 1x34 2.54mm single row +0 +34 +34 +Connector_PinHeader_2.54mm +PinHeader_1x34_P2.54mm_Vertical_SMD_Pin1Left +surface-mounted straight pin header, 1x34, 2.54mm pitch, single row, style 1 (pin 1 left) +Surface mounted pin header SMD 1x34 2.54mm single row style1 pin1 left +0 +34 +34 +Connector_PinHeader_2.54mm +PinHeader_1x34_P2.54mm_Vertical_SMD_Pin1Right +surface-mounted straight pin header, 1x34, 2.54mm pitch, single row, style 2 (pin 1 right) +Surface mounted pin header SMD 1x34 2.54mm single row style2 pin1 right +0 +34 +34 +Connector_PinHeader_2.54mm +PinHeader_1x35_P2.54mm_Horizontal +Through hole angled pin header, 1x35, 2.54mm pitch, 6mm pin length, single row +Through hole angled pin header THT 1x35 2.54mm single row +0 +35 +35 +Connector_PinHeader_2.54mm +PinHeader_1x35_P2.54mm_Vertical +Through hole straight pin header, 1x35, 2.54mm pitch, single row +Through hole pin header THT 1x35 2.54mm single row +0 +35 +35 +Connector_PinHeader_2.54mm +PinHeader_1x35_P2.54mm_Vertical_SMD_Pin1Left +surface-mounted straight pin header, 1x35, 2.54mm pitch, single row, style 1 (pin 1 left) +Surface mounted pin header SMD 1x35 2.54mm single row style1 pin1 left +0 +35 +35 +Connector_PinHeader_2.54mm +PinHeader_1x35_P2.54mm_Vertical_SMD_Pin1Right +surface-mounted straight pin header, 1x35, 2.54mm pitch, single row, style 2 (pin 1 right) +Surface mounted pin header SMD 1x35 2.54mm single row style2 pin1 right +0 +35 +35 +Connector_PinHeader_2.54mm +PinHeader_1x36_P2.54mm_Horizontal +Through hole angled pin header, 1x36, 2.54mm pitch, 6mm pin length, single row +Through hole angled pin header THT 1x36 2.54mm single row +0 +36 +36 +Connector_PinHeader_2.54mm +PinHeader_1x36_P2.54mm_Vertical +Through hole straight pin header, 1x36, 2.54mm pitch, single row +Through hole pin header THT 1x36 2.54mm single row +0 +36 +36 +Connector_PinHeader_2.54mm +PinHeader_1x36_P2.54mm_Vertical_SMD_Pin1Left +surface-mounted straight pin header, 1x36, 2.54mm pitch, single row, style 1 (pin 1 left) +Surface mounted pin header SMD 1x36 2.54mm single row style1 pin1 left +0 +36 +36 +Connector_PinHeader_2.54mm +PinHeader_1x36_P2.54mm_Vertical_SMD_Pin1Right +surface-mounted straight pin header, 1x36, 2.54mm pitch, single row, style 2 (pin 1 right) +Surface mounted pin header SMD 1x36 2.54mm single row style2 pin1 right +0 +36 +36 +Connector_PinHeader_2.54mm +PinHeader_1x37_P2.54mm_Horizontal +Through hole angled pin header, 1x37, 2.54mm pitch, 6mm pin length, single row +Through hole angled pin header THT 1x37 2.54mm single row +0 +37 +37 +Connector_PinHeader_2.54mm +PinHeader_1x37_P2.54mm_Vertical +Through hole straight pin header, 1x37, 2.54mm pitch, single row +Through hole pin header THT 1x37 2.54mm single row +0 +37 +37 +Connector_PinHeader_2.54mm +PinHeader_1x37_P2.54mm_Vertical_SMD_Pin1Left +surface-mounted straight pin header, 1x37, 2.54mm pitch, single row, style 1 (pin 1 left) +Surface mounted pin header SMD 1x37 2.54mm single row style1 pin1 left +0 +37 +37 +Connector_PinHeader_2.54mm +PinHeader_1x37_P2.54mm_Vertical_SMD_Pin1Right +surface-mounted straight pin header, 1x37, 2.54mm pitch, single row, style 2 (pin 1 right) +Surface mounted pin header SMD 1x37 2.54mm single row style2 pin1 right +0 +37 +37 +Connector_PinHeader_2.54mm +PinHeader_1x38_P2.54mm_Horizontal +Through hole angled pin header, 1x38, 2.54mm pitch, 6mm pin length, single row +Through hole angled pin header THT 1x38 2.54mm single row +0 +38 +38 +Connector_PinHeader_2.54mm +PinHeader_1x38_P2.54mm_Vertical +Through hole straight pin header, 1x38, 2.54mm pitch, single row +Through hole pin header THT 1x38 2.54mm single row +0 +38 +38 +Connector_PinHeader_2.54mm +PinHeader_1x38_P2.54mm_Vertical_SMD_Pin1Left +surface-mounted straight pin header, 1x38, 2.54mm pitch, single row, style 1 (pin 1 left) +Surface mounted pin header SMD 1x38 2.54mm single row style1 pin1 left +0 +38 +38 +Connector_PinHeader_2.54mm +PinHeader_1x38_P2.54mm_Vertical_SMD_Pin1Right +surface-mounted straight pin header, 1x38, 2.54mm pitch, single row, style 2 (pin 1 right) +Surface mounted pin header SMD 1x38 2.54mm single row style2 pin1 right +0 +38 +38 +Connector_PinHeader_2.54mm +PinHeader_1x39_P2.54mm_Horizontal +Through hole angled pin header, 1x39, 2.54mm pitch, 6mm pin length, single row +Through hole angled pin header THT 1x39 2.54mm single row +0 +39 +39 +Connector_PinHeader_2.54mm +PinHeader_1x39_P2.54mm_Vertical +Through hole straight pin header, 1x39, 2.54mm pitch, single row +Through hole pin header THT 1x39 2.54mm single row +0 +39 +39 +Connector_PinHeader_2.54mm +PinHeader_1x39_P2.54mm_Vertical_SMD_Pin1Left +surface-mounted straight pin header, 1x39, 2.54mm pitch, single row, style 1 (pin 1 left) +Surface mounted pin header SMD 1x39 2.54mm single row style1 pin1 left +0 +39 +39 +Connector_PinHeader_2.54mm +PinHeader_1x39_P2.54mm_Vertical_SMD_Pin1Right +surface-mounted straight pin header, 1x39, 2.54mm pitch, single row, style 2 (pin 1 right) +Surface mounted pin header SMD 1x39 2.54mm single row style2 pin1 right +0 +39 +39 +Connector_PinHeader_2.54mm +PinHeader_1x40_P2.54mm_Horizontal +Through hole angled pin header, 1x40, 2.54mm pitch, 6mm pin length, single row +Through hole angled pin header THT 1x40 2.54mm single row +0 +40 +40 +Connector_PinHeader_2.54mm +PinHeader_1x40_P2.54mm_Vertical +Through hole straight pin header, 1x40, 2.54mm pitch, single row +Through hole pin header THT 1x40 2.54mm single row +0 +40 +40 +Connector_PinHeader_2.54mm +PinHeader_1x40_P2.54mm_Vertical_SMD_Pin1Left +surface-mounted straight pin header, 1x40, 2.54mm pitch, single row, style 1 (pin 1 left) +Surface mounted pin header SMD 1x40 2.54mm single row style1 pin1 left +0 +40 +40 +Connector_PinHeader_2.54mm +PinHeader_1x40_P2.54mm_Vertical_SMD_Pin1Right +surface-mounted straight pin header, 1x40, 2.54mm pitch, single row, style 2 (pin 1 right) +Surface mounted pin header SMD 1x40 2.54mm single row style2 pin1 right +0 +40 +40 +Connector_PinHeader_2.54mm +PinHeader_2x01_P2.54mm_Horizontal +Through hole angled pin header, 2x01, 2.54mm pitch, 6mm pin length, double rows +Through hole angled pin header THT 2x01 2.54mm double row +0 +2 +2 +Connector_PinHeader_2.54mm +PinHeader_2x01_P2.54mm_Vertical +Through hole straight pin header, 2x01, 2.54mm pitch, double rows +Through hole pin header THT 2x01 2.54mm double row +0 +2 +2 +Connector_PinHeader_2.54mm +PinHeader_2x01_P2.54mm_Vertical_SMD +surface-mounted straight pin header, 2x01, 2.54mm pitch, double rows +Surface mounted pin header SMD 2x01 2.54mm double row +0 +2 +2 +Connector_PinHeader_2.54mm +PinHeader_2x02_P2.54mm_Horizontal +Through hole angled pin header, 2x02, 2.54mm pitch, 6mm pin length, double rows +Through hole angled pin header THT 2x02 2.54mm double row +0 +4 +4 +Connector_PinHeader_2.54mm +PinHeader_2x02_P2.54mm_Vertical +Through hole straight pin header, 2x02, 2.54mm pitch, double rows +Through hole pin header THT 2x02 2.54mm double row +0 +4 +4 +Connector_PinHeader_2.54mm +PinHeader_2x02_P2.54mm_Vertical_SMD +surface-mounted straight pin header, 2x02, 2.54mm pitch, double rows +Surface mounted pin header SMD 2x02 2.54mm double row +0 +4 +4 +Connector_PinHeader_2.54mm +PinHeader_2x03_P2.54mm_Horizontal +Through hole angled pin header, 2x03, 2.54mm pitch, 6mm pin length, double rows +Through hole angled pin header THT 2x03 2.54mm double row +0 +6 +6 +Connector_PinHeader_2.54mm +PinHeader_2x03_P2.54mm_Vertical +Through hole straight pin header, 2x03, 2.54mm pitch, double rows +Through hole pin header THT 2x03 2.54mm double row +0 +6 +6 +Connector_PinHeader_2.54mm +PinHeader_2x03_P2.54mm_Vertical_SMD +surface-mounted straight pin header, 2x03, 2.54mm pitch, double rows +Surface mounted pin header SMD 2x03 2.54mm double row +0 +6 +6 +Connector_PinHeader_2.54mm +PinHeader_2x04_P2.54mm_Horizontal +Through hole angled pin header, 2x04, 2.54mm pitch, 6mm pin length, double rows +Through hole angled pin header THT 2x04 2.54mm double row +0 +8 +8 +Connector_PinHeader_2.54mm +PinHeader_2x04_P2.54mm_Vertical +Through hole straight pin header, 2x04, 2.54mm pitch, double rows +Through hole pin header THT 2x04 2.54mm double row +0 +8 +8 +Connector_PinHeader_2.54mm +PinHeader_2x04_P2.54mm_Vertical_SMD +surface-mounted straight pin header, 2x04, 2.54mm pitch, double rows +Surface mounted pin header SMD 2x04 2.54mm double row +0 +8 +8 +Connector_PinHeader_2.54mm +PinHeader_2x05_P2.54mm_Horizontal +Through hole angled pin header, 2x05, 2.54mm pitch, 6mm pin length, double rows +Through hole angled pin header THT 2x05 2.54mm double row +0 +10 +10 +Connector_PinHeader_2.54mm +PinHeader_2x05_P2.54mm_Vertical +Through hole straight pin header, 2x05, 2.54mm pitch, double rows +Through hole pin header THT 2x05 2.54mm double row +0 +10 +10 +Connector_PinHeader_2.54mm +PinHeader_2x05_P2.54mm_Vertical_SMD +surface-mounted straight pin header, 2x05, 2.54mm pitch, double rows +Surface mounted pin header SMD 2x05 2.54mm double row +0 +10 +10 +Connector_PinHeader_2.54mm +PinHeader_2x06_P2.54mm_Horizontal +Through hole angled pin header, 2x06, 2.54mm pitch, 6mm pin length, double rows +Through hole angled pin header THT 2x06 2.54mm double row +0 +12 +12 +Connector_PinHeader_2.54mm +PinHeader_2x06_P2.54mm_Vertical +Through hole straight pin header, 2x06, 2.54mm pitch, double rows +Through hole pin header THT 2x06 2.54mm double row +0 +12 +12 +Connector_PinHeader_2.54mm +PinHeader_2x06_P2.54mm_Vertical_SMD +surface-mounted straight pin header, 2x06, 2.54mm pitch, double rows +Surface mounted pin header SMD 2x06 2.54mm double row +0 +12 +12 +Connector_PinHeader_2.54mm +PinHeader_2x07_P2.54mm_Horizontal +Through hole angled pin header, 2x07, 2.54mm pitch, 6mm pin length, double rows +Through hole angled pin header THT 2x07 2.54mm double row +0 +14 +14 +Connector_PinHeader_2.54mm +PinHeader_2x07_P2.54mm_Vertical +Through hole straight pin header, 2x07, 2.54mm pitch, double rows +Through hole pin header THT 2x07 2.54mm double row +0 +14 +14 +Connector_PinHeader_2.54mm +PinHeader_2x07_P2.54mm_Vertical_SMD +surface-mounted straight pin header, 2x07, 2.54mm pitch, double rows +Surface mounted pin header SMD 2x07 2.54mm double row +0 +14 +14 +Connector_PinHeader_2.54mm +PinHeader_2x08_P2.54mm_Horizontal +Through hole angled pin header, 2x08, 2.54mm pitch, 6mm pin length, double rows +Through hole angled pin header THT 2x08 2.54mm double row +0 +16 +16 +Connector_PinHeader_2.54mm +PinHeader_2x08_P2.54mm_Vertical +Through hole straight pin header, 2x08, 2.54mm pitch, double rows +Through hole pin header THT 2x08 2.54mm double row +0 +16 +16 +Connector_PinHeader_2.54mm +PinHeader_2x08_P2.54mm_Vertical_SMD +surface-mounted straight pin header, 2x08, 2.54mm pitch, double rows +Surface mounted pin header SMD 2x08 2.54mm double row +0 +16 +16 +Connector_PinHeader_2.54mm +PinHeader_2x09_P2.54mm_Horizontal +Through hole angled pin header, 2x09, 2.54mm pitch, 6mm pin length, double rows +Through hole angled pin header THT 2x09 2.54mm double row +0 +18 +18 +Connector_PinHeader_2.54mm +PinHeader_2x09_P2.54mm_Vertical +Through hole straight pin header, 2x09, 2.54mm pitch, double rows +Through hole pin header THT 2x09 2.54mm double row +0 +18 +18 +Connector_PinHeader_2.54mm +PinHeader_2x09_P2.54mm_Vertical_SMD +surface-mounted straight pin header, 2x09, 2.54mm pitch, double rows +Surface mounted pin header SMD 2x09 2.54mm double row +0 +18 +18 +Connector_PinHeader_2.54mm +PinHeader_2x10_P2.54mm_Horizontal +Through hole angled pin header, 2x10, 2.54mm pitch, 6mm pin length, double rows +Through hole angled pin header THT 2x10 2.54mm double row +0 +20 +20 +Connector_PinHeader_2.54mm +PinHeader_2x10_P2.54mm_Vertical +Through hole straight pin header, 2x10, 2.54mm pitch, double rows +Through hole pin header THT 2x10 2.54mm double row +0 +20 +20 +Connector_PinHeader_2.54mm +PinHeader_2x10_P2.54mm_Vertical_SMD +surface-mounted straight pin header, 2x10, 2.54mm pitch, double rows +Surface mounted pin header SMD 2x10 2.54mm double row +0 +20 +20 +Connector_PinHeader_2.54mm +PinHeader_2x11_P2.54mm_Horizontal +Through hole angled pin header, 2x11, 2.54mm pitch, 6mm pin length, double rows +Through hole angled pin header THT 2x11 2.54mm double row +0 +22 +22 +Connector_PinHeader_2.54mm +PinHeader_2x11_P2.54mm_Vertical +Through hole straight pin header, 2x11, 2.54mm pitch, double rows +Through hole pin header THT 2x11 2.54mm double row +0 +22 +22 +Connector_PinHeader_2.54mm +PinHeader_2x11_P2.54mm_Vertical_SMD +surface-mounted straight pin header, 2x11, 2.54mm pitch, double rows +Surface mounted pin header SMD 2x11 2.54mm double row +0 +22 +22 +Connector_PinHeader_2.54mm +PinHeader_2x12_P2.54mm_Horizontal +Through hole angled pin header, 2x12, 2.54mm pitch, 6mm pin length, double rows +Through hole angled pin header THT 2x12 2.54mm double row +0 +24 +24 +Connector_PinHeader_2.54mm +PinHeader_2x12_P2.54mm_Vertical +Through hole straight pin header, 2x12, 2.54mm pitch, double rows +Through hole pin header THT 2x12 2.54mm double row +0 +24 +24 +Connector_PinHeader_2.54mm +PinHeader_2x12_P2.54mm_Vertical_SMD +surface-mounted straight pin header, 2x12, 2.54mm pitch, double rows +Surface mounted pin header SMD 2x12 2.54mm double row +0 +24 +24 +Connector_PinHeader_2.54mm +PinHeader_2x13_P2.54mm_Horizontal +Through hole angled pin header, 2x13, 2.54mm pitch, 6mm pin length, double rows +Through hole angled pin header THT 2x13 2.54mm double row +0 +26 +26 +Connector_PinHeader_2.54mm +PinHeader_2x13_P2.54mm_Vertical +Through hole straight pin header, 2x13, 2.54mm pitch, double rows +Through hole pin header THT 2x13 2.54mm double row +0 +26 +26 +Connector_PinHeader_2.54mm +PinHeader_2x13_P2.54mm_Vertical_SMD +surface-mounted straight pin header, 2x13, 2.54mm pitch, double rows +Surface mounted pin header SMD 2x13 2.54mm double row +0 +26 +26 +Connector_PinHeader_2.54mm +PinHeader_2x14_P2.54mm_Horizontal +Through hole angled pin header, 2x14, 2.54mm pitch, 6mm pin length, double rows +Through hole angled pin header THT 2x14 2.54mm double row +0 +28 +28 +Connector_PinHeader_2.54mm +PinHeader_2x14_P2.54mm_Vertical +Through hole straight pin header, 2x14, 2.54mm pitch, double rows +Through hole pin header THT 2x14 2.54mm double row +0 +28 +28 +Connector_PinHeader_2.54mm +PinHeader_2x14_P2.54mm_Vertical_SMD +surface-mounted straight pin header, 2x14, 2.54mm pitch, double rows +Surface mounted pin header SMD 2x14 2.54mm double row +0 +28 +28 +Connector_PinHeader_2.54mm +PinHeader_2x15_P2.54mm_Horizontal +Through hole angled pin header, 2x15, 2.54mm pitch, 6mm pin length, double rows +Through hole angled pin header THT 2x15 2.54mm double row +0 +30 +30 +Connector_PinHeader_2.54mm +PinHeader_2x15_P2.54mm_Vertical +Through hole straight pin header, 2x15, 2.54mm pitch, double rows +Through hole pin header THT 2x15 2.54mm double row +0 +30 +30 +Connector_PinHeader_2.54mm +PinHeader_2x15_P2.54mm_Vertical_SMD +surface-mounted straight pin header, 2x15, 2.54mm pitch, double rows +Surface mounted pin header SMD 2x15 2.54mm double row +0 +30 +30 +Connector_PinHeader_2.54mm +PinHeader_2x16_P2.54mm_Horizontal +Through hole angled pin header, 2x16, 2.54mm pitch, 6mm pin length, double rows +Through hole angled pin header THT 2x16 2.54mm double row +0 +32 +32 +Connector_PinHeader_2.54mm +PinHeader_2x16_P2.54mm_Vertical +Through hole straight pin header, 2x16, 2.54mm pitch, double rows +Through hole pin header THT 2x16 2.54mm double row +0 +32 +32 +Connector_PinHeader_2.54mm +PinHeader_2x16_P2.54mm_Vertical_SMD +surface-mounted straight pin header, 2x16, 2.54mm pitch, double rows +Surface mounted pin header SMD 2x16 2.54mm double row +0 +32 +32 +Connector_PinHeader_2.54mm +PinHeader_2x17_P2.54mm_Horizontal +Through hole angled pin header, 2x17, 2.54mm pitch, 6mm pin length, double rows +Through hole angled pin header THT 2x17 2.54mm double row +0 +34 +34 +Connector_PinHeader_2.54mm +PinHeader_2x17_P2.54mm_Vertical +Through hole straight pin header, 2x17, 2.54mm pitch, double rows +Through hole pin header THT 2x17 2.54mm double row +0 +34 +34 +Connector_PinHeader_2.54mm +PinHeader_2x17_P2.54mm_Vertical_SMD +surface-mounted straight pin header, 2x17, 2.54mm pitch, double rows +Surface mounted pin header SMD 2x17 2.54mm double row +0 +34 +34 +Connector_PinHeader_2.54mm +PinHeader_2x18_P2.54mm_Horizontal +Through hole angled pin header, 2x18, 2.54mm pitch, 6mm pin length, double rows +Through hole angled pin header THT 2x18 2.54mm double row +0 +36 +36 +Connector_PinHeader_2.54mm +PinHeader_2x18_P2.54mm_Vertical +Through hole straight pin header, 2x18, 2.54mm pitch, double rows +Through hole pin header THT 2x18 2.54mm double row +0 +36 +36 +Connector_PinHeader_2.54mm +PinHeader_2x18_P2.54mm_Vertical_SMD +surface-mounted straight pin header, 2x18, 2.54mm pitch, double rows +Surface mounted pin header SMD 2x18 2.54mm double row +0 +36 +36 +Connector_PinHeader_2.54mm +PinHeader_2x19_P2.54mm_Horizontal +Through hole angled pin header, 2x19, 2.54mm pitch, 6mm pin length, double rows +Through hole angled pin header THT 2x19 2.54mm double row +0 +38 +38 +Connector_PinHeader_2.54mm +PinHeader_2x19_P2.54mm_Vertical +Through hole straight pin header, 2x19, 2.54mm pitch, double rows +Through hole pin header THT 2x19 2.54mm double row +0 +38 +38 +Connector_PinHeader_2.54mm +PinHeader_2x19_P2.54mm_Vertical_SMD +surface-mounted straight pin header, 2x19, 2.54mm pitch, double rows +Surface mounted pin header SMD 2x19 2.54mm double row +0 +38 +38 +Connector_PinHeader_2.54mm +PinHeader_2x20_P2.54mm_Horizontal +Through hole angled pin header, 2x20, 2.54mm pitch, 6mm pin length, double rows +Through hole angled pin header THT 2x20 2.54mm double row +0 +40 +40 +Connector_PinHeader_2.54mm +PinHeader_2x20_P2.54mm_Vertical +Through hole straight pin header, 2x20, 2.54mm pitch, double rows +Through hole pin header THT 2x20 2.54mm double row +0 +40 +40 +Connector_PinHeader_2.54mm +PinHeader_2x20_P2.54mm_Vertical_SMD +surface-mounted straight pin header, 2x20, 2.54mm pitch, double rows +Surface mounted pin header SMD 2x20 2.54mm double row +0 +40 +40 +Connector_PinHeader_2.54mm +PinHeader_2x21_P2.54mm_Horizontal +Through hole angled pin header, 2x21, 2.54mm pitch, 6mm pin length, double rows +Through hole angled pin header THT 2x21 2.54mm double row +0 +42 +42 +Connector_PinHeader_2.54mm +PinHeader_2x21_P2.54mm_Vertical +Through hole straight pin header, 2x21, 2.54mm pitch, double rows +Through hole pin header THT 2x21 2.54mm double row +0 +42 +42 +Connector_PinHeader_2.54mm +PinHeader_2x21_P2.54mm_Vertical_SMD +surface-mounted straight pin header, 2x21, 2.54mm pitch, double rows +Surface mounted pin header SMD 2x21 2.54mm double row +0 +42 +42 +Connector_PinHeader_2.54mm +PinHeader_2x22_P2.54mm_Horizontal +Through hole angled pin header, 2x22, 2.54mm pitch, 6mm pin length, double rows +Through hole angled pin header THT 2x22 2.54mm double row +0 +44 +44 +Connector_PinHeader_2.54mm +PinHeader_2x22_P2.54mm_Vertical +Through hole straight pin header, 2x22, 2.54mm pitch, double rows +Through hole pin header THT 2x22 2.54mm double row +0 +44 +44 +Connector_PinHeader_2.54mm +PinHeader_2x22_P2.54mm_Vertical_SMD +surface-mounted straight pin header, 2x22, 2.54mm pitch, double rows +Surface mounted pin header SMD 2x22 2.54mm double row +0 +44 +44 +Connector_PinHeader_2.54mm +PinHeader_2x23_P2.54mm_Horizontal +Through hole angled pin header, 2x23, 2.54mm pitch, 6mm pin length, double rows +Through hole angled pin header THT 2x23 2.54mm double row +0 +46 +46 +Connector_PinHeader_2.54mm +PinHeader_2x23_P2.54mm_Vertical +Through hole straight pin header, 2x23, 2.54mm pitch, double rows +Through hole pin header THT 2x23 2.54mm double row +0 +46 +46 +Connector_PinHeader_2.54mm +PinHeader_2x23_P2.54mm_Vertical_SMD +surface-mounted straight pin header, 2x23, 2.54mm pitch, double rows +Surface mounted pin header SMD 2x23 2.54mm double row +0 +46 +46 +Connector_PinHeader_2.54mm +PinHeader_2x24_P2.54mm_Horizontal +Through hole angled pin header, 2x24, 2.54mm pitch, 6mm pin length, double rows +Through hole angled pin header THT 2x24 2.54mm double row +0 +48 +48 +Connector_PinHeader_2.54mm +PinHeader_2x24_P2.54mm_Vertical +Through hole straight pin header, 2x24, 2.54mm pitch, double rows +Through hole pin header THT 2x24 2.54mm double row +0 +48 +48 +Connector_PinHeader_2.54mm +PinHeader_2x24_P2.54mm_Vertical_SMD +surface-mounted straight pin header, 2x24, 2.54mm pitch, double rows +Surface mounted pin header SMD 2x24 2.54mm double row +0 +48 +48 +Connector_PinHeader_2.54mm +PinHeader_2x25_P2.54mm_Horizontal +Through hole angled pin header, 2x25, 2.54mm pitch, 6mm pin length, double rows +Through hole angled pin header THT 2x25 2.54mm double row +0 +50 +50 +Connector_PinHeader_2.54mm +PinHeader_2x25_P2.54mm_Vertical +Through hole straight pin header, 2x25, 2.54mm pitch, double rows +Through hole pin header THT 2x25 2.54mm double row +0 +50 +50 +Connector_PinHeader_2.54mm +PinHeader_2x25_P2.54mm_Vertical_SMD +surface-mounted straight pin header, 2x25, 2.54mm pitch, double rows +Surface mounted pin header SMD 2x25 2.54mm double row +0 +50 +50 +Connector_PinHeader_2.54mm +PinHeader_2x26_P2.54mm_Horizontal +Through hole angled pin header, 2x26, 2.54mm pitch, 6mm pin length, double rows +Through hole angled pin header THT 2x26 2.54mm double row +0 +52 +52 +Connector_PinHeader_2.54mm +PinHeader_2x26_P2.54mm_Vertical +Through hole straight pin header, 2x26, 2.54mm pitch, double rows +Through hole pin header THT 2x26 2.54mm double row +0 +52 +52 +Connector_PinHeader_2.54mm +PinHeader_2x26_P2.54mm_Vertical_SMD +surface-mounted straight pin header, 2x26, 2.54mm pitch, double rows +Surface mounted pin header SMD 2x26 2.54mm double row +0 +52 +52 +Connector_PinHeader_2.54mm +PinHeader_2x27_P2.54mm_Horizontal +Through hole angled pin header, 2x27, 2.54mm pitch, 6mm pin length, double rows +Through hole angled pin header THT 2x27 2.54mm double row +0 +54 +54 +Connector_PinHeader_2.54mm +PinHeader_2x27_P2.54mm_Vertical +Through hole straight pin header, 2x27, 2.54mm pitch, double rows +Through hole pin header THT 2x27 2.54mm double row +0 +54 +54 +Connector_PinHeader_2.54mm +PinHeader_2x27_P2.54mm_Vertical_SMD +surface-mounted straight pin header, 2x27, 2.54mm pitch, double rows +Surface mounted pin header SMD 2x27 2.54mm double row +0 +54 +54 +Connector_PinHeader_2.54mm +PinHeader_2x28_P2.54mm_Horizontal +Through hole angled pin header, 2x28, 2.54mm pitch, 6mm pin length, double rows +Through hole angled pin header THT 2x28 2.54mm double row +0 +56 +56 +Connector_PinHeader_2.54mm +PinHeader_2x28_P2.54mm_Vertical +Through hole straight pin header, 2x28, 2.54mm pitch, double rows +Through hole pin header THT 2x28 2.54mm double row +0 +56 +56 +Connector_PinHeader_2.54mm +PinHeader_2x28_P2.54mm_Vertical_SMD +surface-mounted straight pin header, 2x28, 2.54mm pitch, double rows +Surface mounted pin header SMD 2x28 2.54mm double row +0 +56 +56 +Connector_PinHeader_2.54mm +PinHeader_2x29_P2.54mm_Horizontal +Through hole angled pin header, 2x29, 2.54mm pitch, 6mm pin length, double rows +Through hole angled pin header THT 2x29 2.54mm double row +0 +58 +58 +Connector_PinHeader_2.54mm +PinHeader_2x29_P2.54mm_Vertical +Through hole straight pin header, 2x29, 2.54mm pitch, double rows +Through hole pin header THT 2x29 2.54mm double row +0 +58 +58 +Connector_PinHeader_2.54mm +PinHeader_2x29_P2.54mm_Vertical_SMD +surface-mounted straight pin header, 2x29, 2.54mm pitch, double rows +Surface mounted pin header SMD 2x29 2.54mm double row +0 +58 +58 +Connector_PinHeader_2.54mm +PinHeader_2x30_P2.54mm_Horizontal +Through hole angled pin header, 2x30, 2.54mm pitch, 6mm pin length, double rows +Through hole angled pin header THT 2x30 2.54mm double row +0 +60 +60 +Connector_PinHeader_2.54mm +PinHeader_2x30_P2.54mm_Vertical +Through hole straight pin header, 2x30, 2.54mm pitch, double rows +Through hole pin header THT 2x30 2.54mm double row +0 +60 +60 +Connector_PinHeader_2.54mm +PinHeader_2x30_P2.54mm_Vertical_SMD +surface-mounted straight pin header, 2x30, 2.54mm pitch, double rows +Surface mounted pin header SMD 2x30 2.54mm double row +0 +60 +60 +Connector_PinHeader_2.54mm +PinHeader_2x31_P2.54mm_Horizontal +Through hole angled pin header, 2x31, 2.54mm pitch, 6mm pin length, double rows +Through hole angled pin header THT 2x31 2.54mm double row +0 +62 +62 +Connector_PinHeader_2.54mm +PinHeader_2x31_P2.54mm_Vertical +Through hole straight pin header, 2x31, 2.54mm pitch, double rows +Through hole pin header THT 2x31 2.54mm double row +0 +62 +62 +Connector_PinHeader_2.54mm +PinHeader_2x31_P2.54mm_Vertical_SMD +surface-mounted straight pin header, 2x31, 2.54mm pitch, double rows +Surface mounted pin header SMD 2x31 2.54mm double row +0 +62 +62 +Connector_PinHeader_2.54mm +PinHeader_2x32_P2.54mm_Horizontal +Through hole angled pin header, 2x32, 2.54mm pitch, 6mm pin length, double rows +Through hole angled pin header THT 2x32 2.54mm double row +0 +64 +64 +Connector_PinHeader_2.54mm +PinHeader_2x32_P2.54mm_Vertical +Through hole straight pin header, 2x32, 2.54mm pitch, double rows +Through hole pin header THT 2x32 2.54mm double row +0 +64 +64 +Connector_PinHeader_2.54mm +PinHeader_2x32_P2.54mm_Vertical_SMD +surface-mounted straight pin header, 2x32, 2.54mm pitch, double rows +Surface mounted pin header SMD 2x32 2.54mm double row +0 +64 +64 +Connector_PinHeader_2.54mm +PinHeader_2x33_P2.54mm_Horizontal +Through hole angled pin header, 2x33, 2.54mm pitch, 6mm pin length, double rows +Through hole angled pin header THT 2x33 2.54mm double row +0 +66 +66 +Connector_PinHeader_2.54mm +PinHeader_2x33_P2.54mm_Vertical +Through hole straight pin header, 2x33, 2.54mm pitch, double rows +Through hole pin header THT 2x33 2.54mm double row +0 +66 +66 +Connector_PinHeader_2.54mm +PinHeader_2x33_P2.54mm_Vertical_SMD +surface-mounted straight pin header, 2x33, 2.54mm pitch, double rows +Surface mounted pin header SMD 2x33 2.54mm double row +0 +66 +66 +Connector_PinHeader_2.54mm +PinHeader_2x34_P2.54mm_Horizontal +Through hole angled pin header, 2x34, 2.54mm pitch, 6mm pin length, double rows +Through hole angled pin header THT 2x34 2.54mm double row +0 +68 +68 +Connector_PinHeader_2.54mm +PinHeader_2x34_P2.54mm_Vertical +Through hole straight pin header, 2x34, 2.54mm pitch, double rows +Through hole pin header THT 2x34 2.54mm double row +0 +68 +68 +Connector_PinHeader_2.54mm +PinHeader_2x34_P2.54mm_Vertical_SMD +surface-mounted straight pin header, 2x34, 2.54mm pitch, double rows +Surface mounted pin header SMD 2x34 2.54mm double row +0 +68 +68 +Connector_PinHeader_2.54mm +PinHeader_2x35_P2.54mm_Horizontal +Through hole angled pin header, 2x35, 2.54mm pitch, 6mm pin length, double rows +Through hole angled pin header THT 2x35 2.54mm double row +0 +70 +70 +Connector_PinHeader_2.54mm +PinHeader_2x35_P2.54mm_Vertical +Through hole straight pin header, 2x35, 2.54mm pitch, double rows +Through hole pin header THT 2x35 2.54mm double row +0 +70 +70 +Connector_PinHeader_2.54mm +PinHeader_2x35_P2.54mm_Vertical_SMD +surface-mounted straight pin header, 2x35, 2.54mm pitch, double rows +Surface mounted pin header SMD 2x35 2.54mm double row +0 +70 +70 +Connector_PinHeader_2.54mm +PinHeader_2x36_P2.54mm_Horizontal +Through hole angled pin header, 2x36, 2.54mm pitch, 6mm pin length, double rows +Through hole angled pin header THT 2x36 2.54mm double row +0 +72 +72 +Connector_PinHeader_2.54mm +PinHeader_2x36_P2.54mm_Vertical +Through hole straight pin header, 2x36, 2.54mm pitch, double rows +Through hole pin header THT 2x36 2.54mm double row +0 +72 +72 +Connector_PinHeader_2.54mm +PinHeader_2x36_P2.54mm_Vertical_SMD +surface-mounted straight pin header, 2x36, 2.54mm pitch, double rows +Surface mounted pin header SMD 2x36 2.54mm double row +0 +72 +72 +Connector_PinHeader_2.54mm +PinHeader_2x37_P2.54mm_Horizontal +Through hole angled pin header, 2x37, 2.54mm pitch, 6mm pin length, double rows +Through hole angled pin header THT 2x37 2.54mm double row +0 +74 +74 +Connector_PinHeader_2.54mm +PinHeader_2x37_P2.54mm_Vertical +Through hole straight pin header, 2x37, 2.54mm pitch, double rows +Through hole pin header THT 2x37 2.54mm double row +0 +74 +74 +Connector_PinHeader_2.54mm +PinHeader_2x37_P2.54mm_Vertical_SMD +surface-mounted straight pin header, 2x37, 2.54mm pitch, double rows +Surface mounted pin header SMD 2x37 2.54mm double row +0 +74 +74 +Connector_PinHeader_2.54mm +PinHeader_2x38_P2.54mm_Horizontal +Through hole angled pin header, 2x38, 2.54mm pitch, 6mm pin length, double rows +Through hole angled pin header THT 2x38 2.54mm double row +0 +76 +76 +Connector_PinHeader_2.54mm +PinHeader_2x38_P2.54mm_Vertical +Through hole straight pin header, 2x38, 2.54mm pitch, double rows +Through hole pin header THT 2x38 2.54mm double row +0 +76 +76 +Connector_PinHeader_2.54mm +PinHeader_2x38_P2.54mm_Vertical_SMD +surface-mounted straight pin header, 2x38, 2.54mm pitch, double rows +Surface mounted pin header SMD 2x38 2.54mm double row +0 +76 +76 +Connector_PinHeader_2.54mm +PinHeader_2x39_P2.54mm_Horizontal +Through hole angled pin header, 2x39, 2.54mm pitch, 6mm pin length, double rows +Through hole angled pin header THT 2x39 2.54mm double row +0 +78 +78 +Connector_PinHeader_2.54mm +PinHeader_2x39_P2.54mm_Vertical +Through hole straight pin header, 2x39, 2.54mm pitch, double rows +Through hole pin header THT 2x39 2.54mm double row +0 +78 +78 +Connector_PinHeader_2.54mm +PinHeader_2x39_P2.54mm_Vertical_SMD +surface-mounted straight pin header, 2x39, 2.54mm pitch, double rows +Surface mounted pin header SMD 2x39 2.54mm double row +0 +78 +78 +Connector_PinHeader_2.54mm +PinHeader_2x40_P2.54mm_Horizontal +Through hole angled pin header, 2x40, 2.54mm pitch, 6mm pin length, double rows +Through hole angled pin header THT 2x40 2.54mm double row +0 +80 +80 +Connector_PinHeader_2.54mm +PinHeader_2x40_P2.54mm_Vertical +Through hole straight pin header, 2x40, 2.54mm pitch, double rows +Through hole pin header THT 2x40 2.54mm double row +0 +80 +80 +Connector_PinHeader_2.54mm +PinHeader_2x40_P2.54mm_Vertical_SMD +surface-mounted straight pin header, 2x40, 2.54mm pitch, double rows +Surface mounted pin header SMD 2x40 2.54mm double row +0 +80 +80 +Connector_PinSocket_2.54mm +PinSocket_1x01_P2.54mm_Horizontal +Through hole angled socket strip, 1x01, 2.54mm pitch, 8.51mm socket length, single row (from Kicad 4.0.7), script generated +Through hole angled socket strip THT 1x01 2.54mm single row +0 +1 +1 +Connector_PinSocket_2.54mm +PinSocket_1x01_P2.54mm_Vertical +Through hole straight socket strip, 1x01, 2.54mm pitch, single row (from Kicad 4.0.7), script generated +Through hole socket strip THT 1x01 2.54mm single row +0 +1 +1 +Connector_PinSocket_2.54mm +PinSocket_1x02_P2.54mm_Horizontal +Through hole angled socket strip, 1x02, 2.54mm pitch, 8.51mm socket length, single row (from Kicad 4.0.7), script generated +Through hole angled socket strip THT 1x02 2.54mm single row +0 +2 +2 +Connector_PinSocket_2.54mm +PinSocket_1x02_P2.54mm_Vertical +Through hole straight socket strip, 1x02, 2.54mm pitch, single row (from Kicad 4.0.7), script generated +Through hole socket strip THT 1x02 2.54mm single row +0 +2 +2 +Connector_PinSocket_2.54mm +PinSocket_1x02_P2.54mm_Vertical_SMD_Pin1Left +surface-mounted straight socket strip, 1x02, 2.54mm pitch, single row, style 1 (pin 1 left) (https://cdn.harwin.com/pdfs/M20-786.pdf), script generated +Surface mounted socket strip SMD 1x02 2.54mm single row style1 pin1 left +0 +2 +2 +Connector_PinSocket_2.54mm +PinSocket_1x02_P2.54mm_Vertical_SMD_Pin1Right +surface-mounted straight socket strip, 1x02, 2.54mm pitch, single row, style 2 (pin 1 right) (https://cdn.harwin.com/pdfs/M20-786.pdf), script generated +Surface mounted socket strip SMD 1x02 2.54mm single row style2 pin1 right +0 +2 +2 +Connector_PinSocket_2.54mm +PinSocket_1x03_P2.54mm_Horizontal +Through hole angled socket strip, 1x03, 2.54mm pitch, 8.51mm socket length, single row (from Kicad 4.0.7), script generated +Through hole angled socket strip THT 1x03 2.54mm single row +0 +3 +3 +Connector_PinSocket_2.54mm +PinSocket_1x03_P2.54mm_Vertical +Through hole straight socket strip, 1x03, 2.54mm pitch, single row (from Kicad 4.0.7), script generated +Through hole socket strip THT 1x03 2.54mm single row +0 +3 +3 +Connector_PinSocket_2.54mm +PinSocket_1x03_P2.54mm_Vertical_SMD_Pin1Left +surface-mounted straight socket strip, 1x03, 2.54mm pitch, single row, style 1 (pin 1 left) (https://cdn.harwin.com/pdfs/M20-786.pdf), script generated +Surface mounted socket strip SMD 1x03 2.54mm single row style1 pin1 left +0 +3 +3 +Connector_PinSocket_2.54mm +PinSocket_1x03_P2.54mm_Vertical_SMD_Pin1Right +surface-mounted straight socket strip, 1x03, 2.54mm pitch, single row, style 2 (pin 1 right) (https://cdn.harwin.com/pdfs/M20-786.pdf), script generated +Surface mounted socket strip SMD 1x03 2.54mm single row style2 pin1 right +0 +3 +3 +Connector_PinSocket_2.54mm +PinSocket_1x04_P2.54mm_Horizontal +Through hole angled socket strip, 1x04, 2.54mm pitch, 8.51mm socket length, single row (from Kicad 4.0.7), script generated +Through hole angled socket strip THT 1x04 2.54mm single row +0 +4 +4 +Connector_PinSocket_2.54mm +PinSocket_1x04_P2.54mm_Vertical +Through hole straight socket strip, 1x04, 2.54mm pitch, single row (from Kicad 4.0.7), script generated +Through hole socket strip THT 1x04 2.54mm single row +0 +4 +4 +Connector_PinSocket_2.54mm +PinSocket_1x04_P2.54mm_Vertical_SMD_Pin1Left +surface-mounted straight socket strip, 1x04, 2.54mm pitch, single row, style 1 (pin 1 left) (https://cdn.harwin.com/pdfs/M20-786.pdf), script generated +Surface mounted socket strip SMD 1x04 2.54mm single row style1 pin1 left +0 +4 +4 +Connector_PinSocket_2.54mm +PinSocket_1x04_P2.54mm_Vertical_SMD_Pin1Right +surface-mounted straight socket strip, 1x04, 2.54mm pitch, single row, style 2 (pin 1 right) (https://cdn.harwin.com/pdfs/M20-786.pdf), script generated +Surface mounted socket strip SMD 1x04 2.54mm single row style2 pin1 right +0 +4 +4 +Connector_PinSocket_2.54mm +PinSocket_1x05_P2.54mm_Horizontal +Through hole angled socket strip, 1x05, 2.54mm pitch, 8.51mm socket length, single row (from Kicad 4.0.7), script generated +Through hole angled socket strip THT 1x05 2.54mm single row +0 +5 +5 +Connector_PinSocket_2.54mm +PinSocket_1x05_P2.54mm_Vertical +Through hole straight socket strip, 1x05, 2.54mm pitch, single row (from Kicad 4.0.7), script generated +Through hole socket strip THT 1x05 2.54mm single row +0 +5 +5 +Connector_PinSocket_2.54mm +PinSocket_1x05_P2.54mm_Vertical_SMD_Pin1Left +surface-mounted straight socket strip, 1x05, 2.54mm pitch, single row, style 1 (pin 1 left) (https://cdn.harwin.com/pdfs/M20-786.pdf), script generated +Surface mounted socket strip SMD 1x05 2.54mm single row style1 pin1 left +0 +5 +5 +Connector_PinSocket_2.54mm +PinSocket_1x05_P2.54mm_Vertical_SMD_Pin1Right +surface-mounted straight socket strip, 1x05, 2.54mm pitch, single row, style 2 (pin 1 right) (https://cdn.harwin.com/pdfs/M20-786.pdf), script generated +Surface mounted socket strip SMD 1x05 2.54mm single row style2 pin1 right +0 +5 +5 +Connector_PinSocket_2.54mm +PinSocket_1x06_P2.54mm_Horizontal +Through hole angled socket strip, 1x06, 2.54mm pitch, 8.51mm socket length, single row (from Kicad 4.0.7), script generated +Through hole angled socket strip THT 1x06 2.54mm single row +0 +6 +6 +Connector_PinSocket_2.54mm +PinSocket_1x06_P2.54mm_Vertical +Through hole straight socket strip, 1x06, 2.54mm pitch, single row (from Kicad 4.0.7), script generated +Through hole socket strip THT 1x06 2.54mm single row +0 +6 +6 +Connector_PinSocket_2.54mm +PinSocket_1x06_P2.54mm_Vertical_SMD_Pin1Left +surface-mounted straight socket strip, 1x06, 2.54mm pitch, single row, style 1 (pin 1 left) (https://cdn.harwin.com/pdfs/M20-786.pdf), script generated +Surface mounted socket strip SMD 1x06 2.54mm single row style1 pin1 left +0 +6 +6 +Connector_PinSocket_2.54mm +PinSocket_1x06_P2.54mm_Vertical_SMD_Pin1Right +surface-mounted straight socket strip, 1x06, 2.54mm pitch, single row, style 2 (pin 1 right) (https://cdn.harwin.com/pdfs/M20-786.pdf), script generated +Surface mounted socket strip SMD 1x06 2.54mm single row style2 pin1 right +0 +6 +6 +Connector_PinSocket_2.54mm +PinSocket_1x07_P2.54mm_Horizontal +Through hole angled socket strip, 1x07, 2.54mm pitch, 8.51mm socket length, single row (from Kicad 4.0.7), script generated +Through hole angled socket strip THT 1x07 2.54mm single row +0 +7 +7 +Connector_PinSocket_2.54mm +PinSocket_1x07_P2.54mm_Vertical +Through hole straight socket strip, 1x07, 2.54mm pitch, single row (from Kicad 4.0.7), script generated +Through hole socket strip THT 1x07 2.54mm single row +0 +7 +7 +Connector_PinSocket_2.54mm +PinSocket_1x07_P2.54mm_Vertical_SMD_Pin1Left +surface-mounted straight socket strip, 1x07, 2.54mm pitch, single row, style 1 (pin 1 left) (https://cdn.harwin.com/pdfs/M20-786.pdf), script generated +Surface mounted socket strip SMD 1x07 2.54mm single row style1 pin1 left +0 +7 +7 +Connector_PinSocket_2.54mm +PinSocket_1x07_P2.54mm_Vertical_SMD_Pin1Right +surface-mounted straight socket strip, 1x07, 2.54mm pitch, single row, style 2 (pin 1 right) (https://cdn.harwin.com/pdfs/M20-786.pdf), script generated +Surface mounted socket strip SMD 1x07 2.54mm single row style2 pin1 right +0 +7 +7 +Connector_PinSocket_2.54mm +PinSocket_1x08_P2.54mm_Horizontal +Through hole angled socket strip, 1x08, 2.54mm pitch, 8.51mm socket length, single row (from Kicad 4.0.7), script generated +Through hole angled socket strip THT 1x08 2.54mm single row +0 +8 +8 +Connector_PinSocket_2.54mm +PinSocket_1x08_P2.54mm_Vertical +Through hole straight socket strip, 1x08, 2.54mm pitch, single row (from Kicad 4.0.7), script generated +Through hole socket strip THT 1x08 2.54mm single row +0 +8 +8 +Connector_PinSocket_2.54mm +PinSocket_1x08_P2.54mm_Vertical_SMD_Pin1Left +surface-mounted straight socket strip, 1x08, 2.54mm pitch, single row, style 1 (pin 1 left) (https://cdn.harwin.com/pdfs/M20-786.pdf), script generated +Surface mounted socket strip SMD 1x08 2.54mm single row style1 pin1 left +0 +8 +8 +Connector_PinSocket_2.54mm +PinSocket_1x08_P2.54mm_Vertical_SMD_Pin1Right +surface-mounted straight socket strip, 1x08, 2.54mm pitch, single row, style 2 (pin 1 right) (https://cdn.harwin.com/pdfs/M20-786.pdf), script generated +Surface mounted socket strip SMD 1x08 2.54mm single row style2 pin1 right +0 +8 +8 +Connector_PinSocket_2.54mm +PinSocket_1x09_P2.54mm_Horizontal +Through hole angled socket strip, 1x09, 2.54mm pitch, 8.51mm socket length, single row (from Kicad 4.0.7), script generated +Through hole angled socket strip THT 1x09 2.54mm single row +0 +9 +9 +Connector_PinSocket_2.54mm +PinSocket_1x09_P2.54mm_Vertical +Through hole straight socket strip, 1x09, 2.54mm pitch, single row (from Kicad 4.0.7), script generated +Through hole socket strip THT 1x09 2.54mm single row +0 +9 +9 +Connector_PinSocket_2.54mm +PinSocket_1x09_P2.54mm_Vertical_SMD_Pin1Left +surface-mounted straight socket strip, 1x09, 2.54mm pitch, single row, style 1 (pin 1 left) (https://cdn.harwin.com/pdfs/M20-786.pdf), script generated +Surface mounted socket strip SMD 1x09 2.54mm single row style1 pin1 left +0 +9 +9 +Connector_PinSocket_2.54mm +PinSocket_1x09_P2.54mm_Vertical_SMD_Pin1Right +surface-mounted straight socket strip, 1x09, 2.54mm pitch, single row, style 2 (pin 1 right) (https://cdn.harwin.com/pdfs/M20-786.pdf), script generated +Surface mounted socket strip SMD 1x09 2.54mm single row style2 pin1 right +0 +9 +9 +Connector_PinSocket_2.54mm +PinSocket_1x10_P2.54mm_Horizontal +Through hole angled socket strip, 1x10, 2.54mm pitch, 8.51mm socket length, single row (from Kicad 4.0.7), script generated +Through hole angled socket strip THT 1x10 2.54mm single row +0 +10 +10 +Connector_PinSocket_2.54mm +PinSocket_1x10_P2.54mm_Vertical +Through hole straight socket strip, 1x10, 2.54mm pitch, single row (from Kicad 4.0.7), script generated +Through hole socket strip THT 1x10 2.54mm single row +0 +10 +10 +Connector_PinSocket_2.54mm +PinSocket_1x10_P2.54mm_Vertical_SMD_Pin1Left +surface-mounted straight socket strip, 1x10, 2.54mm pitch, single row, style 1 (pin 1 left) (https://cdn.harwin.com/pdfs/M20-786.pdf), script generated +Surface mounted socket strip SMD 1x10 2.54mm single row style1 pin1 left +0 +10 +10 +Connector_PinSocket_2.54mm +PinSocket_1x10_P2.54mm_Vertical_SMD_Pin1Right +surface-mounted straight socket strip, 1x10, 2.54mm pitch, single row, style 2 (pin 1 right) (https://cdn.harwin.com/pdfs/M20-786.pdf), script generated +Surface mounted socket strip SMD 1x10 2.54mm single row style2 pin1 right +0 +10 +10 +Connector_PinSocket_2.54mm +PinSocket_1x11_P2.54mm_Horizontal +Through hole angled socket strip, 1x11, 2.54mm pitch, 8.51mm socket length, single row (from Kicad 4.0.7), script generated +Through hole angled socket strip THT 1x11 2.54mm single row +0 +11 +11 +Connector_PinSocket_2.54mm +PinSocket_1x11_P2.54mm_Vertical +Through hole straight socket strip, 1x11, 2.54mm pitch, single row (from Kicad 4.0.7), script generated +Through hole socket strip THT 1x11 2.54mm single row +0 +11 +11 +Connector_PinSocket_2.54mm +PinSocket_1x11_P2.54mm_Vertical_SMD_Pin1Left +surface-mounted straight socket strip, 1x11, 2.54mm pitch, single row, style 1 (pin 1 left) (https://cdn.harwin.com/pdfs/M20-786.pdf), script generated +Surface mounted socket strip SMD 1x11 2.54mm single row style1 pin1 left +0 +11 +11 +Connector_PinSocket_2.54mm +PinSocket_1x11_P2.54mm_Vertical_SMD_Pin1Right +surface-mounted straight socket strip, 1x11, 2.54mm pitch, single row, style 2 (pin 1 right) (https://cdn.harwin.com/pdfs/M20-786.pdf), script generated +Surface mounted socket strip SMD 1x11 2.54mm single row style2 pin1 right +0 +11 +11 +Connector_PinSocket_2.54mm +PinSocket_1x12_P2.54mm_Horizontal +Through hole angled socket strip, 1x12, 2.54mm pitch, 8.51mm socket length, single row (from Kicad 4.0.7), script generated +Through hole angled socket strip THT 1x12 2.54mm single row +0 +12 +12 +Connector_PinSocket_2.54mm +PinSocket_1x12_P2.54mm_Vertical +Through hole straight socket strip, 1x12, 2.54mm pitch, single row (from Kicad 4.0.7), script generated +Through hole socket strip THT 1x12 2.54mm single row +0 +12 +12 +Connector_PinSocket_2.54mm +PinSocket_1x12_P2.54mm_Vertical_SMD_Pin1Left +surface-mounted straight socket strip, 1x12, 2.54mm pitch, single row, style 1 (pin 1 left) (https://cdn.harwin.com/pdfs/M20-786.pdf), script generated +Surface mounted socket strip SMD 1x12 2.54mm single row style1 pin1 left +0 +12 +12 +Connector_PinSocket_2.54mm +PinSocket_1x12_P2.54mm_Vertical_SMD_Pin1Right +surface-mounted straight socket strip, 1x12, 2.54mm pitch, single row, style 2 (pin 1 right) (https://cdn.harwin.com/pdfs/M20-786.pdf), script generated +Surface mounted socket strip SMD 1x12 2.54mm single row style2 pin1 right +0 +12 +12 +Connector_PinSocket_2.54mm +PinSocket_1x13_P2.54mm_Horizontal +Through hole angled socket strip, 1x13, 2.54mm pitch, 8.51mm socket length, single row (from Kicad 4.0.7), script generated +Through hole angled socket strip THT 1x13 2.54mm single row +0 +13 +13 +Connector_PinSocket_2.54mm +PinSocket_1x13_P2.54mm_Vertical +Through hole straight socket strip, 1x13, 2.54mm pitch, single row (from Kicad 4.0.7), script generated +Through hole socket strip THT 1x13 2.54mm single row +0 +13 +13 +Connector_PinSocket_2.54mm +PinSocket_1x13_P2.54mm_Vertical_SMD_Pin1Left +surface-mounted straight socket strip, 1x13, 2.54mm pitch, single row, style 1 (pin 1 left) (https://cdn.harwin.com/pdfs/M20-786.pdf), script generated +Surface mounted socket strip SMD 1x13 2.54mm single row style1 pin1 left +0 +13 +13 +Connector_PinSocket_2.54mm +PinSocket_1x13_P2.54mm_Vertical_SMD_Pin1Right +surface-mounted straight socket strip, 1x13, 2.54mm pitch, single row, style 2 (pin 1 right) (https://cdn.harwin.com/pdfs/M20-786.pdf), script generated +Surface mounted socket strip SMD 1x13 2.54mm single row style2 pin1 right +0 +13 +13 +Connector_PinSocket_2.54mm +PinSocket_1x14_P2.54mm_Horizontal +Through hole angled socket strip, 1x14, 2.54mm pitch, 8.51mm socket length, single row (from Kicad 4.0.7), script generated +Through hole angled socket strip THT 1x14 2.54mm single row +0 +14 +14 +Connector_PinSocket_2.54mm +PinSocket_1x14_P2.54mm_Vertical +Through hole straight socket strip, 1x14, 2.54mm pitch, single row (from Kicad 4.0.7), script generated +Through hole socket strip THT 1x14 2.54mm single row +0 +14 +14 +Connector_PinSocket_2.54mm +PinSocket_1x14_P2.54mm_Vertical_SMD_Pin1Left +surface-mounted straight socket strip, 1x14, 2.54mm pitch, single row, style 1 (pin 1 left) (https://cdn.harwin.com/pdfs/M20-786.pdf), script generated +Surface mounted socket strip SMD 1x14 2.54mm single row style1 pin1 left +0 +14 +14 +Connector_PinSocket_2.54mm +PinSocket_1x14_P2.54mm_Vertical_SMD_Pin1Right +surface-mounted straight socket strip, 1x14, 2.54mm pitch, single row, style 2 (pin 1 right) (https://cdn.harwin.com/pdfs/M20-786.pdf), script generated +Surface mounted socket strip SMD 1x14 2.54mm single row style2 pin1 right +0 +14 +14 +Connector_PinSocket_2.54mm +PinSocket_1x15_P2.54mm_Horizontal +Through hole angled socket strip, 1x15, 2.54mm pitch, 8.51mm socket length, single row (from Kicad 4.0.7), script generated +Through hole angled socket strip THT 1x15 2.54mm single row +0 +15 +15 +Connector_PinSocket_2.54mm +PinSocket_1x15_P2.54mm_Vertical +Through hole straight socket strip, 1x15, 2.54mm pitch, single row (from Kicad 4.0.7), script generated +Through hole socket strip THT 1x15 2.54mm single row +0 +15 +15 +Connector_PinSocket_2.54mm +PinSocket_1x15_P2.54mm_Vertical_SMD_Pin1Left +surface-mounted straight socket strip, 1x15, 2.54mm pitch, single row, style 1 (pin 1 left) (https://cdn.harwin.com/pdfs/M20-786.pdf), script generated +Surface mounted socket strip SMD 1x15 2.54mm single row style1 pin1 left +0 +15 +15 +Connector_PinSocket_2.54mm +PinSocket_1x15_P2.54mm_Vertical_SMD_Pin1Right +surface-mounted straight socket strip, 1x15, 2.54mm pitch, single row, style 2 (pin 1 right) (https://cdn.harwin.com/pdfs/M20-786.pdf), script generated +Surface mounted socket strip SMD 1x15 2.54mm single row style2 pin1 right +0 +15 +15 +Connector_PinSocket_2.54mm +PinSocket_1x16_P2.54mm_Horizontal +Through hole angled socket strip, 1x16, 2.54mm pitch, 8.51mm socket length, single row (from Kicad 4.0.7), script generated +Through hole angled socket strip THT 1x16 2.54mm single row +0 +16 +16 +Connector_PinSocket_2.54mm +PinSocket_1x16_P2.54mm_Vertical +Through hole straight socket strip, 1x16, 2.54mm pitch, single row (from Kicad 4.0.7), script generated +Through hole socket strip THT 1x16 2.54mm single row +0 +16 +16 +Connector_PinSocket_2.54mm +PinSocket_1x16_P2.54mm_Vertical_SMD_Pin1Left +surface-mounted straight socket strip, 1x16, 2.54mm pitch, single row, style 1 (pin 1 left) (https://cdn.harwin.com/pdfs/M20-786.pdf), script generated +Surface mounted socket strip SMD 1x16 2.54mm single row style1 pin1 left +0 +16 +16 +Connector_PinSocket_2.54mm +PinSocket_1x16_P2.54mm_Vertical_SMD_Pin1Right +surface-mounted straight socket strip, 1x16, 2.54mm pitch, single row, style 2 (pin 1 right) (https://cdn.harwin.com/pdfs/M20-786.pdf), script generated +Surface mounted socket strip SMD 1x16 2.54mm single row style2 pin1 right +0 +16 +16 +Connector_PinSocket_2.54mm +PinSocket_1x17_P2.54mm_Horizontal +Through hole angled socket strip, 1x17, 2.54mm pitch, 8.51mm socket length, single row (from Kicad 4.0.7), script generated +Through hole angled socket strip THT 1x17 2.54mm single row +0 +17 +17 +Connector_PinSocket_2.54mm +PinSocket_1x17_P2.54mm_Vertical +Through hole straight socket strip, 1x17, 2.54mm pitch, single row (from Kicad 4.0.7), script generated +Through hole socket strip THT 1x17 2.54mm single row +0 +17 +17 +Connector_PinSocket_2.54mm +PinSocket_1x17_P2.54mm_Vertical_SMD_Pin1Left +surface-mounted straight socket strip, 1x17, 2.54mm pitch, single row, style 1 (pin 1 left) (https://cdn.harwin.com/pdfs/M20-786.pdf), script generated +Surface mounted socket strip SMD 1x17 2.54mm single row style1 pin1 left +0 +17 +17 +Connector_PinSocket_2.54mm +PinSocket_1x17_P2.54mm_Vertical_SMD_Pin1Right +surface-mounted straight socket strip, 1x17, 2.54mm pitch, single row, style 2 (pin 1 right) (https://cdn.harwin.com/pdfs/M20-786.pdf), script generated +Surface mounted socket strip SMD 1x17 2.54mm single row style2 pin1 right +0 +17 +17 +Connector_PinSocket_2.54mm +PinSocket_1x18_P2.54mm_Horizontal +Through hole angled socket strip, 1x18, 2.54mm pitch, 8.51mm socket length, single row (from Kicad 4.0.7), script generated +Through hole angled socket strip THT 1x18 2.54mm single row +0 +18 +18 +Connector_PinSocket_2.54mm +PinSocket_1x18_P2.54mm_Vertical +Through hole straight socket strip, 1x18, 2.54mm pitch, single row (from Kicad 4.0.7), script generated +Through hole socket strip THT 1x18 2.54mm single row +0 +18 +18 +Connector_PinSocket_2.54mm +PinSocket_1x18_P2.54mm_Vertical_SMD_Pin1Left +surface-mounted straight socket strip, 1x18, 2.54mm pitch, single row, style 1 (pin 1 left) (https://cdn.harwin.com/pdfs/M20-786.pdf), script generated +Surface mounted socket strip SMD 1x18 2.54mm single row style1 pin1 left +0 +18 +18 +Connector_PinSocket_2.54mm +PinSocket_1x18_P2.54mm_Vertical_SMD_Pin1Right +surface-mounted straight socket strip, 1x18, 2.54mm pitch, single row, style 2 (pin 1 right) (https://cdn.harwin.com/pdfs/M20-786.pdf), script generated +Surface mounted socket strip SMD 1x18 2.54mm single row style2 pin1 right +0 +18 +18 +Connector_PinSocket_2.54mm +PinSocket_1x19_P2.54mm_Horizontal +Through hole angled socket strip, 1x19, 2.54mm pitch, 8.51mm socket length, single row (from Kicad 4.0.7), script generated +Through hole angled socket strip THT 1x19 2.54mm single row +0 +19 +19 +Connector_PinSocket_2.54mm +PinSocket_1x19_P2.54mm_Vertical +Through hole straight socket strip, 1x19, 2.54mm pitch, single row (from Kicad 4.0.7), script generated +Through hole socket strip THT 1x19 2.54mm single row +0 +19 +19 +Connector_PinSocket_2.54mm +PinSocket_1x19_P2.54mm_Vertical_SMD_Pin1Left +surface-mounted straight socket strip, 1x19, 2.54mm pitch, single row, style 1 (pin 1 left) (https://cdn.harwin.com/pdfs/M20-786.pdf), script generated +Surface mounted socket strip SMD 1x19 2.54mm single row style1 pin1 left +0 +19 +19 +Connector_PinSocket_2.54mm +PinSocket_1x19_P2.54mm_Vertical_SMD_Pin1Right +surface-mounted straight socket strip, 1x19, 2.54mm pitch, single row, style 2 (pin 1 right) (https://cdn.harwin.com/pdfs/M20-786.pdf), script generated +Surface mounted socket strip SMD 1x19 2.54mm single row style2 pin1 right +0 +19 +19 +Connector_PinSocket_2.54mm +PinSocket_1x20_P2.54mm_Horizontal +Through hole angled socket strip, 1x20, 2.54mm pitch, 8.51mm socket length, single row (from Kicad 4.0.7), script generated +Through hole angled socket strip THT 1x20 2.54mm single row +0 +20 +20 +Connector_PinSocket_2.54mm +PinSocket_1x20_P2.54mm_Vertical +Through hole straight socket strip, 1x20, 2.54mm pitch, single row (from Kicad 4.0.7), script generated +Through hole socket strip THT 1x20 2.54mm single row +0 +20 +20 +Connector_PinSocket_2.54mm +PinSocket_1x20_P2.54mm_Vertical_SMD_Pin1Left +surface-mounted straight socket strip, 1x20, 2.54mm pitch, single row, style 1 (pin 1 left) (https://cdn.harwin.com/pdfs/M20-786.pdf), script generated +Surface mounted socket strip SMD 1x20 2.54mm single row style1 pin1 left +0 +20 +20 +Connector_PinSocket_2.54mm +PinSocket_1x20_P2.54mm_Vertical_SMD_Pin1Right +surface-mounted straight socket strip, 1x20, 2.54mm pitch, single row, style 2 (pin 1 right) (https://cdn.harwin.com/pdfs/M20-786.pdf), script generated +Surface mounted socket strip SMD 1x20 2.54mm single row style2 pin1 right +0 +20 +20 +Connector_PinSocket_2.54mm +PinSocket_1x21_P2.54mm_Horizontal +Through hole angled socket strip, 1x21, 2.54mm pitch, 8.51mm socket length, single row (from Kicad 4.0.7), script generated +Through hole angled socket strip THT 1x21 2.54mm single row +0 +21 +21 +Connector_PinSocket_2.54mm +PinSocket_1x21_P2.54mm_Vertical +Through hole straight socket strip, 1x21, 2.54mm pitch, single row (from Kicad 4.0.7), script generated +Through hole socket strip THT 1x21 2.54mm single row +0 +21 +21 +Connector_PinSocket_2.54mm +PinSocket_1x21_P2.54mm_Vertical_SMD_Pin1Left +surface-mounted straight socket strip, 1x21, 2.54mm pitch, single row, style 1 (pin 1 left) (https://cdn.harwin.com/pdfs/M20-786.pdf), script generated +Surface mounted socket strip SMD 1x21 2.54mm single row style1 pin1 left +0 +21 +21 +Connector_PinSocket_2.54mm +PinSocket_1x21_P2.54mm_Vertical_SMD_Pin1Right +surface-mounted straight socket strip, 1x21, 2.54mm pitch, single row, style 2 (pin 1 right) (https://cdn.harwin.com/pdfs/M20-786.pdf), script generated +Surface mounted socket strip SMD 1x21 2.54mm single row style2 pin1 right +0 +21 +21 +Connector_PinSocket_2.54mm +PinSocket_1x22_P2.54mm_Horizontal +Through hole angled socket strip, 1x22, 2.54mm pitch, 8.51mm socket length, single row (from Kicad 4.0.7), script generated +Through hole angled socket strip THT 1x22 2.54mm single row +0 +22 +22 +Connector_PinSocket_2.54mm +PinSocket_1x22_P2.54mm_Vertical +Through hole straight socket strip, 1x22, 2.54mm pitch, single row (from Kicad 4.0.7), script generated +Through hole socket strip THT 1x22 2.54mm single row +0 +22 +22 +Connector_PinSocket_2.54mm +PinSocket_1x22_P2.54mm_Vertical_SMD_Pin1Left +surface-mounted straight socket strip, 1x22, 2.54mm pitch, single row, style 1 (pin 1 left) (https://cdn.harwin.com/pdfs/M20-786.pdf), script generated +Surface mounted socket strip SMD 1x22 2.54mm single row style1 pin1 left +0 +22 +22 +Connector_PinSocket_2.54mm +PinSocket_1x22_P2.54mm_Vertical_SMD_Pin1Right +surface-mounted straight socket strip, 1x22, 2.54mm pitch, single row, style 2 (pin 1 right) (https://cdn.harwin.com/pdfs/M20-786.pdf), script generated +Surface mounted socket strip SMD 1x22 2.54mm single row style2 pin1 right +0 +22 +22 +Connector_PinSocket_2.54mm +PinSocket_1x23_P2.54mm_Horizontal +Through hole angled socket strip, 1x23, 2.54mm pitch, 8.51mm socket length, single row (from Kicad 4.0.7), script generated +Through hole angled socket strip THT 1x23 2.54mm single row +0 +23 +23 +Connector_PinSocket_2.54mm +PinSocket_1x23_P2.54mm_Vertical +Through hole straight socket strip, 1x23, 2.54mm pitch, single row (from Kicad 4.0.7), script generated +Through hole socket strip THT 1x23 2.54mm single row +0 +23 +23 +Connector_PinSocket_2.54mm +PinSocket_1x23_P2.54mm_Vertical_SMD_Pin1Left +surface-mounted straight socket strip, 1x23, 2.54mm pitch, single row, style 1 (pin 1 left) (https://cdn.harwin.com/pdfs/M20-786.pdf), script generated +Surface mounted socket strip SMD 1x23 2.54mm single row style1 pin1 left +0 +23 +23 +Connector_PinSocket_2.54mm +PinSocket_1x23_P2.54mm_Vertical_SMD_Pin1Right +surface-mounted straight socket strip, 1x23, 2.54mm pitch, single row, style 2 (pin 1 right) (https://cdn.harwin.com/pdfs/M20-786.pdf), script generated +Surface mounted socket strip SMD 1x23 2.54mm single row style2 pin1 right +0 +23 +23 +Connector_PinSocket_2.54mm +PinSocket_1x24_P2.54mm_Horizontal +Through hole angled socket strip, 1x24, 2.54mm pitch, 8.51mm socket length, single row (from Kicad 4.0.7), script generated +Through hole angled socket strip THT 1x24 2.54mm single row +0 +24 +24 +Connector_PinSocket_2.54mm +PinSocket_1x24_P2.54mm_Vertical +Through hole straight socket strip, 1x24, 2.54mm pitch, single row (from Kicad 4.0.7), script generated +Through hole socket strip THT 1x24 2.54mm single row +0 +24 +24 +Connector_PinSocket_2.54mm +PinSocket_1x24_P2.54mm_Vertical_SMD_Pin1Left +surface-mounted straight socket strip, 1x24, 2.54mm pitch, single row, style 1 (pin 1 left) (https://cdn.harwin.com/pdfs/M20-786.pdf), script generated +Surface mounted socket strip SMD 1x24 2.54mm single row style1 pin1 left +0 +24 +24 +Connector_PinSocket_2.54mm +PinSocket_1x24_P2.54mm_Vertical_SMD_Pin1Right +surface-mounted straight socket strip, 1x24, 2.54mm pitch, single row, style 2 (pin 1 right) (https://cdn.harwin.com/pdfs/M20-786.pdf), script generated +Surface mounted socket strip SMD 1x24 2.54mm single row style2 pin1 right +0 +24 +24 +Connector_PinSocket_2.54mm +PinSocket_1x25_P2.54mm_Horizontal +Through hole angled socket strip, 1x25, 2.54mm pitch, 8.51mm socket length, single row (from Kicad 4.0.7), script generated +Through hole angled socket strip THT 1x25 2.54mm single row +0 +25 +25 +Connector_PinSocket_2.54mm +PinSocket_1x25_P2.54mm_Vertical +Through hole straight socket strip, 1x25, 2.54mm pitch, single row (from Kicad 4.0.7), script generated +Through hole socket strip THT 1x25 2.54mm single row +0 +25 +25 +Connector_PinSocket_2.54mm +PinSocket_1x25_P2.54mm_Vertical_SMD_Pin1Left +surface-mounted straight socket strip, 1x25, 2.54mm pitch, single row, style 1 (pin 1 left) (https://cdn.harwin.com/pdfs/M20-786.pdf), script generated +Surface mounted socket strip SMD 1x25 2.54mm single row style1 pin1 left +0 +25 +25 +Connector_PinSocket_2.54mm +PinSocket_1x25_P2.54mm_Vertical_SMD_Pin1Right +surface-mounted straight socket strip, 1x25, 2.54mm pitch, single row, style 2 (pin 1 right) (https://cdn.harwin.com/pdfs/M20-786.pdf), script generated +Surface mounted socket strip SMD 1x25 2.54mm single row style2 pin1 right +0 +25 +25 +Connector_PinSocket_2.54mm +PinSocket_1x26_P2.54mm_Horizontal +Through hole angled socket strip, 1x26, 2.54mm pitch, 8.51mm socket length, single row (from Kicad 4.0.7), script generated +Through hole angled socket strip THT 1x26 2.54mm single row +0 +26 +26 +Connector_PinSocket_2.54mm +PinSocket_1x26_P2.54mm_Vertical +Through hole straight socket strip, 1x26, 2.54mm pitch, single row (from Kicad 4.0.7), script generated +Through hole socket strip THT 1x26 2.54mm single row +0 +26 +26 +Connector_PinSocket_2.54mm +PinSocket_1x26_P2.54mm_Vertical_SMD_Pin1Left +surface-mounted straight socket strip, 1x26, 2.54mm pitch, single row, style 1 (pin 1 left) (https://cdn.harwin.com/pdfs/M20-786.pdf), script generated +Surface mounted socket strip SMD 1x26 2.54mm single row style1 pin1 left +0 +26 +26 +Connector_PinSocket_2.54mm +PinSocket_1x26_P2.54mm_Vertical_SMD_Pin1Right +surface-mounted straight socket strip, 1x26, 2.54mm pitch, single row, style 2 (pin 1 right) (https://cdn.harwin.com/pdfs/M20-786.pdf), script generated +Surface mounted socket strip SMD 1x26 2.54mm single row style2 pin1 right +0 +26 +26 +Connector_PinSocket_2.54mm +PinSocket_1x27_P2.54mm_Horizontal +Through hole angled socket strip, 1x27, 2.54mm pitch, 8.51mm socket length, single row (from Kicad 4.0.7), script generated +Through hole angled socket strip THT 1x27 2.54mm single row +0 +27 +27 +Connector_PinSocket_2.54mm +PinSocket_1x27_P2.54mm_Vertical +Through hole straight socket strip, 1x27, 2.54mm pitch, single row (from Kicad 4.0.7), script generated +Through hole socket strip THT 1x27 2.54mm single row +0 +27 +27 +Connector_PinSocket_2.54mm +PinSocket_1x27_P2.54mm_Vertical_SMD_Pin1Left +surface-mounted straight socket strip, 1x27, 2.54mm pitch, single row, style 1 (pin 1 left) (https://cdn.harwin.com/pdfs/M20-786.pdf), script generated +Surface mounted socket strip SMD 1x27 2.54mm single row style1 pin1 left +0 +27 +27 +Connector_PinSocket_2.54mm +PinSocket_1x27_P2.54mm_Vertical_SMD_Pin1Right +surface-mounted straight socket strip, 1x27, 2.54mm pitch, single row, style 2 (pin 1 right) (https://cdn.harwin.com/pdfs/M20-786.pdf), script generated +Surface mounted socket strip SMD 1x27 2.54mm single row style2 pin1 right +0 +27 +27 +Connector_PinSocket_2.54mm +PinSocket_1x28_P2.54mm_Horizontal +Through hole angled socket strip, 1x28, 2.54mm pitch, 8.51mm socket length, single row (from Kicad 4.0.7), script generated +Through hole angled socket strip THT 1x28 2.54mm single row +0 +28 +28 +Connector_PinSocket_2.54mm +PinSocket_1x28_P2.54mm_Vertical +Through hole straight socket strip, 1x28, 2.54mm pitch, single row (from Kicad 4.0.7), script generated +Through hole socket strip THT 1x28 2.54mm single row +0 +28 +28 +Connector_PinSocket_2.54mm +PinSocket_1x28_P2.54mm_Vertical_SMD_Pin1Left +surface-mounted straight socket strip, 1x28, 2.54mm pitch, single row, style 1 (pin 1 left) (https://cdn.harwin.com/pdfs/M20-786.pdf), script generated +Surface mounted socket strip SMD 1x28 2.54mm single row style1 pin1 left +0 +28 +28 +Connector_PinSocket_2.54mm +PinSocket_1x28_P2.54mm_Vertical_SMD_Pin1Right +surface-mounted straight socket strip, 1x28, 2.54mm pitch, single row, style 2 (pin 1 right) (https://cdn.harwin.com/pdfs/M20-786.pdf), script generated +Surface mounted socket strip SMD 1x28 2.54mm single row style2 pin1 right +0 +28 +28 +Connector_PinSocket_2.54mm +PinSocket_1x29_P2.54mm_Horizontal +Through hole angled socket strip, 1x29, 2.54mm pitch, 8.51mm socket length, single row (from Kicad 4.0.7), script generated +Through hole angled socket strip THT 1x29 2.54mm single row +0 +29 +29 +Connector_PinSocket_2.54mm +PinSocket_1x29_P2.54mm_Vertical +Through hole straight socket strip, 1x29, 2.54mm pitch, single row (from Kicad 4.0.7), script generated +Through hole socket strip THT 1x29 2.54mm single row +0 +29 +29 +Connector_PinSocket_2.54mm +PinSocket_1x29_P2.54mm_Vertical_SMD_Pin1Left +surface-mounted straight socket strip, 1x29, 2.54mm pitch, single row, style 1 (pin 1 left) (https://cdn.harwin.com/pdfs/M20-786.pdf), script generated +Surface mounted socket strip SMD 1x29 2.54mm single row style1 pin1 left +0 +29 +29 +Connector_PinSocket_2.54mm +PinSocket_1x29_P2.54mm_Vertical_SMD_Pin1Right +surface-mounted straight socket strip, 1x29, 2.54mm pitch, single row, style 2 (pin 1 right) (https://cdn.harwin.com/pdfs/M20-786.pdf), script generated +Surface mounted socket strip SMD 1x29 2.54mm single row style2 pin1 right +0 +29 +29 +Connector_PinSocket_2.54mm +PinSocket_1x30_P2.54mm_Horizontal +Through hole angled socket strip, 1x30, 2.54mm pitch, 8.51mm socket length, single row (from Kicad 4.0.7), script generated +Through hole angled socket strip THT 1x30 2.54mm single row +0 +30 +30 +Connector_PinSocket_2.54mm +PinSocket_1x30_P2.54mm_Vertical +Through hole straight socket strip, 1x30, 2.54mm pitch, single row (from Kicad 4.0.7), script generated +Through hole socket strip THT 1x30 2.54mm single row +0 +30 +30 +Connector_PinSocket_2.54mm +PinSocket_1x30_P2.54mm_Vertical_SMD_Pin1Left +surface-mounted straight socket strip, 1x30, 2.54mm pitch, single row, style 1 (pin 1 left) (https://cdn.harwin.com/pdfs/M20-786.pdf), script generated +Surface mounted socket strip SMD 1x30 2.54mm single row style1 pin1 left +0 +30 +30 +Connector_PinSocket_2.54mm +PinSocket_1x30_P2.54mm_Vertical_SMD_Pin1Right +surface-mounted straight socket strip, 1x30, 2.54mm pitch, single row, style 2 (pin 1 right) (https://cdn.harwin.com/pdfs/M20-786.pdf), script generated +Surface mounted socket strip SMD 1x30 2.54mm single row style2 pin1 right +0 +30 +30 +Connector_PinSocket_2.54mm +PinSocket_1x31_P2.54mm_Horizontal +Through hole angled socket strip, 1x31, 2.54mm pitch, 8.51mm socket length, single row (from Kicad 4.0.7), script generated +Through hole angled socket strip THT 1x31 2.54mm single row +0 +31 +31 +Connector_PinSocket_2.54mm +PinSocket_1x31_P2.54mm_Vertical +Through hole straight socket strip, 1x31, 2.54mm pitch, single row (from Kicad 4.0.7), script generated +Through hole socket strip THT 1x31 2.54mm single row +0 +31 +31 +Connector_PinSocket_2.54mm +PinSocket_1x31_P2.54mm_Vertical_SMD_Pin1Left +surface-mounted straight socket strip, 1x31, 2.54mm pitch, single row, style 1 (pin 1 left) (https://cdn.harwin.com/pdfs/M20-786.pdf), script generated +Surface mounted socket strip SMD 1x31 2.54mm single row style1 pin1 left +0 +31 +31 +Connector_PinSocket_2.54mm +PinSocket_1x31_P2.54mm_Vertical_SMD_Pin1Right +surface-mounted straight socket strip, 1x31, 2.54mm pitch, single row, style 2 (pin 1 right) (https://cdn.harwin.com/pdfs/M20-786.pdf), script generated +Surface mounted socket strip SMD 1x31 2.54mm single row style2 pin1 right +0 +31 +31 +Connector_PinSocket_2.54mm +PinSocket_1x32_P2.54mm_Horizontal +Through hole angled socket strip, 1x32, 2.54mm pitch, 8.51mm socket length, single row (from Kicad 4.0.7), script generated +Through hole angled socket strip THT 1x32 2.54mm single row +0 +32 +32 +Connector_PinSocket_2.54mm +PinSocket_1x32_P2.54mm_Vertical +Through hole straight socket strip, 1x32, 2.54mm pitch, single row (from Kicad 4.0.7), script generated +Through hole socket strip THT 1x32 2.54mm single row +0 +32 +32 +Connector_PinSocket_2.54mm +PinSocket_1x32_P2.54mm_Vertical_SMD_Pin1Left +surface-mounted straight socket strip, 1x32, 2.54mm pitch, single row, style 1 (pin 1 left) (https://cdn.harwin.com/pdfs/M20-786.pdf), script generated +Surface mounted socket strip SMD 1x32 2.54mm single row style1 pin1 left +0 +32 +32 +Connector_PinSocket_2.54mm +PinSocket_1x32_P2.54mm_Vertical_SMD_Pin1Right +surface-mounted straight socket strip, 1x32, 2.54mm pitch, single row, style 2 (pin 1 right) (https://cdn.harwin.com/pdfs/M20-786.pdf), script generated +Surface mounted socket strip SMD 1x32 2.54mm single row style2 pin1 right +0 +32 +32 +Connector_PinSocket_2.54mm +PinSocket_1x33_P2.54mm_Horizontal +Through hole angled socket strip, 1x33, 2.54mm pitch, 8.51mm socket length, single row (from Kicad 4.0.7), script generated +Through hole angled socket strip THT 1x33 2.54mm single row +0 +33 +33 +Connector_PinSocket_2.54mm +PinSocket_1x33_P2.54mm_Vertical +Through hole straight socket strip, 1x33, 2.54mm pitch, single row (from Kicad 4.0.7), script generated +Through hole socket strip THT 1x33 2.54mm single row +0 +33 +33 +Connector_PinSocket_2.54mm +PinSocket_1x33_P2.54mm_Vertical_SMD_Pin1Left +surface-mounted straight socket strip, 1x33, 2.54mm pitch, single row, style 1 (pin 1 left) (https://cdn.harwin.com/pdfs/M20-786.pdf), script generated +Surface mounted socket strip SMD 1x33 2.54mm single row style1 pin1 left +0 +33 +33 +Connector_PinSocket_2.54mm +PinSocket_1x33_P2.54mm_Vertical_SMD_Pin1Right +surface-mounted straight socket strip, 1x33, 2.54mm pitch, single row, style 2 (pin 1 right) (https://cdn.harwin.com/pdfs/M20-786.pdf), script generated +Surface mounted socket strip SMD 1x33 2.54mm single row style2 pin1 right +0 +33 +33 +Connector_PinSocket_2.54mm +PinSocket_1x34_P2.54mm_Horizontal +Through hole angled socket strip, 1x34, 2.54mm pitch, 8.51mm socket length, single row (from Kicad 4.0.7), script generated +Through hole angled socket strip THT 1x34 2.54mm single row +0 +34 +34 +Connector_PinSocket_2.54mm +PinSocket_1x34_P2.54mm_Vertical +Through hole straight socket strip, 1x34, 2.54mm pitch, single row (from Kicad 4.0.7), script generated +Through hole socket strip THT 1x34 2.54mm single row +0 +34 +34 +Connector_PinSocket_2.54mm +PinSocket_1x34_P2.54mm_Vertical_SMD_Pin1Left +surface-mounted straight socket strip, 1x34, 2.54mm pitch, single row, style 1 (pin 1 left) (https://cdn.harwin.com/pdfs/M20-786.pdf), script generated +Surface mounted socket strip SMD 1x34 2.54mm single row style1 pin1 left +0 +34 +34 +Connector_PinSocket_2.54mm +PinSocket_1x34_P2.54mm_Vertical_SMD_Pin1Right +surface-mounted straight socket strip, 1x34, 2.54mm pitch, single row, style 2 (pin 1 right) (https://cdn.harwin.com/pdfs/M20-786.pdf), script generated +Surface mounted socket strip SMD 1x34 2.54mm single row style2 pin1 right +0 +34 +34 +Connector_PinSocket_2.54mm +PinSocket_1x35_P2.54mm_Horizontal +Through hole angled socket strip, 1x35, 2.54mm pitch, 8.51mm socket length, single row (from Kicad 4.0.7), script generated +Through hole angled socket strip THT 1x35 2.54mm single row +0 +35 +35 +Connector_PinSocket_2.54mm +PinSocket_1x35_P2.54mm_Vertical +Through hole straight socket strip, 1x35, 2.54mm pitch, single row (from Kicad 4.0.7), script generated +Through hole socket strip THT 1x35 2.54mm single row +0 +35 +35 +Connector_PinSocket_2.54mm +PinSocket_1x35_P2.54mm_Vertical_SMD_Pin1Left +surface-mounted straight socket strip, 1x35, 2.54mm pitch, single row, style 1 (pin 1 left) (https://cdn.harwin.com/pdfs/M20-786.pdf), script generated +Surface mounted socket strip SMD 1x35 2.54mm single row style1 pin1 left +0 +35 +35 +Connector_PinSocket_2.54mm +PinSocket_1x35_P2.54mm_Vertical_SMD_Pin1Right +surface-mounted straight socket strip, 1x35, 2.54mm pitch, single row, style 2 (pin 1 right) (https://cdn.harwin.com/pdfs/M20-786.pdf), script generated +Surface mounted socket strip SMD 1x35 2.54mm single row style2 pin1 right +0 +35 +35 +Connector_PinSocket_2.54mm +PinSocket_1x36_P2.54mm_Horizontal +Through hole angled socket strip, 1x36, 2.54mm pitch, 8.51mm socket length, single row (from Kicad 4.0.7), script generated +Through hole angled socket strip THT 1x36 2.54mm single row +0 +36 +36 +Connector_PinSocket_2.54mm +PinSocket_1x36_P2.54mm_Vertical +Through hole straight socket strip, 1x36, 2.54mm pitch, single row (from Kicad 4.0.7), script generated +Through hole socket strip THT 1x36 2.54mm single row +0 +36 +36 +Connector_PinSocket_2.54mm +PinSocket_1x36_P2.54mm_Vertical_SMD_Pin1Left +surface-mounted straight socket strip, 1x36, 2.54mm pitch, single row, style 1 (pin 1 left) (https://cdn.harwin.com/pdfs/M20-786.pdf), script generated +Surface mounted socket strip SMD 1x36 2.54mm single row style1 pin1 left +0 +36 +36 +Connector_PinSocket_2.54mm +PinSocket_1x36_P2.54mm_Vertical_SMD_Pin1Right +surface-mounted straight socket strip, 1x36, 2.54mm pitch, single row, style 2 (pin 1 right) (https://cdn.harwin.com/pdfs/M20-786.pdf), script generated +Surface mounted socket strip SMD 1x36 2.54mm single row style2 pin1 right +0 +36 +36 +Connector_PinSocket_2.54mm +PinSocket_1x37_P2.54mm_Horizontal +Through hole angled socket strip, 1x37, 2.54mm pitch, 8.51mm socket length, single row (from Kicad 4.0.7), script generated +Through hole angled socket strip THT 1x37 2.54mm single row +0 +37 +37 +Connector_PinSocket_2.54mm +PinSocket_1x37_P2.54mm_Vertical +Through hole straight socket strip, 1x37, 2.54mm pitch, single row (from Kicad 4.0.7), script generated +Through hole socket strip THT 1x37 2.54mm single row +0 +37 +37 +Connector_PinSocket_2.54mm +PinSocket_1x37_P2.54mm_Vertical_SMD_Pin1Left +surface-mounted straight socket strip, 1x37, 2.54mm pitch, single row, style 1 (pin 1 left) (https://cdn.harwin.com/pdfs/M20-786.pdf), script generated +Surface mounted socket strip SMD 1x37 2.54mm single row style1 pin1 left +0 +37 +37 +Connector_PinSocket_2.54mm +PinSocket_1x37_P2.54mm_Vertical_SMD_Pin1Right +surface-mounted straight socket strip, 1x37, 2.54mm pitch, single row, style 2 (pin 1 right) (https://cdn.harwin.com/pdfs/M20-786.pdf), script generated +Surface mounted socket strip SMD 1x37 2.54mm single row style2 pin1 right +0 +37 +37 +Connector_PinSocket_2.54mm +PinSocket_1x38_P2.54mm_Horizontal +Through hole angled socket strip, 1x38, 2.54mm pitch, 8.51mm socket length, single row (from Kicad 4.0.7), script generated +Through hole angled socket strip THT 1x38 2.54mm single row +0 +38 +38 +Connector_PinSocket_2.54mm +PinSocket_1x38_P2.54mm_Vertical +Through hole straight socket strip, 1x38, 2.54mm pitch, single row (from Kicad 4.0.7), script generated +Through hole socket strip THT 1x38 2.54mm single row +0 +38 +38 +Connector_PinSocket_2.54mm +PinSocket_1x38_P2.54mm_Vertical_SMD_Pin1Left +surface-mounted straight socket strip, 1x38, 2.54mm pitch, single row, style 1 (pin 1 left) (https://cdn.harwin.com/pdfs/M20-786.pdf), script generated +Surface mounted socket strip SMD 1x38 2.54mm single row style1 pin1 left +0 +38 +38 +Connector_PinSocket_2.54mm +PinSocket_1x38_P2.54mm_Vertical_SMD_Pin1Right +surface-mounted straight socket strip, 1x38, 2.54mm pitch, single row, style 2 (pin 1 right) (https://cdn.harwin.com/pdfs/M20-786.pdf), script generated +Surface mounted socket strip SMD 1x38 2.54mm single row style2 pin1 right +0 +38 +38 +Connector_PinSocket_2.54mm +PinSocket_1x39_P2.54mm_Horizontal +Through hole angled socket strip, 1x39, 2.54mm pitch, 8.51mm socket length, single row (from Kicad 4.0.7), script generated +Through hole angled socket strip THT 1x39 2.54mm single row +0 +39 +39 +Connector_PinSocket_2.54mm +PinSocket_1x39_P2.54mm_Vertical +Through hole straight socket strip, 1x39, 2.54mm pitch, single row (from Kicad 4.0.7), script generated +Through hole socket strip THT 1x39 2.54mm single row +0 +39 +39 +Connector_PinSocket_2.54mm +PinSocket_1x39_P2.54mm_Vertical_SMD_Pin1Left +surface-mounted straight socket strip, 1x39, 2.54mm pitch, single row, style 1 (pin 1 left) (https://cdn.harwin.com/pdfs/M20-786.pdf), script generated +Surface mounted socket strip SMD 1x39 2.54mm single row style1 pin1 left +0 +39 +39 +Connector_PinSocket_2.54mm +PinSocket_1x39_P2.54mm_Vertical_SMD_Pin1Right +surface-mounted straight socket strip, 1x39, 2.54mm pitch, single row, style 2 (pin 1 right) (https://cdn.harwin.com/pdfs/M20-786.pdf), script generated +Surface mounted socket strip SMD 1x39 2.54mm single row style2 pin1 right +0 +39 +39 +Connector_PinSocket_2.54mm +PinSocket_1x40_P2.54mm_Horizontal +Through hole angled socket strip, 1x40, 2.54mm pitch, 8.51mm socket length, single row (from Kicad 4.0.7), script generated +Through hole angled socket strip THT 1x40 2.54mm single row +0 +40 +40 +Connector_PinSocket_2.54mm +PinSocket_1x40_P2.54mm_Vertical +Through hole straight socket strip, 1x40, 2.54mm pitch, single row (from Kicad 4.0.7), script generated +Through hole socket strip THT 1x40 2.54mm single row +0 +40 +40 +Connector_PinSocket_2.54mm +PinSocket_1x40_P2.54mm_Vertical_SMD_Pin1Left +surface-mounted straight socket strip, 1x40, 2.54mm pitch, single row, style 1 (pin 1 left) (https://cdn.harwin.com/pdfs/M20-786.pdf), script generated +Surface mounted socket strip SMD 1x40 2.54mm single row style1 pin1 left +0 +40 +40 +Connector_PinSocket_2.54mm +PinSocket_1x40_P2.54mm_Vertical_SMD_Pin1Right +surface-mounted straight socket strip, 1x40, 2.54mm pitch, single row, style 2 (pin 1 right) (https://cdn.harwin.com/pdfs/M20-786.pdf), script generated +Surface mounted socket strip SMD 1x40 2.54mm single row style2 pin1 right +0 +40 +40 +Connector_PinSocket_2.54mm +PinSocket_2x01_P2.54mm_Horizontal +Through hole angled socket strip, 2x01, 2.54mm pitch, 8.51mm socket length, double cols (from Kicad 4.0.7), script generated +Through hole angled socket strip THT 2x01 2.54mm double row +0 +2 +2 +Connector_PinSocket_2.54mm +PinSocket_2x01_P2.54mm_Vertical +Through hole straight socket strip, 2x01, 2.54mm pitch, double cols (from Kicad 4.0.7), script generated +Through hole socket strip THT 2x01 2.54mm double row +0 +2 +2 +Connector_PinSocket_2.54mm +PinSocket_2x01_P2.54mm_Vertical_SMD +surface-mounted straight socket strip, 2x01, 2.54mm pitch, double cols (from Kicad 4.0.7), script generated +Surface mounted socket strip SMD 2x01 2.54mm double row +0 +2 +2 +Connector_PinSocket_2.54mm +PinSocket_2x02_P2.54mm_Horizontal +Through hole angled socket strip, 2x02, 2.54mm pitch, 8.51mm socket length, double cols (from Kicad 4.0.7), script generated +Through hole angled socket strip THT 2x02 2.54mm double row +0 +4 +4 +Connector_PinSocket_2.54mm +PinSocket_2x02_P2.54mm_Vertical +Through hole straight socket strip, 2x02, 2.54mm pitch, double cols (from Kicad 4.0.7), script generated +Through hole socket strip THT 2x02 2.54mm double row +0 +4 +4 +Connector_PinSocket_2.54mm +PinSocket_2x02_P2.54mm_Vertical_SMD +surface-mounted straight socket strip, 2x02, 2.54mm pitch, double cols (from Kicad 4.0.7), script generated +Surface mounted socket strip SMD 2x02 2.54mm double row +0 +4 +4 +Connector_PinSocket_2.54mm +PinSocket_2x03_P2.54mm_Horizontal +Through hole angled socket strip, 2x03, 2.54mm pitch, 8.51mm socket length, double cols (from Kicad 4.0.7), script generated +Through hole angled socket strip THT 2x03 2.54mm double row +0 +6 +6 +Connector_PinSocket_2.54mm +PinSocket_2x03_P2.54mm_Vertical +Through hole straight socket strip, 2x03, 2.54mm pitch, double cols (from Kicad 4.0.7), script generated +Through hole socket strip THT 2x03 2.54mm double row +0 +6 +6 +Connector_PinSocket_2.54mm +PinSocket_2x03_P2.54mm_Vertical_SMD +surface-mounted straight socket strip, 2x03, 2.54mm pitch, double cols (from Kicad 4.0.7), script generated +Surface mounted socket strip SMD 2x03 2.54mm double row +0 +6 +6 +Connector_PinSocket_2.54mm +PinSocket_2x04_P2.54mm_Horizontal +Through hole angled socket strip, 2x04, 2.54mm pitch, 8.51mm socket length, double cols (from Kicad 4.0.7), script generated +Through hole angled socket strip THT 2x04 2.54mm double row +0 +8 +8 +Connector_PinSocket_2.54mm +PinSocket_2x04_P2.54mm_Vertical +Through hole straight socket strip, 2x04, 2.54mm pitch, double cols (from Kicad 4.0.7), script generated +Through hole socket strip THT 2x04 2.54mm double row +0 +8 +8 +Connector_PinSocket_2.54mm +PinSocket_2x04_P2.54mm_Vertical_SMD +surface-mounted straight socket strip, 2x04, 2.54mm pitch, double cols (from Kicad 4.0.7), script generated +Surface mounted socket strip SMD 2x04 2.54mm double row +0 +8 +8 +Connector_PinSocket_2.54mm +PinSocket_2x05_P2.54mm_Horizontal +Through hole angled socket strip, 2x05, 2.54mm pitch, 8.51mm socket length, double cols (from Kicad 4.0.7), script generated +Through hole angled socket strip THT 2x05 2.54mm double row +0 +10 +10 +Connector_PinSocket_2.54mm +PinSocket_2x05_P2.54mm_Vertical +Through hole straight socket strip, 2x05, 2.54mm pitch, double cols (from Kicad 4.0.7), script generated +Through hole socket strip THT 2x05 2.54mm double row +0 +10 +10 +Connector_PinSocket_2.54mm +PinSocket_2x05_P2.54mm_Vertical_SMD +surface-mounted straight socket strip, 2x05, 2.54mm pitch, double cols (from Kicad 4.0.7), script generated +Surface mounted socket strip SMD 2x05 2.54mm double row +0 +10 +10 +Connector_PinSocket_2.54mm +PinSocket_2x06_P2.54mm_Horizontal +Through hole angled socket strip, 2x06, 2.54mm pitch, 8.51mm socket length, double cols (from Kicad 4.0.7), script generated +Through hole angled socket strip THT 2x06 2.54mm double row +0 +12 +12 +Connector_PinSocket_2.54mm +PinSocket_2x06_P2.54mm_Vertical +Through hole straight socket strip, 2x06, 2.54mm pitch, double cols (from Kicad 4.0.7), script generated +Through hole socket strip THT 2x06 2.54mm double row +0 +12 +12 +Connector_PinSocket_2.54mm +PinSocket_2x06_P2.54mm_Vertical_SMD +surface-mounted straight socket strip, 2x06, 2.54mm pitch, double cols (from Kicad 4.0.7), script generated +Surface mounted socket strip SMD 2x06 2.54mm double row +0 +12 +12 +Connector_PinSocket_2.54mm +PinSocket_2x07_P2.54mm_Horizontal +Through hole angled socket strip, 2x07, 2.54mm pitch, 8.51mm socket length, double cols (from Kicad 4.0.7), script generated +Through hole angled socket strip THT 2x07 2.54mm double row +0 +14 +14 +Connector_PinSocket_2.54mm +PinSocket_2x07_P2.54mm_Vertical +Through hole straight socket strip, 2x07, 2.54mm pitch, double cols (from Kicad 4.0.7), script generated +Through hole socket strip THT 2x07 2.54mm double row +0 +14 +14 +Connector_PinSocket_2.54mm +PinSocket_2x07_P2.54mm_Vertical_SMD +surface-mounted straight socket strip, 2x07, 2.54mm pitch, double cols (from Kicad 4.0.7), script generated +Surface mounted socket strip SMD 2x07 2.54mm double row +0 +14 +14 +Connector_PinSocket_2.54mm +PinSocket_2x08_P2.54mm_Horizontal +Through hole angled socket strip, 2x08, 2.54mm pitch, 8.51mm socket length, double cols (from Kicad 4.0.7), script generated +Through hole angled socket strip THT 2x08 2.54mm double row +0 +16 +16 +Connector_PinSocket_2.54mm +PinSocket_2x08_P2.54mm_Vertical +Through hole straight socket strip, 2x08, 2.54mm pitch, double cols (from Kicad 4.0.7), script generated +Through hole socket strip THT 2x08 2.54mm double row +0 +16 +16 +Connector_PinSocket_2.54mm +PinSocket_2x08_P2.54mm_Vertical_SMD +surface-mounted straight socket strip, 2x08, 2.54mm pitch, double cols (from Kicad 4.0.7), script generated +Surface mounted socket strip SMD 2x08 2.54mm double row +0 +16 +16 +Connector_PinSocket_2.54mm +PinSocket_2x09_P2.54mm_Horizontal +Through hole angled socket strip, 2x09, 2.54mm pitch, 8.51mm socket length, double cols (from Kicad 4.0.7), script generated +Through hole angled socket strip THT 2x09 2.54mm double row +0 +18 +18 +Connector_PinSocket_2.54mm +PinSocket_2x09_P2.54mm_Vertical +Through hole straight socket strip, 2x09, 2.54mm pitch, double cols (from Kicad 4.0.7), script generated +Through hole socket strip THT 2x09 2.54mm double row +0 +18 +18 +Connector_PinSocket_2.54mm +PinSocket_2x09_P2.54mm_Vertical_SMD +surface-mounted straight socket strip, 2x09, 2.54mm pitch, double cols (from Kicad 4.0.7), script generated +Surface mounted socket strip SMD 2x09 2.54mm double row +0 +18 +18 +Connector_PinSocket_2.54mm +PinSocket_2x10_P2.54mm_Horizontal +Through hole angled socket strip, 2x10, 2.54mm pitch, 8.51mm socket length, double cols (from Kicad 4.0.7), script generated +Through hole angled socket strip THT 2x10 2.54mm double row +0 +20 +20 +Connector_PinSocket_2.54mm +PinSocket_2x10_P2.54mm_Vertical +Through hole straight socket strip, 2x10, 2.54mm pitch, double cols (from Kicad 4.0.7), script generated +Through hole socket strip THT 2x10 2.54mm double row +0 +20 +20 +Connector_PinSocket_2.54mm +PinSocket_2x10_P2.54mm_Vertical_SMD +surface-mounted straight socket strip, 2x10, 2.54mm pitch, double cols (from Kicad 4.0.7), script generated +Surface mounted socket strip SMD 2x10 2.54mm double row +0 +20 +20 +Connector_PinSocket_2.54mm +PinSocket_2x11_P2.54mm_Horizontal +Through hole angled socket strip, 2x11, 2.54mm pitch, 8.51mm socket length, double cols (from Kicad 4.0.7), script generated +Through hole angled socket strip THT 2x11 2.54mm double row +0 +22 +22 +Connector_PinSocket_2.54mm +PinSocket_2x11_P2.54mm_Vertical +Through hole straight socket strip, 2x11, 2.54mm pitch, double cols (from Kicad 4.0.7), script generated +Through hole socket strip THT 2x11 2.54mm double row +0 +22 +22 +Connector_PinSocket_2.54mm +PinSocket_2x11_P2.54mm_Vertical_SMD +surface-mounted straight socket strip, 2x11, 2.54mm pitch, double cols (from Kicad 4.0.7), script generated +Surface mounted socket strip SMD 2x11 2.54mm double row +0 +22 +22 +Connector_PinSocket_2.54mm +PinSocket_2x12_P2.54mm_Horizontal +Through hole angled socket strip, 2x12, 2.54mm pitch, 8.51mm socket length, double cols (from Kicad 4.0.7), script generated +Through hole angled socket strip THT 2x12 2.54mm double row +0 +24 +24 +Connector_PinSocket_2.54mm +PinSocket_2x12_P2.54mm_Vertical +Through hole straight socket strip, 2x12, 2.54mm pitch, double cols (from Kicad 4.0.7), script generated +Through hole socket strip THT 2x12 2.54mm double row +0 +24 +24 +Connector_PinSocket_2.54mm +PinSocket_2x12_P2.54mm_Vertical_SMD +surface-mounted straight socket strip, 2x12, 2.54mm pitch, double cols (from Kicad 4.0.7), script generated +Surface mounted socket strip SMD 2x12 2.54mm double row +0 +24 +24 +Connector_PinSocket_2.54mm +PinSocket_2x13_P2.54mm_Horizontal +Through hole angled socket strip, 2x13, 2.54mm pitch, 8.51mm socket length, double cols (from Kicad 4.0.7), script generated +Through hole angled socket strip THT 2x13 2.54mm double row +0 +26 +26 +Connector_PinSocket_2.54mm +PinSocket_2x13_P2.54mm_Vertical +Through hole straight socket strip, 2x13, 2.54mm pitch, double cols (from Kicad 4.0.7), script generated +Through hole socket strip THT 2x13 2.54mm double row +0 +26 +26 +Connector_PinSocket_2.54mm +PinSocket_2x13_P2.54mm_Vertical_SMD +surface-mounted straight socket strip, 2x13, 2.54mm pitch, double cols (from Kicad 4.0.7), script generated +Surface mounted socket strip SMD 2x13 2.54mm double row +0 +26 +26 +Connector_PinSocket_2.54mm +PinSocket_2x14_P2.54mm_Horizontal +Through hole angled socket strip, 2x14, 2.54mm pitch, 8.51mm socket length, double cols (from Kicad 4.0.7), script generated +Through hole angled socket strip THT 2x14 2.54mm double row +0 +28 +28 +Connector_PinSocket_2.54mm +PinSocket_2x14_P2.54mm_Vertical +Through hole straight socket strip, 2x14, 2.54mm pitch, double cols (from Kicad 4.0.7), script generated +Through hole socket strip THT 2x14 2.54mm double row +0 +28 +28 +Connector_PinSocket_2.54mm +PinSocket_2x14_P2.54mm_Vertical_SMD +surface-mounted straight socket strip, 2x14, 2.54mm pitch, double cols (from Kicad 4.0.7), script generated +Surface mounted socket strip SMD 2x14 2.54mm double row +0 +28 +28 +Connector_PinSocket_2.54mm +PinSocket_2x15_P2.54mm_Horizontal +Through hole angled socket strip, 2x15, 2.54mm pitch, 8.51mm socket length, double cols (from Kicad 4.0.7), script generated +Through hole angled socket strip THT 2x15 2.54mm double row +0 +30 +30 +Connector_PinSocket_2.54mm +PinSocket_2x15_P2.54mm_Vertical +Through hole straight socket strip, 2x15, 2.54mm pitch, double cols (from Kicad 4.0.7), script generated +Through hole socket strip THT 2x15 2.54mm double row +0 +30 +30 +Connector_PinSocket_2.54mm +PinSocket_2x15_P2.54mm_Vertical_SMD +surface-mounted straight socket strip, 2x15, 2.54mm pitch, double cols (from Kicad 4.0.7), script generated +Surface mounted socket strip SMD 2x15 2.54mm double row +0 +30 +30 +Connector_PinSocket_2.54mm +PinSocket_2x16_P2.54mm_Horizontal +Through hole angled socket strip, 2x16, 2.54mm pitch, 8.51mm socket length, double cols (from Kicad 4.0.7), script generated +Through hole angled socket strip THT 2x16 2.54mm double row +0 +32 +32 +Connector_PinSocket_2.54mm +PinSocket_2x16_P2.54mm_Vertical +Through hole straight socket strip, 2x16, 2.54mm pitch, double cols (from Kicad 4.0.7), script generated +Through hole socket strip THT 2x16 2.54mm double row +0 +32 +32 +Connector_PinSocket_2.54mm +PinSocket_2x16_P2.54mm_Vertical_SMD +surface-mounted straight socket strip, 2x16, 2.54mm pitch, double cols (from Kicad 4.0.7), script generated +Surface mounted socket strip SMD 2x16 2.54mm double row +0 +32 +32 +Connector_PinSocket_2.54mm +PinSocket_2x17_P2.54mm_Horizontal +Through hole angled socket strip, 2x17, 2.54mm pitch, 8.51mm socket length, double cols (from Kicad 4.0.7), script generated +Through hole angled socket strip THT 2x17 2.54mm double row +0 +34 +34 +Connector_PinSocket_2.54mm +PinSocket_2x17_P2.54mm_Vertical +Through hole straight socket strip, 2x17, 2.54mm pitch, double cols (from Kicad 4.0.7), script generated +Through hole socket strip THT 2x17 2.54mm double row +0 +34 +34 +Connector_PinSocket_2.54mm +PinSocket_2x17_P2.54mm_Vertical_SMD +surface-mounted straight socket strip, 2x17, 2.54mm pitch, double cols (from Kicad 4.0.7), script generated +Surface mounted socket strip SMD 2x17 2.54mm double row +0 +34 +34 +Connector_PinSocket_2.54mm +PinSocket_2x18_P2.54mm_Horizontal +Through hole angled socket strip, 2x18, 2.54mm pitch, 8.51mm socket length, double cols (from Kicad 4.0.7), script generated +Through hole angled socket strip THT 2x18 2.54mm double row +0 +36 +36 +Connector_PinSocket_2.54mm +PinSocket_2x18_P2.54mm_Vertical +Through hole straight socket strip, 2x18, 2.54mm pitch, double cols (from Kicad 4.0.7), script generated +Through hole socket strip THT 2x18 2.54mm double row +0 +36 +36 +Connector_PinSocket_2.54mm +PinSocket_2x18_P2.54mm_Vertical_SMD +surface-mounted straight socket strip, 2x18, 2.54mm pitch, double cols (from Kicad 4.0.7), script generated +Surface mounted socket strip SMD 2x18 2.54mm double row +0 +36 +36 +Connector_PinSocket_2.54mm +PinSocket_2x19_P2.54mm_Horizontal +Through hole angled socket strip, 2x19, 2.54mm pitch, 8.51mm socket length, double cols (from Kicad 4.0.7), script generated +Through hole angled socket strip THT 2x19 2.54mm double row +0 +38 +38 +Connector_PinSocket_2.54mm +PinSocket_2x19_P2.54mm_Vertical +Through hole straight socket strip, 2x19, 2.54mm pitch, double cols (from Kicad 4.0.7), script generated +Through hole socket strip THT 2x19 2.54mm double row +0 +38 +38 +Connector_PinSocket_2.54mm +PinSocket_2x19_P2.54mm_Vertical_SMD +surface-mounted straight socket strip, 2x19, 2.54mm pitch, double cols (from Kicad 4.0.7), script generated +Surface mounted socket strip SMD 2x19 2.54mm double row +0 +38 +38 +Connector_PinSocket_2.54mm +PinSocket_2x20_P2.54mm_Horizontal +Through hole angled socket strip, 2x20, 2.54mm pitch, 8.51mm socket length, double cols (from Kicad 4.0.7), script generated +Through hole angled socket strip THT 2x20 2.54mm double row +0 +40 +40 +Connector_PinSocket_2.54mm +PinSocket_2x20_P2.54mm_Vertical +Through hole straight socket strip, 2x20, 2.54mm pitch, double cols (from Kicad 4.0.7), script generated +Through hole socket strip THT 2x20 2.54mm double row +0 +40 +40 +Connector_PinSocket_2.54mm +PinSocket_2x20_P2.54mm_Vertical_SMD +surface-mounted straight socket strip, 2x20, 2.54mm pitch, double cols (from Kicad 4.0.7), script generated +Surface mounted socket strip SMD 2x20 2.54mm double row +0 +40 +40 +Connector_PinSocket_2.54mm +PinSocket_2x21_P2.54mm_Horizontal +Through hole angled socket strip, 2x21, 2.54mm pitch, 8.51mm socket length, double cols (from Kicad 4.0.7), script generated +Through hole angled socket strip THT 2x21 2.54mm double row +0 +42 +42 +Connector_PinSocket_2.54mm +PinSocket_2x21_P2.54mm_Vertical +Through hole straight socket strip, 2x21, 2.54mm pitch, double cols (from Kicad 4.0.7), script generated +Through hole socket strip THT 2x21 2.54mm double row +0 +42 +42 +Connector_PinSocket_2.54mm +PinSocket_2x21_P2.54mm_Vertical_SMD +surface-mounted straight socket strip, 2x21, 2.54mm pitch, double cols (from Kicad 4.0.7), script generated +Surface mounted socket strip SMD 2x21 2.54mm double row +0 +42 +42 +Connector_PinSocket_2.54mm +PinSocket_2x22_P2.54mm_Horizontal +Through hole angled socket strip, 2x22, 2.54mm pitch, 8.51mm socket length, double cols (from Kicad 4.0.7), script generated +Through hole angled socket strip THT 2x22 2.54mm double row +0 +44 +44 +Connector_PinSocket_2.54mm +PinSocket_2x22_P2.54mm_Vertical +Through hole straight socket strip, 2x22, 2.54mm pitch, double cols (from Kicad 4.0.7), script generated +Through hole socket strip THT 2x22 2.54mm double row +0 +44 +44 +Connector_PinSocket_2.54mm +PinSocket_2x22_P2.54mm_Vertical_SMD +surface-mounted straight socket strip, 2x22, 2.54mm pitch, double cols (from Kicad 4.0.7), script generated +Surface mounted socket strip SMD 2x22 2.54mm double row +0 +44 +44 +Connector_PinSocket_2.54mm +PinSocket_2x23_P2.54mm_Horizontal +Through hole angled socket strip, 2x23, 2.54mm pitch, 8.51mm socket length, double cols (from Kicad 4.0.7), script generated +Through hole angled socket strip THT 2x23 2.54mm double row +0 +46 +46 +Connector_PinSocket_2.54mm +PinSocket_2x23_P2.54mm_Vertical +Through hole straight socket strip, 2x23, 2.54mm pitch, double cols (from Kicad 4.0.7), script generated +Through hole socket strip THT 2x23 2.54mm double row +0 +46 +46 +Connector_PinSocket_2.54mm +PinSocket_2x23_P2.54mm_Vertical_SMD +surface-mounted straight socket strip, 2x23, 2.54mm pitch, double cols (from Kicad 4.0.7), script generated +Surface mounted socket strip SMD 2x23 2.54mm double row +0 +46 +46 +Connector_PinSocket_2.54mm +PinSocket_2x24_P2.54mm_Horizontal +Through hole angled socket strip, 2x24, 2.54mm pitch, 8.51mm socket length, double cols (from Kicad 4.0.7), script generated +Through hole angled socket strip THT 2x24 2.54mm double row +0 +48 +48 +Connector_PinSocket_2.54mm +PinSocket_2x24_P2.54mm_Vertical +Through hole straight socket strip, 2x24, 2.54mm pitch, double cols (from Kicad 4.0.7), script generated +Through hole socket strip THT 2x24 2.54mm double row +0 +48 +48 +Connector_PinSocket_2.54mm +PinSocket_2x24_P2.54mm_Vertical_SMD +surface-mounted straight socket strip, 2x24, 2.54mm pitch, double cols (from Kicad 4.0.7), script generated +Surface mounted socket strip SMD 2x24 2.54mm double row +0 +48 +48 +Connector_PinSocket_2.54mm +PinSocket_2x25_P2.54mm_Horizontal +Through hole angled socket strip, 2x25, 2.54mm pitch, 8.51mm socket length, double cols (from Kicad 4.0.7), script generated +Through hole angled socket strip THT 2x25 2.54mm double row +0 +50 +50 +Connector_PinSocket_2.54mm +PinSocket_2x25_P2.54mm_Vertical +Through hole straight socket strip, 2x25, 2.54mm pitch, double cols (from Kicad 4.0.7), script generated +Through hole socket strip THT 2x25 2.54mm double row +0 +50 +50 +Connector_PinSocket_2.54mm +PinSocket_2x25_P2.54mm_Vertical_SMD +surface-mounted straight socket strip, 2x25, 2.54mm pitch, double cols (from Kicad 4.0.7), script generated +Surface mounted socket strip SMD 2x25 2.54mm double row +0 +50 +50 +Connector_PinSocket_2.54mm +PinSocket_2x26_P2.54mm_Horizontal +Through hole angled socket strip, 2x26, 2.54mm pitch, 8.51mm socket length, double cols (from Kicad 4.0.7), script generated +Through hole angled socket strip THT 2x26 2.54mm double row +0 +52 +52 +Connector_PinSocket_2.54mm +PinSocket_2x26_P2.54mm_Vertical +Through hole straight socket strip, 2x26, 2.54mm pitch, double cols (from Kicad 4.0.7), script generated +Through hole socket strip THT 2x26 2.54mm double row +0 +52 +52 +Connector_PinSocket_2.54mm +PinSocket_2x26_P2.54mm_Vertical_SMD +surface-mounted straight socket strip, 2x26, 2.54mm pitch, double cols (from Kicad 4.0.7), script generated +Surface mounted socket strip SMD 2x26 2.54mm double row +0 +52 +52 +Connector_PinSocket_2.54mm +PinSocket_2x27_P2.54mm_Horizontal +Through hole angled socket strip, 2x27, 2.54mm pitch, 8.51mm socket length, double cols (from Kicad 4.0.7), script generated +Through hole angled socket strip THT 2x27 2.54mm double row +0 +54 +54 +Connector_PinSocket_2.54mm +PinSocket_2x27_P2.54mm_Vertical +Through hole straight socket strip, 2x27, 2.54mm pitch, double cols (from Kicad 4.0.7), script generated +Through hole socket strip THT 2x27 2.54mm double row +0 +54 +54 +Connector_PinSocket_2.54mm +PinSocket_2x27_P2.54mm_Vertical_SMD +surface-mounted straight socket strip, 2x27, 2.54mm pitch, double cols (from Kicad 4.0.7), script generated +Surface mounted socket strip SMD 2x27 2.54mm double row +0 +54 +54 +Connector_PinSocket_2.54mm +PinSocket_2x28_P2.54mm_Horizontal +Through hole angled socket strip, 2x28, 2.54mm pitch, 8.51mm socket length, double cols (from Kicad 4.0.7), script generated +Through hole angled socket strip THT 2x28 2.54mm double row +0 +56 +56 +Connector_PinSocket_2.54mm +PinSocket_2x28_P2.54mm_Vertical +Through hole straight socket strip, 2x28, 2.54mm pitch, double cols (from Kicad 4.0.7), script generated +Through hole socket strip THT 2x28 2.54mm double row +0 +56 +56 +Connector_PinSocket_2.54mm +PinSocket_2x28_P2.54mm_Vertical_SMD +surface-mounted straight socket strip, 2x28, 2.54mm pitch, double cols (from Kicad 4.0.7), script generated +Surface mounted socket strip SMD 2x28 2.54mm double row +0 +56 +56 +Connector_PinSocket_2.54mm +PinSocket_2x29_P2.54mm_Horizontal +Through hole angled socket strip, 2x29, 2.54mm pitch, 8.51mm socket length, double cols (from Kicad 4.0.7), script generated +Through hole angled socket strip THT 2x29 2.54mm double row +0 +58 +58 +Connector_PinSocket_2.54mm +PinSocket_2x29_P2.54mm_Vertical +Through hole straight socket strip, 2x29, 2.54mm pitch, double cols (from Kicad 4.0.7), script generated +Through hole socket strip THT 2x29 2.54mm double row +0 +58 +58 +Connector_PinSocket_2.54mm +PinSocket_2x29_P2.54mm_Vertical_SMD +surface-mounted straight socket strip, 2x29, 2.54mm pitch, double cols (from Kicad 4.0.7), script generated +Surface mounted socket strip SMD 2x29 2.54mm double row +0 +58 +58 +Connector_PinSocket_2.54mm +PinSocket_2x30_P2.54mm_Horizontal +Through hole angled socket strip, 2x30, 2.54mm pitch, 8.51mm socket length, double cols (from Kicad 4.0.7), script generated +Through hole angled socket strip THT 2x30 2.54mm double row +0 +60 +60 +Connector_PinSocket_2.54mm +PinSocket_2x30_P2.54mm_Vertical +Through hole straight socket strip, 2x30, 2.54mm pitch, double cols (from Kicad 4.0.7), script generated +Through hole socket strip THT 2x30 2.54mm double row +0 +60 +60 +Connector_PinSocket_2.54mm +PinSocket_2x30_P2.54mm_Vertical_SMD +surface-mounted straight socket strip, 2x30, 2.54mm pitch, double cols (from Kicad 4.0.7), script generated +Surface mounted socket strip SMD 2x30 2.54mm double row +0 +60 +60 +Connector_PinSocket_2.54mm +PinSocket_2x31_P2.54mm_Horizontal +Through hole angled socket strip, 2x31, 2.54mm pitch, 8.51mm socket length, double cols (from Kicad 4.0.7), script generated +Through hole angled socket strip THT 2x31 2.54mm double row +0 +62 +62 +Connector_PinSocket_2.54mm +PinSocket_2x31_P2.54mm_Vertical +Through hole straight socket strip, 2x31, 2.54mm pitch, double cols (from Kicad 4.0.7), script generated +Through hole socket strip THT 2x31 2.54mm double row +0 +62 +62 +Connector_PinSocket_2.54mm +PinSocket_2x31_P2.54mm_Vertical_SMD +surface-mounted straight socket strip, 2x31, 2.54mm pitch, double cols (from Kicad 4.0.7), script generated +Surface mounted socket strip SMD 2x31 2.54mm double row +0 +62 +62 +Connector_PinSocket_2.54mm +PinSocket_2x32_P2.54mm_Horizontal +Through hole angled socket strip, 2x32, 2.54mm pitch, 8.51mm socket length, double cols (from Kicad 4.0.7), script generated +Through hole angled socket strip THT 2x32 2.54mm double row +0 +64 +64 +Connector_PinSocket_2.54mm +PinSocket_2x32_P2.54mm_Vertical +Through hole straight socket strip, 2x32, 2.54mm pitch, double cols (from Kicad 4.0.7), script generated +Through hole socket strip THT 2x32 2.54mm double row +0 +64 +64 +Connector_PinSocket_2.54mm +PinSocket_2x32_P2.54mm_Vertical_SMD +surface-mounted straight socket strip, 2x32, 2.54mm pitch, double cols (from Kicad 4.0.7), script generated +Surface mounted socket strip SMD 2x32 2.54mm double row +0 +64 +64 +Connector_PinSocket_2.54mm +PinSocket_2x33_P2.54mm_Horizontal +Through hole angled socket strip, 2x33, 2.54mm pitch, 8.51mm socket length, double cols (from Kicad 4.0.7), script generated +Through hole angled socket strip THT 2x33 2.54mm double row +0 +66 +66 +Connector_PinSocket_2.54mm +PinSocket_2x33_P2.54mm_Vertical +Through hole straight socket strip, 2x33, 2.54mm pitch, double cols (from Kicad 4.0.7), script generated +Through hole socket strip THT 2x33 2.54mm double row +0 +66 +66 +Connector_PinSocket_2.54mm +PinSocket_2x33_P2.54mm_Vertical_SMD +surface-mounted straight socket strip, 2x33, 2.54mm pitch, double cols (from Kicad 4.0.7), script generated +Surface mounted socket strip SMD 2x33 2.54mm double row +0 +66 +66 +Connector_PinSocket_2.54mm +PinSocket_2x34_P2.54mm_Horizontal +Through hole angled socket strip, 2x34, 2.54mm pitch, 8.51mm socket length, double cols (from Kicad 4.0.7), script generated +Through hole angled socket strip THT 2x34 2.54mm double row +0 +68 +68 +Connector_PinSocket_2.54mm +PinSocket_2x34_P2.54mm_Vertical +Through hole straight socket strip, 2x34, 2.54mm pitch, double cols (from Kicad 4.0.7), script generated +Through hole socket strip THT 2x34 2.54mm double row +0 +68 +68 +Connector_PinSocket_2.54mm +PinSocket_2x34_P2.54mm_Vertical_SMD +surface-mounted straight socket strip, 2x34, 2.54mm pitch, double cols (from Kicad 4.0.7), script generated +Surface mounted socket strip SMD 2x34 2.54mm double row +0 +68 +68 +Connector_PinSocket_2.54mm +PinSocket_2x35_P2.54mm_Horizontal +Through hole angled socket strip, 2x35, 2.54mm pitch, 8.51mm socket length, double cols (from Kicad 4.0.7), script generated +Through hole angled socket strip THT 2x35 2.54mm double row +0 +70 +70 +Connector_PinSocket_2.54mm +PinSocket_2x35_P2.54mm_Vertical +Through hole straight socket strip, 2x35, 2.54mm pitch, double cols (from Kicad 4.0.7), script generated +Through hole socket strip THT 2x35 2.54mm double row +0 +70 +70 +Connector_PinSocket_2.54mm +PinSocket_2x35_P2.54mm_Vertical_SMD +surface-mounted straight socket strip, 2x35, 2.54mm pitch, double cols (from Kicad 4.0.7), script generated +Surface mounted socket strip SMD 2x35 2.54mm double row +0 +70 +70 +Connector_PinSocket_2.54mm +PinSocket_2x36_P2.54mm_Horizontal +Through hole angled socket strip, 2x36, 2.54mm pitch, 8.51mm socket length, double cols (from Kicad 4.0.7), script generated +Through hole angled socket strip THT 2x36 2.54mm double row +0 +72 +72 +Connector_PinSocket_2.54mm +PinSocket_2x36_P2.54mm_Vertical +Through hole straight socket strip, 2x36, 2.54mm pitch, double cols (from Kicad 4.0.7), script generated +Through hole socket strip THT 2x36 2.54mm double row +0 +72 +72 +Connector_PinSocket_2.54mm +PinSocket_2x36_P2.54mm_Vertical_SMD +surface-mounted straight socket strip, 2x36, 2.54mm pitch, double cols (from Kicad 4.0.7), script generated +Surface mounted socket strip SMD 2x36 2.54mm double row +0 +72 +72 +Connector_PinSocket_2.54mm +PinSocket_2x37_P2.54mm_Horizontal +Through hole angled socket strip, 2x37, 2.54mm pitch, 8.51mm socket length, double cols (from Kicad 4.0.7), script generated +Through hole angled socket strip THT 2x37 2.54mm double row +0 +74 +74 +Connector_PinSocket_2.54mm +PinSocket_2x37_P2.54mm_Vertical +Through hole straight socket strip, 2x37, 2.54mm pitch, double cols (from Kicad 4.0.7), script generated +Through hole socket strip THT 2x37 2.54mm double row +0 +74 +74 +Connector_PinSocket_2.54mm +PinSocket_2x37_P2.54mm_Vertical_SMD +surface-mounted straight socket strip, 2x37, 2.54mm pitch, double cols (from Kicad 4.0.7), script generated +Surface mounted socket strip SMD 2x37 2.54mm double row +0 +74 +74 +Connector_PinSocket_2.54mm +PinSocket_2x38_P2.54mm_Horizontal +Through hole angled socket strip, 2x38, 2.54mm pitch, 8.51mm socket length, double cols (from Kicad 4.0.7), script generated +Through hole angled socket strip THT 2x38 2.54mm double row +0 +76 +76 +Connector_PinSocket_2.54mm +PinSocket_2x38_P2.54mm_Vertical +Through hole straight socket strip, 2x38, 2.54mm pitch, double cols (from Kicad 4.0.7), script generated +Through hole socket strip THT 2x38 2.54mm double row +0 +76 +76 +Connector_PinSocket_2.54mm +PinSocket_2x38_P2.54mm_Vertical_SMD +surface-mounted straight socket strip, 2x38, 2.54mm pitch, double cols (from Kicad 4.0.7), script generated +Surface mounted socket strip SMD 2x38 2.54mm double row +0 +76 +76 +Connector_PinSocket_2.54mm +PinSocket_2x39_P2.54mm_Horizontal +Through hole angled socket strip, 2x39, 2.54mm pitch, 8.51mm socket length, double cols (from Kicad 4.0.7), script generated +Through hole angled socket strip THT 2x39 2.54mm double row +0 +78 +78 +Connector_PinSocket_2.54mm +PinSocket_2x39_P2.54mm_Vertical +Through hole straight socket strip, 2x39, 2.54mm pitch, double cols (from Kicad 4.0.7), script generated +Through hole socket strip THT 2x39 2.54mm double row +0 +78 +78 +Connector_PinSocket_2.54mm +PinSocket_2x39_P2.54mm_Vertical_SMD +surface-mounted straight socket strip, 2x39, 2.54mm pitch, double cols (from Kicad 4.0.7), script generated +Surface mounted socket strip SMD 2x39 2.54mm double row +0 +78 +78 +Connector_PinSocket_2.54mm +PinSocket_2x40_P2.54mm_Horizontal +Through hole angled socket strip, 2x40, 2.54mm pitch, 8.51mm socket length, double cols (from Kicad 4.0.7), script generated +Through hole angled socket strip THT 2x40 2.54mm double row +0 +80 +80 +Connector_PinSocket_2.54mm +PinSocket_2x40_P2.54mm_Vertical +Through hole straight socket strip, 2x40, 2.54mm pitch, double cols (from Kicad 4.0.7), script generated +Through hole socket strip THT 2x40 2.54mm double row +0 +80 +80 +Connector_PinSocket_2.54mm +PinSocket_2x40_P2.54mm_Vertical_SMD +surface-mounted straight socket strip, 2x40, 2.54mm pitch, double cols (from Kicad 4.0.7), script generated +Surface mounted socket strip SMD 2x40 2.54mm double row +0 +80 +80 +Crystal +Crystal_AT310_D3.0mm_L10.0mm_Horizontal +Crystal THT AT310 10.0mm-10.5mm length 3.0mm diameter +['AT310'] +0 +2 +2 +Crystal +Crystal_AT310_D3.0mm_L10.0mm_Horizontal_1EP_style1 +Crystal THT AT310 10.0mm-10.5mm length 3.0mm diameter +['AT310'] +0 +3 +3 +Crystal +Crystal_AT310_D3.0mm_L10.0mm_Horizontal_1EP_style2 +Crystal THT AT310 10.0mm-10.5mm length 3.0mm diameter +['AT310'] +0 +5 +3 +Crystal +Crystal_AT310_D3.0mm_L10.0mm_Vertical +Crystal THT AT310 10.0mm-10.5mm length 3.0mm diameter +['AT310'] +0 +2 +2 +Crystal +Crystal_C26-LF_D2.1mm_L6.5mm_Horizontal +Crystal THT C26-LF 6.5mm length 2.06mm diameter +['C26-LF'] +0 +2 +2 +Crystal +Crystal_C26-LF_D2.1mm_L6.5mm_Horizontal_1EP_style1 +Crystal THT C26-LF 6.5mm length 2.06mm diameter +['C26-LF'] +0 +3 +3 +Crystal +Crystal_C26-LF_D2.1mm_L6.5mm_Horizontal_1EP_style2 +Crystal THT C26-LF 6.5mm length 2.06mm diameter +['C26-LF'] +0 +5 +3 +Crystal +Crystal_C26-LF_D2.1mm_L6.5mm_Vertical +Crystal THT C26-LF 6.5mm length 2.06mm diameter +['C26-LF'] +0 +2 +2 +Crystal +Crystal_C38-LF_D3.0mm_L8.0mm_Horizontal +Crystal THT C38-LF 8.0mm length 3.0mm diameter +['C38-LF'] +0 +2 +2 +Crystal +Crystal_C38-LF_D3.0mm_L8.0mm_Horizontal_1EP_style1 +Crystal THT C38-LF 8.0mm length 3.0mm diameter +['C38-LF'] +0 +3 +3 +Crystal +Crystal_C38-LF_D3.0mm_L8.0mm_Horizontal_1EP_style2 +Crystal THT C38-LF 8.0mm length 3.0mm diameter +['C38-LF'] +0 +5 +3 +Crystal +Crystal_C38-LF_D3.0mm_L8.0mm_Vertical +Crystal THT C38-LF 8.0mm length 3.0mm diameter +['C38-LF'] +0 +2 +2 +Crystal +Crystal_DS10_D1.0mm_L4.3mm_Horizontal +Crystal THT DS10 4.3mm length 1.0mm diameter http://www.microcrystal.com/images/_Product-Documentation/03_TF_metal_Packages/01_Datasheet/DS-Series.pdf +['DS10'] +0 +2 +2 +Crystal +Crystal_DS10_D1.0mm_L4.3mm_Horizontal_1EP_style1 +Crystal THT DS10 4.3mm length 1.0mm diameter http://www.microcrystal.com/images/_Product-Documentation/03_TF_metal_Packages/01_Datasheet/DS-Series.pdf +['DS10'] +0 +3 +3 +Crystal +Crystal_DS10_D1.0mm_L4.3mm_Horizontal_1EP_style2 +Crystal THT DS10 4.3mm length 1.0mm diameter http://www.microcrystal.com/images/_Product-Documentation/03_TF_metal_Packages/01_Datasheet/DS-Series.pdf +['DS10'] +0 +5 +3 +Crystal +Crystal_DS10_D1.0mm_L4.3mm_Vertical +Crystal THT DS10 4.3mm length 1.0mm diameter http://www.microcrystal.com/images/_Product-Documentation/03_TF_metal_Packages/01_Datasheet/DS-Series.pdf +['DS10'] +0 +2 +2 +Crystal +Crystal_DS15_D1.5mm_L5.0mm_Horizontal +Crystal THT DS15 5.0mm length 1.5mm diameter http://www.microcrystal.com/images/_Product-Documentation/03_TF_metal_Packages/01_Datasheet/DS-Series.pdf +['DS15'] +0 +2 +2 +Crystal +Crystal_DS15_D1.5mm_L5.0mm_Horizontal_1EP_style1 +Crystal THT DS15 5.0mm length 1.5mm diameter http://www.microcrystal.com/images/_Product-Documentation/03_TF_metal_Packages/01_Datasheet/DS-Series.pdf +['DS15'] +0 +3 +3 +Crystal +Crystal_DS15_D1.5mm_L5.0mm_Horizontal_1EP_style2 +Crystal THT DS15 5.0mm length 1.5mm diameter http://www.microcrystal.com/images/_Product-Documentation/03_TF_metal_Packages/01_Datasheet/DS-Series.pdf +['DS15'] +0 +5 +3 +Crystal +Crystal_DS15_D1.5mm_L5.0mm_Vertical +Crystal THT DS15 5.0mm length 1.5mm diameter http://www.microcrystal.com/images/_Product-Documentation/03_TF_metal_Packages/01_Datasheet/DS-Series.pdf +['DS15'] +0 +2 +2 +Crystal +Crystal_DS26_D2.0mm_L6.0mm_Horizontal +Crystal THT DS26 6.0mm length 2.0mm diameter http://www.microcrystal.com/images/_Product-Documentation/03_TF_metal_Packages/01_Datasheet/DS-Series.pdf +['DS26'] +0 +2 +2 +Crystal +Crystal_DS26_D2.0mm_L6.0mm_Horizontal_1EP_style1 +Crystal THT DS26 6.0mm length 2.0mm diameter http://www.microcrystal.com/images/_Product-Documentation/03_TF_metal_Packages/01_Datasheet/DS-Series.pdf +['DS26'] +0 +3 +3 +Crystal +Crystal_DS26_D2.0mm_L6.0mm_Horizontal_1EP_style2 +Crystal THT DS26 6.0mm length 2.0mm diameter http://www.microcrystal.com/images/_Product-Documentation/03_TF_metal_Packages/01_Datasheet/DS-Series.pdf +['DS26'] +0 +5 +3 +Crystal +Crystal_DS26_D2.0mm_L6.0mm_Vertical +Crystal THT DS26 6.0mm length 2.0mm diameter http://www.microcrystal.com/images/_Product-Documentation/03_TF_metal_Packages/01_Datasheet/DS-Series.pdf +['DS26'] +0 +2 +2 +Crystal +Crystal_HC18-U_Horizontal +Crystal THT HC-18/U http://5hertz.com/pdfs/04404_D.pdf +THT crystal +0 +2 +2 +Crystal +Crystal_HC18-U_Horizontal_1EP_style1 +Crystal THT HC-18/U http://5hertz.com/pdfs/04404_D.pdf +THT crystal +0 +3 +3 +Crystal +Crystal_HC18-U_Horizontal_1EP_style2 +Crystal THT HC-18/U http://5hertz.com/pdfs/04404_D.pdf +THT crystal +0 +5 +3 +Crystal +Crystal_HC18-U_Vertical +Crystal THT HC-18/U, http://5hertz.com/pdfs/04404_D.pdf +THT crystalHC-18/U +0 +2 +2 +Crystal +Crystal_HC33-U_Horizontal +Crystal THT HC-33/U http://pdi.bentech-taiwan.com/PDI/GEN20SPEV20HC3320U.pdf +THT crystal +0 +2 +2 +Crystal +Crystal_HC33-U_Horizontal_1EP_style1 +Crystal THT HC-33/U http://pdi.bentech-taiwan.com/PDI/GEN20SPEV20HC3320U.pdf +THT crystal +0 +3 +3 +Crystal +Crystal_HC33-U_Horizontal_1EP_style2 +Crystal THT HC-33/U http://pdi.bentech-taiwan.com/PDI/GEN20SPEV20HC3320U.pdf +THT crystal +0 +5 +3 +Crystal +Crystal_HC33-U_Vertical +Crystal THT HC-33/U, http://pdi.bentech-taiwan.com/PDI/GEN20SPEV20HC3320U.pdf +THT crystalHC-33/U +0 +2 +2 +Crystal +Crystal_HC35-U +Crystal, Quarz, HC35/U, http://www.kvg-gmbh.de/assets/uploads/files/product_pdfs/TO71xx.pdf +Crystal Quarz HC35/U +0 +3 +3 +Crystal +Crystal_HC49-4H_Vertical +Crystal THT HC-49-4H http://5hertz.com/pdfs/04404_D.pdf +THT crystalHC-49-4H +0 +2 +2 +Crystal +Crystal_HC49-U-3Pin_Vertical +Crystal THT HC-49/U, 3pin-version, http://www.raltron.com/products/pdfspecs/crystal_hc_49_45_51.pdf +THT crystalHC-49/U +0 +3 +3 +Crystal +Crystal_HC49-U_Horizontal +Crystal THT HC-49/U http://5hertz.com/pdfs/04404_D.pdf +THT crystal +0 +2 +2 +Crystal +Crystal_HC49-U_Horizontal_1EP_style1 +Crystal THT HC-49/U http://5hertz.com/pdfs/04404_D.pdf +THT crystal +0 +3 +3 +Crystal +Crystal_HC49-U_Horizontal_1EP_style2 +Crystal THT HC-49/U http://5hertz.com/pdfs/04404_D.pdf +THT crystal +0 +5 +3 +Crystal +Crystal_HC49-U_Vertical +Crystal THT HC-49/U http://5hertz.com/pdfs/04404_D.pdf +THT crystalHC-49/U +0 +2 +2 +Crystal +Crystal_HC50_Horizontal +Crystal THT HC-50 http://www.crovencrystals.com/croven_pdf/HC-50_Crystal_Holder_Rev_00.pdf +THT crystal +0 +2 +2 +Crystal +Crystal_HC50_Horizontal_1EP_style1 +Crystal THT HC-50 http://www.crovencrystals.com/croven_pdf/HC-50_Crystal_Holder_Rev_00.pdf +THT crystal +0 +3 +3 +Crystal +Crystal_HC50_Horizontal_1EP_style2 +Crystal THT HC-50 http://www.crovencrystals.com/croven_pdf/HC-50_Crystal_Holder_Rev_00.pdf +THT crystal +0 +5 +3 +Crystal +Crystal_HC50_Vertical +Crystal THT HC-50, http://www.crovencrystals.com/croven_pdf/HC-50_Crystal_Holder_Rev_00.pdf +THT crystalHC-50 +0 +2 +2 +Crystal +Crystal_HC51-U_Vertical +Crystal THT HC-51/U, http://www.crovencrystals.com/croven_pdf/HC-51_Crystal_Holder_Rev_00.pdf +THT crystalHC-51/U +0 +2 +2 +Crystal +Crystal_HC51_Horizontal +Crystal THT HC-51 http://www.crovencrystals.com/croven_pdf/HC-51_Crystal_Holder_Rev_00.pdf +THT crystal +0 +2 +2 +Crystal +Crystal_HC51_Horizontal_1EP_style1 +Crystal THT HC-51 http://www.crovencrystals.com/croven_pdf/HC-51_Crystal_Holder_Rev_00.pdf +THT crystal +0 +3 +3 +Crystal +Crystal_HC51_Horizontal_1EP_style2 +Crystal THT HC-51 http://www.crovencrystals.com/croven_pdf/HC-51_Crystal_Holder_Rev_00.pdf +THT crystal +0 +5 +3 +Crystal +Crystal_HC52-6mm_Horizontal +Crystal THT HC-51/6mm http://www.kvg-gmbh.de/assets/uploads/files/product_pdfs/XS71xx.pdf +THT crystal +0 +2 +2 +Crystal +Crystal_HC52-6mm_Horizontal_1EP_style1 +Crystal THT HC-51/6mm http://www.kvg-gmbh.de/assets/uploads/files/product_pdfs/XS71xx.pdf +THT crystal +0 +3 +3 +Crystal +Crystal_HC52-6mm_Horizontal_1EP_style2 +Crystal THT HC-51/6mm http://www.kvg-gmbh.de/assets/uploads/files/product_pdfs/XS71xx.pdf +THT crystal +0 +5 +3 +Crystal +Crystal_HC52-6mm_Vertical +Crystal THT HC-52/6mm, http://www.kvg-gmbh.de/assets/uploads/files/product_pdfs/XS71xx.pdf +THT crystalHC-49/U +0 +2 +2 +Crystal +Crystal_HC52-8mm_Horizontal +Crystal THT HC-51/8mm http://www.kvg-gmbh.de/assets/uploads/files/product_pdfs/XS71xx.pdf +THT crystal +0 +2 +2 +Crystal +Crystal_HC52-8mm_Horizontal_1EP_style1 +Crystal THT HC-51/8mm http://www.kvg-gmbh.de/assets/uploads/files/product_pdfs/XS71xx.pdf +THT crystal +0 +3 +3 +Crystal +Crystal_HC52-8mm_Horizontal_1EP_style2 +Crystal THT HC-51/8mm http://www.kvg-gmbh.de/assets/uploads/files/product_pdfs/XS71xx.pdf +THT crystal +0 +5 +3 +Crystal +Crystal_HC52-8mm_Vertical +Crystal THT HC-52/8mm, http://www.kvg-gmbh.de/assets/uploads/files/product_pdfs/XS71xx.pdf +THT crystalHC-49/U +0 +2 +2 +Crystal +Crystal_HC52-U-3Pin_Vertical +Crystal THT HC-52/U, http://www.kvg-gmbh.de/assets/uploads/files/product_pdfs/XS71xx.pdf +THT crystalHC-52/U +0 +3 +3 +Crystal +Crystal_HC52-U_Horizontal +Crystal THT HC-51/U http://www.kvg-gmbh.de/assets/uploads/files/product_pdfs/XS71xx.pdf +THT crystal +0 +2 +2 +Crystal +Crystal_HC52-U_Horizontal_1EP_style1 +Crystal THT HC-51/U http://www.kvg-gmbh.de/assets/uploads/files/product_pdfs/XS71xx.pdf +THT crystal +0 +3 +3 +Crystal +Crystal_HC52-U_Horizontal_1EP_style2 +Crystal THT HC-51/U http://www.kvg-gmbh.de/assets/uploads/files/product_pdfs/XS71xx.pdf +THT crystal +0 +5 +3 +Crystal +Crystal_HC52-U_Vertical +Crystal THT HC-52/U, http://www.kvg-gmbh.de/assets/uploads/files/product_pdfs/XS71xx.pdf +THT crystal HC-52/U +0 +2 +2 +Crystal +Crystal_Round_D1.0mm_Vertical +Crystal THT DS10 1.0mm diameter http://www.microcrystal.com/images/_Product-Documentation/03_TF_metal_Packages/01_Datasheet/DS-Series.pdf +['DS10'] +0 +2 +2 +Crystal +Crystal_Round_D1.5mm_Vertical +Crystal THT DS15 5.0mm length 1.5mm diameter http://www.microcrystal.com/images/_Product-Documentation/03_TF_metal_Packages/01_Datasheet/DS-Series.pdf +['DS15'] +0 +2 +2 +Crystal +Crystal_Round_D2.0mm_Vertical +Crystal THT DS26 6.0mm length 2.0mm diameter http://www.microcrystal.com/images/_Product-Documentation/03_TF_metal_Packages/01_Datasheet/DS-Series.pdf +['DS26'] +0 +2 +2 +Crystal +Crystal_Round_D3.0mm_Vertical +Crystal THT C38-LF 8.0mm length 3.0mm diameter +['C38-LF'] +0 +2 +2 +Crystal +Crystal_SMD_0603-2Pin_6.0x3.5mm +SMD Crystal SERIES SMD0603/2 http://www.petermann-technik.de/fileadmin/petermann/pdf/SMD0603-2.pdf, 6.0x3.5mm^2 package +SMD SMT crystal +0 +2 +2 +Crystal +Crystal_SMD_0603-2Pin_6.0x3.5mm_HandSoldering +SMD Crystal SERIES SMD0603/2 http://www.petermann-technik.de/fileadmin/petermann/pdf/SMD0603-2.pdf, hand-soldering, 6.0x3.5mm^2 package +SMD SMT crystal hand-soldering +0 +2 +2 +Crystal +Crystal_SMD_0603-4Pin_6.0x3.5mm +SMD Crystal SERIES SMD0603/4 http://www.petermann-technik.de/fileadmin/petermann/pdf/SMD0603-4.pdf, 6.0x3.5mm^2 package +SMD SMT crystal +0 +4 +4 +Crystal +Crystal_SMD_0603-4Pin_6.0x3.5mm_HandSoldering +SMD Crystal SERIES SMD0603/4 http://www.petermann-technik.de/fileadmin/petermann/pdf/SMD0603-4.pdf, hand-soldering, 6.0x3.5mm^2 package +SMD SMT crystal hand-soldering +0 +4 +4 +Crystal +Crystal_SMD_2012-2Pin_2.0x1.2mm +SMD Crystal 2012/2 http://txccrystal.com/images/pdf/9ht11.pdf, 2.0x1.2mm^2 package +SMD SMT crystal +0 +2 +2 +Crystal +Crystal_SMD_2012-2Pin_2.0x1.2mm_HandSoldering +SMD Crystal 2012/2 http://txccrystal.com/images/pdf/9ht11.pdf, hand-soldering, 2.0x1.2mm^2 package +SMD SMT crystal hand-soldering +0 +2 +2 +Crystal +Crystal_SMD_2016-4Pin_2.0x1.6mm +SMD Crystal SERIES SMD2016/4 http://www.q-crystal.com/upload/5/2015552223166229.pdf, 2.0x1.6mm^2 package +SMD SMT crystal +0 +4 +4 +Crystal +Crystal_SMD_2520-4Pin_2.5x2.0mm +SMD Crystal SERIES SMD2520/4 http://www.newxtal.com/UploadFiles/Images/2012-11-12-09-29-09-776.pdf, 2.5x2.0mm^2 package +SMD SMT crystal +0 +4 +4 +Crystal +Crystal_SMD_3215-2Pin_3.2x1.5mm +SMD Crystal FC-135 https://support.epson.biz/td/api/doc_check.php?dl=brief_FC-135R_en.pdf +SMD SMT Crystal +0 +2 +2 +Crystal +Crystal_SMD_3225-4Pin_3.2x2.5mm +SMD Crystal SERIES SMD3225/4 http://www.txccrystal.com/images/pdf/7m-accuracy.pdf, 3.2x2.5mm^2 package +SMD SMT crystal +0 +4 +4 +Crystal +Crystal_SMD_3225-4Pin_3.2x2.5mm_HandSoldering +SMD Crystal SERIES SMD3225/4 http://www.txccrystal.com/images/pdf/7m-accuracy.pdf, hand-soldering, 3.2x2.5mm^2 package +SMD SMT crystal hand-soldering +0 +4 +4 +Crystal +Crystal_SMD_5032-2Pin_5.0x3.2mm +SMD Crystal SERIES SMD2520/2 http://www.icbase.com/File/PDF/HKC/HKC00061008.pdf, 5.0x3.2mm^2 package +SMD SMT crystal +0 +2 +2 +Crystal +Crystal_SMD_5032-2Pin_5.0x3.2mm_HandSoldering +SMD Crystal SERIES SMD2520/2 http://www.icbase.com/File/PDF/HKC/HKC00061008.pdf, hand-soldering, 5.0x3.2mm^2 package +SMD SMT crystal hand-soldering +0 +2 +2 +Crystal +Crystal_SMD_5032-4Pin_5.0x3.2mm +SMD Crystal SERIES SMD2520/4 http://www.icbase.com/File/PDF/HKC/HKC00061008.pdf, 5.0x3.2mm^2 package +SMD SMT crystal +0 +4 +4 +Crystal +Crystal_SMD_7050-2Pin_7.0x5.0mm +SMD Crystal SERIES SMD7050/4 https://www.foxonline.com/pdfs/FQ7050.pdf, 7.0x5.0mm^2 package +SMD SMT crystal +0 +2 +2 +Crystal +Crystal_SMD_7050-2Pin_7.0x5.0mm_HandSoldering +SMD Crystal SERIES SMD7050/4 https://www.foxonline.com/pdfs/FQ7050.pdf, hand-soldering, 7.0x5.0mm^2 package +SMD SMT crystal hand-soldering +0 +2 +2 +Crystal +Crystal_SMD_7050-4Pin_7.0x5.0mm +SMD Crystal SERIES SMD7050/4 https://www.foxonline.com/pdfs/FQ7050.pdf, 7.0x5.0mm^2 package +SMD SMT crystal +0 +4 +4 +Crystal +Crystal_SMD_Abracon_ABM3-2Pin_5.0x3.2mm +Abracon Miniature Ceramic Smd Crystal ABM3 http://www.abracon.com/Resonators/abm3.pdf, 5.0x3.2mm^2 package +SMD SMT crystal +0 +2 +2 +Crystal +Crystal_SMD_Abracon_ABM3-2Pin_5.0x3.2mm_HandSoldering +Abracon Miniature Ceramic Smd Crystal ABM3 http://www.abracon.com/Resonators/abm3.pdf, hand-soldering, 5.0x3.2mm^2 package +SMD SMT crystal hand-soldering +0 +2 +2 +Crystal +Crystal_SMD_Abracon_ABM3B-4Pin_5.0x3.2mm +Abracon Miniature Ceramic Smd Crystal ABM3B http://www.abracon.com/Resonators/abm3b.pdf, 5.0x3.2mm^2 package +SMD SMT crystal +0 +4 +4 +Crystal +Crystal_SMD_Abracon_ABM3C-4Pin_5.0x3.2mm +Abracon Miniature Ceramic Smd Crystal ABM3C http://www.abracon.com/Resonators/abm3c.pdf, 5.0x3.2mm^2 package +SMD SMT crystal +0 +4 +4 +Crystal +Crystal_SMD_Abracon_ABM7-2Pin_6.0x3.5mm +SMD Crystal Abracon ABM7, https://abracon.com/Resonators/abm7.pdf +SMD SMT crystal +0 +2 +2 +Crystal +Crystal_SMD_Abracon_ABM8G-4Pin_3.2x2.5mm +Abracon Miniature Ceramic Smd Crystal ABM8G http://www.abracon.com/Resonators/ABM8G.pdf, 3.2x2.5mm^2 package +SMD SMT crystal +0 +4 +4 +Crystal +Crystal_SMD_Abracon_ABM10-4Pin_2.5x2.0mm +Abracon Miniature Ceramic Smd Crystal ABM10 http://www.abracon.com/Resonators/ABM10.pdf +SMD SMT crystal Abracon ABM10 +0 +4 +4 +Crystal +Crystal_SMD_Abracon_ABS25-4Pin_8.0x3.8mm +Abracon Miniature Ceramic SMD Crystal ABS25 https://abracon.com/Resonators/abs25.pdf, 8.0x3.8mm^2 package +SMD SMT crystal +0 +4 +4 +Crystal +Crystal_SMD_ECS_CSM3X-2Pin_7.6x4.1mm +http://www.ecsxtal.com/store/pdf/CSM-3X.pdf +Crystal CSM-3X +0 +2 +2 +Crystal +Crystal_SMD_EuroQuartz_EQ161-2Pin_3.2x1.5mm +SMD Crystal EuroQuartz EQ161 series http://cdn-reichelt.de/documents/datenblatt/B400/PG32768C.pdf, 3.2x1.5mm^2 package +SMD SMT crystal +0 +2 +2 +Crystal +Crystal_SMD_EuroQuartz_EQ161-2Pin_3.2x1.5mm_HandSoldering +SMD Crystal EuroQuartz EQ161 series http://cdn-reichelt.de/documents/datenblatt/B400/PG32768C.pdf, hand-soldering, 3.2x1.5mm^2 package +SMD SMT crystal hand-soldering +0 +2 +2 +Crystal +Crystal_SMD_EuroQuartz_MJ-4Pin_5.0x3.2mm +SMD Crystal EuroQuartz MJ series http://cdn-reichelt.de/documents/datenblatt/B400/MJ.pdf, 5.0x3.2mm^2 package +SMD SMT crystal +0 +4 +4 +Crystal +Crystal_SMD_EuroQuartz_MJ-4Pin_5.0x3.2mm_HandSoldering +SMD Crystal EuroQuartz MJ series http://cdn-reichelt.de/documents/datenblatt/B400/MJ.pdf, hand-soldering, 5.0x3.2mm^2 package +SMD SMT crystal hand-soldering +0 +4 +4 +Crystal +Crystal_SMD_EuroQuartz_MQ-4Pin_7.0x5.0mm +SMD Crystal EuroQuartz MQ series http://cdn-reichelt.de/documents/datenblatt/B400/MQ.pdf, 7.0x5.0mm^2 package +SMD SMT crystal +0 +4 +4 +Crystal +Crystal_SMD_EuroQuartz_MQ-4Pin_7.0x5.0mm_HandSoldering +SMD Crystal EuroQuartz MQ series http://cdn-reichelt.de/documents/datenblatt/B400/MQ.pdf, hand-soldering, 7.0x5.0mm^2 package +SMD SMT crystal hand-soldering +0 +4 +4 +Crystal +Crystal_SMD_EuroQuartz_MQ2-2Pin_7.0x5.0mm +SMD Crystal EuroQuartz MQ2 series http://cdn-reichelt.de/documents/datenblatt/B400/MQ.pdf, 7.0x5.0mm^2 package +SMD SMT crystal +0 +2 +2 +Crystal +Crystal_SMD_EuroQuartz_MQ2-2Pin_7.0x5.0mm_HandSoldering +SMD Crystal EuroQuartz MQ2 series http://cdn-reichelt.de/documents/datenblatt/B400/MQ.pdf, hand-soldering, 7.0x5.0mm^2 package +SMD SMT crystal hand-soldering +0 +2 +2 +Crystal +Crystal_SMD_EuroQuartz_MT-4Pin_3.2x2.5mm +SMD Crystal EuroQuartz MT series http://cdn-reichelt.de/documents/datenblatt/B400/MT.pdf, 3.2x2.5mm^2 package +SMD SMT crystal +0 +4 +4 +Crystal +Crystal_SMD_EuroQuartz_MT-4Pin_3.2x2.5mm_HandSoldering +SMD Crystal EuroQuartz MT series http://cdn-reichelt.de/documents/datenblatt/B400/MT.pdf, hand-soldering, 3.2x2.5mm^2 package +SMD SMT crystal hand-soldering +0 +4 +4 +Crystal +Crystal_SMD_EuroQuartz_X22-4Pin_2.5x2.0mm +SMD Crystal EuroQuartz X22 series http://cdn-reichelt.de/documents/datenblatt/B400/DS_X22.pdf, 2.5x2.0mm^2 package +SMD SMT crystal +0 +4 +4 +Crystal +Crystal_SMD_EuroQuartz_X22-4Pin_2.5x2.0mm_HandSoldering +SMD Crystal EuroQuartz X22 series http://cdn-reichelt.de/documents/datenblatt/B400/DS_X22.pdf, hand-soldering, 2.5x2.0mm^2 package +SMD SMT crystal hand-soldering +0 +4 +4 +Crystal +Crystal_SMD_FOX_FE-2Pin_7.5x5.0mm +crystal Ceramic Resin Sealed SMD http://www.foxonline.com/pdfs/fe.pdf, 7.5x5.0mm^2 package +SMD SMT crystal +0 +2 +2 +Crystal +Crystal_SMD_FOX_FE-2Pin_7.5x5.0mm_HandSoldering +crystal Ceramic Resin Sealed SMD http://www.foxonline.com/pdfs/fe.pdf, hand-soldering, 7.5x5.0mm^2 package +SMD SMT crystal hand-soldering +0 +2 +2 +Crystal +Crystal_SMD_FOX_FQ7050-2Pin_7.0x5.0mm +FOX SMD Crystal SERIES SMD7050/4 https://www.foxonline.com/pdfs/FQ7050.pdf, 7.0x5.0mm^2 package +SMD SMT crystal +0 +2 +2 +Crystal +Crystal_SMD_FOX_FQ7050-2Pin_7.0x5.0mm_HandSoldering +FOX SMD Crystal SERIES SMD7050/4 https://www.foxonline.com/pdfs/FQ7050.pdf, hand-soldering, 7.0x5.0mm^2 package +SMD SMT crystal hand-soldering +0 +2 +2 +Crystal +Crystal_SMD_FOX_FQ7050-4Pin_7.0x5.0mm +FOX SMD Crystal SERIES SMD7050/4 https://www.foxonline.com/pdfs/FQ7050.pdf, 7.0x5.0mm^2 package +SMD SMT crystal +0 +4 +4 +Crystal +Crystal_SMD_FrontierElectronics_FM206 +SMD Watch Crystal FrontierElectronics FM206 6.0mm length 1.9mm diameter http://www.chinafronter.com/wp-content/uploads/2013/12/FM206.pdf +['FM206'] +0 +3 +3 +Crystal +Crystal_SMD_G8-2Pin_3.2x1.5mm +SMD Crystal G8, 3.2x1.5mm^2 package +SMD SMT crystal +0 +2 +2 +Crystal +Crystal_SMD_G8-2Pin_3.2x1.5mm_HandSoldering +SMD Crystal G8, hand-soldering, 3.2x1.5mm^2 package +SMD SMT crystal hand-soldering +0 +2 +2 +Crystal +Crystal_SMD_HC49-SD +SMD Crystal HC-49-SD http://cdn-reichelt.de/documents/datenblatt/B400/xxx-HC49-SMD.pdf, 11.4x4.7mm^2 package +SMD SMT crystal +0 +2 +2 +Crystal +Crystal_SMD_HC49-SD_HandSoldering +SMD Crystal HC-49-SD http://cdn-reichelt.de/documents/datenblatt/B400/xxx-HC49-SMD.pdf, hand-soldering, 11.4x4.7mm^2 package +SMD SMT crystal hand-soldering +0 +2 +2 +Crystal +Crystal_SMD_MicroCrystal_CC1V-T1A-2Pin_8.0x3.7mm +SMD Crystal MicroCrystal CC1V-T1A series http://www.microcrystal.com/images/_Product-Documentation/01_TF_ceramic_Packages/01_Datasheet/CC1V-T1A.pdf, 8.0x3.7mm^2 package +SMD SMT crystal +0 +2 +2 +Crystal +Crystal_SMD_MicroCrystal_CC1V-T1A-2Pin_8.0x3.7mm_HandSoldering +SMD Crystal MicroCrystal CC1V-T1A series http://www.microcrystal.com/images/_Product-Documentation/01_TF_ceramic_Packages/01_Datasheet/CC1V-T1A.pdf, hand-soldering, 8.0x3.7mm^2 package +SMD SMT crystal hand-soldering +0 +2 +2 +Crystal +Crystal_SMD_MicroCrystal_CC4V-T1A-2Pin_5.0x1.9mm +SMD Crystal MicroCrystal CC4V-T1A series http://cdn-reichelt.de/documents/datenblatt/B400/CC4V-T1A.pdf, 5.0x1.9mm^2 package +SMD SMT crystal +0 +2 +2 +Crystal +Crystal_SMD_MicroCrystal_CC4V-T1A-2Pin_5.0x1.9mm_HandSoldering +SMD Crystal MicroCrystal CC4V-T1A series http://cdn-reichelt.de/documents/datenblatt/B400/CC4V-T1A.pdf, hand-soldering, 5.0x1.9mm^2 package +SMD SMT crystal hand-soldering +0 +2 +2 +Crystal +Crystal_SMD_MicroCrystal_CC5V-T1A-2Pin_4.1x1.5mm +SMD Crystal MicroCrystal CC5V-T1A series http://cdn-reichelt.de/documents/datenblatt/B400/CC5V-T1A.pdf, 4.1x1.5mm^2 package +SMD SMT crystal +0 +2 +2 +Crystal +Crystal_SMD_MicroCrystal_CC5V-T1A-2Pin_4.1x1.5mm_HandSoldering +SMD Crystal MicroCrystal CC5V-T1A series http://cdn-reichelt.de/documents/datenblatt/B400/CC5V-T1A.pdf, hand-soldering, 4.1x1.5mm^2 package +SMD SMT crystal hand-soldering +0 +2 +2 +Crystal +Crystal_SMD_MicroCrystal_CC7V-T1A-2Pin_3.2x1.5mm +SMD Crystal MicroCrystal CC7V-T1A/CM7V-T1A series http://www.microcrystal.com/images/_Product-Documentation/01_TF_ceramic_Packages/01_Datasheet/CC1V-T1A.pdf, 3.2x1.5mm^2 package +SMD SMT crystal +0 +2 +2 +Crystal +Crystal_SMD_MicroCrystal_CC7V-T1A-2Pin_3.2x1.5mm_HandSoldering +SMD Crystal MicroCrystal CC7V-T1A/CM7V-T1A series http://www.microcrystal.com/images/_Product-Documentation/01_TF_ceramic_Packages/01_Datasheet/CC1V-T1A.pdf, hand-soldering, 3.2x1.5mm^2 package +SMD SMT crystal hand-soldering +0 +2 +2 +Crystal +Crystal_SMD_MicroCrystal_CC8V-T1A-2Pin_2.0x1.2mm +SMD Crystal MicroCrystal CC8V-T1A/CM8V-T1A series http://www.microcrystal.com/images/_Product-Documentation/01_TF_ceramic_Packages/01_Datasheet/CC8V-T1A.pdf, 2.0x1.2mm^2 package +SMD SMT crystal +0 +2 +2 +Crystal +Crystal_SMD_MicroCrystal_CC8V-T1A-2Pin_2.0x1.2mm_HandSoldering +SMD Crystal MicroCrystal CC8V-T1A/CM8V-T1A series http://www.microcrystal.com/images/_Product-Documentation/01_TF_ceramic_Packages/01_Datasheet/CC8V-T1A.pdf, hand-soldering, 2.0x1.2mm^2 package +SMD SMT crystal hand-soldering +0 +2 +2 +Crystal +Crystal_SMD_MicroCrystal_CM9V-T1A-2Pin_1.6x1.0mm +SMD Crystal MicroCrystal CM9V-T1A series http://www.microcrystal.com/images/_Product-Documentation/01_TF_ceramic_Packages/01_Datasheet/CM9V-T1A.pdf, 1.6x1.0mm^2 package +SMD SMT crystal +0 +2 +2 +Crystal +Crystal_SMD_MicroCrystal_CM9V-T1A-2Pin_1.6x1.0mm_HandSoldering +SMD Crystal MicroCrystal CM9V-T1A series http://www.microcrystal.com/images/_Product-Documentation/01_TF_ceramic_Packages/01_Datasheet/CM9V-T1A.pdf, hand-soldering, 1.6x1.0mm^2 package +SMD SMT crystal hand-soldering +0 +2 +2 +Crystal +Crystal_SMD_MicroCrystal_MS1V-T1K +SMD Watch Crystal MicroCrystal MS1V-T1K 6.1mm length 2.0mm diameter http://www.microcrystal.com/images/_Product-Documentation/03_TF_metal_Packages/01_Datasheet/MS1V-T1K.pdf +['MS1V-T1K'] +0 +3 +3 +Crystal +Crystal_SMD_MicroCrystal_MS3V-T1R +SMD Watch Crystal MicroCrystal MS3V-T1R 5.2mm length 1.4mm diameter http://www.microcrystal.com/images/_Product-Documentation/03_TF_metal_Packages/01_Datasheet/MS3V-T1R.pdf +['MS3V-T1R'] +0 +3 +3 +Crystal +Crystal_SMD_Qantek_QC5CB-2Pin_5x3.2mm +SMD Crystal Qantek QC5CB, https://www.qantek.com/tl_files/products/crystals/QC5CB.pdf +SMD SMT crystal +0 +2 +2 +Crystal +Crystal_SMD_SeikoEpson_FA238-4Pin_3.2x2.5mm +crystal Epson Toyocom FA-238 https://support.epson.biz/td/api/doc_check.php?dl=brief_fa-238v_en.pdf, 3.2x2.5mm^2 package +SMD SMT crystal +0 +4 +4 +Crystal +Crystal_SMD_SeikoEpson_FA238-4Pin_3.2x2.5mm_HandSoldering +crystal Epson Toyocom FA-238 series https://support.epson.biz/td/api/doc_check.php?dl=brief_fa-238v_en.pdf, hand-soldering, 3.2x2.5mm^2 package +SMD SMT crystal hand-soldering +0 +4 +4 +Crystal +Crystal_SMD_SeikoEpson_FA238V-4Pin_3.2x2.5mm +crystal Epson Toyocom FA-238 series https://support.epson.biz/td/api/doc_check.php?dl=brief_fa-238v_en.pdf, 3.2x2.5mm^2 package +SMD SMT crystal +0 +4 +4 +Crystal +Crystal_SMD_SeikoEpson_FA238V-4Pin_3.2x2.5mm_HandSoldering +crystal Epson Toyocom FA-238 series http://www.mouser.com/ds/2/137/1721499-465440.pdf, hand-soldering, 3.2x2.5mm^2 package +SMD SMT crystal hand-soldering +0 +4 +4 +Crystal +Crystal_SMD_SeikoEpson_MA406-4Pin_11.7x4.0mm +SMD Crystal Seiko Epson MC-506 http://media.digikey.com/pdf/Data%20Sheets/Epson%20PDFs/MA-505,506.pdf, 11.7x4.0mm^2 package +SMD SMT crystal +0 +4 +4 +Crystal +Crystal_SMD_SeikoEpson_MA406-4Pin_11.7x4.0mm_HandSoldering +SMD Crystal Seiko Epson MC-506 http://media.digikey.com/pdf/Data%20Sheets/Epson%20PDFs/MA-505,506.pdf, hand-soldering, 11.7x4.0mm^2 package +SMD SMT crystal hand-soldering +0 +4 +4 +Crystal +Crystal_SMD_SeikoEpson_MA505-2Pin_12.7x5.1mm +SMD Crystal Seiko Epson MC-505 http://media.digikey.com/pdf/Data%20Sheets/Epson%20PDFs/MA-505,506.pdf, 12.7x5.1mm^2 package +SMD SMT crystal +0 +2 +2 +Crystal +Crystal_SMD_SeikoEpson_MA505-2Pin_12.7x5.1mm_HandSoldering +SMD Crystal Seiko Epson MC-505 http://media.digikey.com/pdf/Data%20Sheets/Epson%20PDFs/MA-505,506.pdf, hand-soldering, 12.7x5.1mm^2 package +SMD SMT crystal hand-soldering +0 +2 +2 +Crystal +Crystal_SMD_SeikoEpson_MA506-4Pin_12.7x5.1mm +SMD Crystal Seiko Epson MC-506 http://media.digikey.com/pdf/Data%20Sheets/Epson%20PDFs/MA-505,506.pdf, 12.7x5.1mm^2 package +SMD SMT crystal +0 +4 +4 +Crystal +Crystal_SMD_SeikoEpson_MA506-4Pin_12.7x5.1mm_HandSoldering +SMD Crystal Seiko Epson MC-506 http://media.digikey.com/pdf/Data%20Sheets/Epson%20PDFs/MA-505,506.pdf, hand-soldering, 12.7x5.1mm^2 package +SMD SMT crystal hand-soldering +0 +4 +4 +Crystal +Crystal_SMD_SeikoEpson_MC146-4Pin_6.7x1.5mm +SMD Crystal Seiko Epson MC-146 https://support.epson.biz/td/api/doc_check.php?dl=brief_MC-156_en.pdf, 6.7x1.5mm^2 package +SMD SMT crystal +0 +4 +4 +Crystal +Crystal_SMD_SeikoEpson_MC146-4Pin_6.7x1.5mm_HandSoldering +SMD Crystal Seiko Epson MC-146 https://support.epson.biz/td/api/doc_check.php?dl=brief_MC-156_en.pdf, hand-soldering, 6.7x1.5mm^2 package +SMD SMT crystal hand-soldering +0 +4 +4 +Crystal +Crystal_SMD_SeikoEpson_MC156-4Pin_7.1x2.5mm +SMD Crystal Seiko Epson MC-156 https://support.epson.biz/td/api/doc_check.php?dl=brief_MC-156_en.pdf, 7.1x2.5mm^2 package +SMD SMT crystal +0 +4 +4 +Crystal +Crystal_SMD_SeikoEpson_MC156-4Pin_7.1x2.5mm_HandSoldering +SMD Crystal Seiko Epson MC-156 https://support.epson.biz/td/api/doc_check.php?dl=brief_MC-156_en.pdf, hand-soldering, 7.1x2.5mm^2 package +SMD SMT crystal hand-soldering +0 +4 +4 +Crystal +Crystal_SMD_SeikoEpson_MC306-4Pin_8.0x3.2mm +SMD Crystal Seiko Epson MC-306 https://support.epson.biz/td/api/doc_check.php?dl=brief_MC-306_en.pdf, 8.0x3.2mm^2 package +SMD SMT crystal +0 +4 +4 +Crystal +Crystal_SMD_SeikoEpson_MC306-4Pin_8.0x3.2mm_HandSoldering +SMD Crystal Seiko Epson MC-306 https://support.epson.biz/td/api/doc_check.php?dl=brief_MC-306_en.pdf, hand-soldering, 8.0x3.2mm^2 package +SMD SMT crystal hand-soldering +0 +4 +4 +Crystal +Crystal_SMD_SeikoEpson_MC405-2Pin_9.6x4.1mm +SMD Crystal Seiko Epson MC-405 https://support.epson.biz/td/api/doc_check.php?dl=brief_MC-306_en.pdf, 9.6x4.1mm^2 package +SMD SMT crystal +0 +2 +2 +Crystal +Crystal_SMD_SeikoEpson_MC405-2Pin_9.6x4.1mm_HandSoldering +SMD Crystal Seiko Epson MC-405 https://support.epson.biz/td/api/doc_check.php?dl=brief_MC-306_en.pdf, hand-soldering, 9.6x4.1mm^2 package +SMD SMT crystal hand-soldering +0 +2 +2 +Crystal +Crystal_SMD_SeikoEpson_MC406-4Pin_9.6x4.1mm +SMD Crystal Seiko Epson MC-406 https://support.epson.biz/td/api/doc_check.php?dl=brief_MC-306_en.pdf, 9.6x4.1mm^2 package +SMD SMT crystal +0 +4 +4 +Crystal +Crystal_SMD_SeikoEpson_MC406-4Pin_9.6x4.1mm_HandSoldering +SMD Crystal Seiko Epson MC-406 https://support.epson.biz/td/api/doc_check.php?dl=brief_MC-306_en.pdf, hand-soldering, 9.6x4.1mm^2 package +SMD SMT crystal hand-soldering +0 +4 +4 +Crystal +Crystal_SMD_SeikoEpson_TSX3225-4Pin_3.2x2.5mm +crystal Epson Toyocom TSX-3225 series https://support.epson.biz/td/api/doc_check.php?dl=brief_fa-238v_en.pdf, 3.2x2.5mm^2 package +SMD SMT crystal +0 +4 +4 +Crystal +Crystal_SMD_SeikoEpson_TSX3225-4Pin_3.2x2.5mm_HandSoldering +crystal Epson Toyocom TSX-3225 series https://support.epson.biz/td/api/doc_check.php?dl=brief_fa-238v_en.pdf, hand-soldering, 3.2x2.5mm^2 package +SMD SMT crystal hand-soldering +0 +4 +4 +Crystal +Crystal_SMD_TXC_7A-2Pin_5x3.2mm +SMD Crystal TXC 7A http://txccrystal.com/images/pdf/7a.pdf +SMD SMT crystal +0 +2 +2 +Crystal +Crystal_SMD_TXC_7M-4Pin_3.2x2.5mm +SMD Crystal TXC 7M http://www.txccrystal.com/images/pdf/7m-accuracy.pdf, 3.2x2.5mm^2 package +SMD SMT crystal +0 +4 +4 +Crystal +Crystal_SMD_TXC_7M-4Pin_3.2x2.5mm_HandSoldering +SMD Crystal TXC 7M http://www.txccrystal.com/images/pdf/7m-accuracy.pdf, hand-soldering, 3.2x2.5mm^2 package +SMD SMT crystal hand-soldering +0 +4 +4 +Crystal +Crystal_SMD_TXC_9HT11-2Pin_2.0x1.2mm +SMD Crystal TXC 9HT11 http://txccrystal.com/images/pdf/9ht11.pdf, 2.0x1.2mm^2 package +SMD SMT crystal +0 +2 +2 +Crystal +Crystal_SMD_TXC_9HT11-2Pin_2.0x1.2mm_HandSoldering +SMD Crystal TXC 9HT11 http://txccrystal.com/images/pdf/9ht11.pdf, hand-soldering, 2.0x1.2mm^2 package +SMD SMT crystal hand-soldering +0 +2 +2 +Crystal +Crystal_SMD_TXC_AX_8045-2Pin_8.0x4.5mm +http://www.txccrystal.com/images/pdf/ax-automotive.pdf +SMD SMT crystal +0 +2 +2 +Crystal +Resonator-2Pin_W6.0mm_H3.0mm +Ceramic Resomator/Filter 6.0x3.0mm^2, length*width=6.0x3.0mm^2 package, package length=6.0mm, package width=3.0mm, 2 pins +THT ceramic resonator filter +0 +2 +2 +Crystal +Resonator-2Pin_W7.0mm_H2.5mm +Ceramic Resomator/Filter 7.0x2.5mm^2, length*width=7.0x2.5mm^2 package, package length=7.0mm, package width=2.5mm, 2 pins +THT ceramic resonator filter +0 +2 +2 +Crystal +Resonator-2Pin_W8.0mm_H3.5mm +Ceramic Resomator/Filter 8.0x3.5mm^2, length*width=8.0x3.5mm^2 package, package length=8.0mm, package width=3.5mm, 2 pins +THT ceramic resonator filter +0 +2 +2 +Crystal +Resonator-2Pin_W10.0mm_H5.0mm +Ceramic Resomator/Filter 10.0x5.0 RedFrequency MG/MT/MX series, http://www.red-frequency.com/download/datenblatt/redfrequency-datenblatt-ir-zta.pdf, length*width=10.0x5.0mm^2 package, package length=10.0mm, package width=5.0mm, 2 pins +THT ceramic resonator filter +0 +2 +2 +Crystal +Resonator-3Pin_W6.0mm_H3.0mm +Ceramic Resomator/Filter 6.0x3.0mm^2, length*width=6.0x3.0mm^2 package, package length=6.0mm, package width=3.0mm, 3 pins +THT ceramic resonator filter +0 +3 +3 +Crystal +Resonator-3Pin_W7.0mm_H2.5mm +Ceramic Resomator/Filter 7.0x2.5mm^2, length*width=7.0x2.5mm^2 package, package length=7.0mm, package width=2.5mm, 3 pins +THT ceramic resonator filter +0 +3 +3 +Crystal +Resonator-3Pin_W8.0mm_H3.5mm +Ceramic Resomator/Filter 8.0x3.5mm^2, length*width=8.0x3.5mm^2 package, package length=8.0mm, package width=3.5mm, 3 pins +THT ceramic resonator filter +0 +3 +3 +Crystal +Resonator-3Pin_W10.0mm_H5.0mm +Ceramic Resomator/Filter 10.0x5.0mm^2 RedFrequency MG/MT/MX series, http://www.red-frequency.com/download/datenblatt/redfrequency-datenblatt-ir-zta.pdf, length*width=10.0x5.0mm^2 package, package length=10.0mm, package width=5.0mm, 3 pins +THT ceramic resonator filter +0 +3 +3 +Crystal +Resonator_muRata_CSTLSxxxG-3Pin_W8.0mm_H3.0mm +Ceramic Resomator/Filter Murata CSTLSxxxG, http://www.murata.com/~/media/webrenewal/support/library/catalog/products/timingdevice/ceralock/p17e.ashx, length*width=8.0x3.0mm^2 package, package length=8.0mm, package width=3.0mm, 3 pins +THT ceramic resonator filter CSTLSxxxG +0 +3 +3 +Crystal +Resonator_muRata_CSTLSxxxX-3Pin_W5.5mm_H3.0mm +Ceramic Resomator/Filter Murata CSTLSxxxX, http://www.murata.com/~/media/webrenewal/support/library/catalog/products/timingdevice/ceralock/p17e.ashx, length*width=5.5x3.0mm^2 package, package length=5.5mm, package width=3.0mm, 3 pins +THT ceramic resonator filter CSTLSxxxX +0 +3 +3 +Crystal +Resonator_muRata_DSN6-3Pin_W7.0mm_H2.5mm +Ceramic Resomator/Filter Murata DSN6, http://cdn-reichelt.de/documents/datenblatt/B400/DSN6NC51H.pdf, length*width=7.0x2.5mm^2 package, package length=7.0mm, package width=2.5mm, 3 pins +THT ceramic resonator filter DSN6 +0 +3 +3 +Crystal +Resonator_muRata_DSS6-3Pin_W7.0mm_H2.5mm +Ceramic Resomator/Filter Murata DSS6, http://cdn-reichelt.de/documents/datenblatt/B400/DSN6NC51H.pdf, length*width=7.0x2.5mm^2 package, package length=7.0mm, package width=2.5mm, 3 pins +THT ceramic resonator filter DSS6 +0 +3 +3 +Crystal +Resonator_SMD-3Pin_7.2x3.0mm +SMD Resomator/Filter 7.2x3.0mm, Murata CSTCC8M00G53-R0; 8MHz resonator, SMD, Farnell (Element 14) #1170435, http://www.farnell.com/datasheets/19296.pdf?_ga=1.247244932.122297557.1475167906, 7.2x3.0mm^2 package +SMD SMT ceramic resonator filter filter +0 +3 +3 +Crystal +Resonator_SMD-3Pin_7.2x3.0mm_HandSoldering +SMD Resomator/Filter 7.2x3.0mm, Murata CSTCC8M00G53-R0; 8MHz resonator, SMD, Farnell (Element 14) #1170435, http://www.farnell.com/datasheets/19296.pdf?_ga=1.247244932.122297557.1475167906, hand-soldering, 7.2x3.0mm^2 package +SMD SMT ceramic resonator filter filter hand-soldering +0 +3 +3 +Crystal +Resonator_SMD_muRata_CDSCB-2Pin_4.5x2.0mm +SMD Resomator/Filter Murata CDSCB, http://cdn-reichelt.de/documents/datenblatt/B400/SFECV-107.pdf, 4.5x2.0mm^2 package +SMD SMT ceramic resonator filter filter +0 +2 +2 +Crystal +Resonator_SMD_muRata_CDSCB-2Pin_4.5x2.0mm_HandSoldering +SMD Resomator/Filter Murata CDSCB, http://cdn-reichelt.de/documents/datenblatt/B400/SFECV-107.pdf, hand-soldering, 4.5x2.0mm^2 package +SMD SMT ceramic resonator filter filter hand-soldering +0 +2 +2 +Crystal +Resonator_SMD_muRata_CSTxExxV-3Pin_3.0x1.1mm +SMD Resomator/Filter Murata CSTCE, https://www.murata.com/en-eu/products/productdata/8801162264606/SPEC-CSTNE16M0VH3C000R0.pdf +SMD SMT ceramic resonator filter +0 +3 +3 +Crystal +Resonator_SMD_muRata_CSTxExxV-3Pin_3.0x1.1mm_HandSoldering +SMD Resomator/Filter Murata CSTCE, https://www.murata.com/en-eu/products/productdata/8801162264606/SPEC-CSTNE16M0VH3C000R0.pdf +SMD SMT ceramic resonator filter +0 +3 +3 +Crystal +Resonator_SMD_muRata_SFECV-3Pin_6.9x2.9mm +SMD Resomator/Filter Murata SFECV, http://cdn-reichelt.de/documents/datenblatt/B400/SFECV-107.pdf, 6.9x2.9mm^2 package +SMD SMT ceramic resonator filter filter +0 +3 +3 +Crystal +Resonator_SMD_muRata_SFECV-3Pin_6.9x2.9mm_HandSoldering +SMD Resomator/Filter Murata SFECV, http://cdn-reichelt.de/documents/datenblatt/B400/SFECV-107.pdf, hand-soldering, 6.9x2.9mm^2 package +SMD SMT ceramic resonator filter filter hand-soldering +0 +3 +3 +Crystal +Resonator_SMD_muRata_SFSKA-3Pin_7.9x3.8mm +SMD Resomator/Filter Murata SFSKA, http://cdn-reichelt.de/documents/datenblatt/B400/SFECV-107.pdf, 7.9x3.8mm^2 package +SMD SMT ceramic resonator filter filter +0 +3 +3 +Crystal +Resonator_SMD_muRata_SFSKA-3Pin_7.9x3.8mm_HandSoldering +SMD Resomator/Filter Murata SFSKA, http://cdn-reichelt.de/documents/datenblatt/B400/SFECV-107.pdf, hand-soldering, 7.9x3.8mm^2 package +SMD SMT ceramic resonator filter filter hand-soldering +0 +3 +3 +Crystal +Resonator_SMD_muRata_TPSKA-3Pin_7.9x3.8mm +SMD Resomator/Filter Murata TPSKA, http://cdn-reichelt.de/documents/datenblatt/B400/SFECV-107.pdf, 7.9x3.8mm^2 package +SMD SMT ceramic resonator filter filter +0 +3 +3 +Crystal +Resonator_SMD_muRata_TPSKA-3Pin_7.9x3.8mm_HandSoldering +SMD Resomator/Filter Murata TPSKA, http://cdn-reichelt.de/documents/datenblatt/B400/SFECV-107.pdf, hand-soldering, 7.9x3.8mm^2 package +SMD SMT ceramic resonator filter filter hand-soldering +0 +3 +3 +Diode_SMD +Diode_Bridge_Diotec_ABS +SMD diode bridge ABS (Diotec), see https://diotec.com/tl_files/diotec/files/pdf/datasheets/abs2.pdf +ABS MBLS +0 +4 +4 +Diode_SMD +Diode_Bridge_Diotec_MicroDil_3.0x3.0x1.8mm +SMD package Diotec Diotec MicroDil, body 3.0x3.0x1.8mm (e.g. diode bridge), see https://diotec.com/tl_files/diotec/files/pdf/datasheets/mys40.pdf +Diotec MicroDil diode bridge +0 +4 +4 +Diode_SMD +Diode_Bridge_Diotec_SO-DIL-Slim +SMD diode bridge Diotec SO-DIL Slim, see https://diotec.com/tl_files/diotec/files/pdf/datasheets/b40fs.pdf +DFS SO-DIL Slim +0 +4 +4 +Diode_SMD +Diode_Bridge_Vishay_DFS +SMD diode bridge DFS, see http://www.vishay.com/docs/88854/padlayouts.pdf +DFS +0 +4 +4 +Diode_SMD +Diode_Bridge_Vishay_DFSFlat +SMD diode bridge Low Profile DFS "Flat", see http://www.vishay.com/docs/88874/dfl15005.pdf +DFS +0 +4 +4 +Diode_SMD +Diode_Bridge_Vishay_MBLS +SMD diode bridge MBLS, see http://www.vishay.com/docs/89959/mbl104s.pdf http://www.vishay.com/docs/88854/padlayouts.pdf +DFS +0 +4 +4 +Diode_SMD +D_0201_0603Metric +Diode SMD 0201 (0603 Metric), square (rectangular) end terminal, IPC_7351 nominal, (Body size source: https://www.vishay.com/docs/20052/crcw0201e3.pdf), generated with kicad-footprint-generator +diode +0 +4 +2 +Diode_SMD +D_0402_1005Metric +Diode SMD 0402 (1005 Metric), square (rectangular) end terminal, IPC_7351 nominal, (Body size source: http://www.tortai-tech.com/upload/download/2011102023233369053.pdf), generated with kicad-footprint-generator +diode +0 +2 +2 +Diode_SMD +D_0603_1608Metric +Diode SMD 0603 (1608 Metric), square (rectangular) end terminal, IPC_7351 nominal, (Body size source: http://www.tortai-tech.com/upload/download/2011102023233369053.pdf), generated with kicad-footprint-generator +diode +0 +2 +2 +Diode_SMD +D_0603_1608Metric_Castellated +Diode SMD 0603 (1608 Metric), castellated end terminal, IPC_7351 nominal, (Body size source: http://www.tortai-tech.com/upload/download/2011102023233369053.pdf), generated with kicad-footprint-generator +diode castellated +0 +2 +2 +Diode_SMD +D_0603_1608Metric_Pad1.05x0.95mm_HandSolder +Diode SMD 0603 (1608 Metric), square (rectangular) end terminal, IPC_7351 nominal, (Body size source: http://www.tortai-tech.com/upload/download/2011102023233369053.pdf), generated with kicad-footprint-generator +diode handsolder +0 +2 +2 +Diode_SMD +D_0805_2012Metric +Diode SMD 0805 (2012 Metric), square (rectangular) end terminal, IPC_7351 nominal, (Body size source: https://docs.google.com/spreadsheets/d/1BsfQQcO9C6DZCsRaXUlFlo91Tg2WpOkGARC1WS5S8t0/edit?usp=sharing), generated with kicad-footprint-generator +diode +0 +2 +2 +Diode_SMD +D_0805_2012Metric_Castellated +Diode SMD 0805 (2012 Metric), castellated end terminal, IPC_7351 nominal, (Body size source: https://docs.google.com/spreadsheets/d/1BsfQQcO9C6DZCsRaXUlFlo91Tg2WpOkGARC1WS5S8t0/edit?usp=sharing), generated with kicad-footprint-generator +diode castellated +0 +2 +2 +Diode_SMD +D_0805_2012Metric_Pad1.15x1.40mm_HandSolder +Diode SMD 0805 (2012 Metric), square (rectangular) end terminal, IPC_7351 nominal, (Body size source: https://docs.google.com/spreadsheets/d/1BsfQQcO9C6DZCsRaXUlFlo91Tg2WpOkGARC1WS5S8t0/edit?usp=sharing), generated with kicad-footprint-generator +diode handsolder +0 +2 +2 +Diode_SMD +D_01005_0402Metric +Diode SMD 01005 (0402 Metric), square (rectangular) end terminal, IPC_7351 nominal, (Body size source: http://www.vishay.com/docs/20056/crcw01005e3.pdf), generated with kicad-footprint-generator +diode +0 +4 +2 +Diode_SMD +D_1206_3216Metric +Diode SMD 1206 (3216 Metric), square (rectangular) end terminal, IPC_7351 nominal, (Body size source: http://www.tortai-tech.com/upload/download/2011102023233369053.pdf), generated with kicad-footprint-generator +diode +0 +2 +2 +Diode_SMD +D_1206_3216Metric_Castellated +Diode SMD 1206 (3216 Metric), castellated end terminal, IPC_7351 nominal, (Body size source: http://www.tortai-tech.com/upload/download/2011102023233369053.pdf), generated with kicad-footprint-generator +diode castellated +0 +2 +2 +Diode_SMD +D_1206_3216Metric_Pad1.42x1.75mm_HandSolder +Diode SMD 1206 (3216 Metric), square (rectangular) end terminal, IPC_7351 nominal, (Body size source: http://www.tortai-tech.com/upload/download/2011102023233369053.pdf), generated with kicad-footprint-generator +diode handsolder +0 +2 +2 +Diode_SMD +D_1210_3225Metric +Diode SMD 1210 (3225 Metric), square (rectangular) end terminal, IPC_7351 nominal, (Body size source: http://www.tortai-tech.com/upload/download/2011102023233369053.pdf), generated with kicad-footprint-generator +diode +0 +2 +2 +Diode_SMD +D_1210_3225Metric_Castellated +Diode SMD 1210 (3225 Metric), castellated end terminal, IPC_7351 nominal, (Body size source: http://www.tortai-tech.com/upload/download/2011102023233369053.pdf), generated with kicad-footprint-generator +diode castellated +0 +2 +2 +Diode_SMD +D_1210_3225Metric_Pad1.42x2.65mm_HandSolder +Diode SMD 1210 (3225 Metric), square (rectangular) end terminal, IPC_7351 nominal, (Body size source: http://www.tortai-tech.com/upload/download/2011102023233369053.pdf), generated with kicad-footprint-generator +diode handsolder +0 +2 +2 +Diode_SMD +D_1806_4516Metric +Diode SMD 1806 (4516 Metric), square (rectangular) end terminal, IPC_7351 nominal, (Body size source: https://www.modelithics.com/models/Vendor/MuRata/BLM41P.pdf), generated with kicad-footprint-generator +diode +0 +2 +2 +Diode_SMD +D_1806_4516Metric_Castellated +Diode SMD 1806 (4516 Metric), castellated end terminal, IPC_7351 nominal, (Body size source: https://www.modelithics.com/models/Vendor/MuRata/BLM41P.pdf), generated with kicad-footprint-generator +diode castellated +0 +2 +2 +Diode_SMD +D_1806_4516Metric_Pad1.57x1.80mm_HandSolder +Diode SMD 1806 (4516 Metric), square (rectangular) end terminal, IPC_7351 nominal, (Body size source: https://www.modelithics.com/models/Vendor/MuRata/BLM41P.pdf), generated with kicad-footprint-generator +diode handsolder +0 +2 +2 +Diode_SMD +D_1812_4532Metric +Diode SMD 1812 (4532 Metric), square (rectangular) end terminal, IPC_7351 nominal, (Body size source: https://www.nikhef.nl/pub/departments/mt/projects/detectorR_D/dtddice/ERJ2G.pdf), generated with kicad-footprint-generator +diode +0 +2 +2 +Diode_SMD +D_1812_4532Metric_Castellated +Diode SMD 1812 (4532 Metric), castellated end terminal, IPC_7351 nominal, (Body size source: https://www.nikhef.nl/pub/departments/mt/projects/detectorR_D/dtddice/ERJ2G.pdf), generated with kicad-footprint-generator +diode castellated +0 +2 +2 +Diode_SMD +D_1812_4532Metric_Pad1.30x3.40mm_HandSolder +Diode SMD 1812 (4532 Metric), square (rectangular) end terminal, IPC_7351 nominal, (Body size source: https://www.nikhef.nl/pub/departments/mt/projects/detectorR_D/dtddice/ERJ2G.pdf), generated with kicad-footprint-generator +diode handsolder +0 +2 +2 +Diode_SMD +D_2010_5025Metric +Diode SMD 2010 (5025 Metric), square (rectangular) end terminal, IPC_7351 nominal, (Body size source: http://www.tortai-tech.com/upload/download/2011102023233369053.pdf), generated with kicad-footprint-generator +diode +0 +2 +2 +Diode_SMD +D_2010_5025Metric_Castellated +Diode SMD 2010 (5025 Metric), castellated end terminal, IPC_7351 nominal, (Body size source: http://www.tortai-tech.com/upload/download/2011102023233369053.pdf), generated with kicad-footprint-generator +diode castellated +0 +2 +2 +Diode_SMD +D_2010_5025Metric_Pad1.52x2.65mm_HandSolder +Diode SMD 2010 (5025 Metric), square (rectangular) end terminal, IPC_7351 nominal, (Body size source: http://www.tortai-tech.com/upload/download/2011102023233369053.pdf), generated with kicad-footprint-generator +diode handsolder +0 +2 +2 +Diode_SMD +D_2114_3652Metric +Diode SMD 2114 (3652 Metric), square (rectangular) end terminal, IPC_7351 nominal, (Body size from: http://datasheets.avx.com/schottky.pdf), generated with kicad-footprint-generator +diode +0 +2 +2 +Diode_SMD +D_2114_3652Metric_Castellated +Diode SMD 2114 (3652 Metric), castellated end terminal, IPC_7351 nominal, (Body size from: http://datasheets.avx.com/schottky.pdf), generated with kicad-footprint-generator +diode castellated +0 +2 +2 +Diode_SMD +D_2114_3652Metric_Pad1.85x3.75mm_HandSolder +Diode SMD 2114 (3652 Metric), square (rectangular) end terminal, IPC_7351 nominal, (Body size from: http://datasheets.avx.com/schottky.pdf), generated with kicad-footprint-generator +diode handsolder +0 +2 +2 +Diode_SMD +D_2512_6332Metric +Diode SMD 2512 (6332 Metric), square (rectangular) end terminal, IPC_7351 nominal, (Body size source: http://www.tortai-tech.com/upload/download/2011102023233369053.pdf), generated with kicad-footprint-generator +diode +0 +2 +2 +Diode_SMD +D_2512_6332Metric_Castellated +Diode SMD 2512 (6332 Metric), castellated end terminal, IPC_7351 nominal, (Body size source: http://www.tortai-tech.com/upload/download/2011102023233369053.pdf), generated with kicad-footprint-generator +diode castellated +0 +2 +2 +Diode_SMD +D_2512_6332Metric_Pad1.52x3.35mm_HandSolder +Diode SMD 2512 (6332 Metric), square (rectangular) end terminal, IPC_7351 nominal, (Body size source: http://www.tortai-tech.com/upload/download/2011102023233369053.pdf), generated with kicad-footprint-generator +diode handsolder +0 +2 +2 +Diode_SMD +D_2816_7142Metric +Diode SMD 2816 (7142 Metric), square (rectangular) end terminal, IPC_7351 nominal, (Body size from: https://www.vishay.com/docs/30100/wsl.pdf), generated with kicad-footprint-generator +diode +0 +2 +2 +Diode_SMD +D_2816_7142Metric_Castellated +Diode SMD 2816 (7142 Metric), castellated end terminal, IPC_7351 nominal, (Body size from: https://www.vishay.com/docs/30100/wsl.pdf), generated with kicad-footprint-generator +diode castellated +0 +2 +2 +Diode_SMD +D_2816_7142Metric_Pad3.20x4.45mm_HandSolder +Diode SMD 2816 (7142 Metric), square (rectangular) end terminal, IPC_7351 nominal, (Body size from: https://www.vishay.com/docs/30100/wsl.pdf), generated with kicad-footprint-generator +diode handsolder +0 +2 +2 +Diode_SMD +D_3220_8050Metric +Diode SMD 3220 (8050 Metric), square (rectangular) end terminal, IPC_7351 nominal, (Body size from: http://datasheets.avx.com/schottky.pdf), generated with kicad-footprint-generator +diode +0 +2 +2 +Diode_SMD +D_3220_8050Metric_Castellated +Diode SMD 3220 (8050 Metric), castellated end terminal, IPC_7351 nominal, (Body size from: http://datasheets.avx.com/schottky.pdf), generated with kicad-footprint-generator +diode castellated +0 +2 +2 +Diode_SMD +D_3220_8050Metric_Pad2.65x5.15mm_HandSolder +Diode SMD 3220 (8050 Metric), square (rectangular) end terminal, IPC_7351 nominal, (Body size from: http://datasheets.avx.com/schottky.pdf), generated with kicad-footprint-generator +diode handsolder +0 +2 +2 +Diode_SMD +D_MELF +Diode, MELF,, +Diode MELF +0 +2 +2 +Diode_SMD +D_MELF-RM10_Universal_Handsoldering +Diode, Universal, MELF, RM10, Handsoldering, SMD, Thruhole, +Diode Universal MELF RM10 Handsoldering SMD Thruhole +0 +2 +2 +Diode_SMD +D_MELF_Handsoldering +Diode MELF Handsoldering +Diode MELF Handsoldering +0 +2 +2 +Diode_SMD +D_MicroMELF +Diode, MicroMELF, http://www.vishay.com/docs/85597/bzm55-se.pdf +MicroMELF Diode +0 +2 +2 +Diode_SMD +D_MicroMELF_Hadsoldering +Diode, MicroMELF, hand-soldering, http://www.vishay.com/docs/85597/bzm55-se.pdf +MicroMELF Diode +0 +2 +2 +Diode_SMD +D_MiniMELF +Diode Mini-MELF +Diode Mini-MELF +0 +2 +2 +Diode_SMD +D_MiniMELF_Handsoldering +Diode Mini-MELF Handsoldering +Diode Mini-MELF Handsoldering +0 +2 +2 +Diode_SMD +D_PowerDI-123 +http://www.diodes.com/_files/datasheets/ds30497.pdf +PowerDI diode vishay +0 +2 +2 +Diode_SMD +D_Powermite2_AK +Microsemi Powermite 2 SMD power package (https://www.microsemi.com/packaging-information/partpackage/details?pid=5341) +PowerMite2 +0 +2 +2 +Diode_SMD +D_Powermite2_KA +Microsemi Powermite 2 SMD power package (https://www.microsemi.com/packaging-information/partpackage/details?pid=5341) +PowerMite2 +0 +2 +2 +Diode_SMD +D_Powermite3 +Microsemi Powermite 3 SMD power package (https://www.microsemi.com/packaging-information/partpackage/details?pid=5340) +PowerMite3 +0 +3 +3 +Diode_SMD +D_Powermite_AK +Microsemi Powermite SMD power package (https://www.microsemi.com/packaging-information/partpackage/details?pid=5339, https://www.onsemi.com/pub/Collateral/457-04.PDF) +Powermite +0 +2 +2 +Diode_SMD +D_Powermite_KA +Microsemi Powermite SMD power package (https://www.microsemi.com/packaging-information/partpackage/details?pid=5339, https://www.onsemi.com/pub/Collateral/457-04.PDF) +Powermite +0 +2 +2 +Diode_SMD +D_QFN_3.3x3.3mm_P0.65mm +QFN, diode, 3.3x3.3x1mm (https://www.wolfspeed.com/media/downloads/846/C3D1P7060Q.pdf) +diode qfn 3.3 +0 +3 +2 +Diode_SMD +D_SC-80 +JEITA SC-80 +SC-80 +0 +2 +2 +Diode_SMD +D_SC-80_HandSoldering +JEITA SC-80 +SC-80 +0 +2 +2 +Diode_SMD +D_SMA +Diode SMA (DO-214AC) +Diode SMA (DO-214AC) +0 +2 +2 +Diode_SMD +D_SMA-SMB_Universal_Handsoldering +Diode, Universal, SMA (DO-214AC) or SMB (DO-214AA), Handsoldering, +Diode Universal SMA (DO-214AC) SMB (DO-214AA) Handsoldering +0 +2 +2 +Diode_SMD +D_SMA_Handsoldering +Diode SMA (DO-214AC) Handsoldering +Diode SMA (DO-214AC) Handsoldering +0 +2 +2 +Diode_SMD +D_SMB +Diode SMB (DO-214AA) +Diode SMB (DO-214AA) +0 +2 +2 +Diode_SMD +D_SMB-SMC_Universal_Handsoldering +Diode, Universal, SMB(DO-214AA) or SMC (DO-214AB), Handsoldering, +Diode Universal SMB(DO-214AA) SMC (DO-214AB) Handsoldering +0 +2 +2 +Diode_SMD +D_SMB_Handsoldering +Diode SMB (DO-214AA) Handsoldering +Diode SMB (DO-214AA) Handsoldering +0 +2 +2 +Diode_SMD +D_SMB_Modified +Diode SMB (DO-214AA) Modified (http://www.littelfuse.com/~/media/electronics/datasheets/sidactors/littelfuse_sidactor_battrax_positive_negative_modified_do_214_datasheet.pdf.pdf) +Diode SMB (DO-214AA) +0 +3 +3 +Diode_SMD +D_SMC +Diode SMC (DO-214AB) +Diode SMC (DO-214AB) +0 +2 +2 +Diode_SMD +D_SMC-RM10_Universal_Handsoldering +Diode, Universal, SMC (DO-214AB), RM10, Handsoldering, SMD, Thruhole +Diode Universal SMC (DO-214AB) RM10 Handsoldering SMD Thruhole +0 +2 +2 +Diode_SMD +D_SMC_Handsoldering +Diode SMC (DO-214AB) Handsoldering +Diode SMC (DO-214AB) Handsoldering +0 +2 +2 +Diode_SMD +D_SOD-110 +SOD-110 +SOD-110 +0 +2 +2 +Diode_SMD +D_SOD-123 +SOD-123 +SOD-123 +0 +2 +2 +Diode_SMD +D_SOD-123F +D_SOD-123F +D_SOD-123F +0 +2 +2 +Diode_SMD +D_SOD-323 +SOD-323 +SOD-323 +0 +2 +2 +Diode_SMD +D_SOD-323F +SOD-323F http://www.nxp.com/documents/outline_drawing/SOD323F.pdf +SOD-323F +0 +2 +2 +Diode_SMD +D_SOD-323_HandSoldering +SOD-323 +SOD-323 +0 +2 +2 +Diode_SMD +D_SOD-523 +http://www.diodes.com/datasheets/ap02001.pdf p.144 +Diode SOD523 +0 +2 +2 +Diode_SMD +D_SOT-23_ANK +SOT-23, Single Diode +SOT-23 +0 +3 +2 +Diode_SMD +D_SOT-23_NKA +SOT-23, Single Diode +SOT-23 +0 +3 +2 +Diode_SMD +D_TUMD2 +ROHM - TUMD2 +TUMD2 +0 +2 +2 +Diode_SMD +Littelfuse_PolyZen-LS +http://m.littelfuse.com/~/media/electronics/datasheets/polyzen_devices/littelfuse_polyzen_standard_polyzen_catalog_datasheet.pdf.pdf +Diode Polymer Protected Zener Diode Littelfuse LS +0 +3 +3 +Diode_THT +Diode_Bridge_15.1x15.1x6.3mm_P10.9mm +Single phase bridge rectifier case 15.1x15.1mm, pitch 10.9mm, see https://diotec.com/tl_files/diotec/files/pdf/datasheets/pb1000.pdf +Diode Bridge PB10xxS +0 +4 +4 +Diode_THT +Diode_Bridge_15.2x15.2x6.3mm_P10.9mm +Single phase bridge rectifier case 15.2x15.2mm, pitch 10.9mm, see https://diotec.com/tl_files/diotec/files/pdf/datasheets/kbpc600.pdf +Diode Bridge KBPC6xx +0 +4 +4 +Diode_THT +Diode_Bridge_15.7x15.7x6.3mm_P10.8mm +Single phase bridge rectifier case 15.7x15.7 +Diode Bridge +0 +4 +4 +Diode_THT +Diode_Bridge_16.7x16.7x6.3mm_P10.8mm +Single phase bridge rectifier case 16.7x16.7 +Diode Bridge +0 +4 +4 +Diode_THT +Diode_Bridge_19.0x3.5x10.0mm_P5.0mm +Vishay GBU rectifier package, 5.08mm pitch, see http://www.vishay.com/docs/88606/g3sba20.pdf +Vishay GBU rectifier diode bridge +0 +4 +4 +Diode_THT +Diode_Bridge_19.0x19.0x6.8mm_P12.7mm +Single phase bridge rectifier case 19x19mm, pitch 12.7mm, see https://diotec.com/tl_files/diotec/files/pdf/datasheets/pb1000.pdf +Diode Bridge PB10xx +0 +4 +4 +Diode_THT +Diode_Bridge_28.6x28.6x7.3mm_P18.0mm_P11.6mm +Single phase bridge rectifier case 28.6x28.6mm, pitch 18.0mm & 11.6mm, see https://diotec.com/tl_files/diotec/files/pdf/datasheets/kbpc1500fw.pdf +Diode Bridge KBPCxxxxWP +0 +4 +4 +Diode_THT +Diode_Bridge_32.0x5.6x17.0mm_P10.0mm_P7.5mm +Diotec 32x5.6x17mm rectifier package, 7.5mm/10mm pitch, see https://diotec.com/tl_files/diotec/files/pdf/datasheets/b40c3700.pdf +Diotec rectifier diode bridge +0 +4 +4 +Diode_THT +Diode_Bridge_DIP-4_W5.08mm_P2.54mm +4-lead dip package for diode bridges, row spacing 5.08mm, pin-spacing 2.54mm, see http://www.vishay.com/docs/88898/b2m.pdf +DIL DIP PDIP 5.08mm 2.54 +0 +4 +4 +Diode_THT +Diode_Bridge_DIP-4_W7.62mm_P5.08mm +4-lead dip package for diode bridges, row spacing 7.62 mm (300 mils), see http://cdn-reichelt.de/documents/datenblatt/A400/HDBL101G_20SERIES-TSC.pdf +DIL DIP PDIP 5.08mm 7.62mm 300mil +0 +4 +4 +Diode_THT +Diode_Bridge_Round_D8.9mm +4-lead round diode bridge package, diameter 8.9mm, pin pitch 5.08mm, see http://cdn-reichelt.de/documents/datenblatt/A400/W005M-W10M_SEP.PDF +diode bridge 8.9mm 8.85mm WOB pitch 5.08mm +0 +4 +4 +Diode_THT +Diode_Bridge_Round_D9.0mm +4-lead round diode bridge package, diameter 9.0mm, pin pitch 5.0mm, see https://diotec.com/tl_files/diotec/files/pdf/datasheets/b40r.pdf +diode bridge 9.0mm 8.85mm WOB pitch 5.0mm +0 +4 +4 +Diode_THT +Diode_Bridge_Round_D9.8mm +4-lead round diode bridge package, diameter 9.8mm, pin pitch 5.08mm, see http://www.vishay.com/docs/88769/woo5g.pdf +diode bridge 9.8mm WOG pitch 5.08mm +0 +4 +4 +Diode_THT +Diode_Bridge_Vishay_GBL +Vishay GBL rectifier package, 5.08mm pitch, see http://www.vishay.com/docs/88609/gbl005.pdf +Vishay GBL rectifier diode bridge +0 +4 +4 +Diode_THT +Diode_Bridge_Vishay_GBU +Vishay GBU rectifier package, 5.08mm pitch, see http://www.vishay.com/docs/88606/g3sba20.pdf +Vishay GBU rectifier diode bridge +0 +4 +4 +Diode_THT +Diode_Bridge_Vishay_KBL +Vishay KBL rectifier package, 5.08mm pitch, see http://www.vishay.com/docs/88655/kbl005.pdf +Vishay KBL rectifier diode bridge +0 +4 +4 +Diode_THT +Diode_Bridge_Vishay_KBPC1 +Single phase bridge rectifier case KBPC1, see http://www.vishay.com/docs/93585/vs-kbpc1series.pdf +Diode Bridge +0 +4 +4 +Diode_THT +Diode_Bridge_Vishay_KBPC6 +Single phase bridge rectifier case KBPC6, see http://www.vishay.com/docs/93585/vs-kbpc1series.pdf +Diode Bridge +0 +4 +4 +Diode_THT +Diode_Bridge_Vishay_KBU +Vishay KBU rectifier package, 5.08mm pitch, see http://www.vishay.com/docs/88656/kbu4.pdf +Vishay KBU rectifier diode bridge +0 +4 +4 +Diode_THT +D_5KPW_P7.62mm_Vertical_AnodeUp +Diode, 5KPW series, Axial, Vertical, pin pitch=7.62mm, , length*diameter=9*8mm^2, , http://www.diodes.com/_files/packages/8686949.gif +Diode 5KPW series Axial Vertical pin pitch 7.62mm length 9mm diameter 8mm +0 +2 +2 +Diode_THT +D_5KPW_P7.62mm_Vertical_KathodeUp +Diode, 5KPW series, Axial, Vertical, pin pitch=7.62mm, , length*diameter=9*8mm^2, , http://www.diodes.com/_files/packages/8686949.gif +Diode 5KPW series Axial Vertical pin pitch 7.62mm length 9mm diameter 8mm +0 +2 +2 +Diode_THT +D_5KPW_P12.70mm_Horizontal +Diode, 5KPW series, Axial, Horizontal, pin pitch=12.7mm, , length*diameter=9*8mm^2, , http://www.diodes.com/_files/packages/8686949.gif +Diode 5KPW series Axial Horizontal pin pitch 12.7mm length 9mm diameter 8mm +0 +2 +2 +Diode_THT +D_5KP_P7.62mm_Vertical_AnodeUp +Diode, 5KP series, Axial, Vertical, pin pitch=7.62mm, , length*diameter=7.62*9.53mm^2, , http://www.diodes.com/_files/packages/8686949.gif +Diode 5KP series Axial Vertical pin pitch 7.62mm length 7.62mm diameter 9.53mm +0 +2 +2 +Diode_THT +D_5KP_P7.62mm_Vertical_KathodeUp +Diode, 5KP series, Axial, Vertical, pin pitch=7.62mm, , length*diameter=7.62*9.53mm^2, , http://www.diodes.com/_files/packages/8686949.gif +Diode 5KP series Axial Vertical pin pitch 7.62mm length 7.62mm diameter 9.53mm +0 +2 +2 +Diode_THT +D_5KP_P10.16mm_Horizontal +Diode, 5KP series, Axial, Horizontal, pin pitch=10.16mm, , length*diameter=7.62*9.53mm^2, , http://www.diodes.com/_files/packages/8686949.gif +Diode 5KP series Axial Horizontal pin pitch 10.16mm length 7.62mm diameter 9.53mm +0 +2 +2 +Diode_THT +D_5KP_P12.70mm_Horizontal +Diode, 5KP series, Axial, Horizontal, pin pitch=12.7mm, , length*diameter=7.62*9.53mm^2, , http://www.diodes.com/_files/packages/8686949.gif +Diode 5KP series Axial Horizontal pin pitch 12.7mm length 7.62mm diameter 9.53mm +0 +2 +2 +Diode_THT +D_5W_P5.08mm_Vertical_AnodeUp +Diode, 5W series, Axial, Vertical, pin pitch=5.08mm, , length*diameter=8.9*3.7mm^2, , http://www.diodes.com/_files/packages/8686949.gif +Diode 5W series Axial Vertical pin pitch 5.08mm length 8.9mm diameter 3.7mm +0 +2 +2 +Diode_THT +D_5W_P5.08mm_Vertical_KathodeUp +Diode, 5W series, Axial, Vertical, pin pitch=5.08mm, , length*diameter=8.9*3.7mm^2, , http://www.diodes.com/_files/packages/8686949.gif +Diode 5W series Axial Vertical pin pitch 5.08mm length 8.9mm diameter 3.7mm +0 +2 +2 +Diode_THT +D_5W_P10.16mm_Horizontal +Diode, 5W series, Axial, Horizontal, pin pitch=10.16mm, , length*diameter=8.9*3.7mm^2, , http://www.diodes.com/_files/packages/8686949.gif +Diode 5W series Axial Horizontal pin pitch 10.16mm length 8.9mm diameter 3.7mm +0 +2 +2 +Diode_THT +D_5W_P12.70mm_Horizontal +Diode, 5W series, Axial, Horizontal, pin pitch=12.7mm, , length*diameter=8.9*3.7mm^2, , http://www.diodes.com/_files/packages/8686949.gif +Diode 5W series Axial Horizontal pin pitch 12.7mm length 8.9mm diameter 3.7mm +0 +2 +2 +Diode_THT +D_A-405_P2.54mm_Vertical_AnodeUp +Diode, A-405 series, Axial, Vertical, pin pitch=2.54mm, , length*diameter=5.2*2.7mm^2, , http://www.diodes.com/_files/packages/A-405.pdf +Diode A-405 series Axial Vertical pin pitch 2.54mm length 5.2mm diameter 2.7mm +0 +2 +2 +Diode_THT +D_A-405_P2.54mm_Vertical_KathodeUp +Diode, A-405 series, Axial, Vertical, pin pitch=2.54mm, , length*diameter=5.2*2.7mm^2, , http://www.diodes.com/_files/packages/A-405.pdf +Diode A-405 series Axial Vertical pin pitch 2.54mm length 5.2mm diameter 2.7mm +0 +2 +2 +Diode_THT +D_A-405_P5.08mm_Vertical_AnodeUp +Diode, A-405 series, Axial, Vertical, pin pitch=5.08mm, , length*diameter=5.2*2.7mm^2, , http://www.diodes.com/_files/packages/A-405.pdf +Diode A-405 series Axial Vertical pin pitch 5.08mm length 5.2mm diameter 2.7mm +0 +2 +2 +Diode_THT +D_A-405_P5.08mm_Vertical_KathodeUp +Diode, A-405 series, Axial, Vertical, pin pitch=5.08mm, , length*diameter=5.2*2.7mm^2, , http://www.diodes.com/_files/packages/A-405.pdf +Diode A-405 series Axial Vertical pin pitch 5.08mm length 5.2mm diameter 2.7mm +0 +2 +2 +Diode_THT +D_A-405_P7.62mm_Horizontal +Diode, A-405 series, Axial, Horizontal, pin pitch=7.62mm, , length*diameter=5.2*2.7mm^2, , http://www.diodes.com/_files/packages/A-405.pdf +Diode A-405 series Axial Horizontal pin pitch 7.62mm length 5.2mm diameter 2.7mm +0 +2 +2 +Diode_THT +D_A-405_P10.16mm_Horizontal +Diode, A-405 series, Axial, Horizontal, pin pitch=10.16mm, , length*diameter=5.2*2.7mm^2, , http://www.diodes.com/_files/packages/A-405.pdf +Diode A-405 series Axial Horizontal pin pitch 10.16mm length 5.2mm diameter 2.7mm +0 +2 +2 +Diode_THT +D_A-405_P12.70mm_Horizontal +Diode, A-405 series, Axial, Horizontal, pin pitch=12.7mm, , length*diameter=5.2*2.7mm^2, , http://www.diodes.com/_files/packages/A-405.pdf +Diode A-405 series Axial Horizontal pin pitch 12.7mm length 5.2mm diameter 2.7mm +0 +2 +2 +Diode_THT +D_DO-15_P2.54mm_Vertical_AnodeUp +Diode, DO-15 series, Axial, Vertical, pin pitch=2.54mm, , length*diameter=7.6*3.6mm^2, , http://www.diodes.com/_files/packages/DO-15.pdf +Diode DO-15 series Axial Vertical pin pitch 2.54mm length 7.6mm diameter 3.6mm +0 +2 +2 +Diode_THT +D_DO-15_P2.54mm_Vertical_KathodeUp +Diode, DO-15 series, Axial, Vertical, pin pitch=2.54mm, , length*diameter=7.6*3.6mm^2, , http://www.diodes.com/_files/packages/DO-15.pdf +Diode DO-15 series Axial Vertical pin pitch 2.54mm length 7.6mm diameter 3.6mm +0 +2 +2 +Diode_THT +D_DO-15_P3.81mm_Vertical_AnodeUp +Diode, DO-15 series, Axial, Vertical, pin pitch=3.81mm, , length*diameter=7.6*3.6mm^2, , http://www.diodes.com/_files/packages/DO-15.pdf +Diode DO-15 series Axial Vertical pin pitch 3.81mm length 7.6mm diameter 3.6mm +0 +2 +2 +Diode_THT +D_DO-15_P3.81mm_Vertical_KathodeUp +Diode, DO-15 series, Axial, Vertical, pin pitch=3.81mm, , length*diameter=7.6*3.6mm^2, , http://www.diodes.com/_files/packages/DO-15.pdf +Diode DO-15 series Axial Vertical pin pitch 3.81mm length 7.6mm diameter 3.6mm +0 +2 +2 +Diode_THT +D_DO-15_P5.08mm_Vertical_AnodeUp +Diode, DO-15 series, Axial, Vertical, pin pitch=5.08mm, , length*diameter=7.6*3.6mm^2, , http://www.diodes.com/_files/packages/DO-15.pdf +Diode DO-15 series Axial Vertical pin pitch 5.08mm length 7.6mm diameter 3.6mm +0 +2 +2 +Diode_THT +D_DO-15_P5.08mm_Vertical_KathodeUp +Diode, DO-15 series, Axial, Vertical, pin pitch=5.08mm, , length*diameter=7.6*3.6mm^2, , http://www.diodes.com/_files/packages/DO-15.pdf +Diode DO-15 series Axial Vertical pin pitch 5.08mm length 7.6mm diameter 3.6mm +0 +2 +2 +Diode_THT +D_DO-15_P10.16mm_Horizontal +Diode, DO-15 series, Axial, Horizontal, pin pitch=10.16mm, , length*diameter=7.6*3.6mm^2, , http://www.diodes.com/_files/packages/DO-15.pdf +Diode DO-15 series Axial Horizontal pin pitch 10.16mm length 7.6mm diameter 3.6mm +0 +2 +2 +Diode_THT +D_DO-15_P12.70mm_Horizontal +Diode, DO-15 series, Axial, Horizontal, pin pitch=12.7mm, , length*diameter=7.6*3.6mm^2, , http://www.diodes.com/_files/packages/DO-15.pdf +Diode DO-15 series Axial Horizontal pin pitch 12.7mm length 7.6mm diameter 3.6mm +0 +2 +2 +Diode_THT +D_DO-15_P15.24mm_Horizontal +Diode, DO-15 series, Axial, Horizontal, pin pitch=15.24mm, , length*diameter=7.6*3.6mm^2, , http://www.diodes.com/_files/packages/DO-15.pdf +Diode DO-15 series Axial Horizontal pin pitch 15.24mm length 7.6mm diameter 3.6mm +0 +2 +2 +Diode_THT +D_DO-27_P5.08mm_Vertical_AnodeUp +Diode, DO-27 series, Axial, Vertical, pin pitch=5.08mm, , length*diameter=9.52*5.33mm^2, , http://www.slottechforum.com/slotinfo/Techstuff/CD2%20Diodes%20and%20Transistors/Cases/Diode%20DO-27.jpg +Diode DO-27 series Axial Vertical pin pitch 5.08mm length 9.52mm diameter 5.33mm +0 +2 +2 +Diode_THT +D_DO-27_P5.08mm_Vertical_KathodeUp +Diode, DO-27 series, Axial, Vertical, pin pitch=5.08mm, , length*diameter=9.52*5.33mm^2, , http://www.slottechforum.com/slotinfo/Techstuff/CD2%20Diodes%20and%20Transistors/Cases/Diode%20DO-27.jpg +Diode DO-27 series Axial Vertical pin pitch 5.08mm length 9.52mm diameter 5.33mm +0 +2 +2 +Diode_THT +D_DO-27_P12.70mm_Horizontal +Diode, DO-27 series, Axial, Horizontal, pin pitch=12.7mm, , length*diameter=9.52*5.33mm^2, , http://www.slottechforum.com/slotinfo/Techstuff/CD2%20Diodes%20and%20Transistors/Cases/Diode%20DO-27.jpg +Diode DO-27 series Axial Horizontal pin pitch 12.7mm length 9.52mm diameter 5.33mm +0 +2 +2 +Diode_THT +D_DO-27_P15.24mm_Horizontal +Diode, DO-27 series, Axial, Horizontal, pin pitch=15.24mm, , length*diameter=9.52*5.33mm^2, , http://www.slottechforum.com/slotinfo/Techstuff/CD2%20Diodes%20and%20Transistors/Cases/Diode%20DO-27.jpg +Diode DO-27 series Axial Horizontal pin pitch 15.24mm length 9.52mm diameter 5.33mm +0 +2 +2 +Diode_THT +D_DO-34_SOD68_P2.54mm_Vertical_AnodeUp +Diode, DO-34_SOD68 series, Axial, Vertical, pin pitch=2.54mm, , length*diameter=3.04*1.6mm^2, , https://www.nxp.com/docs/en/data-sheet/KTY83_SER.pdf +Diode DO-34_SOD68 series Axial Vertical pin pitch 2.54mm length 3.04mm diameter 1.6mm +0 +2 +2 +Diode_THT +D_DO-34_SOD68_P2.54mm_Vertical_KathodeUp +Diode, DO-34_SOD68 series, Axial, Vertical, pin pitch=2.54mm, , length*diameter=3.04*1.6mm^2, , https://www.nxp.com/docs/en/data-sheet/KTY83_SER.pdf +Diode DO-34_SOD68 series Axial Vertical pin pitch 2.54mm length 3.04mm diameter 1.6mm +0 +2 +2 +Diode_THT +D_DO-34_SOD68_P5.08mm_Vertical_AnodeUp +Diode, DO-34_SOD68 series, Axial, Vertical, pin pitch=5.08mm, , length*diameter=3.04*1.6mm^2, , https://www.nxp.com/docs/en/data-sheet/KTY83_SER.pdf +Diode DO-34_SOD68 series Axial Vertical pin pitch 5.08mm length 3.04mm diameter 1.6mm +0 +2 +2 +Diode_THT +D_DO-34_SOD68_P5.08mm_Vertical_KathodeUp +Diode, DO-34_SOD68 series, Axial, Vertical, pin pitch=5.08mm, , length*diameter=3.04*1.6mm^2, , https://www.nxp.com/docs/en/data-sheet/KTY83_SER.pdf +Diode DO-34_SOD68 series Axial Vertical pin pitch 5.08mm length 3.04mm diameter 1.6mm +0 +2 +2 +Diode_THT +D_DO-34_SOD68_P7.62mm_Horizontal +Diode, DO-34_SOD68 series, Axial, Horizontal, pin pitch=7.62mm, , length*diameter=3.04*1.6mm^2, , https://www.nxp.com/docs/en/data-sheet/KTY83_SER.pdf +Diode DO-34_SOD68 series Axial Horizontal pin pitch 7.62mm length 3.04mm diameter 1.6mm +0 +2 +2 +Diode_THT +D_DO-34_SOD68_P10.16mm_Horizontal +Diode, DO-34_SOD68 series, Axial, Horizontal, pin pitch=10.16mm, , length*diameter=3.04*1.6mm^2, , https://www.nxp.com/docs/en/data-sheet/KTY83_SER.pdf +Diode DO-34_SOD68 series Axial Horizontal pin pitch 10.16mm length 3.04mm diameter 1.6mm +0 +2 +2 +Diode_THT +D_DO-34_SOD68_P12.70mm_Horizontal +Diode, DO-34_SOD68 series, Axial, Horizontal, pin pitch=12.7mm, , length*diameter=3.04*1.6mm^2, , https://www.nxp.com/docs/en/data-sheet/KTY83_SER.pdf +Diode DO-34_SOD68 series Axial Horizontal pin pitch 12.7mm length 3.04mm diameter 1.6mm +0 +2 +2 +Diode_THT +D_DO-35_SOD27_P2.54mm_Vertical_AnodeUp +Diode, DO-35_SOD27 series, Axial, Vertical, pin pitch=2.54mm, , length*diameter=4*2mm^2, , http://www.diodes.com/_files/packages/DO-35.pdf +Diode DO-35_SOD27 series Axial Vertical pin pitch 2.54mm length 4mm diameter 2mm +0 +2 +2 +Diode_THT +D_DO-35_SOD27_P2.54mm_Vertical_KathodeUp +Diode, DO-35_SOD27 series, Axial, Vertical, pin pitch=2.54mm, , length*diameter=4*2mm^2, , http://www.diodes.com/_files/packages/DO-35.pdf +Diode DO-35_SOD27 series Axial Vertical pin pitch 2.54mm length 4mm diameter 2mm +0 +2 +2 +Diode_THT +D_DO-35_SOD27_P3.81mm_Vertical_AnodeUp +Diode, DO-35_SOD27 series, Axial, Vertical, pin pitch=3.81mm, , length*diameter=4*2mm^2, , http://www.diodes.com/_files/packages/DO-35.pdf +Diode DO-35_SOD27 series Axial Vertical pin pitch 3.81mm length 4mm diameter 2mm +0 +2 +2 +Diode_THT +D_DO-35_SOD27_P3.81mm_Vertical_KathodeUp +Diode, DO-35_SOD27 series, Axial, Vertical, pin pitch=3.81mm, , length*diameter=4*2mm^2, , http://www.diodes.com/_files/packages/DO-35.pdf +Diode DO-35_SOD27 series Axial Vertical pin pitch 3.81mm length 4mm diameter 2mm +0 +2 +2 +Diode_THT +D_DO-35_SOD27_P5.08mm_Vertical_AnodeUp +Diode, DO-35_SOD27 series, Axial, Vertical, pin pitch=5.08mm, , length*diameter=4*2mm^2, , http://www.diodes.com/_files/packages/DO-35.pdf +Diode DO-35_SOD27 series Axial Vertical pin pitch 5.08mm length 4mm diameter 2mm +0 +2 +2 +Diode_THT +D_DO-35_SOD27_P5.08mm_Vertical_KathodeUp +Diode, DO-35_SOD27 series, Axial, Vertical, pin pitch=5.08mm, , length*diameter=4*2mm^2, , http://www.diodes.com/_files/packages/DO-35.pdf +Diode DO-35_SOD27 series Axial Vertical pin pitch 5.08mm length 4mm diameter 2mm +0 +2 +2 +Diode_THT +D_DO-35_SOD27_P7.62mm_Horizontal +Diode, DO-35_SOD27 series, Axial, Horizontal, pin pitch=7.62mm, , length*diameter=4*2mm^2, , http://www.diodes.com/_files/packages/DO-35.pdf +Diode DO-35_SOD27 series Axial Horizontal pin pitch 7.62mm length 4mm diameter 2mm +0 +2 +2 +Diode_THT +D_DO-35_SOD27_P10.16mm_Horizontal +Diode, DO-35_SOD27 series, Axial, Horizontal, pin pitch=10.16mm, , length*diameter=4*2mm^2, , http://www.diodes.com/_files/packages/DO-35.pdf +Diode DO-35_SOD27 series Axial Horizontal pin pitch 10.16mm length 4mm diameter 2mm +0 +2 +2 +Diode_THT +D_DO-35_SOD27_P12.70mm_Horizontal +Diode, DO-35_SOD27 series, Axial, Horizontal, pin pitch=12.7mm, , length*diameter=4*2mm^2, , http://www.diodes.com/_files/packages/DO-35.pdf +Diode DO-35_SOD27 series Axial Horizontal pin pitch 12.7mm length 4mm diameter 2mm +0 +2 +2 +Diode_THT +D_DO-41_SOD81_P2.54mm_Vertical_AnodeUp +Diode, DO-41_SOD81 series, Axial, Vertical, pin pitch=2.54mm, , length*diameter=5.2*2.7mm^2, , http://www.diodes.com/_files/packages/DO-41%20(Plastic).pdf +Diode DO-41_SOD81 series Axial Vertical pin pitch 2.54mm length 5.2mm diameter 2.7mm +0 +2 +2 +Diode_THT +D_DO-41_SOD81_P2.54mm_Vertical_KathodeUp +Diode, DO-41_SOD81 series, Axial, Vertical, pin pitch=2.54mm, , length*diameter=5.2*2.7mm^2, , http://www.diodes.com/_files/packages/DO-41%20(Plastic).pdf +Diode DO-41_SOD81 series Axial Vertical pin pitch 2.54mm length 5.2mm diameter 2.7mm +0 +2 +2 +Diode_THT +D_DO-41_SOD81_P3.81mm_Vertical_AnodeUp +Diode, DO-41_SOD81 series, Axial, Vertical, pin pitch=3.81mm, , length*diameter=5.2*2.7mm^2, , https://www.diodes.com/assets/Package-Files/DO-41-Plastic.pdf +Diode DO-41_SOD81 series Axial Vertical pin pitch 3.81mm length 5.2mm diameter 2.7mm +0 +2 +2 +Diode_THT +D_DO-41_SOD81_P3.81mm_Vertical_KathodeUp +Diode, DO-41_SOD81 series, Axial, Vertical, pin pitch=3.81mm, , length*diameter=5.2*2.7mm^2, , https://www.diodes.com/assets/Package-Files/DO-41-Plastic.pdf +Diode DO-41_SOD81 series Axial Vertical pin pitch 3.81mm length 5.2mm diameter 2.7mm +0 +2 +2 +Diode_THT +D_DO-41_SOD81_P5.08mm_Vertical_AnodeUp +Diode, DO-41_SOD81 series, Axial, Vertical, pin pitch=5.08mm, , length*diameter=5.2*2.7mm^2, , http://www.diodes.com/_files/packages/DO-41%20(Plastic).pdf +Diode DO-41_SOD81 series Axial Vertical pin pitch 5.08mm length 5.2mm diameter 2.7mm +0 +2 +2 +Diode_THT +D_DO-41_SOD81_P5.08mm_Vertical_KathodeUp +Diode, DO-41_SOD81 series, Axial, Vertical, pin pitch=5.08mm, , length*diameter=5.2*2.7mm^2, , http://www.diodes.com/_files/packages/DO-41%20(Plastic).pdf +Diode DO-41_SOD81 series Axial Vertical pin pitch 5.08mm length 5.2mm diameter 2.7mm +0 +2 +2 +Diode_THT +D_DO-41_SOD81_P7.62mm_Horizontal +Diode, DO-41_SOD81 series, Axial, Horizontal, pin pitch=7.62mm, , length*diameter=5.2*2.7mm^2, , http://www.diodes.com/_files/packages/DO-41%20(Plastic).pdf +Diode DO-41_SOD81 series Axial Horizontal pin pitch 7.62mm length 5.2mm diameter 2.7mm +0 +2 +2 +Diode_THT +D_DO-41_SOD81_P10.16mm_Horizontal +Diode, DO-41_SOD81 series, Axial, Horizontal, pin pitch=10.16mm, , length*diameter=5.2*2.7mm^2, , http://www.diodes.com/_files/packages/DO-41%20(Plastic).pdf +Diode DO-41_SOD81 series Axial Horizontal pin pitch 10.16mm length 5.2mm diameter 2.7mm +0 +2 +2 +Diode_THT +D_DO-41_SOD81_P12.70mm_Horizontal +Diode, DO-41_SOD81 series, Axial, Horizontal, pin pitch=12.7mm, , length*diameter=5.2*2.7mm^2, , http://www.diodes.com/_files/packages/DO-41%20(Plastic).pdf +Diode DO-41_SOD81 series Axial Horizontal pin pitch 12.7mm length 5.2mm diameter 2.7mm +0 +2 +2 +Diode_THT +D_DO-201AD_P3.81mm_Vertical_AnodeUp +Diode, DO-201AD series, Axial, Vertical, pin pitch=3.81mm, , length*diameter=9.5*5.2mm^2, , http://www.diodes.com/_files/packages/DO-201AD.pdf +Diode DO-201AD series Axial Vertical pin pitch 3.81mm length 9.5mm diameter 5.2mm +0 +2 +2 +Diode_THT +D_DO-201AD_P3.81mm_Vertical_KathodeUp +Diode, DO-201AD series, Axial, Vertical, pin pitch=3.81mm, , length*diameter=9.5*5.2mm^2, , http://www.diodes.com/_files/packages/DO-201AD.pdf +Diode DO-201AD series Axial Vertical pin pitch 3.81mm length 9.5mm diameter 5.2mm +0 +2 +2 +Diode_THT +D_DO-201AD_P5.08mm_Vertical_AnodeUp +Diode, DO-201AD series, Axial, Vertical, pin pitch=5.08mm, , length*diameter=9.5*5.2mm^2, , http://www.diodes.com/_files/packages/DO-201AD.pdf +Diode DO-201AD series Axial Vertical pin pitch 5.08mm length 9.5mm diameter 5.2mm +0 +2 +2 +Diode_THT +D_DO-201AD_P5.08mm_Vertical_KathodeUp +Diode, DO-201AD series, Axial, Vertical, pin pitch=5.08mm, , length*diameter=9.5*5.2mm^2, , http://www.diodes.com/_files/packages/DO-201AD.pdf +Diode DO-201AD series Axial Vertical pin pitch 5.08mm length 9.5mm diameter 5.2mm +0 +2 +2 +Diode_THT +D_DO-201AD_P12.70mm_Horizontal +Diode, DO-201AD series, Axial, Horizontal, pin pitch=12.7mm, , length*diameter=9.5*5.2mm^2, , http://www.diodes.com/_files/packages/DO-201AD.pdf +Diode DO-201AD series Axial Horizontal pin pitch 12.7mm length 9.5mm diameter 5.2mm +0 +2 +2 +Diode_THT +D_DO-201AD_P15.24mm_Horizontal +Diode, DO-201AD series, Axial, Horizontal, pin pitch=15.24mm, , length*diameter=9.5*5.2mm^2, , http://www.diodes.com/_files/packages/DO-201AD.pdf +Diode DO-201AD series Axial Horizontal pin pitch 15.24mm length 9.5mm diameter 5.2mm +0 +2 +2 +Diode_THT +D_DO-201AE_P3.81mm_Vertical_AnodeUp +Diode, DO-201AE series, Axial, Vertical, pin pitch=3.81mm, , length*diameter=9*5.3mm^2, , http://www.farnell.com/datasheets/529758.pdf +Diode DO-201AE series Axial Vertical pin pitch 3.81mm length 9mm diameter 5.3mm +0 +2 +2 +Diode_THT +D_DO-201AE_P3.81mm_Vertical_KathodeUp +Diode, DO-201AE series, Axial, Vertical, pin pitch=3.81mm, , length*diameter=9*5.3mm^2, , http://www.farnell.com/datasheets/529758.pdf +Diode DO-201AE series Axial Vertical pin pitch 3.81mm length 9mm diameter 5.3mm +0 +2 +2 +Diode_THT +D_DO-201AE_P5.08mm_Vertical_AnodeUp +Diode, DO-201AE series, Axial, Vertical, pin pitch=5.08mm, , length*diameter=9*5.3mm^2, , http://www.farnell.com/datasheets/529758.pdf +Diode DO-201AE series Axial Vertical pin pitch 5.08mm length 9mm diameter 5.3mm +0 +2 +2 +Diode_THT +D_DO-201AE_P5.08mm_Vertical_KathodeUp +Diode, DO-201AE series, Axial, Vertical, pin pitch=5.08mm, , length*diameter=9*5.3mm^2, , http://www.farnell.com/datasheets/529758.pdf +Diode DO-201AE series Axial Vertical pin pitch 5.08mm length 9mm diameter 5.3mm +0 +2 +2 +Diode_THT +D_DO-201AE_P12.70mm_Horizontal +Diode, DO-201AE series, Axial, Horizontal, pin pitch=12.7mm, , length*diameter=9*5.3mm^2, , http://www.farnell.com/datasheets/529758.pdf +Diode DO-201AE series Axial Horizontal pin pitch 12.7mm length 9mm diameter 5.3mm +0 +2 +2 +Diode_THT +D_DO-201AE_P15.24mm_Horizontal +Diode, DO-201AE series, Axial, Horizontal, pin pitch=15.24mm, , length*diameter=9*5.3mm^2, , http://www.farnell.com/datasheets/529758.pdf +Diode DO-201AE series Axial Horizontal pin pitch 15.24mm length 9mm diameter 5.3mm +0 +2 +2 +Diode_THT +D_DO-201_P3.81mm_Vertical_AnodeUp +Diode, DO-201 series, Axial, Vertical, pin pitch=3.81mm, , length*diameter=9.53*5.21mm^2, , http://www.diodes.com/_files/packages/DO-201.pdf +Diode DO-201 series Axial Vertical pin pitch 3.81mm length 9.53mm diameter 5.21mm +0 +2 +2 +Diode_THT +D_DO-201_P3.81mm_Vertical_KathodeUp +Diode, DO-201 series, Axial, Vertical, pin pitch=3.81mm, , length*diameter=9.53*5.21mm^2, , http://www.diodes.com/_files/packages/DO-201.pdf +Diode DO-201 series Axial Vertical pin pitch 3.81mm length 9.53mm diameter 5.21mm +0 +2 +2 +Diode_THT +D_DO-201_P5.08mm_Vertical_AnodeUp +Diode, DO-201 series, Axial, Vertical, pin pitch=5.08mm, , length*diameter=9.53*5.21mm^2, , http://www.diodes.com/_files/packages/DO-201.pdf +Diode DO-201 series Axial Vertical pin pitch 5.08mm length 9.53mm diameter 5.21mm +0 +2 +2 +Diode_THT +D_DO-201_P5.08mm_Vertical_KathodeUp +Diode, DO-201 series, Axial, Vertical, pin pitch=5.08mm, , length*diameter=9.53*5.21mm^2, , http://www.diodes.com/_files/packages/DO-201.pdf +Diode DO-201 series Axial Vertical pin pitch 5.08mm length 9.53mm diameter 5.21mm +0 +2 +2 +Diode_THT +D_DO-201_P12.70mm_Horizontal +Diode, DO-201 series, Axial, Horizontal, pin pitch=12.7mm, , length*diameter=9.53*5.21mm^2, , http://www.diodes.com/_files/packages/DO-201.pdf +Diode DO-201 series Axial Horizontal pin pitch 12.7mm length 9.53mm diameter 5.21mm +0 +2 +2 +Diode_THT +D_DO-201_P15.24mm_Horizontal +Diode, DO-201 series, Axial, Horizontal, pin pitch=15.24mm, , length*diameter=9.53*5.21mm^2, , http://www.diodes.com/_files/packages/DO-201.pdf +Diode DO-201 series Axial Horizontal pin pitch 15.24mm length 9.53mm diameter 5.21mm +0 +2 +2 +Diode_THT +D_P600_R-6_P7.62mm_Vertical_AnodeUp +Diode, P600_R-6 series, Axial, Vertical, pin pitch=7.62mm, , length*diameter=9.1*9.1mm^2, , http://www.vishay.com/docs/88692/p600a.pdf, http://www.diodes.com/_files/packages/R-6.pdf +Diode P600_R-6 series Axial Vertical pin pitch 7.62mm length 9.1mm diameter 9.1mm +0 +2 +2 +Diode_THT +D_P600_R-6_P7.62mm_Vertical_KathodeUp +Diode, P600_R-6 series, Axial, Vertical, pin pitch=7.62mm, , length*diameter=9.1*9.1mm^2, , http://www.vishay.com/docs/88692/p600a.pdf, http://www.diodes.com/_files/packages/R-6.pdf +Diode P600_R-6 series Axial Vertical pin pitch 7.62mm length 9.1mm diameter 9.1mm +0 +2 +2 +Diode_THT +D_P600_R-6_P12.70mm_Horizontal +Diode, P600_R-6 series, Axial, Horizontal, pin pitch=12.7mm, , length*diameter=9.1*9.1mm^2, , http://www.vishay.com/docs/88692/p600a.pdf, http://www.diodes.com/_files/packages/R-6.pdf +Diode P600_R-6 series Axial Horizontal pin pitch 12.7mm length 9.1mm diameter 9.1mm +0 +2 +2 +Diode_THT +D_P600_R-6_P20.00mm_Horizontal +Diode, P600_R-6 series, Axial, Horizontal, pin pitch=20mm, , length*diameter=9.1*9.1mm^2, , http://www.vishay.com/docs/88692/p600a.pdf, http://www.diodes.com/_files/packages/R-6.pdf +Diode P600_R-6 series Axial Horizontal pin pitch 20mm length 9.1mm diameter 9.1mm +0 +2 +2 +Diode_THT +D_T-1_P2.54mm_Vertical_AnodeUp +Diode, T-1 series, Axial, Vertical, pin pitch=2.54mm, , length*diameter=3.2*2.6mm^2, , http://www.diodes.com/_files/packages/T-1.pdf +Diode T-1 series Axial Vertical pin pitch 2.54mm length 3.2mm diameter 2.6mm +0 +2 +2 +Diode_THT +D_T-1_P2.54mm_Vertical_KathodeUp +Diode, T-1 series, Axial, Vertical, pin pitch=2.54mm, , length*diameter=3.2*2.6mm^2, , http://www.diodes.com/_files/packages/T-1.pdf +Diode T-1 series Axial Vertical pin pitch 2.54mm length 3.2mm diameter 2.6mm +0 +2 +2 +Diode_THT +D_T-1_P5.08mm_Horizontal +Diode, T-1 series, Axial, Horizontal, pin pitch=5.08mm, , length*diameter=3.2*2.6mm^2, , http://www.diodes.com/_files/packages/T-1.pdf +Diode T-1 series Axial Horizontal pin pitch 5.08mm length 3.2mm diameter 2.6mm +0 +2 +2 +Diode_THT +D_T-1_P10.16mm_Horizontal +Diode, T-1 series, Axial, Horizontal, pin pitch=10.16mm, , length*diameter=3.2*2.6mm^2, , http://www.diodes.com/_files/packages/T-1.pdf +Diode T-1 series Axial Horizontal pin pitch 10.16mm length 3.2mm diameter 2.6mm +0 +2 +2 +Diode_THT +D_T-1_P12.70mm_Horizontal +Diode, T-1 series, Axial, Horizontal, pin pitch=12.7mm, , length*diameter=3.2*2.6mm^2, , http://www.diodes.com/_files/packages/T-1.pdf +Diode T-1 series Axial Horizontal pin pitch 12.7mm length 3.2mm diameter 2.6mm +0 +2 +2 +Inductor_SMD +L_6.3x6.3_H3 +Choke, SMD, 6.3x6.3mm 3mm height +Choke SMD +0 +2 +2 +Inductor_SMD +L_7.3x7.3_H3.5 +Choke, SMD, 7.3x7.3mm 3.5mm height +Choke SMD +0 +2 +2 +Inductor_SMD +L_7.3x7.3_H4.5 +Choke, SMD, 7.3x7.3mm 4.5mm height +Choke SMD +0 +2 +2 +Inductor_SMD +L_10.4x10.4_H4.8 +Choke, SMD, 10.4x10.4mm 4.8mm height +Choke SMD +0 +2 +2 +Inductor_SMD +L_12x12mm_H4.5mm +Choke, SMD, 12x12mm 4.5mm height +Choke SMD +0 +2 +2 +Inductor_SMD +L_12x12mm_H6mm +Choke, SMD, 12x12mm 6mm height +Choke SMD +0 +2 +2 +Inductor_SMD +L_12x12mm_H8mm +Choke, SMD, 12x12mm 8mm height +Choke SMD +0 +2 +2 +Inductor_SMD +L_0201_0603Metric +Inductor SMD 0201 (0603 Metric), square (rectangular) end terminal, IPC_7351 nominal, (Body size source: https://www.vishay.com/docs/20052/crcw0201e3.pdf), generated with kicad-footprint-generator +inductor +0 +4 +2 +Inductor_SMD +L_0402_1005Metric +Inductor SMD 0402 (1005 Metric), square (rectangular) end terminal, IPC_7351 nominal, (Body size source: http://www.tortai-tech.com/upload/download/2011102023233369053.pdf), generated with kicad-footprint-generator +inductor +0 +2 +2 +Inductor_SMD +L_0603_1608Metric +Inductor SMD 0603 (1608 Metric), square (rectangular) end terminal, IPC_7351 nominal, (Body size source: http://www.tortai-tech.com/upload/download/2011102023233369053.pdf), generated with kicad-footprint-generator +inductor +0 +2 +2 +Inductor_SMD +L_0603_1608Metric_Pad1.05x0.95mm_HandSolder +Capacitor SMD 0603 (1608 Metric), square (rectangular) end terminal, IPC_7351 nominal with elongated pad for handsoldering. (Body size source: http://www.tortai-tech.com/upload/download/2011102023233369053.pdf), generated with kicad-footprint-generator +inductor handsolder +0 +2 +2 +Inductor_SMD +L_0805_2012Metric +Inductor SMD 0805 (2012 Metric), square (rectangular) end terminal, IPC_7351 nominal, (Body size source: https://docs.google.com/spreadsheets/d/1BsfQQcO9C6DZCsRaXUlFlo91Tg2WpOkGARC1WS5S8t0/edit?usp=sharing), generated with kicad-footprint-generator +inductor +0 +2 +2 +Inductor_SMD +L_0805_2012Metric_Pad1.15x1.40mm_HandSolder +Capacitor SMD 0805 (2012 Metric), square (rectangular) end terminal, IPC_7351 nominal with elongated pad for handsoldering. (Body size source: https://docs.google.com/spreadsheets/d/1BsfQQcO9C6DZCsRaXUlFlo91Tg2WpOkGARC1WS5S8t0/edit?usp=sharing), generated with kicad-footprint-generator +inductor handsolder +0 +2 +2 +Inductor_SMD +L_01005_0402Metric +Inductor SMD 01005 (0402 Metric), square (rectangular) end terminal, IPC_7351 nominal, (Body size source: http://www.vishay.com/docs/20056/crcw01005e3.pdf), generated with kicad-footprint-generator +inductor +0 +4 +2 +Inductor_SMD +L_1206_3216Metric +Inductor SMD 1206 (3216 Metric), square (rectangular) end terminal, IPC_7351 nominal, (Body size source: http://www.tortai-tech.com/upload/download/2011102023233369053.pdf), generated with kicad-footprint-generator +inductor +0 +2 +2 +Inductor_SMD +L_1206_3216Metric_Pad1.42x1.75mm_HandSolder +Capacitor SMD 1206 (3216 Metric), square (rectangular) end terminal, IPC_7351 nominal with elongated pad for handsoldering. (Body size source: http://www.tortai-tech.com/upload/download/2011102023233369053.pdf), generated with kicad-footprint-generator +inductor handsolder +0 +2 +2 +Inductor_SMD +L_1210_3225Metric +Inductor SMD 1210 (3225 Metric), square (rectangular) end terminal, IPC_7351 nominal, (Body size source: http://www.tortai-tech.com/upload/download/2011102023233369053.pdf), generated with kicad-footprint-generator +inductor +0 +2 +2 +Inductor_SMD +L_1210_3225Metric_Pad1.42x2.65mm_HandSolder +Capacitor SMD 1210 (3225 Metric), square (rectangular) end terminal, IPC_7351 nominal with elongated pad for handsoldering. (Body size source: http://www.tortai-tech.com/upload/download/2011102023233369053.pdf), generated with kicad-footprint-generator +inductor handsolder +0 +2 +2 +Inductor_SMD +L_1806_4516Metric +Inductor SMD 1806 (4516 Metric), square (rectangular) end terminal, IPC_7351 nominal, (Body size source: https://www.modelithics.com/models/Vendor/MuRata/BLM41P.pdf), generated with kicad-footprint-generator +inductor +0 +2 +2 +Inductor_SMD +L_1806_4516Metric_Pad1.57x1.80mm_HandSolder +Capacitor SMD 1806 (4516 Metric), square (rectangular) end terminal, IPC_7351 nominal with elongated pad for handsoldering. (Body size source: https://www.modelithics.com/models/Vendor/MuRata/BLM41P.pdf), generated with kicad-footprint-generator +inductor handsolder +0 +2 +2 +Inductor_SMD +L_1812_4532Metric +Inductor SMD 1812 (4532 Metric), square (rectangular) end terminal, IPC_7351 nominal, (Body size source: https://www.nikhef.nl/pub/departments/mt/projects/detectorR_D/dtddice/ERJ2G.pdf), generated with kicad-footprint-generator +inductor +0 +2 +2 +Inductor_SMD +L_1812_4532Metric_Pad1.30x3.40mm_HandSolder +Capacitor SMD 1812 (4532 Metric), square (rectangular) end terminal, IPC_7351 nominal with elongated pad for handsoldering. (Body size source: https://www.nikhef.nl/pub/departments/mt/projects/detectorR_D/dtddice/ERJ2G.pdf), generated with kicad-footprint-generator +inductor handsolder +0 +2 +2 +Inductor_SMD +L_2010_5025Metric +Inductor SMD 2010 (5025 Metric), square (rectangular) end terminal, IPC_7351 nominal, (Body size source: http://www.tortai-tech.com/upload/download/2011102023233369053.pdf), generated with kicad-footprint-generator +inductor +0 +2 +2 +Inductor_SMD +L_2010_5025Metric_Pad1.52x2.65mm_HandSolder +Capacitor SMD 2010 (5025 Metric), square (rectangular) end terminal, IPC_7351 nominal with elongated pad for handsoldering. (Body size source: http://www.tortai-tech.com/upload/download/2011102023233369053.pdf), generated with kicad-footprint-generator +inductor handsolder +0 +2 +2 +Inductor_SMD +L_2512_6332Metric +Inductor SMD 2512 (6332 Metric), square (rectangular) end terminal, IPC_7351 nominal, (Body size source: http://www.tortai-tech.com/upload/download/2011102023233369053.pdf), generated with kicad-footprint-generator +inductor +0 +2 +2 +Inductor_SMD +L_2512_6332Metric_Pad1.52x3.35mm_HandSolder +Capacitor SMD 2512 (6332 Metric), square (rectangular) end terminal, IPC_7351 nominal with elongated pad for handsoldering. (Body size source: http://www.tortai-tech.com/upload/download/2011102023233369053.pdf), generated with kicad-footprint-generator +inductor handsolder +0 +2 +2 +Inductor_SMD +L_2816_7142Metric +Inductor SMD 2816 (7142 Metric), square (rectangular) end terminal, IPC_7351 nominal, (Body size from: https://www.vishay.com/docs/30100/wsl.pdf), generated with kicad-footprint-generator +inductor +0 +2 +2 +Inductor_SMD +L_2816_7142Metric_Pad3.20x4.45mm_HandSolder +Capacitor SMD 2816 (7142 Metric), square (rectangular) end terminal, IPC_7351 nominal with elongated pad for handsoldering. (Body size from: https://www.vishay.com/docs/30100/wsl.pdf), generated with kicad-footprint-generator +inductor handsolder +0 +2 +2 +Inductor_SMD +L_Abracon_ASPI-3012S +smd shielded power inductor http://www.abracon.com/Magnetics/power/ASPI-3012S.pdf +inductor abracon smd shielded +0 +2 +2 +Inductor_SMD +L_Bourns-SRN1060 +Bourns SRN1060 series SMD inductor https://www.bourns.com/docs/Product-Datasheets/SRN1060.pdf +Bourns SRN1060 SMD inductor +0 +2 +2 +Inductor_SMD +L_Bourns-SRN4018 +Bourns SRN4018 series SMD inductor, https://www.bourns.com/docs/Product-Datasheets/SRN4018.pdf +Bourns SRN4018 SMD inductor +0 +2 +2 +Inductor_SMD +L_Bourns-SRN6028 +Bourns SRN6028 series SMD inductor +Bourns SRN6028 SMD inductor +0 +2 +2 +Inductor_SMD +L_Bourns-SRR1005 +Bourns SRR1005 series SMD inductor +Bourns SRR1005 SMD inductor +0 +2 +2 +Inductor_SMD +L_Bourns-SRU8043 +Bourns SRU8043 series SMD inductor +Bourns SRU8043 SMD inductor +0 +2 +2 +Inductor_SMD +L_Bourns_SDR1806 +https://www.bourns.com/docs/Product-Datasheets/SDR1806.pdf +Bourns SDR1806 +0 +2 +2 +Inductor_SMD +L_Bourns_SRN6045TA +http://www.bourns.com/docs/product-datasheets/srn6045ta.pdf +Semi-shielded Power Inductor +0 +2 +2 +Inductor_SMD +L_Bourns_SRP1245A +Bourns SRP1245A series SMD inductor http://www.bourns.com/docs/Product-Datasheets/SRP1245A.pdf +Bourns SRP1245A SMD inductor +0 +2 +2 +Inductor_SMD +L_Bourns_SRP2313AA +Bourns SRR1260 series SMD inductor http://www.bourns.com/docs/product-datasheets/srp2313aa.pdf +Bourns SRR1260 SMD inductor +0 +4 +2 +Inductor_SMD +L_Bourns_SRR1210A +Bourns SRR1210A series SMD inductor https://www.bourns.com/docs/Product-Datasheets/SRR1210A.pdf +Bourns SRR1210A SMD inductor +0 +2 +2 +Inductor_SMD +L_Bourns_SRR1260 +Bourns SRR1260 series SMD inductor http://www.bourns.com/docs/Product-Datasheets/SRR1260.pdf +Bourns SRR1260 SMD inductor +0 +2 +2 +Inductor_SMD +L_Coilcraft_LPS4018 +SMD Inductor Coilcraft LPS4018 https://www.coilcraft.com/misc/lps4018d.html +L Coilcraft LPS4018 +0 +14 +2 +Inductor_SMD +L_Coilcraft_LPS5030 +Shielded Power Inductor SMD, Coilcraft LPS5030, https://www.coilcraft.com/pdfs/lps5030.pdf, StepUp generated footprint +inductor +0 +2 +2 +Inductor_SMD +L_Coilcraft_XAL5030 +L_Coilcraft_XAL5030 +L Coilcraft XAL5030 +0 +2 +2 +Inductor_SMD +L_Coilcraft_XxL4020 +L_Coilcraft_XxL4020 https://www.coilcraft.com/pdfs/xfl4020.pdf +L Coilcraft XxL4020 +0 +2 +2 +Inductor_SMD +L_Coilcraft_XxL4030 +L_Coilcraft_XxL4030 https://www.coilcraft.com/pdfs/xfl4030.pdf +L Coilcraft XxL4030 +0 +2 +2 +Inductor_SMD +L_Coilcraft_XxL4040 +L_Coilcraft_XxL4040 https://www.coilcraft.com/pdfs/xal4000.pdf +L Coilcraft XxL4040 +0 +2 +2 +Inductor_SMD +L_CommonMode_Wuerth_WE-SL2 +http://katalog.we-online.de/en/pbs/WE-SL2?sid=5fbec16187#vs_t1:c1_ct:1 +Wuerth WE-SL2 +0 +4 +4 +Inductor_SMD +L_Fastron_PISN +Choke, Drossel, PISN, SMD, Fastron, +Choke Drossel PISN SMD Fastron +0 +2 +2 +Inductor_SMD +L_Fastron_PISN_Handsoldering +Choke, Drossel, PISN, SMD, Fastron, +Choke Drossel PISN SMD Fastron +0 +2 +2 +Inductor_SMD +L_Fastron_PISR +Choke, Drossel, PISR, Fastron, SMD, +Choke Drossel PISR Fastron SMD +0 +2 +2 +Inductor_SMD +L_Fastron_PISR_Handsoldering +Choke, Drossel, PISR, Fastron, SMD, +Choke Drossel PISR Fastron SMD +0 +2 +2 +Inductor_SMD +L_Murata_DEM35xxC +https://www.murata.com/~/media/webrenewal/products/inductor/chip/tokoproducts/wirewoundferritetypeforpl/m_dem3518c.ashx +Inductor SMD DEM35xxC +0 +2 +2 +Inductor_SMD +L_Neosid_Air-Coil_SML_1turn_HDM0131A +Neosid, Air-Coil, SML, 1turn, HDM0131A, +Neosid Air-Coil SML 1turn HDM0131A +0 +2 +2 +Inductor_SMD +L_Neosid_Air-Coil_SML_2turn_HAM0231A +Neosid, Air-Coil, SML, 2turn, HAM0231A, +Neosid Air-Coil SML 2turn HAM0231A +0 +2 +2 +Inductor_SMD +L_Neosid_Air-Coil_SML_2turn_HDM0231A +Neosid, Air-Coil, SML, 2turn, HDM0231A, +Neosid Air-Coil SML 2turn HDM0231A +0 +2 +2 +Inductor_SMD +L_Neosid_Air-Coil_SML_3turn_HAM0331A +Neosid, Air-Coil, SML, 2turn, HAM0331A, +Neosid Air-Coil SML 3turn HAM0331A +0 +2 +2 +Inductor_SMD +L_Neosid_Air-Coil_SML_3turn_HDM0331A +Neosid, Air-Coil, SML, 3turn, HDM0331A, +Neosid Air-Coil SML 3turn HDM0331A +0 +2 +2 +Inductor_SMD +L_Neosid_Air-Coil_SML_4turn_HAM0431A +Neosid, Air-Coil, SML, 4turn, HAM0431A, +Neosid Air-Coil SML 4turn HAM0431A +0 +2 +2 +Inductor_SMD +L_Neosid_Air-Coil_SML_4turn_HDM0431A +Neosid, Air-Coil, SML, 4turn, HDM0431A, +Neosid Air-Coil SML 4turn HDM0431A +0 +2 +2 +Inductor_SMD +L_Neosid_Air-Coil_SML_5turn_HAM0531A +Neosid, Air-Coil, SML, 5turn, HAM0531A, +Neosid Air-Coil SML 5turn HAM0531A +0 +2 +2 +Inductor_SMD +L_Neosid_Air-Coil_SML_5turn_HDM0531A +Neosid, Air-Coil, SML, 5turn, HDM0531A, +Neosid Air-Coil SML 5turn HDM0531A +0 +2 +2 +Inductor_SMD +L_Neosid_Air-Coil_SML_6-10turn_HAM0631A-HAM1031A +Neosid, Air-Coil, SML, 6-10turn, HAM0631A-HAM1031A, +Neosid Air-Coil SML 6-10turn HAM0631A-HAM1031A +0 +2 +2 +Inductor_SMD +L_Neosid_Air-Coil_SML_6-10turn_HDM0431A-HDM1031A +Neosid, Air-Coil, SML, 6-10turn, HDM0431A-HDM1031A, +Neosid Air-Coil SML 6-10turn HDM0431A-HDM1031A +0 +2 +2 +Inductor_SMD +L_Neosid_Air-Coil_SML_6turn_HAM0631A +Neosid, Air-Coil, SML, 6turn, HAM0631A, +Neosid Air-Coil SML 6turn HAM0631A +0 +2 +2 +Inductor_SMD +L_Neosid_MicroCoil_Ms36-L +Neosid, Micro Coil, Inductor, Ms36-L, SMD, Festinduktivitaet, anti clockwise, +Neosid Micro Coil Inductor Ms36-L SMD Festinduktivitaet anti clockwise +0 +2 +2 +Inductor_SMD +L_Neosid_Ms42 +Neosid, Inductor, SMs42, Festinduktivitaet, SMD, magneticaly shielded, +Neosid Inductor SMs42 Festinduktivitaet SMD magneticaly shielded +0 +2 +2 +Inductor_SMD +L_Neosid_Ms50 +Neosid, Power Inductor, Ms50, SMD, Festinduktivitaet, +Neosid Power Inductor Ms50 SMD Festinduktivitaet +0 +2 +2 +Inductor_SMD +L_Neosid_Ms50T +Neosid, Power Inductor, Ms50T, SMD, Festinduktivitaet, high temperature, +Neosid Power Inductor Ms50T SMD Festinduktivitaet high temperature +0 +2 +2 +Inductor_SMD +L_Neosid_Ms85 +Neosid, Ms85, Ms85T, SMD Inductor, Festinduktivitaet, SMD, +Neosid Ms85 Ms85T SMD Inductor Festinduktivitaet SMD +0 +2 +2 +Inductor_SMD +L_Neosid_Ms85T +Neosid, Ms85, Ms85T, SMD Inductor, Festinduktivitaet, SMD, +Neosid Ms85 Ms85T SMD Inductor Festinduktivitaet SMD +0 +2 +2 +Inductor_SMD +L_Neosid_Ms95 +Neosid,Inductor,Ms95, Ms95a, Ms95T, Festinduktivitaet, SMD, +NeosidInductorMs95 Ms95a Ms95T Festinduktivitaet SMD +0 +2 +2 +Inductor_SMD +L_Neosid_Ms95a +Neosid,Inductor,Ms95, Ms95a, Ms95T, Festinduktivitaet, SMD, +NeosidInductorMs95 Ms95a Ms95T Festinduktivitaet SMD +0 +2 +2 +Inductor_SMD +L_Neosid_Ms95T +Neosid,Inductor,Ms95, Ms95a, Ms95T, Festinduktivitaet, SMD, +NeosidInductorMs95 Ms95a Ms95T Festinduktivitaet SMD +0 +2 +2 +Inductor_SMD +L_Neosid_SM-NE95H +Neosid, Inductor,SM-NE95H, Festinduktivitaet, SMD, +Neosid Inductor SM-NE95H Festinduktivitaet SMD +0 +2 +2 +Inductor_SMD +L_Neosid_SM-NE127 +Neosid, Inductor, SM-NE127, Festinduktivitaet, SMD, +Neosid Inductor SM-NE127 Festinduktivitaet SMD +0 +2 +2 +Inductor_SMD +L_Neosid_SM-NE127_HandSoldering +Neosid, Inductor, SM-NE127, Festinduktivitaet, SMD, +Neosid Inductor SM-NE127 Festinduktivitaet SMD +0 +2 +2 +Inductor_SMD +L_Neosid_SM-NE150 +Neosid, Inductor, SM-NE150, Festinduktivitaet, SMD, +Neosid Inductor SM-NE150 Festinduktivitaet SMD +0 +2 +2 +Inductor_SMD +L_Neosid_SM-PIC0512H +Neosid, Inductor, PIC0512H, Power Inductor, Festinduktivitaet, SMD, +Neosid Inductor PIC0512H Power Inductor Festinduktivitaet SMD +0 +2 +2 +Inductor_SMD +L_Neosid_SM-PIC0602H +Neosid, Power Inductor, SM-PIC0602H, Festinduktivitaet, SMD, +Neosid Power Inductor SM-PIC0602H Festinduktivitaet SMD +0 +2 +2 +Inductor_SMD +L_Neosid_SM-PIC0612H +Neosid, Power Inductor, SM-PIC0612H, Festinduktivitaet, SMD, +Neosid Power Inductor SM-PIC0612H Festinduktivitaet SMD +0 +2 +2 +Inductor_SMD +L_Neosid_SM-PIC1004H +Neosid, Inductor, SM-PIC1004H, Festinduktivitaet, SMD, +Neosid Inductor SM-PIC1004H Festinduktivitaet SMD +0 +2 +2 +Inductor_SMD +L_Neosid_SMS-ME3010 +Neosid, Inductor, SMS-ME3010, Festinduktivitaet, SMD, magnetically shielded, +Neosid Inductor SMS-ME3010 Festinduktivitaet SMD magnetically shielded +0 +2 +2 +Inductor_SMD +L_Neosid_SMS-ME3015 +Neosid, Power Inductor, SMS-ME3015, Festinduktivitaet, SMD, magnetically shielded, +Neosid Power Inductor SMS-ME3015 Festinduktivitaet SMD magnetically shielded +0 +2 +2 +Inductor_SMD +L_Neosid_SMs42 +Neosid, Inductor, SMs42, Festinduktivitaet, SMD, magneticaly shielded, +Neosid Inductor SMs42 Festinduktivitaet SMD magneticaly shielded +0 +2 +2 +Inductor_SMD +L_Neosid_SMs50 +Neosid, Inductor, SMs50, Festinduktivitaet, SMD, magneticaly shielded, +Neosid Inductor SMs50 Festinduktivitaet SMD magneticaly shielded +0 +2 +2 +Inductor_SMD +L_Neosid_SMs85 +Neosid, Inductor, SMs85, Festinduktivitaet, SMD, magnetically shielded, +Neosid Inductor SMs85 Festinduktivitaet SMD magnetically shielded +0 +2 +2 +Inductor_SMD +L_Neosid_SMs95_SMs95p +Neosid, Inductor, SMs95, Festinduktivitaet, SMD, magnetically shielded, +Neosid Inductor SMs95 Festinduktivitaet SMD magnetically shielded +0 +2 +2 +Inductor_SMD +L_Pulse_PA4320 +Inductor SMD Pulse PA4320 http://productfinder.pulseeng.com/products/datasheets/P787.pdf +Inductor SMD Pulse PA4320 +0 +2 +2 +Inductor_SMD +L_Sagami_CER1242B +Inductor, Sagami, h=4.5mm, http://www.sagami-elec.co.jp/file/CER1242B-CER1257B-CER1277B.pdf +inductor sagami cer12xxb smd +0 +2 +2 +Inductor_SMD +L_Sagami_CER1257B +Inductor, Sagami, h=6.0mm, http://www.sagami-elec.co.jp/file/CER1242B-CER1257B-CER1277B.pdf +inductor sagami cer12xxb smd +0 +2 +2 +Inductor_SMD +L_Sagami_CER1277B +Inductor, Sagami, h=8.0mm, http://www.sagami-elec.co.jp/file/CER1242B-CER1257B-CER1277B.pdf +inductor sagami cer12xxb smd +0 +2 +2 +Inductor_SMD +L_Sagami_CWR1242C +Sagami power inductor, CWR1242C, H=4.5mm (http://www.sagami-elec.co.jp/file/16Car_SMDCwr.pdf) +inductor sagami cwr12xx smd +0 +4 +2 +Inductor_SMD +L_Sagami_CWR1257C +Sagami power inductor, CWR1242C, H=6.0mm (http://www.sagami-elec.co.jp/file/16Car_SMDCwr.pdf) +inductor sagami cwr12xx smd +0 +4 +2 +Inductor_SMD +L_Sagami_CWR1277C +Sagami power inductor, CWR1242C, H=7.7mm (http://www.sagami-elec.co.jp/file/16Car_SMDCwr.pdf) +inductor sagami cwr12xx smd +0 +4 +2 +Inductor_SMD +L_SigTra_SC3316F +http://www.signaltransformer.com/sites/all/pdf/smd/P080_SC3316F.pdf +Choke +0 +2 +2 +Inductor_SMD +L_Taiyo-Yuden_MD-1616 +Inductor, Taiyo Yuden, MD series, Taiyo-Yuden_MD-1616, 1.6mmx1.6mm +inductor taiyo-yuden md smd +0 +2 +2 +Inductor_SMD +L_Taiyo-Yuden_MD-2020 +Inductor, Taiyo Yuden, MD series, Taiyo-Yuden_MD-2020, 2.0mmx2.0mm +inductor taiyo-yuden md smd +0 +2 +2 +Inductor_SMD +L_Taiyo-Yuden_MD-3030 +Inductor, Taiyo Yuden, MD series, Taiyo-Yuden_MD-3030, 3.0mmx3.0mm +inductor taiyo-yuden md smd +0 +2 +2 +Inductor_SMD +L_Taiyo-Yuden_MD-4040 +Inductor, Taiyo Yuden, MD series, Taiyo-Yuden_MD-4040, 4.0mmx4.0mm +inductor taiyo-yuden md smd +0 +2 +2 +Inductor_SMD +L_Taiyo-Yuden_MD-5050 +Inductor, Taiyo Yuden, MD series, Taiyo-Yuden_MD-5050, 5.0mmx5.0mm +inductor taiyo-yuden md smd +0 +2 +2 +Inductor_SMD +L_Taiyo-Yuden_NR-20xx +Inductor, Taiyo Yuden, NR series, Taiyo-Yuden_NR-20xx, 2.0mmx2.0mm +inductor taiyo-yuden nr smd +0 +2 +2 +Inductor_SMD +L_Taiyo-Yuden_NR-20xx_HandSoldering +Inductor, Taiyo Yuden, NR series, Taiyo-Yuden_NR-20xx, 2.0mmx2.0mm +inductor taiyo-yuden nr smd +0 +2 +2 +Inductor_SMD +L_Taiyo-Yuden_NR-24xx +Inductor, Taiyo Yuden, NR series, Taiyo-Yuden_NR-24xx, 2.4mmx2.4mm +inductor taiyo-yuden nr smd +0 +2 +2 +Inductor_SMD +L_Taiyo-Yuden_NR-24xx_HandSoldering +Inductor, Taiyo Yuden, NR series, Taiyo-Yuden_NR-24xx, 2.4mmx2.4mm +inductor taiyo-yuden nr smd +0 +2 +2 +Inductor_SMD +L_Taiyo-Yuden_NR-30xx +Inductor, Taiyo Yuden, NR series, Taiyo-Yuden_NR-30xx, 3.0mmx3.0mm +inductor taiyo-yuden nr smd +0 +2 +2 +Inductor_SMD +L_Taiyo-Yuden_NR-30xx_HandSoldering +Inductor, Taiyo Yuden, NR series, Taiyo-Yuden_NR-30xx, 3.0mmx3.0mm +inductor taiyo-yuden nr smd +0 +2 +2 +Inductor_SMD +L_Taiyo-Yuden_NR-40xx +Inductor, Taiyo Yuden, NR series, Taiyo-Yuden_NR-40xx, 4.0mmx4.0mm +inductor taiyo-yuden nr smd +0 +2 +2 +Inductor_SMD +L_Taiyo-Yuden_NR-40xx_HandSoldering +Inductor, Taiyo Yuden, NR series, Taiyo-Yuden_NR-40xx, 4.0mmx4.0mm +inductor taiyo-yuden nr smd +0 +2 +2 +Inductor_SMD +L_Taiyo-Yuden_NR-50xx +Inductor, Taiyo Yuden, NR series, Taiyo-Yuden_NR-50xx, 4.9mmx4.9mm +inductor taiyo-yuden nr smd +0 +2 +2 +Inductor_SMD +L_Taiyo-Yuden_NR-50xx_HandSoldering +Inductor, Taiyo Yuden, NR series, Taiyo-Yuden_NR-50xx, 4.9mmx4.9mm +inductor taiyo-yuden nr smd +0 +2 +2 +Inductor_SMD +L_Taiyo-Yuden_NR-60xx +Inductor, Taiyo Yuden, NR series, Taiyo-Yuden_NR-60xx, 6.0mmx6.0mm +inductor taiyo-yuden nr smd +0 +2 +2 +Inductor_SMD +L_Taiyo-Yuden_NR-60xx_HandSoldering +Inductor, Taiyo Yuden, NR series, Taiyo-Yuden_NR-60xx, 6.0mmx6.0mm +inductor taiyo-yuden nr smd +0 +2 +2 +Inductor_SMD +L_Taiyo-Yuden_NR-80xx +Inductor, Taiyo Yuden, NR series, Taiyo-Yuden_NR-80xx, 8.0mmx8.0mm +inductor taiyo-yuden nr smd +0 +2 +2 +Inductor_SMD +L_Taiyo-Yuden_NR-80xx_HandSoldering +Inductor, Taiyo Yuden, NR series, Taiyo-Yuden_NR-80xx, 8.0mmx8.0mm +inductor taiyo-yuden nr smd +0 +2 +2 +Inductor_SMD +L_TDK_VLF10040 +Inductor,TDK, TDK-VLP-8040, 8.6mmx8.6mm +inductor TDK VLP smd VLF10040 +0 +2 +2 +Inductor_SMD +L_TDK_VLP8040 +Inductor,TDK, TDK-VLP-8040, 8.6mmx8.6mm +inductor TDK VLP smd VLP8040 +0 +2 +2 +Inductor_SMD +L_TracoPower_TCK-141 +Choke, SMD, 4.0x4.0mm 2.1mm height, https://www.tracopower.com/products/tck141.pdf +Choke SMD +0 +2 +2 +Inductor_SMD +L_Vishay_IHLP-1212 +Inductor, Vishay, IHLP series, 3.0mmx3.0mm +inductor vishay ihlp smd +0 +2 +2 +Inductor_SMD +L_Vishay_IHLP-1616 +Inductor, Vishay, IHLP series, 4.1mmx4.1mm +inductor vishay ihlp smd +0 +2 +2 +Inductor_SMD +L_Vishay_IHLP-2020 +Inductor, Vishay, IHLP series, 5.1mmx5.1mm +inductor vishay ihlp smd +0 +2 +2 +Inductor_SMD +L_Vishay_IHLP-2525 +Inductor, Vishay, IHLP series, 6.3mmx6.3mm +inductor vishay ihlp smd +0 +2 +2 +Inductor_SMD +L_Vishay_IHLP-4040 +Inductor, Vishay, IHLP series, 10.2mmx10.2mm +inductor vishay ihlp smd +0 +2 +2 +Inductor_SMD +L_Vishay_IHLP-5050 +Inductor, Vishay, IHLP series, 12.7mmx12.7mm +inductor vishay ihlp smd +0 +2 +2 +Inductor_SMD +L_Vishay_IHLP-6767 +Inductor, Vishay, IHLP series, 17.0mmx17.0mm +inductor vishay ihlp smd +0 +2 +2 +Inductor_SMD +L_Vishay_IHSM-3825 +Inductor, Vishay, Vishay_IHSM-3825, http://www.vishay.com/docs/34018/ihsm3825.pdf, 11.2mmx6.3mm +inductor vishay icsm smd +0 +2 +2 +Inductor_SMD +L_Vishay_IHSM-4825 +Inductor, Vishay, Vishay_IHSM-4825, http://www.vishay.com/docs/34019/ihsm4825.pdf, 13.7mmx6.3mm +inductor vishay icsm smd +0 +2 +2 +Inductor_SMD +L_Vishay_IHSM-5832 +Inductor, Vishay, Vishay_IHSM-5832, http://www.vishay.com/docs/34020/ihsm5832.pdf, 16.3mmx8.1mm +inductor vishay icsm smd +0 +2 +2 +Inductor_SMD +L_Vishay_IHSM-7832 +Inductor, Vishay, Vishay_IHSM-7832, http://www.vishay.com/docs/34021/ihsm7832.pdf, 19.8mmx8.1mm +inductor vishay icsm smd +0 +2 +2 +Inductor_SMD +L_Wuerth_HCI-1030 +Inductor, Wuerth Elektronik, Wuerth_HCI-1030, 10.6mmx10.6mm +inductor Wuerth hci smd +0 +2 +2 +Inductor_SMD +L_Wuerth_HCI-1040 +Inductor, Wuerth Elektronik, Wuerth_HCI-1040, 10.2mmx10.2mm +inductor Wuerth hci smd +0 +2 +2 +Inductor_SMD +L_Wuerth_HCI-1050 +Inductor, Wuerth Elektronik, Wuerth_HCI-1050, 10.2mmx10.2mm +inductor Wuerth hci smd +0 +2 +2 +Inductor_SMD +L_Wuerth_HCI-1335 +Inductor, Wuerth Elektronik, Wuerth_HCI-1335, 12.8mmx12.8mm +inductor Wuerth hci smd +0 +2 +2 +Inductor_SMD +L_Wuerth_HCI-1350 +Inductor, Wuerth Elektronik, Wuerth_HCI-1350, 12.8mmx12.8mm +inductor Wuerth hci smd +0 +2 +2 +Inductor_SMD +L_Wuerth_HCI-1365 +Inductor, Wuerth Elektronik, Wuerth_HCI-1365, 12.8mmx12.8mm +inductor Wuerth hci smd +0 +2 +2 +Inductor_SMD +L_Wuerth_HCI-1890 +Inductor, Wuerth Elektronik, Wuerth_HCI-1890, 18.2mmx18.2mm +inductor Wuerth hci smd +0 +2 +2 +Inductor_SMD +L_Wuerth_HCI-2212 +Inductor, Wuerth Elektronik, Wuerth_HCI-2212, 22.5mmx22.0mm +inductor Wuerth hci smd +0 +2 +2 +Inductor_SMD +L_Wuerth_HCI-5040 +Inductor, Wuerth Elektronik, Wuerth_HCI-5040, 5.5mmx5.2mm +inductor Wuerth hci smd +0 +2 +2 +Inductor_SMD +L_Wuerth_HCI-7030 +Inductor, Wuerth Elektronik, Wuerth_HCI-7030, 6.9mmx6.9mm +inductor Wuerth hci smd +0 +2 +2 +Inductor_SMD +L_Wuerth_HCI-7040 +Inductor, Wuerth Elektronik, Wuerth_HCI-7040, 6.9mmx6.9mm +inductor Wuerth hci smd +0 +2 +2 +Inductor_SMD +L_Wuerth_HCI-7050 +Inductor, Wuerth Elektronik, Wuerth_HCI-7050, 6.9mmx6.9mm +inductor Wuerth hci smd +0 +2 +2 +Inductor_SMD +L_Wuerth_HCM-1050 +Inductor, Wuerth Elektronik, Wuerth_HCM-1050, 10.2mmx7.0mm +inductor Wuerth hcm smd +0 +2 +2 +Inductor_SMD +L_Wuerth_HCM-1052 +Inductor, Wuerth Elektronik, Wuerth_HCM-1052, 10.5mmx10.3mm +inductor Wuerth hcm smd +0 +2 +2 +Inductor_SMD +L_Wuerth_HCM-1070 +Inductor, Wuerth Elektronik, Wuerth_HCM-1070, 10.1mmx7.0mm +inductor Wuerth hcm smd +0 +2 +2 +Inductor_SMD +L_Wuerth_HCM-1078 +Inductor, Wuerth Elektronik, Wuerth_HCM-1078, 9.4mmx6.2mm +inductor Wuerth hcm smd +0 +2 +2 +Inductor_SMD +L_Wuerth_HCM-1190 +Inductor, Wuerth Elektronik, Wuerth_HCM-1190, 10.5mmx11.0mm +inductor Wuerth hcm smd +0 +2 +2 +Inductor_SMD +L_Wuerth_HCM-1240 +Inductor, Wuerth Elektronik, Wuerth_HCM-1240, 10.0mmx11.8mm +inductor Wuerth hcm smd +0 +2 +2 +Inductor_SMD +L_Wuerth_HCM-1350 +Inductor, Wuerth Elektronik, Wuerth_HCM-1350, 13.5mmx13.3mm +inductor Wuerth hcm smd +0 +2 +2 +Inductor_SMD +L_Wuerth_HCM-1390 +Inductor, Wuerth Elektronik, Wuerth_HCM-1390, 12.5mmx13.0mm +inductor Wuerth hcm smd +0 +2 +2 +Inductor_SMD +L_Wuerth_HCM-7050 +Inductor, Wuerth Elektronik, Wuerth_HCM-7050, 7.2mmx7.0mm +inductor Wuerth hcm smd +0 +2 +2 +Inductor_SMD +L_Wuerth_HCM-7070 +Inductor, Wuerth Elektronik, Wuerth_HCM-7070, 7.4mmx7.2mm +inductor Wuerth hcm smd +0 +2 +2 +Inductor_SMD +L_Wuerth_MAPI-1610 +Inductor, Wuerth Elektronik, Wuerth_MAPI-1610, 1.6mmx1.6mm +inductor Wuerth smd +0 +2 +2 +Inductor_SMD +L_Wuerth_MAPI-2010 +Inductor, Wuerth Elektronik, Wuerth_MAPI-2010, 2.0mmx1.6mm +inductor Wuerth smd +0 +2 +2 +Inductor_SMD +L_Wuerth_MAPI-2506 +Inductor, Wuerth Elektronik, Wuerth_MAPI-2506, 2.5mmx2.0mm +inductor Wuerth smd +0 +2 +2 +Inductor_SMD +L_Wuerth_MAPI-2508 +Inductor, Wuerth Elektronik, Wuerth_MAPI-2508, 2.5mmx2.0mm +inductor Wuerth smd +0 +2 +2 +Inductor_SMD +L_Wuerth_MAPI-2510 +Inductor, Wuerth Elektronik, Wuerth_MAPI-2510, 2.5mmx2.0mm +inductor Wuerth smd +0 +2 +2 +Inductor_SMD +L_Wuerth_MAPI-2512 +Inductor, Wuerth Elektronik, Wuerth_MAPI-2512, 2.5mmx2.0mm +inductor Wuerth smd +0 +2 +2 +Inductor_SMD +L_Wuerth_MAPI-3010 +Inductor, Wuerth Elektronik, Wuerth_MAPI-3010, 3.0mmx3.0mm +inductor Wuerth smd +0 +2 +2 +Inductor_SMD +L_Wuerth_MAPI-3012 +Inductor, Wuerth Elektronik, Wuerth_MAPI-3012, 3.0mmx3.0mm +inductor Wuerth smd +0 +2 +2 +Inductor_SMD +L_Wuerth_MAPI-3015 +Inductor, Wuerth Elektronik, Wuerth_MAPI-3015, 3.0mmx3.0mm +inductor Wuerth smd +0 +2 +2 +Inductor_SMD +L_Wuerth_MAPI-3020 +Inductor, Wuerth Elektronik, Wuerth_MAPI-3020, 3.0mmx3.0mm +inductor Wuerth smd +0 +2 +2 +Inductor_SMD +L_Wuerth_MAPI-4020 +Inductor, Wuerth Elektronik, Wuerth_MAPI-4020, 4.0mmx4.0mm +inductor Wuerth smd +0 +2 +2 +Inductor_SMD +L_Wuerth_MAPI-4030 +Inductor, Wuerth Elektronik, Wuerth_MAPI-4030, 4.0mmx4.0mm +inductor Wuerth smd +0 +2 +2 +Inductor_SMD +L_Wuerth_WE-DD-Typ-L-Typ-XL-Typ-XXL +Choke, Double, Doppeldrossel, SMD, , Wuerth, WE-DD, Typ L, Typ XL, Typ XXL, +Choke Double Doppeldrossel SMD Wuerth WE-DD TypL TypXL TypXXL +0 +4 +4 +Inductor_SMD +L_Wuerth_WE-DD-Typ-M-Typ-S +Choke, Double, Doppeldrossel, SMD, , Wuerth, WE-DD, Typ M, Typ S, +Choke Double Doppeldrossel SMD Wuerth WE-DD TypM TypS +0 +4 +4 +Inductor_SMD +L_Wuerth_WE-PD-Typ-7345 +Choke, Drossel, WE-PD Typ LS, Wuerth, SMD, +Choke Drossel WE-PDTypLS Wuerth SMD +0 +2 +2 +Inductor_SMD +L_Wuerth_WE-PD-Typ-LS +Choke, Drossel, WE-PD Typ LS, Wuerth, SMD, +Choke Drossel WE-PDTypLS Wuerth SMD +0 +2 +2 +Inductor_SMD +L_Wuerth_WE-PD-Typ-LS_Handsoldering +Choke, Drossel, WE-PD Typ LS, Wuerth, SMD, Handsoldering, +Choke Drossel WE-PDTypLS Wuerth SMD Handsoldering +0 +2 +2 +Inductor_SMD +L_Wuerth_WE-PD-Typ-M-Typ-S +Choke, Drossel, WE-PD, Typ M, Typ S, Wuerth, SMD, +Choke Drossel WE-PD TypM TypS Wuerth SMD +0 +2 +2 +Inductor_SMD +L_Wuerth_WE-PD-Typ-M-Typ-S_Handsoldering +Choke, Drossel, WE-PD, Typ M, Typ S, Wuerth, SMD, Handsoldering, +Choke Drossel WE-PD TypM TypS Wuerth SMD Handsoldering +0 +2 +2 +Inductor_SMD +L_Wuerth_WE-PD2-Typ-L +Choke, Drossel, WE-PD2, Typ L, Wuerth, SMD, +Choke Drossel WE-PD2 TypL Wuerth SMD +0 +2 +2 +Inductor_SMD +L_Wuerth_WE-PD2-Typ-MS +Choke, Drossel, WE-PD2, Typ MS, Wuerth, SMD, +Choke Drossel WE-PD2 TypMS Wuerth SMD +0 +2 +2 +Inductor_SMD +L_Wuerth_WE-PD2-Typ-XL +Choke, Drossel, WE-PD2, Typ XL, Wuerth, SMD, +Choke Drossel WE-PD2 TypXL Wuerth SMD +0 +2 +2 +Inductor_SMD +L_Wuerth_WE-PD4-Typ-X +Choke, Drossel, WE-PD4, Typ X, Wuerth, SMD, +Choke Drossel WE-PD4 TypX Wuerth SMD +0 +2 +2 +Inductor_SMD +L_Wuerth_WE-PDF +Choke, Drossel, WE-PDF, Wuerth, SMD, +Choke Drossel WE-PDF Wuerth SMD +0 +2 +2 +Inductor_SMD +L_Wuerth_WE-PDF_Handsoldering +Choke, Drossel, WE-PDF, Handsoldering, Wuerth, SMD, +Choke Drossel WE-PDF Handsoldering Wuerth SMD +0 +2 +2 +Inductor_SMD +L_Wuerth_WE-TPC-3816 +Inductor, WE-TPC, Wuerth, SMD, http://katalog.we-online.de/pbs/datasheet/744031220.pdf +Inductor WE-TPC Wuerth SMD +0 +10 +2 +LED_THT +LED_BL-FL7680RGB +'Piranha' RGB LED, through hole, common anode, 7.62x7.62mm, BGRA pin order, https://cdn-shop.adafruit.com/datasheets/BL-FL7680RGB.pdf +RGB LED Piranha Super-Flux BetLux +0 +4 +4 +LED_THT +LED_D1.8mm_W1.8mm_H2.4mm_Horizontal_O1.27mm_Z1.6mm +LED, , diameter 1.8mm size 1.8x2.4mm^2 z-position of LED center 1.6mm, 2 pins +LED diameter 1.8mm size 1.8x2.4mm^2 z-position of LED center 1.6mm 2 pins +0 +2 +2 +LED_THT +LED_D1.8mm_W1.8mm_H2.4mm_Horizontal_O1.27mm_Z4.9mm +LED, , diameter 1.8mm size 1.8x2.4mm^2 z-position of LED center 1.6mm, 2 pins, diameter 1.8mm size 1.8x2.4mm^2 z-position of LED center 1.6mm, 2 pins, diameter 1.8mm size 1.8x2.4mm^2 z-position of LED center 1.6mm, 2 pins, diameter 1.8mm size 1.8x2.4mm^2 z-position of LED center 4.9mm, 2 pins +LED diameter 1.8mm size 1.8x2.4mm^2 z-position of LED center 1.6mm 2 pins diameter 1.8mm size 1.8x2.4mm^2 z-position of LED center 1.6mm 2 pins diameter 1.8mm size 1.8x2.4mm^2 z-position of LED center 1.6mm 2 pins diameter 1.8mm size 1.8x2.4mm^2 z-position of LED center 4.9mm 2 pins +0 +2 +2 +LED_THT +LED_D1.8mm_W1.8mm_H2.4mm_Horizontal_O1.27mm_Z8.2mm +LED, , diameter 1.8mm size 1.8x2.4mm^2 z-position of LED center 1.6mm, 2 pins, diameter 1.8mm size 1.8x2.4mm^2 z-position of LED center 1.6mm, 2 pins, diameter 1.8mm size 1.8x2.4mm^2 z-position of LED center 1.6mm, 2 pins, diameter 1.8mm size 1.8x2.4mm^2 z-position of LED center 4.9mm, 2 pins, diameter 1.8mm size 1.8x2.4mm^2 z-position of LED center 4.9mm, 2 pins, diameter 1.8mm size 1.8x2.4mm^2 z-position of LED center 4.9mm, 2 pins, diameter 1.8mm size 1.8x2.4mm^2 z-position of LED center 8.2mm, 2 pins +LED diameter 1.8mm size 1.8x2.4mm^2 z-position of LED center 1.6mm 2 pins diameter 1.8mm size 1.8x2.4mm^2 z-position of LED center 1.6mm 2 pins diameter 1.8mm size 1.8x2.4mm^2 z-position of LED center 1.6mm 2 pins diameter 1.8mm size 1.8x2.4mm^2 z-position of LED center 4.9mm 2 pins diameter 1.8mm size 1.8x2.4mm^2 z-position of LED center 4.9mm 2 pins diameter 1.8mm size 1.8x2.4mm^2 z-position of LED center 4.9mm 2 pins diameter 1.8mm size 1.8x2.4mm^2 z-position of LED center 8.2mm 2 pins +0 +2 +2 +LED_THT +LED_D1.8mm_W1.8mm_H2.4mm_Horizontal_O3.81mm_Z1.6mm +LED, , diameter 1.8mm size 1.8x2.4mm^2 z-position of LED center 1.6mm, 2 pins, diameter 1.8mm size 1.8x2.4mm^2 z-position of LED center 1.6mm, 2 pins +LED diameter 1.8mm size 1.8x2.4mm^2 z-position of LED center 1.6mm 2 pins diameter 1.8mm size 1.8x2.4mm^2 z-position of LED center 1.6mm 2 pins +0 +2 +2 +LED_THT +LED_D1.8mm_W1.8mm_H2.4mm_Horizontal_O3.81mm_Z4.9mm +LED, , diameter 1.8mm size 1.8x2.4mm^2 z-position of LED center 1.6mm, 2 pins, diameter 1.8mm size 1.8x2.4mm^2 z-position of LED center 1.6mm, 2 pins, diameter 1.8mm size 1.8x2.4mm^2 z-position of LED center 1.6mm, 2 pins, diameter 1.8mm size 1.8x2.4mm^2 z-position of LED center 4.9mm, 2 pins, diameter 1.8mm size 1.8x2.4mm^2 z-position of LED center 4.9mm, 2 pins +LED diameter 1.8mm size 1.8x2.4mm^2 z-position of LED center 1.6mm 2 pins diameter 1.8mm size 1.8x2.4mm^2 z-position of LED center 1.6mm 2 pins diameter 1.8mm size 1.8x2.4mm^2 z-position of LED center 1.6mm 2 pins diameter 1.8mm size 1.8x2.4mm^2 z-position of LED center 4.9mm 2 pins diameter 1.8mm size 1.8x2.4mm^2 z-position of LED center 4.9mm 2 pins +0 +2 +2 +LED_THT +LED_D1.8mm_W1.8mm_H2.4mm_Horizontal_O3.81mm_Z8.2mm +LED, , diameter 1.8mm size 1.8x2.4mm^2 z-position of LED center 1.6mm, 2 pins, diameter 1.8mm size 1.8x2.4mm^2 z-position of LED center 1.6mm, 2 pins, diameter 1.8mm size 1.8x2.4mm^2 z-position of LED center 1.6mm, 2 pins, diameter 1.8mm size 1.8x2.4mm^2 z-position of LED center 4.9mm, 2 pins, diameter 1.8mm size 1.8x2.4mm^2 z-position of LED center 4.9mm, 2 pins, diameter 1.8mm size 1.8x2.4mm^2 z-position of LED center 4.9mm, 2 pins, diameter 1.8mm size 1.8x2.4mm^2 z-position of LED center 8.2mm, 2 pins, diameter 1.8mm size 1.8x2.4mm^2 z-position of LED center 8.2mm, 2 pins +LED diameter 1.8mm size 1.8x2.4mm^2 z-position of LED center 1.6mm 2 pins diameter 1.8mm size 1.8x2.4mm^2 z-position of LED center 1.6mm 2 pins diameter 1.8mm size 1.8x2.4mm^2 z-position of LED center 1.6mm 2 pins diameter 1.8mm size 1.8x2.4mm^2 z-position of LED center 4.9mm 2 pins diameter 1.8mm size 1.8x2.4mm^2 z-position of LED center 4.9mm 2 pins diameter 1.8mm size 1.8x2.4mm^2 z-position of LED center 4.9mm 2 pins diameter 1.8mm size 1.8x2.4mm^2 z-position of LED center 8.2mm 2 pins diameter 1.8mm size 1.8x2.4mm^2 z-position of LED center 8.2mm 2 pins +0 +2 +2 +LED_THT +LED_D1.8mm_W1.8mm_H2.4mm_Horizontal_O6.35mm_Z1.6mm +LED, , diameter 1.8mm size 1.8x2.4mm^2 z-position of LED center 1.6mm, 2 pins, diameter 1.8mm size 1.8x2.4mm^2 z-position of LED center 1.6mm, 2 pins, diameter 1.8mm size 1.8x2.4mm^2 z-position of LED center 1.6mm, 2 pins +LED diameter 1.8mm size 1.8x2.4mm^2 z-position of LED center 1.6mm 2 pins diameter 1.8mm size 1.8x2.4mm^2 z-position of LED center 1.6mm 2 pins diameter 1.8mm size 1.8x2.4mm^2 z-position of LED center 1.6mm 2 pins +0 +2 +2 +LED_THT +LED_D1.8mm_W1.8mm_H2.4mm_Horizontal_O6.35mm_Z4.9mm +LED, , diameter 1.8mm size 1.8x2.4mm^2 z-position of LED center 1.6mm, 2 pins, diameter 1.8mm size 1.8x2.4mm^2 z-position of LED center 1.6mm, 2 pins, diameter 1.8mm size 1.8x2.4mm^2 z-position of LED center 1.6mm, 2 pins, diameter 1.8mm size 1.8x2.4mm^2 z-position of LED center 4.9mm, 2 pins, diameter 1.8mm size 1.8x2.4mm^2 z-position of LED center 4.9mm, 2 pins, diameter 1.8mm size 1.8x2.4mm^2 z-position of LED center 4.9mm, 2 pins +LED diameter 1.8mm size 1.8x2.4mm^2 z-position of LED center 1.6mm 2 pins diameter 1.8mm size 1.8x2.4mm^2 z-position of LED center 1.6mm 2 pins diameter 1.8mm size 1.8x2.4mm^2 z-position of LED center 1.6mm 2 pins diameter 1.8mm size 1.8x2.4mm^2 z-position of LED center 4.9mm 2 pins diameter 1.8mm size 1.8x2.4mm^2 z-position of LED center 4.9mm 2 pins diameter 1.8mm size 1.8x2.4mm^2 z-position of LED center 4.9mm 2 pins +0 +2 +2 +LED_THT +LED_D1.8mm_W1.8mm_H2.4mm_Horizontal_O6.35mm_Z8.2mm +LED, , diameter 1.8mm size 1.8x2.4mm^2 z-position of LED center 1.6mm, 2 pins, diameter 1.8mm size 1.8x2.4mm^2 z-position of LED center 1.6mm, 2 pins, diameter 1.8mm size 1.8x2.4mm^2 z-position of LED center 1.6mm, 2 pins, diameter 1.8mm size 1.8x2.4mm^2 z-position of LED center 4.9mm, 2 pins, diameter 1.8mm size 1.8x2.4mm^2 z-position of LED center 4.9mm, 2 pins, diameter 1.8mm size 1.8x2.4mm^2 z-position of LED center 4.9mm, 2 pins, diameter 1.8mm size 1.8x2.4mm^2 z-position of LED center 8.2mm, 2 pins, diameter 1.8mm size 1.8x2.4mm^2 z-position of LED center 8.2mm, 2 pins, diameter 1.8mm size 1.8x2.4mm^2 z-position of LED center 8.2mm, 2 pins +LED diameter 1.8mm size 1.8x2.4mm^2 z-position of LED center 1.6mm 2 pins diameter 1.8mm size 1.8x2.4mm^2 z-position of LED center 1.6mm 2 pins diameter 1.8mm size 1.8x2.4mm^2 z-position of LED center 1.6mm 2 pins diameter 1.8mm size 1.8x2.4mm^2 z-position of LED center 4.9mm 2 pins diameter 1.8mm size 1.8x2.4mm^2 z-position of LED center 4.9mm 2 pins diameter 1.8mm size 1.8x2.4mm^2 z-position of LED center 4.9mm 2 pins diameter 1.8mm size 1.8x2.4mm^2 z-position of LED center 8.2mm 2 pins diameter 1.8mm size 1.8x2.4mm^2 z-position of LED center 8.2mm 2 pins diameter 1.8mm size 1.8x2.4mm^2 z-position of LED center 8.2mm 2 pins +0 +2 +2 +LED_THT +LED_D1.8mm_W3.3mm_H2.4mm +LED, Round, Rectangular size 3.3x2.4mm^2 diameter 1.8mm, 2 pins +LED Round Rectangular size 3.3x2.4mm^2 diameter 1.8mm 2 pins +0 +2 +2 +LED_THT +LED_D2.0mm_W4.0mm_H2.8mm_FlatTop +LED, Round, FlatTop, Rectangular size 4.0x2.8mm^2 diameter 2.0mm, 2 pins, http://www.kingbright.com/attachments/file/psearch/000/00/00/L-1034IDT(Ver.9A).pdf +LED Round FlatTop Rectangular size 4.0x2.8mm^2 diameter 2.0mm 2 pins +0 +2 +2 +LED_THT +LED_D2.0mm_W4.8mm_H2.5mm_FlatTop +LED, Round, FlatTop, Rectangular size 4.8x2.5mm^2 diameter 2.0mm, 2 pins, http://www.kingbright.com/attachments/file/psearch/000/00/00/L-13GD(Ver.11B).pdf +LED Round FlatTop Rectangular size 4.8x2.5mm^2 diameter 2.0mm 2 pins +0 +2 +2 +LED_THT +LED_D3.0mm +LED, diameter 3.0mm, 2 pins +LED diameter 3.0mm 2 pins +0 +2 +2 +LED_THT +LED_D3.0mm-3 +LED, diameter 3.0mm, 2 pins, diameter 3.0mm, 3 pins, http://www.kingbright.com/attachments/file/psearch/000/00/00/L-3VSURKCGKC(Ver.8A).pdf +LED diameter 3.0mm 2 pins diameter 3.0mm 3 pins +0 +3 +3 +LED_THT +LED_D3.0mm_Clear +IR-LED, diameter 3.0mm, 2 pins, color: clear +IR infrared LED diameter 3.0mm 2 pins clear +0 +2 +2 +LED_THT +LED_D3.0mm_FlatTop +LED, Round, FlatTop, diameter 3.0mm, 2 pins, http://www.kingbright.com/attachments/file/psearch/000/00/00/L-47XEC(Ver.9A).pdf +LED Round FlatTop diameter 3.0mm 2 pins +0 +2 +2 +LED_THT +LED_D3.0mm_Horizontal_O1.27mm_Z2.0mm +LED, diameter 3.0mm z-position of LED center 2.0mm, 2 pins +LED diameter 3.0mm z-position of LED center 2.0mm 2 pins +0 +2 +2 +LED_THT +LED_D3.0mm_Horizontal_O1.27mm_Z2.0mm_Clear +LED, diameter 3.0mm z-position of LED center 2.0mm, 2 pins +LED diameter 3.0mm z-position of LED center 2.0mm 2 pins +0 +2 +2 +LED_THT +LED_D3.0mm_Horizontal_O1.27mm_Z2.0mm_IRBlack +LED, diameter 3.0mm z-position of LED center 2.0mm, 2 pins +LED diameter 3.0mm z-position of LED center 2.0mm 2 pins +0 +2 +2 +LED_THT +LED_D3.0mm_Horizontal_O1.27mm_Z2.0mm_IRGrey +LED, diameter 3.0mm z-position of LED center 2.0mm, 2 pins +LED diameter 3.0mm z-position of LED center 2.0mm 2 pins +0 +2 +2 +LED_THT +LED_D3.0mm_Horizontal_O1.27mm_Z6.0mm +LED, diameter 3.0mm z-position of LED center 2.0mm, 2 pins, diameter 3.0mm z-position of LED center 2.0mm, 2 pins, diameter 3.0mm z-position of LED center 2.0mm, 2 pins, diameter 3.0mm z-position of LED center 6.0mm, 2 pins +LED diameter 3.0mm z-position of LED center 2.0mm 2 pins diameter 3.0mm z-position of LED center 2.0mm 2 pins diameter 3.0mm z-position of LED center 2.0mm 2 pins diameter 3.0mm z-position of LED center 6.0mm 2 pins +0 +2 +2 +LED_THT +LED_D3.0mm_Horizontal_O1.27mm_Z10.0mm +LED, diameter 3.0mm z-position of LED center 2.0mm, 2 pins, diameter 3.0mm z-position of LED center 2.0mm, 2 pins, diameter 3.0mm z-position of LED center 2.0mm, 2 pins, diameter 3.0mm z-position of LED center 6.0mm, 2 pins, diameter 3.0mm z-position of LED center 6.0mm, 2 pins, diameter 3.0mm z-position of LED center 6.0mm, 2 pins, diameter 3.0mm z-position of LED center 10.0mm, 2 pins +LED diameter 3.0mm z-position of LED center 2.0mm 2 pins diameter 3.0mm z-position of LED center 2.0mm 2 pins diameter 3.0mm z-position of LED center 2.0mm 2 pins diameter 3.0mm z-position of LED center 6.0mm 2 pins diameter 3.0mm z-position of LED center 6.0mm 2 pins diameter 3.0mm z-position of LED center 6.0mm 2 pins diameter 3.0mm z-position of LED center 10.0mm 2 pins +0 +2 +2 +LED_THT +LED_D3.0mm_Horizontal_O3.81mm_Z2.0mm +LED, diameter 3.0mm z-position of LED center 2.0mm, 2 pins, diameter 3.0mm z-position of LED center 2.0mm, 2 pins +LED diameter 3.0mm z-position of LED center 2.0mm 2 pins diameter 3.0mm z-position of LED center 2.0mm 2 pins +0 +2 +2 +LED_THT +LED_D3.0mm_Horizontal_O3.81mm_Z6.0mm +LED, diameter 3.0mm z-position of LED center 2.0mm, 2 pins, diameter 3.0mm z-position of LED center 2.0mm, 2 pins, diameter 3.0mm z-position of LED center 2.0mm, 2 pins, diameter 3.0mm z-position of LED center 6.0mm, 2 pins, diameter 3.0mm z-position of LED center 6.0mm, 2 pins +LED diameter 3.0mm z-position of LED center 2.0mm 2 pins diameter 3.0mm z-position of LED center 2.0mm 2 pins diameter 3.0mm z-position of LED center 2.0mm 2 pins diameter 3.0mm z-position of LED center 6.0mm 2 pins diameter 3.0mm z-position of LED center 6.0mm 2 pins +0 +2 +2 +LED_THT +LED_D3.0mm_Horizontal_O3.81mm_Z10.0mm +LED, diameter 3.0mm z-position of LED center 2.0mm, 2 pins, diameter 3.0mm z-position of LED center 2.0mm, 2 pins, diameter 3.0mm z-position of LED center 2.0mm, 2 pins, diameter 3.0mm z-position of LED center 6.0mm, 2 pins, diameter 3.0mm z-position of LED center 6.0mm, 2 pins, diameter 3.0mm z-position of LED center 6.0mm, 2 pins, diameter 3.0mm z-position of LED center 10.0mm, 2 pins, diameter 3.0mm z-position of LED center 10.0mm, 2 pins +LED diameter 3.0mm z-position of LED center 2.0mm 2 pins diameter 3.0mm z-position of LED center 2.0mm 2 pins diameter 3.0mm z-position of LED center 2.0mm 2 pins diameter 3.0mm z-position of LED center 6.0mm 2 pins diameter 3.0mm z-position of LED center 6.0mm 2 pins diameter 3.0mm z-position of LED center 6.0mm 2 pins diameter 3.0mm z-position of LED center 10.0mm 2 pins diameter 3.0mm z-position of LED center 10.0mm 2 pins +0 +2 +2 +LED_THT +LED_D3.0mm_Horizontal_O6.35mm_Z2.0mm +LED, diameter 3.0mm z-position of LED center 2.0mm, 2 pins, diameter 3.0mm z-position of LED center 2.0mm, 2 pins, diameter 3.0mm z-position of LED center 2.0mm, 2 pins +LED diameter 3.0mm z-position of LED center 2.0mm 2 pins diameter 3.0mm z-position of LED center 2.0mm 2 pins diameter 3.0mm z-position of LED center 2.0mm 2 pins +0 +2 +2 +LED_THT +LED_D3.0mm_Horizontal_O6.35mm_Z6.0mm +LED, diameter 3.0mm z-position of LED center 2.0mm, 2 pins, diameter 3.0mm z-position of LED center 2.0mm, 2 pins, diameter 3.0mm z-position of LED center 2.0mm, 2 pins, diameter 3.0mm z-position of LED center 6.0mm, 2 pins, diameter 3.0mm z-position of LED center 6.0mm, 2 pins, diameter 3.0mm z-position of LED center 6.0mm, 2 pins +LED diameter 3.0mm z-position of LED center 2.0mm 2 pins diameter 3.0mm z-position of LED center 2.0mm 2 pins diameter 3.0mm z-position of LED center 2.0mm 2 pins diameter 3.0mm z-position of LED center 6.0mm 2 pins diameter 3.0mm z-position of LED center 6.0mm 2 pins diameter 3.0mm z-position of LED center 6.0mm 2 pins +0 +2 +2 +LED_THT +LED_D3.0mm_Horizontal_O6.35mm_Z10.0mm +LED, diameter 3.0mm z-position of LED center 2.0mm, 2 pins, diameter 3.0mm z-position of LED center 2.0mm, 2 pins, diameter 3.0mm z-position of LED center 2.0mm, 2 pins, diameter 3.0mm z-position of LED center 6.0mm, 2 pins, diameter 3.0mm z-position of LED center 6.0mm, 2 pins, diameter 3.0mm z-position of LED center 6.0mm, 2 pins, diameter 3.0mm z-position of LED center 10.0mm, 2 pins, diameter 3.0mm z-position of LED center 10.0mm, 2 pins, diameter 3.0mm z-position of LED center 10.0mm, 2 pins +LED diameter 3.0mm z-position of LED center 2.0mm 2 pins diameter 3.0mm z-position of LED center 2.0mm 2 pins diameter 3.0mm z-position of LED center 2.0mm 2 pins diameter 3.0mm z-position of LED center 6.0mm 2 pins diameter 3.0mm z-position of LED center 6.0mm 2 pins diameter 3.0mm z-position of LED center 6.0mm 2 pins diameter 3.0mm z-position of LED center 10.0mm 2 pins diameter 3.0mm z-position of LED center 10.0mm 2 pins diameter 3.0mm z-position of LED center 10.0mm 2 pins +0 +2 +2 +LED_THT +LED_D3.0mm_IRBlack +IR-ED, diameter 3.0mm, 2 pins, color: black +IR infrared LED diameter 3.0mm 2 pins black +0 +2 +2 +LED_THT +LED_D3.0mm_IRGrey +IR-LED, diameter 3.0mm, 2 pins, color: grey +IR infrared LED diameter 3.0mm 2 pins grey +0 +2 +2 +LED_THT +LED_D4.0mm +LED, diameter 4.0mm, 2 pins, http://www.kingbright.com/attachments/file/psearch/000/00/00/L-43GD(Ver.12B).pdf +LED diameter 4.0mm 2 pins +0 +2 +2 +LED_THT +LED_D5.0mm +LED, diameter 5.0mm, 2 pins, http://cdn-reichelt.de/documents/datenblatt/A500/LL-504BC2E-009.pdf +LED diameter 5.0mm 2 pins +0 +2 +2 +LED_THT +LED_D5.0mm-3 +LED, diameter 5.0mm, 2 pins, diameter 5.0mm, 3 pins, http://www.kingbright.com/attachments/file/psearch/000/00/00/L-59EGC(Ver.17A).pdf +LED diameter 5.0mm 2 pins diameter 5.0mm 3 pins +0 +3 +3 +LED_THT +LED_D5.0mm-3_Horizontal_O3.81mm_Z3.0mm +LED, diameter 5.0mm z-position of LED center 3.0mm, 3 pins, diameter 5.0mm z-position of LED center 3.0mm, 2 pins +LED diameter 5.0mm z-position of LED center 3.0mm 3 pins diameter 5.0mm z-position of LED center 3.0mm 2 pins +0 +3 +3 +LED_THT +LED_D5.0mm-4_RGB +LED, diameter 5.0mm, 2 pins, diameter 5.0mm, 3 pins, diameter 5.0mm, 4 pins, http://www.kingbright.com/attachments/file/psearch/000/00/00/L-154A4SUREQBFZGEW(Ver.9A).pdf +LED diameter 5.0mm 2 pins diameter 5.0mm 3 pins diameter 5.0mm 4 pins RGB RGBLED +0 +4 +4 +LED_THT +LED_D5.0mm-4_RGB_Staggered_Pins +LED, diameter 5.0mm, 2 pins, diameter 5.0mm, 3 pins, diameter 5.0mm, 4 pins, http://www.kingbright.com/attachments/file/psearch/000/00/00/L-154A4SUREQBFZGEW(Ver.9A).pdf +LED diameter 5.0mm 2 pins diameter 5.0mm 3 pins diameter 5.0mm 4 pins RGB RGBLED +0 +4 +4 +LED_THT +LED_D5.0mm-4_RGB_Wide_Pins +LED, diameter 5.0mm, 2 pins, diameter 5.0mm, 3 pins, diameter 5.0mm, 4 pins, http://www.kingbright.com/attachments/file/psearch/000/00/00/L-154A4SUREQBFZGEW(Ver.9A).pdf +LED diameter 5.0mm 2 pins diameter 5.0mm 3 pins diameter 5.0mm 4 pins RGB RGBLED +0 +4 +4 +LED_THT +LED_D5.0mm_Clear +LED, diameter 5.0mm, 2 pins, http://cdn-reichelt.de/documents/datenblatt/A500/LL-504BC2E-009.pdf +LED diameter 5.0mm 2 pins +0 +2 +2 +LED_THT +LED_D5.0mm_FlatTop +LED, Round, FlatTop, diameter 5.0mm, 2 pins, http://www.kingbright.com/attachments/file/psearch/000/00/00/L-483GDT(Ver.15B).pdf +LED Round FlatTop diameter 5.0mm 2 pins +0 +2 +2 +LED_THT +LED_D5.0mm_Horizontal_O1.27mm_Z3.0mm +LED, diameter 5.0mm z-position of LED center 3.0mm, 2 pins +LED diameter 5.0mm z-position of LED center 3.0mm 2 pins +0 +2 +2 +LED_THT +LED_D5.0mm_Horizontal_O1.27mm_Z3.0mm_Clear +LED, diameter 5.0mm z-position of LED center 3.0mm, 2 pins +LED diameter 5.0mm z-position of LED center 3.0mm 2 pins +0 +2 +2 +LED_THT +LED_D5.0mm_Horizontal_O1.27mm_Z3.0mm_IRBlack +LED, diameter 5.0mm z-position of LED center 3.0mm, 2 pins +LED diameter 5.0mm z-position of LED center 3.0mm 2 pins +0 +2 +2 +LED_THT +LED_D5.0mm_Horizontal_O1.27mm_Z3.0mm_IRGrey +LED, diameter 5.0mm z-position of LED center 3.0mm, 2 pins +LED diameter 5.0mm z-position of LED center 3.0mm 2 pins +0 +2 +2 +LED_THT +LED_D5.0mm_Horizontal_O1.27mm_Z9.0mm +LED, diameter 5.0mm z-position of LED center 3.0mm, 2 pins, diameter 5.0mm z-position of LED center 3.0mm, 2 pins, diameter 5.0mm z-position of LED center 3.0mm, 2 pins, diameter 5.0mm z-position of LED center 9.0mm, 2 pins +LED diameter 5.0mm z-position of LED center 3.0mm 2 pins diameter 5.0mm z-position of LED center 3.0mm 2 pins diameter 5.0mm z-position of LED center 3.0mm 2 pins diameter 5.0mm z-position of LED center 9.0mm 2 pins +0 +2 +2 +LED_THT +LED_D5.0mm_Horizontal_O1.27mm_Z15.0mm +LED, diameter 5.0mm z-position of LED center 3.0mm, 2 pins, diameter 5.0mm z-position of LED center 3.0mm, 2 pins, diameter 5.0mm z-position of LED center 3.0mm, 2 pins, diameter 5.0mm z-position of LED center 9.0mm, 2 pins, diameter 5.0mm z-position of LED center 9.0mm, 2 pins, diameter 5.0mm z-position of LED center 9.0mm, 2 pins, diameter 5.0mm z-position of LED center 15.0mm, 2 pins +LED diameter 5.0mm z-position of LED center 3.0mm 2 pins diameter 5.0mm z-position of LED center 3.0mm 2 pins diameter 5.0mm z-position of LED center 3.0mm 2 pins diameter 5.0mm z-position of LED center 9.0mm 2 pins diameter 5.0mm z-position of LED center 9.0mm 2 pins diameter 5.0mm z-position of LED center 9.0mm 2 pins diameter 5.0mm z-position of LED center 15.0mm 2 pins +0 +2 +2 +LED_THT +LED_D5.0mm_Horizontal_O3.81mm_Z3.0mm +LED, diameter 5.0mm z-position of LED center 3.0mm, 2 pins, diameter 5.0mm z-position of LED center 3.0mm, 2 pins +LED diameter 5.0mm z-position of LED center 3.0mm 2 pins diameter 5.0mm z-position of LED center 3.0mm 2 pins +0 +2 +2 +LED_THT +LED_D5.0mm_Horizontal_O3.81mm_Z9.0mm +LED, diameter 5.0mm z-position of LED center 3.0mm, 2 pins, diameter 5.0mm z-position of LED center 3.0mm, 2 pins, diameter 5.0mm z-position of LED center 3.0mm, 2 pins, diameter 5.0mm z-position of LED center 9.0mm, 2 pins, diameter 5.0mm z-position of LED center 9.0mm, 2 pins +LED diameter 5.0mm z-position of LED center 3.0mm 2 pins diameter 5.0mm z-position of LED center 3.0mm 2 pins diameter 5.0mm z-position of LED center 3.0mm 2 pins diameter 5.0mm z-position of LED center 9.0mm 2 pins diameter 5.0mm z-position of LED center 9.0mm 2 pins +0 +2 +2 +LED_THT +LED_D5.0mm_Horizontal_O3.81mm_Z15.0mm +LED, diameter 5.0mm z-position of LED center 3.0mm, 2 pins, diameter 5.0mm z-position of LED center 3.0mm, 2 pins, diameter 5.0mm z-position of LED center 3.0mm, 2 pins, diameter 5.0mm z-position of LED center 9.0mm, 2 pins, diameter 5.0mm z-position of LED center 9.0mm, 2 pins, diameter 5.0mm z-position of LED center 9.0mm, 2 pins, diameter 5.0mm z-position of LED center 15.0mm, 2 pins, diameter 5.0mm z-position of LED center 15.0mm, 2 pins +LED diameter 5.0mm z-position of LED center 3.0mm 2 pins diameter 5.0mm z-position of LED center 3.0mm 2 pins diameter 5.0mm z-position of LED center 3.0mm 2 pins diameter 5.0mm z-position of LED center 9.0mm 2 pins diameter 5.0mm z-position of LED center 9.0mm 2 pins diameter 5.0mm z-position of LED center 9.0mm 2 pins diameter 5.0mm z-position of LED center 15.0mm 2 pins diameter 5.0mm z-position of LED center 15.0mm 2 pins +0 +2 +2 +LED_THT +LED_D5.0mm_Horizontal_O6.35mm_Z3.0mm +LED, diameter 5.0mm z-position of LED center 3.0mm, 2 pins, diameter 5.0mm z-position of LED center 3.0mm, 2 pins, diameter 5.0mm z-position of LED center 3.0mm, 2 pins +LED diameter 5.0mm z-position of LED center 3.0mm 2 pins diameter 5.0mm z-position of LED center 3.0mm 2 pins diameter 5.0mm z-position of LED center 3.0mm 2 pins +0 +2 +2 +LED_THT +LED_D5.0mm_Horizontal_O6.35mm_Z9.0mm +LED, diameter 5.0mm z-position of LED center 3.0mm, 2 pins, diameter 5.0mm z-position of LED center 3.0mm, 2 pins, diameter 5.0mm z-position of LED center 3.0mm, 2 pins, diameter 5.0mm z-position of LED center 9.0mm, 2 pins, diameter 5.0mm z-position of LED center 9.0mm, 2 pins, diameter 5.0mm z-position of LED center 9.0mm, 2 pins +LED diameter 5.0mm z-position of LED center 3.0mm 2 pins diameter 5.0mm z-position of LED center 3.0mm 2 pins diameter 5.0mm z-position of LED center 3.0mm 2 pins diameter 5.0mm z-position of LED center 9.0mm 2 pins diameter 5.0mm z-position of LED center 9.0mm 2 pins diameter 5.0mm z-position of LED center 9.0mm 2 pins +0 +2 +2 +LED_THT +LED_D5.0mm_Horizontal_O6.35mm_Z15.0mm +LED, diameter 5.0mm z-position of LED center 3.0mm, 2 pins, diameter 5.0mm z-position of LED center 3.0mm, 2 pins, diameter 5.0mm z-position of LED center 3.0mm, 2 pins, diameter 5.0mm z-position of LED center 9.0mm, 2 pins, diameter 5.0mm z-position of LED center 9.0mm, 2 pins, diameter 5.0mm z-position of LED center 9.0mm, 2 pins, diameter 5.0mm z-position of LED center 15.0mm, 2 pins, diameter 5.0mm z-position of LED center 15.0mm, 2 pins, diameter 5.0mm z-position of LED center 15.0mm, 2 pins +LED diameter 5.0mm z-position of LED center 3.0mm 2 pins diameter 5.0mm z-position of LED center 3.0mm 2 pins diameter 5.0mm z-position of LED center 3.0mm 2 pins diameter 5.0mm z-position of LED center 9.0mm 2 pins diameter 5.0mm z-position of LED center 9.0mm 2 pins diameter 5.0mm z-position of LED center 9.0mm 2 pins diameter 5.0mm z-position of LED center 15.0mm 2 pins diameter 5.0mm z-position of LED center 15.0mm 2 pins diameter 5.0mm z-position of LED center 15.0mm 2 pins +0 +2 +2 +LED_THT +LED_D5.0mm_IRBlack +LED, diameter 5.0mm, 2 pins, http://cdn-reichelt.de/documents/datenblatt/A500/LL-504BC2E-009.pdf +LED diameter 5.0mm 2 pins +0 +2 +2 +LED_THT +LED_D5.0mm_IRGrey +LED, diameter 5.0mm, 2 pins, http://cdn-reichelt.de/documents/datenblatt/A500/LL-504BC2E-009.pdf +LED diameter 5.0mm 2 pins +0 +2 +2 +LED_THT +LED_D8.0mm +LED, diameter 8.0mm, 2 pins, http://cdn-reichelt.de/documents/datenblatt/A500/LED8MMGE_LED8MMGN_LED8MMRT%23KIN.pdf +LED diameter 8.0mm 2 pins +0 +2 +2 +LED_THT +LED_D8.0mm-3 +LED, diameter 8.0mm, 2 pins, diameter 8.0mm, 3 pins +LED diameter 8.0mm 2 pins diameter 8.0mm 3 pins +0 +3 +3 +LED_THT +LED_D10.0mm +LED, diameter 10.0mm, 2 pins, http://cdn-reichelt.de/documents/datenblatt/A500/LED10-4500RT%23KIN.pdf +LED diameter 10.0mm 2 pins +0 +2 +2 +LED_THT +LED_D10.0mm-3 +LED, diameter 10.0mm, 2 pins, diameter 10.0mm, 3 pins, http://www.kingbright.com/attachments/file/psearch/000/00/00/L-819EGW(Ver.14A).pdf +LED diameter 10.0mm 2 pins diameter 10.0mm 3 pins +0 +3 +3 +LED_THT +LED_D20.0mm +LED, diameter 20.0mm, 2 pins, http://cdn-reichelt.de/documents/datenblatt/A500/DLC2-6GD%28V6%29.pdf +LED diameter 20.0mm 2 pins +0 +2 +2 +LED_THT +LED_Oval_W5.2mm_H3.8mm +LED_Oval, Oval, Oval size 5.2x3.8mm^2, 2 pins, http://www.kingbright.com/attachments/file/psearch/000/00/00/L-5603QBC-D(Ver.12B).pdf +LED_Oval Oval Oval size 5.2x3.8mm^2 2 pins +0 +2 +2 +LED_THT +LED_Rectangular_W3.0mm_H2.0mm +LED_Rectangular, Rectangular, Rectangular size 3.0x2.0mm^2, 2 pins, http://www.kingbright.com/attachments/file/psearch/000/00/00/L-169XCGDK(Ver.9B).pdf +LED_Rectangular Rectangular Rectangular size 3.0x2.0mm^2 2 pins +0 +2 +2 +LED_THT +LED_Rectangular_W3.9mm_H1.8mm +LED_Rectangular, Rectangular, Rectangular size 3.9x1.8mm^2, 2 pins, http://www.kingbright.com/attachments/file/psearch/000/00/00/L-2774GD(Ver.7B).pdf +LED_Rectangular Rectangular Rectangular size 3.9x1.8mm^2 2 pins +0 +2 +2 +LED_THT +LED_Rectangular_W3.9mm_H1.8mm_FlatTop +LED_Rectangular, Rectangular, Rectangular size 3.9x1.8mm^2, 2 pins, http://www.kingbright.com/attachments/file/psearch/000/00/00/L-2774GD(Ver.7B).pdf +LED_Rectangular Rectangular Rectangular size 3.9x1.8mm^2 2 pins +0 +2 +2 +LED_THT +LED_Rectangular_W3.9mm_H1.9mm +LED_Rectangular, Rectangular, Rectangular size 3.9x1.9mm^2, 2 pins, http://www.kingbright.com/attachments/file/psearch/000/00/00/L-144GDT(Ver.14B).pdf +LED_Rectangular Rectangular Rectangular size 3.9x1.9mm^2 2 pins +0 +2 +2 +LED_THT +LED_Rectangular_W5.0mm_H2.0mm +LED_Rectangular, Rectangular, Rectangular size 5.0x2.0mm^2, 2 pins, http://www.kingbright.com/attachments/file/psearch/000/00/00/L-169XCGDK(Ver.9B).pdf +LED_Rectangular Rectangular Rectangular size 5.0x2.0mm^2 2 pins +0 +2 +2 +LED_THT +LED_Rectangular_W5.0mm_H2.0mm-3Pins +LED_Rectangular, Rectangular, Rectangular size 5.0x2.0mm^2, 3 pins, http://www.kingbright.com/attachments/file/psearch/000/00/00/L-169XCGDK(Ver.9B).pdf +LED_Rectangular Rectangular Rectangular size 5.0x2.0mm^2 3 pins +0 +3 +3 +LED_THT +LED_Rectangular_W5.0mm_H2.0mm_Horizontal_O1.27mm_Z1.0mm +LED_Rectangular, Rectangular, Rectangular size 5.0x2.0mm^2 z-position of LED center 1.0mm, 2 pins +LED_Rectangular Rectangular Rectangular size 5.0x2.0mm^2 z-position of LED center 1.0mm 2 pins +0 +2 +2 +LED_THT +LED_Rectangular_W5.0mm_H2.0mm_Horizontal_O1.27mm_Z3.0mm +LED_Rectangular, Rectangular, Rectangular size 5.0x2.0mm^2 z-position of LED center 1.0mm, 2 pins, Rectangular size 5.0x2.0mm^2 z-position of LED center 1.0mm, 2 pins, Rectangular size 5.0x2.0mm^2 z-position of LED center 1.0mm, 2 pins, Rectangular size 5.0x2.0mm^2 z-position of LED center 3.0mm, 2 pins +LED_Rectangular Rectangular Rectangular size 5.0x2.0mm^2 z-position of LED center 1.0mm 2 pins Rectangular size 5.0x2.0mm^2 z-position of LED center 1.0mm 2 pins Rectangular size 5.0x2.0mm^2 z-position of LED center 1.0mm 2 pins Rectangular size 5.0x2.0mm^2 z-position of LED center 3.0mm 2 pins +0 +2 +2 +LED_THT +LED_Rectangular_W5.0mm_H2.0mm_Horizontal_O1.27mm_Z5.0mm +LED_Rectangular, Rectangular, Rectangular size 5.0x2.0mm^2 z-position of LED center 1.0mm, 2 pins, Rectangular size 5.0x2.0mm^2 z-position of LED center 1.0mm, 2 pins, Rectangular size 5.0x2.0mm^2 z-position of LED center 1.0mm, 2 pins, Rectangular size 5.0x2.0mm^2 z-position of LED center 3.0mm, 2 pins, Rectangular size 5.0x2.0mm^2 z-position of LED center 3.0mm, 2 pins, Rectangular size 5.0x2.0mm^2 z-position of LED center 3.0mm, 2 pins, Rectangular size 5.0x2.0mm^2 z-position of LED center 5.0mm, 2 pins +LED_Rectangular Rectangular Rectangular size 5.0x2.0mm^2 z-position of LED center 1.0mm 2 pins Rectangular size 5.0x2.0mm^2 z-position of LED center 1.0mm 2 pins Rectangular size 5.0x2.0mm^2 z-position of LED center 1.0mm 2 pins Rectangular size 5.0x2.0mm^2 z-position of LED center 3.0mm 2 pins Rectangular size 5.0x2.0mm^2 z-position of LED center 3.0mm 2 pins Rectangular size 5.0x2.0mm^2 z-position of LED center 3.0mm 2 pins Rectangular size 5.0x2.0mm^2 z-position of LED center 5.0mm 2 pins +0 +2 +2 +LED_THT +LED_Rectangular_W5.0mm_H2.0mm_Horizontal_O3.81mm_Z1.0mm +LED_Rectangular, Rectangular, Rectangular size 5.0x2.0mm^2 z-position of LED center 1.0mm, 2 pins, Rectangular size 5.0x2.0mm^2 z-position of LED center 1.0mm, 2 pins +LED_Rectangular Rectangular Rectangular size 5.0x2.0mm^2 z-position of LED center 1.0mm 2 pins Rectangular size 5.0x2.0mm^2 z-position of LED center 1.0mm 2 pins +0 +2 +2 +LED_THT +LED_Rectangular_W5.0mm_H2.0mm_Horizontal_O3.81mm_Z3.0mm +LED_Rectangular, Rectangular, Rectangular size 5.0x2.0mm^2 z-position of LED center 1.0mm, 2 pins, Rectangular size 5.0x2.0mm^2 z-position of LED center 1.0mm, 2 pins, Rectangular size 5.0x2.0mm^2 z-position of LED center 1.0mm, 2 pins, Rectangular size 5.0x2.0mm^2 z-position of LED center 3.0mm, 2 pins, Rectangular size 5.0x2.0mm^2 z-position of LED center 3.0mm, 2 pins +LED_Rectangular Rectangular Rectangular size 5.0x2.0mm^2 z-position of LED center 1.0mm 2 pins Rectangular size 5.0x2.0mm^2 z-position of LED center 1.0mm 2 pins Rectangular size 5.0x2.0mm^2 z-position of LED center 1.0mm 2 pins Rectangular size 5.0x2.0mm^2 z-position of LED center 3.0mm 2 pins Rectangular size 5.0x2.0mm^2 z-position of LED center 3.0mm 2 pins +0 +2 +2 +LED_THT +LED_Rectangular_W5.0mm_H2.0mm_Horizontal_O3.81mm_Z5.0mm +LED_Rectangular, Rectangular, Rectangular size 5.0x2.0mm^2 z-position of LED center 1.0mm, 2 pins, Rectangular size 5.0x2.0mm^2 z-position of LED center 1.0mm, 2 pins, Rectangular size 5.0x2.0mm^2 z-position of LED center 1.0mm, 2 pins, Rectangular size 5.0x2.0mm^2 z-position of LED center 3.0mm, 2 pins, Rectangular size 5.0x2.0mm^2 z-position of LED center 3.0mm, 2 pins, Rectangular size 5.0x2.0mm^2 z-position of LED center 3.0mm, 2 pins, Rectangular size 5.0x2.0mm^2 z-position of LED center 5.0mm, 2 pins, Rectangular size 5.0x2.0mm^2 z-position of LED center 5.0mm, 2 pins +LED_Rectangular Rectangular Rectangular size 5.0x2.0mm^2 z-position of LED center 1.0mm 2 pins Rectangular size 5.0x2.0mm^2 z-position of LED center 1.0mm 2 pins Rectangular size 5.0x2.0mm^2 z-position of LED center 1.0mm 2 pins Rectangular size 5.0x2.0mm^2 z-position of LED center 3.0mm 2 pins Rectangular size 5.0x2.0mm^2 z-position of LED center 3.0mm 2 pins Rectangular size 5.0x2.0mm^2 z-position of LED center 3.0mm 2 pins Rectangular size 5.0x2.0mm^2 z-position of LED center 5.0mm 2 pins Rectangular size 5.0x2.0mm^2 z-position of LED center 5.0mm 2 pins +0 +2 +2 +LED_THT +LED_Rectangular_W5.0mm_H2.0mm_Horizontal_O6.35mm_Z1.0mm +LED_Rectangular, Rectangular, Rectangular size 5.0x2.0mm^2 z-position of LED center 1.0mm, 2 pins, Rectangular size 5.0x2.0mm^2 z-position of LED center 1.0mm, 2 pins, Rectangular size 5.0x2.0mm^2 z-position of LED center 1.0mm, 2 pins +LED_Rectangular Rectangular Rectangular size 5.0x2.0mm^2 z-position of LED center 1.0mm 2 pins Rectangular size 5.0x2.0mm^2 z-position of LED center 1.0mm 2 pins Rectangular size 5.0x2.0mm^2 z-position of LED center 1.0mm 2 pins +0 +2 +2 +LED_THT +LED_Rectangular_W5.0mm_H2.0mm_Horizontal_O6.35mm_Z3.0mm +LED_Rectangular, Rectangular, Rectangular size 5.0x2.0mm^2 z-position of LED center 1.0mm, 2 pins, Rectangular size 5.0x2.0mm^2 z-position of LED center 1.0mm, 2 pins, Rectangular size 5.0x2.0mm^2 z-position of LED center 1.0mm, 2 pins, Rectangular size 5.0x2.0mm^2 z-position of LED center 3.0mm, 2 pins, Rectangular size 5.0x2.0mm^2 z-position of LED center 3.0mm, 2 pins, Rectangular size 5.0x2.0mm^2 z-position of LED center 3.0mm, 2 pins +LED_Rectangular Rectangular Rectangular size 5.0x2.0mm^2 z-position of LED center 1.0mm 2 pins Rectangular size 5.0x2.0mm^2 z-position of LED center 1.0mm 2 pins Rectangular size 5.0x2.0mm^2 z-position of LED center 1.0mm 2 pins Rectangular size 5.0x2.0mm^2 z-position of LED center 3.0mm 2 pins Rectangular size 5.0x2.0mm^2 z-position of LED center 3.0mm 2 pins Rectangular size 5.0x2.0mm^2 z-position of LED center 3.0mm 2 pins +0 +2 +2 +LED_THT +LED_Rectangular_W5.0mm_H2.0mm_Horizontal_O6.35mm_Z5.0mm +LED_Rectangular, Rectangular, Rectangular size 5.0x2.0mm^2 z-position of LED center 1.0mm, 2 pins, Rectangular size 5.0x2.0mm^2 z-position of LED center 1.0mm, 2 pins, Rectangular size 5.0x2.0mm^2 z-position of LED center 1.0mm, 2 pins, Rectangular size 5.0x2.0mm^2 z-position of LED center 3.0mm, 2 pins, Rectangular size 5.0x2.0mm^2 z-position of LED center 3.0mm, 2 pins, Rectangular size 5.0x2.0mm^2 z-position of LED center 3.0mm, 2 pins, Rectangular size 5.0x2.0mm^2 z-position of LED center 5.0mm, 2 pins, Rectangular size 5.0x2.0mm^2 z-position of LED center 5.0mm, 2 pins, Rectangular size 5.0x2.0mm^2 z-position of LED center 5.0mm, 2 pins +LED_Rectangular Rectangular Rectangular size 5.0x2.0mm^2 z-position of LED center 1.0mm 2 pins Rectangular size 5.0x2.0mm^2 z-position of LED center 1.0mm 2 pins Rectangular size 5.0x2.0mm^2 z-position of LED center 1.0mm 2 pins Rectangular size 5.0x2.0mm^2 z-position of LED center 3.0mm 2 pins Rectangular size 5.0x2.0mm^2 z-position of LED center 3.0mm 2 pins Rectangular size 5.0x2.0mm^2 z-position of LED center 3.0mm 2 pins Rectangular size 5.0x2.0mm^2 z-position of LED center 5.0mm 2 pins Rectangular size 5.0x2.0mm^2 z-position of LED center 5.0mm 2 pins Rectangular size 5.0x2.0mm^2 z-position of LED center 5.0mm 2 pins +0 +2 +2 +LED_THT +LED_Rectangular_W5.0mm_H5.0mm +LED_Rectangular, Rectangular, Rectangular size 5.0x5.0mm^2, 2 pins, http://www.kingbright.com/attachments/file/psearch/000/00/00/L-169XCGDK(Ver.9B).pdf +LED_Rectangular Rectangular Rectangular size 5.0x5.0mm^2 2 pins +0 +2 +2 +LED_THT +LED_Rectangular_W7.62mm_H4.55mm_P5.08mm_R3 +Datasheet can be found at https://www.gme.cz/data/attachments/dsh.511-795.1.pdf +LED automotive super flux 7.62mm +0 +4 +2 +LED_THT +LED_SideEmitter_Rectangular_W4.5mm_H1.6mm +LED_SideEmitter_Rectangular, Rectangular, SideEmitter, Rectangular size 4.5x1.6mm^2, 2 pins, http://cdn-reichelt.de/documents/datenblatt/A500/LED15MMGE_LED15MMGN%23KIN.pdf +LED_SideEmitter_Rectangular Rectangular SideEmitter Rectangular size 4.5x1.6mm^2 2 pins +0 +2 +2 +LED_THT +LED_VCCLite_5381H1_6.35x6.35mm +Red 5381 Series LED VCCLite https://vcclite.com/wp-content/uploads/wpallimport/files/files/5381Series.pdf http://static.vcclite.com/pdf/Mounting%20Hole%20Pattern%202.pdf +Red 5381 Series LED +0 +2 +2 +LED_THT +LED_VCCLite_5381H3_6.35x6.35mm +Amber 5381 Series LED VCCLite https://vcclite.com/wp-content/uploads/wpallimport/files/files/5381Series.pdf http://static.vcclite.com/pdf/Mounting%20Hole%20Pattern%202.pdf +Amber 5381 Series LED +0 +2 +2 +LED_THT +LED_VCCLite_5381H5_6.35x6.35mm +Green 5381 Series LED VCCLite https://vcclite.com/wp-content/uploads/wpallimport/files/files/5381Series.pdf http://static.vcclite.com/pdf/Mounting%20Hole%20Pattern%202.pdf +Green 5381 Series LED +0 +2 +2 +LED_THT +LED_VCCLite_5381H7_6.35x6.35mm +Yellow 5381 Series LED VCCLite https://vcclite.com/wp-content/uploads/wpallimport/files/files/5381Series.pdf http://static.vcclite.com/pdf/Mounting%20Hole%20Pattern%202.pdf +Yellow 5381 Series LED +0 +2 +2 +MountingHole +MountingHole_2.1mm +Mounting Hole 2.1mm, no annular +mounting hole 2.1mm no annular +0 +0 +0 +MountingHole +MountingHole_2.2mm_M2 +Mounting Hole 2.2mm, no annular, M2 +mounting hole 2.2mm no annular m2 +0 +0 +0 +MountingHole +MountingHole_2.2mm_M2_DIN965 +Mounting Hole 2.2mm, no annular, M2, DIN965 +mounting hole 2.2mm no annular m2 din965 +0 +0 +0 +MountingHole +MountingHole_2.2mm_M2_DIN965_Pad +Mounting Hole 2.2mm, M2, DIN965 +mounting hole 2.2mm m2 din965 +0 +1 +1 +MountingHole +MountingHole_2.2mm_M2_ISO7380 +Mounting Hole 2.2mm, no annular, M2, ISO7380 +mounting hole 2.2mm no annular m2 iso7380 +0 +0 +0 +MountingHole +MountingHole_2.2mm_M2_ISO7380_Pad +Mounting Hole 2.2mm, M2, ISO7380 +mounting hole 2.2mm m2 iso7380 +0 +1 +1 +MountingHole +MountingHole_2.2mm_M2_ISO14580 +Mounting Hole 2.2mm, no annular, M2, ISO14580 +mounting hole 2.2mm no annular m2 iso14580 +0 +0 +0 +MountingHole +MountingHole_2.2mm_M2_ISO14580_Pad +Mounting Hole 2.2mm, M2, ISO14580 +mounting hole 2.2mm m2 iso14580 +0 +1 +1 +MountingHole +MountingHole_2.2mm_M2_Pad +Mounting Hole 2.2mm, M2 +mounting hole 2.2mm m2 +0 +1 +1 +MountingHole +MountingHole_2.2mm_M2_Pad_Via +Mounting Hole 2.2mm, M2 +mounting hole 2.2mm m2 +0 +9 +1 +MountingHole +MountingHole_2.5mm +Mounting Hole 2.5mm, no annular +mounting hole 2.5mm no annular +0 +0 +0 +MountingHole +MountingHole_2.5mm_Pad +Mounting Hole 2.5mm +mounting hole 2.5mm +0 +1 +1 +MountingHole +MountingHole_2.5mm_Pad_Via +Mounting Hole 2.5mm +mounting hole 2.5mm +0 +9 +1 +MountingHole +MountingHole_2.7mm +Mounting Hole 2.7mm, no annular +mounting hole 2.7mm no annular +0 +0 +0 +MountingHole +MountingHole_2.7mm_M2.5 +Mounting Hole 2.7mm, no annular, M2.5 +mounting hole 2.7mm no annular m2.5 +0 +0 +0 +MountingHole +MountingHole_2.7mm_M2.5_DIN965 +Mounting Hole 2.7mm, no annular, M2.5, DIN965 +mounting hole 2.7mm no annular m2.5 din965 +0 +0 +0 +MountingHole +MountingHole_2.7mm_M2.5_DIN965_Pad +Mounting Hole 2.7mm, M2.5, DIN965 +mounting hole 2.7mm m2.5 din965 +0 +1 +1 +MountingHole +MountingHole_2.7mm_M2.5_ISO7380 +Mounting Hole 2.7mm, no annular, M2.5, ISO7380 +mounting hole 2.7mm no annular m2.5 iso7380 +0 +0 +0 +MountingHole +MountingHole_2.7mm_M2.5_ISO7380_Pad +Mounting Hole 2.7mm, M2.5, ISO7380 +mounting hole 2.7mm m2.5 iso7380 +0 +1 +1 +MountingHole +MountingHole_2.7mm_M2.5_ISO14580 +Mounting Hole 2.7mm, no annular, M2.5, ISO14580 +mounting hole 2.7mm no annular m2.5 iso14580 +0 +0 +0 +MountingHole +MountingHole_2.7mm_M2.5_ISO14580_Pad +Mounting Hole 2.7mm, M2.5, ISO14580 +mounting hole 2.7mm m2.5 iso14580 +0 +1 +1 +MountingHole +MountingHole_2.7mm_M2.5_Pad +Mounting Hole 2.7mm, M2.5 +mounting hole 2.7mm m2.5 +0 +1 +1 +MountingHole +MountingHole_2.7mm_M2.5_Pad_Via +Mounting Hole 2.7mm +mounting hole 2.7mm +0 +9 +1 +MountingHole +MountingHole_2.7mm_Pad +Mounting Hole 2.7mm +mounting hole 2.7mm +0 +1 +1 +MountingHole +MountingHole_2.7mm_Pad_Via +Mounting Hole 2.7mm +mounting hole 2.7mm +0 +9 +1 +MountingHole +MountingHole_2mm +Mounting Hole 2mm, no annular +mounting hole 2mm no annular +0 +0 +0 +MountingHole +MountingHole_3.2mm_M3 +Mounting Hole 3.2mm, no annular, M3 +mounting hole 3.2mm no annular m3 +0 +0 +0 +MountingHole +MountingHole_3.2mm_M3_DIN965 +Mounting Hole 3.2mm, no annular, M3, DIN965 +mounting hole 3.2mm no annular m3 din965 +0 +0 +0 +MountingHole +MountingHole_3.2mm_M3_DIN965_Pad +Mounting Hole 3.2mm, M3, DIN965 +mounting hole 3.2mm m3 din965 +0 +1 +1 +MountingHole +MountingHole_3.2mm_M3_ISO7380 +Mounting Hole 3.2mm, no annular, M3, ISO7380 +mounting hole 3.2mm no annular m3 iso7380 +0 +0 +0 +MountingHole +MountingHole_3.2mm_M3_ISO7380_Pad +Mounting Hole 3.2mm, M3, ISO7380 +mounting hole 3.2mm m3 iso7380 +0 +1 +1 +MountingHole +MountingHole_3.2mm_M3_ISO14580 +Mounting Hole 3.2mm, no annular, M3, ISO14580 +mounting hole 3.2mm no annular m3 iso14580 +0 +0 +0 +MountingHole +MountingHole_3.2mm_M3_ISO14580_Pad +Mounting Hole 3.2mm, M3, ISO14580 +mounting hole 3.2mm m3 iso14580 +0 +1 +1 +MountingHole +MountingHole_3.2mm_M3_Pad +Mounting Hole 3.2mm, M3 +mounting hole 3.2mm m3 +0 +1 +1 +MountingHole +MountingHole_3.2mm_M3_Pad_Via +Mounting Hole 3.2mm, M3 +mounting hole 3.2mm m3 +0 +9 +1 +MountingHole +MountingHole_3.5mm +Mounting Hole 3.5mm, no annular +mounting hole 3.5mm no annular +0 +0 +0 +MountingHole +MountingHole_3.5mm_Pad +Mounting Hole 3.5mm +mounting hole 3.5mm +0 +1 +1 +MountingHole +MountingHole_3.5mm_Pad_Via +Mounting Hole 3.5mm +mounting hole 3.5mm +0 +9 +1 +MountingHole +MountingHole_3.7mm +Mounting Hole 3.7mm, no annular +mounting hole 3.7mm no annular +0 +0 +0 +MountingHole +MountingHole_3.7mm_Pad +Mounting Hole 3.7mm +mounting hole 3.7mm +0 +1 +1 +MountingHole +MountingHole_3.7mm_Pad_Via +Mounting Hole 3.7mm +mounting hole 3.7mm +0 +9 +1 +MountingHole +MountingHole_3mm +Mounting Hole 3mm, no annular +mounting hole 3mm no annular +0 +0 +0 +MountingHole +MountingHole_3mm_Pad +Mounting Hole 3mm +mounting hole 3mm +0 +1 +1 +MountingHole +MountingHole_3mm_Pad_Via +Mounting Hole 3mm +mounting hole 3mm +0 +9 +1 +MountingHole +MountingHole_4.3mm_M4 +Mounting Hole 4.3mm, no annular, M4 +mounting hole 4.3mm no annular m4 +0 +0 +0 +MountingHole +MountingHole_4.3mm_M4_DIN965 +Mounting Hole 4.3mm, no annular, M4, DIN965 +mounting hole 4.3mm no annular m4 din965 +0 +0 +0 +MountingHole +MountingHole_4.3mm_M4_DIN965_Pad +Mounting Hole 4.3mm, M4, DIN965 +mounting hole 4.3mm m4 din965 +0 +1 +1 +MountingHole +MountingHole_4.3mm_M4_ISO7380 +Mounting Hole 4.3mm, no annular, M4, ISO7380 +mounting hole 4.3mm no annular m4 iso7380 +0 +0 +0 +MountingHole +MountingHole_4.3mm_M4_ISO7380_Pad +Mounting Hole 4.3mm, M4, ISO7380 +mounting hole 4.3mm m4 iso7380 +0 +1 +1 +MountingHole +MountingHole_4.3mm_M4_ISO14580 +Mounting Hole 4.3mm, no annular, M4, ISO14580 +mounting hole 4.3mm no annular m4 iso14580 +0 +0 +0 +MountingHole +MountingHole_4.3mm_M4_ISO14580_Pad +Mounting Hole 4.3mm, M4, ISO14580 +mounting hole 4.3mm m4 iso14580 +0 +1 +1 +MountingHole +MountingHole_4.3mm_M4_Pad +Mounting Hole 4.3mm, M4 +mounting hole 4.3mm m4 +0 +1 +1 +MountingHole +MountingHole_4.3mm_M4_Pad_Via +Mounting Hole 4.3mm, M4 +mounting hole 4.3mm m4 +0 +9 +1 +MountingHole +MountingHole_4.3x6.2mm_M4_Pad +Mounting Hole 4.3x6.2mm, M4 +mounting hole 4.3x6.2mm m4 +0 +1 +1 +MountingHole +MountingHole_4.3x6.2mm_M4_Pad_Via +Mounting Hole 4.3x6.2mm, M4 +mounting hole 4.3x6.2mm m4 +0 +17 +1 +MountingHole +MountingHole_4.5mm +Mounting Hole 4.5mm, no annular +mounting hole 4.5mm no annular +0 +0 +0 +MountingHole +MountingHole_4.5mm_Pad +Mounting Hole 4.5mm +mounting hole 4.5mm +0 +1 +1 +MountingHole +MountingHole_4.5mm_Pad_Via +Mounting Hole 4.5mm +mounting hole 4.5mm +0 +9 +1 +MountingHole +MountingHole_4mm +Mounting Hole 4mm, no annular +mounting hole 4mm no annular +0 +0 +0 +MountingHole +MountingHole_4mm_Pad +Mounting Hole 4mm +mounting hole 4mm +0 +1 +1 +MountingHole +MountingHole_4mm_Pad_Via +Mounting Hole 4mm +mounting hole 4mm +0 +9 +1 +MountingHole +MountingHole_5.3mm_M5 +Mounting Hole 5.3mm, no annular, M5 +mounting hole 5.3mm no annular m5 +0 +0 +0 +MountingHole +MountingHole_5.3mm_M5_DIN965 +Mounting Hole 5.3mm, no annular, M5, DIN965 +mounting hole 5.3mm no annular m5 din965 +0 +0 +0 +MountingHole +MountingHole_5.3mm_M5_DIN965_Pad +Mounting Hole 5.3mm, M5, DIN965 +mounting hole 5.3mm m5 din965 +0 +1 +1 +MountingHole +MountingHole_5.3mm_M5_ISO7380 +Mounting Hole 5.3mm, no annular, M5, ISO7380 +mounting hole 5.3mm no annular m5 iso7380 +0 +0 +0 +MountingHole +MountingHole_5.3mm_M5_ISO7380_Pad +Mounting Hole 5.3mm, M5, ISO7380 +mounting hole 5.3mm m5 iso7380 +0 +1 +1 +MountingHole +MountingHole_5.3mm_M5_ISO14580 +Mounting Hole 5.3mm, no annular, M5, ISO14580 +mounting hole 5.3mm no annular m5 iso14580 +0 +0 +0 +MountingHole +MountingHole_5.3mm_M5_ISO14580_Pad +Mounting Hole 5.3mm, M5, ISO14580 +mounting hole 5.3mm m5 iso14580 +0 +1 +1 +MountingHole +MountingHole_5.3mm_M5_Pad +Mounting Hole 5.3mm, M5 +mounting hole 5.3mm m5 +0 +1 +1 +MountingHole +MountingHole_5.3mm_M5_Pad_Via +Mounting Hole 5.3mm, M5 +mounting hole 5.3mm m5 +0 +9 +1 +MountingHole +MountingHole_5.5mm +Mounting Hole 5.5mm, no annular +mounting hole 5.5mm no annular +0 +0 +0 +MountingHole +MountingHole_5.5mm_Pad +Mounting Hole 5.5mm +mounting hole 5.5mm +0 +1 +1 +MountingHole +MountingHole_5.5mm_Pad_Via +Mounting Hole 5.5mm +mounting hole 5.5mm +0 +9 +1 +MountingHole +MountingHole_5mm +Mounting Hole 5mm, no annular +mounting hole 5mm no annular +0 +0 +0 +MountingHole +MountingHole_5mm_Pad +Mounting Hole 5mm +mounting hole 5mm +0 +1 +1 +MountingHole +MountingHole_5mm_Pad_Via +Mounting Hole 5mm +mounting hole 5mm +0 +9 +1 +MountingHole +MountingHole_6.4mm_M6 +Mounting Hole 6.4mm, no annular, M6 +mounting hole 6.4mm no annular m6 +0 +0 +0 +MountingHole +MountingHole_6.4mm_M6_DIN965 +Mounting Hole 6.4mm, no annular, M6, DIN965 +mounting hole 6.4mm no annular m6 din965 +0 +0 +0 +MountingHole +MountingHole_6.4mm_M6_DIN965_Pad +Mounting Hole 6.4mm, M6, DIN965 +mounting hole 6.4mm m6 din965 +0 +1 +1 +MountingHole +MountingHole_6.4mm_M6_ISO7380 +Mounting Hole 6.4mm, no annular, M6, ISO7380 +mounting hole 6.4mm no annular m6 iso7380 +0 +0 +0 +MountingHole +MountingHole_6.4mm_M6_ISO7380_Pad +Mounting Hole 6.4mm, M6, ISO7380 +mounting hole 6.4mm m6 iso7380 +0 +1 +1 +MountingHole +MountingHole_6.4mm_M6_ISO14580 +Mounting Hole 6.4mm, no annular, M6, ISO14580 +mounting hole 6.4mm no annular m6 iso14580 +0 +0 +0 +MountingHole +MountingHole_6.4mm_M6_ISO14580_Pad +Mounting Hole 6.4mm, M6, ISO14580 +mounting hole 6.4mm m6 iso14580 +0 +1 +1 +MountingHole +MountingHole_6.4mm_M6_Pad +Mounting Hole 6.4mm, M6 +mounting hole 6.4mm m6 +0 +1 +1 +MountingHole +MountingHole_6.4mm_M6_Pad_Via +Mounting Hole 6.4mm, M6 +mounting hole 6.4mm m6 +0 +9 +1 +MountingHole +MountingHole_6.5mm +Mounting Hole 6.5mm, no annular +mounting hole 6.5mm no annular +0 +0 +0 +MountingHole +MountingHole_6.5mm_Pad +Mounting Hole 6.5mm +mounting hole 6.5mm +0 +1 +1 +MountingHole +MountingHole_6.5mm_Pad_Via +Mounting Hole 6.5mm +mounting hole 6.5mm +0 +9 +1 +MountingHole +MountingHole_6mm +Mounting Hole 6mm, no annular +mounting hole 6mm no annular +0 +0 +0 +MountingHole +MountingHole_6mm_Pad +Mounting Hole 6mm +mounting hole 6mm +0 +1 +1 +MountingHole +MountingHole_6mm_Pad_Via +Mounting Hole 6mm +mounting hole 6mm +0 +9 +1 +MountingHole +MountingHole_8.4mm_M8 +Mounting Hole 8.4mm, no annular, M8 +mounting hole 8.4mm no annular m8 +0 +0 +0 +MountingHole +MountingHole_8.4mm_M8_Pad +Mounting Hole 8.4mm, M8 +mounting hole 8.4mm m8 +0 +1 +1 +MountingHole +MountingHole_8.4mm_M8_Pad_Via +Mounting Hole 8.4mm, M8 +mounting hole 8.4mm m8 +0 +9 +1 +Package_DIP +DIP-4_W7.62mm +4-lead though-hole mounted DIP package, row spacing 7.62 mm (300 mils) +THT DIP DIL PDIP 2.54mm 7.62mm 300mil +0 +4 +4 +Package_DIP +DIP-4_W7.62mm_LongPads +4-lead though-hole mounted DIP package, row spacing 7.62 mm (300 mils), LongPads +THT DIP DIL PDIP 2.54mm 7.62mm 300mil LongPads +0 +4 +4 +Package_DIP +DIP-4_W7.62mm_SMDSocket_SmallPads +4-lead though-hole mounted DIP package, row spacing 7.62 mm (300 mils), SMDSocket, SmallPads +THT DIP DIL PDIP 2.54mm 7.62mm 300mil SMDSocket SmallPads +0 +4 +4 +Package_DIP +DIP-4_W7.62mm_Socket +4-lead though-hole mounted DIP package, row spacing 7.62 mm (300 mils), Socket +THT DIP DIL PDIP 2.54mm 7.62mm 300mil Socket +0 +4 +4 +Package_DIP +DIP-4_W7.62mm_Socket_LongPads +4-lead though-hole mounted DIP package, row spacing 7.62 mm (300 mils), Socket, LongPads +THT DIP DIL PDIP 2.54mm 7.62mm 300mil Socket LongPads +0 +4 +4 +Package_DIP +DIP-4_W8.89mm_SMDSocket_LongPads +4-lead though-hole mounted DIP package, row spacing 8.89 mm (350 mils), SMDSocket, LongPads +THT DIP DIL PDIP 2.54mm 8.89mm 350mil SMDSocket LongPads +0 +4 +4 +Package_DIP +DIP-4_W10.16mm +4-lead though-hole mounted DIP package, row spacing 10.16 mm (400 mils) +THT DIP DIL PDIP 2.54mm 10.16mm 400mil +0 +4 +4 +Package_DIP +DIP-4_W10.16mm_LongPads +4-lead though-hole mounted DIP package, row spacing 10.16 mm (400 mils), LongPads +THT DIP DIL PDIP 2.54mm 10.16mm 400mil LongPads +0 +4 +4 +Package_DIP +DIP-5-6_W7.62mm +5-lead though-hole mounted DIP package, row spacing 7.62 mm (300 mils) +THT DIP DIL PDIP 2.54mm 7.62mm 300mil +0 +5 +5 +Package_DIP +DIP-5-6_W7.62mm_LongPads +5-lead though-hole mounted DIP package, row spacing 7.62 mm (300 mils), LongPads +THT DIP DIL PDIP 2.54mm 7.62mm 300mil LongPads +0 +5 +5 +Package_DIP +DIP-5-6_W7.62mm_SMDSocket_SmallPads +5-lead though-hole mounted DIP package, row spacing 7.62 mm (300 mils), SMDSocket, SmallPads +THT DIP DIL PDIP 2.54mm 7.62mm 300mil SMDSocket SmallPads +0 +5 +5 +Package_DIP +DIP-5-6_W7.62mm_Socket +5-lead though-hole mounted DIP package, row spacing 7.62 mm (300 mils), Socket +THT DIP DIL PDIP 2.54mm 7.62mm 300mil Socket +0 +5 +5 +Package_DIP +DIP-5-6_W7.62mm_Socket_LongPads +5-lead though-hole mounted DIP package, row spacing 7.62 mm (300 mils), Socket, LongPads +THT DIP DIL PDIP 2.54mm 7.62mm 300mil Socket LongPads +0 +5 +5 +Package_DIP +DIP-5-6_W8.89mm_SMDSocket_LongPads +5-lead though-hole mounted DIP package, row spacing 8.89 mm (350 mils), SMDSocket, LongPads +THT DIP DIL PDIP 2.54mm 8.89mm 350mil SMDSocket LongPads +0 +5 +5 +Package_DIP +DIP-5-6_W10.16mm +5-lead though-hole mounted DIP package, row spacing 10.16 mm (400 mils) +THT DIP DIL PDIP 2.54mm 10.16mm 400mil +0 +5 +5 +Package_DIP +DIP-5-6_W10.16mm_LongPads +5-lead though-hole mounted DIP package, row spacing 10.16 mm (400 mils), LongPads +THT DIP DIL PDIP 2.54mm 10.16mm 400mil LongPads +0 +5 +5 +Package_DIP +DIP-6_W7.62mm +6-lead though-hole mounted DIP package, row spacing 7.62 mm (300 mils) +THT DIP DIL PDIP 2.54mm 7.62mm 300mil +0 +6 +6 +Package_DIP +DIP-6_W7.62mm_LongPads +6-lead though-hole mounted DIP package, row spacing 7.62 mm (300 mils), LongPads +THT DIP DIL PDIP 2.54mm 7.62mm 300mil LongPads +0 +6 +6 +Package_DIP +DIP-6_W7.62mm_SMDSocket_SmallPads +6-lead though-hole mounted DIP package, row spacing 7.62 mm (300 mils), SMDSocket, SmallPads +THT DIP DIL PDIP 2.54mm 7.62mm 300mil SMDSocket SmallPads +0 +6 +6 +Package_DIP +DIP-6_W7.62mm_Socket +6-lead though-hole mounted DIP package, row spacing 7.62 mm (300 mils), Socket +THT DIP DIL PDIP 2.54mm 7.62mm 300mil Socket +0 +6 +6 +Package_DIP +DIP-6_W7.62mm_Socket_LongPads +6-lead though-hole mounted DIP package, row spacing 7.62 mm (300 mils), Socket, LongPads +THT DIP DIL PDIP 2.54mm 7.62mm 300mil Socket LongPads +0 +6 +6 +Package_DIP +DIP-6_W8.89mm_SMDSocket_LongPads +6-lead though-hole mounted DIP package, row spacing 8.89 mm (350 mils), SMDSocket, LongPads +THT DIP DIL PDIP 2.54mm 8.89mm 350mil SMDSocket LongPads +0 +6 +6 +Package_DIP +DIP-6_W10.16mm +6-lead though-hole mounted DIP package, row spacing 10.16 mm (400 mils) +THT DIP DIL PDIP 2.54mm 10.16mm 400mil +0 +6 +6 +Package_DIP +DIP-6_W10.16mm_LongPads +6-lead though-hole mounted DIP package, row spacing 10.16 mm (400 mils), LongPads +THT DIP DIL PDIP 2.54mm 10.16mm 400mil LongPads +0 +6 +6 +Package_DIP +DIP-8-N6_W7.62mm +8-lead though-hole mounted DIP package, row spacing 7.62 mm (300 mils), missing pin 6 +THT DIP DIL PDIP 2.54mm 7.62mm 300mil +0 +7 +7 +Package_DIP +DIP-8-N7_W7.62mm +8-lead though-hole mounted DIP package, row spacing 7.62 mm (300 mils), missing pin 7 +THT DIP DIL PDIP 2.54mm 7.62mm 300mil +0 +7 +7 +Package_DIP +DIP-8_W7.62mm +8-lead though-hole mounted DIP package, row spacing 7.62 mm (300 mils) +THT DIP DIL PDIP 2.54mm 7.62mm 300mil +0 +8 +8 +Package_DIP +DIP-8_W7.62mm_LongPads +8-lead though-hole mounted DIP package, row spacing 7.62 mm (300 mils), LongPads +THT DIP DIL PDIP 2.54mm 7.62mm 300mil LongPads +0 +8 +8 +Package_DIP +DIP-8_W7.62mm_SMDSocket_SmallPads +8-lead though-hole mounted DIP package, row spacing 7.62 mm (300 mils), SMDSocket, SmallPads +THT DIP DIL PDIP 2.54mm 7.62mm 300mil SMDSocket SmallPads +0 +8 +8 +Package_DIP +DIP-8_W7.62mm_Socket +8-lead though-hole mounted DIP package, row spacing 7.62 mm (300 mils), Socket +THT DIP DIL PDIP 2.54mm 7.62mm 300mil Socket +0 +8 +8 +Package_DIP +DIP-8_W7.62mm_Socket_LongPads +8-lead though-hole mounted DIP package, row spacing 7.62 mm (300 mils), Socket, LongPads +THT DIP DIL PDIP 2.54mm 7.62mm 300mil Socket LongPads +0 +8 +8 +Package_DIP +DIP-8_W8.89mm_SMDSocket_LongPads +8-lead though-hole mounted DIP package, row spacing 8.89 mm (350 mils), SMDSocket, LongPads +THT DIP DIL PDIP 2.54mm 8.89mm 350mil SMDSocket LongPads +0 +8 +8 +Package_DIP +DIP-8_W10.16mm +8-lead though-hole mounted DIP package, row spacing 10.16 mm (400 mils) +THT DIP DIL PDIP 2.54mm 10.16mm 400mil +0 +8 +8 +Package_DIP +DIP-8_W10.16mm_LongPads +8-lead though-hole mounted DIP package, row spacing 10.16 mm (400 mils), LongPads +THT DIP DIL PDIP 2.54mm 10.16mm 400mil LongPads +0 +8 +8 +Package_DIP +DIP-10_W7.62mm +10-lead though-hole mounted DIP package, row spacing 7.62 mm (300 mils) +THT DIP DIL PDIP 2.54mm 7.62mm 300mil +0 +10 +10 +Package_DIP +DIP-10_W7.62mm_LongPads +10-lead though-hole mounted DIP package, row spacing 7.62 mm (300 mils), LongPads +THT DIP DIL PDIP 2.54mm 7.62mm 300mil LongPads +0 +10 +10 +Package_DIP +DIP-10_W7.62mm_SMDSocket_SmallPads +10-lead though-hole mounted DIP package, row spacing 7.62 mm (300 mils), SMDSocket, SmallPads +THT DIP DIL PDIP 2.54mm 7.62mm 300mil SMDSocket SmallPads +0 +10 +10 +Package_DIP +DIP-10_W7.62mm_Socket +10-lead though-hole mounted DIP package, row spacing 7.62 mm (300 mils), Socket +THT DIP DIL PDIP 2.54mm 7.62mm 300mil Socket +0 +10 +10 +Package_DIP +DIP-10_W7.62mm_Socket_LongPads +10-lead though-hole mounted DIP package, row spacing 7.62 mm (300 mils), Socket, LongPads +THT DIP DIL PDIP 2.54mm 7.62mm 300mil Socket LongPads +0 +10 +10 +Package_DIP +DIP-10_W8.89mm_SMDSocket_LongPads +10-lead though-hole mounted DIP package, row spacing 8.89 mm (350 mils), SMDSocket, LongPads +THT DIP DIL PDIP 2.54mm 8.89mm 350mil SMDSocket LongPads +0 +10 +10 +Package_DIP +DIP-10_W10.16mm +10-lead though-hole mounted DIP package, row spacing 10.16 mm (400 mils) +THT DIP DIL PDIP 2.54mm 10.16mm 400mil +0 +10 +10 +Package_DIP +DIP-10_W10.16mm_LongPads +10-lead though-hole mounted DIP package, row spacing 10.16 mm (400 mils), LongPads +THT DIP DIL PDIP 2.54mm 10.16mm 400mil LongPads +0 +10 +10 +Package_DIP +DIP-12_W7.62mm +12-lead though-hole mounted DIP package, row spacing 7.62 mm (300 mils) +THT DIP DIL PDIP 2.54mm 7.62mm 300mil +0 +12 +12 +Package_DIP +DIP-12_W7.62mm_LongPads +12-lead though-hole mounted DIP package, row spacing 7.62 mm (300 mils), LongPads +THT DIP DIL PDIP 2.54mm 7.62mm 300mil LongPads +0 +12 +12 +Package_DIP +DIP-12_W7.62mm_SMDSocket_SmallPads +12-lead though-hole mounted DIP package, row spacing 7.62 mm (300 mils), SMDSocket, SmallPads +THT DIP DIL PDIP 2.54mm 7.62mm 300mil SMDSocket SmallPads +0 +12 +12 +Package_DIP +DIP-12_W7.62mm_Socket +12-lead though-hole mounted DIP package, row spacing 7.62 mm (300 mils), Socket +THT DIP DIL PDIP 2.54mm 7.62mm 300mil Socket +0 +12 +12 +Package_DIP +DIP-12_W7.62mm_Socket_LongPads +12-lead though-hole mounted DIP package, row spacing 7.62 mm (300 mils), Socket, LongPads +THT DIP DIL PDIP 2.54mm 7.62mm 300mil Socket LongPads +0 +12 +12 +Package_DIP +DIP-12_W8.89mm_SMDSocket_LongPads +12-lead though-hole mounted DIP package, row spacing 8.89 mm (350 mils), SMDSocket, LongPads +THT DIP DIL PDIP 2.54mm 8.89mm 350mil SMDSocket LongPads +0 +12 +12 +Package_DIP +DIP-12_W10.16mm +12-lead though-hole mounted DIP package, row spacing 10.16 mm (400 mils) +THT DIP DIL PDIP 2.54mm 10.16mm 400mil +0 +12 +12 +Package_DIP +DIP-12_W10.16mm_LongPads +12-lead though-hole mounted DIP package, row spacing 10.16 mm (400 mils), LongPads +THT DIP DIL PDIP 2.54mm 10.16mm 400mil LongPads +0 +12 +12 +Package_DIP +DIP-14_W7.62mm +14-lead though-hole mounted DIP package, row spacing 7.62 mm (300 mils) +THT DIP DIL PDIP 2.54mm 7.62mm 300mil +0 +14 +14 +Package_DIP +DIP-14_W7.62mm_LongPads +14-lead though-hole mounted DIP package, row spacing 7.62 mm (300 mils), LongPads +THT DIP DIL PDIP 2.54mm 7.62mm 300mil LongPads +0 +14 +14 +Package_DIP +DIP-14_W7.62mm_SMDSocket_SmallPads +14-lead though-hole mounted DIP package, row spacing 7.62 mm (300 mils), SMDSocket, SmallPads +THT DIP DIL PDIP 2.54mm 7.62mm 300mil SMDSocket SmallPads +0 +14 +14 +Package_DIP +DIP-14_W7.62mm_Socket +14-lead though-hole mounted DIP package, row spacing 7.62 mm (300 mils), Socket +THT DIP DIL PDIP 2.54mm 7.62mm 300mil Socket +0 +14 +14 +Package_DIP +DIP-14_W7.62mm_Socket_LongPads +14-lead though-hole mounted DIP package, row spacing 7.62 mm (300 mils), Socket, LongPads +THT DIP DIL PDIP 2.54mm 7.62mm 300mil Socket LongPads +0 +14 +14 +Package_DIP +DIP-14_W8.89mm_SMDSocket_LongPads +14-lead though-hole mounted DIP package, row spacing 8.89 mm (350 mils), SMDSocket, LongPads +THT DIP DIL PDIP 2.54mm 8.89mm 350mil SMDSocket LongPads +0 +14 +14 +Package_DIP +DIP-14_W10.16mm +14-lead though-hole mounted DIP package, row spacing 10.16 mm (400 mils) +THT DIP DIL PDIP 2.54mm 10.16mm 400mil +0 +14 +14 +Package_DIP +DIP-14_W10.16mm_LongPads +14-lead though-hole mounted DIP package, row spacing 10.16 mm (400 mils), LongPads +THT DIP DIL PDIP 2.54mm 10.16mm 400mil LongPads +0 +14 +14 +Package_DIP +DIP-16_W7.62mm +16-lead though-hole mounted DIP package, row spacing 7.62 mm (300 mils) +THT DIP DIL PDIP 2.54mm 7.62mm 300mil +0 +16 +16 +Package_DIP +DIP-16_W7.62mm_LongPads +16-lead though-hole mounted DIP package, row spacing 7.62 mm (300 mils), LongPads +THT DIP DIL PDIP 2.54mm 7.62mm 300mil LongPads +0 +16 +16 +Package_DIP +DIP-16_W7.62mm_SMDSocket_SmallPads +16-lead though-hole mounted DIP package, row spacing 7.62 mm (300 mils), SMDSocket, SmallPads +THT DIP DIL PDIP 2.54mm 7.62mm 300mil SMDSocket SmallPads +0 +16 +16 +Package_DIP +DIP-16_W7.62mm_Socket +16-lead though-hole mounted DIP package, row spacing 7.62 mm (300 mils), Socket +THT DIP DIL PDIP 2.54mm 7.62mm 300mil Socket +0 +16 +16 +Package_DIP +DIP-16_W7.62mm_Socket_LongPads +16-lead though-hole mounted DIP package, row spacing 7.62 mm (300 mils), Socket, LongPads +THT DIP DIL PDIP 2.54mm 7.62mm 300mil Socket LongPads +0 +16 +16 +Package_DIP +DIP-16_W8.89mm_SMDSocket_LongPads +16-lead though-hole mounted DIP package, row spacing 8.89 mm (350 mils), SMDSocket, LongPads +THT DIP DIL PDIP 2.54mm 8.89mm 350mil SMDSocket LongPads +0 +16 +16 +Package_DIP +DIP-16_W10.16mm +16-lead though-hole mounted DIP package, row spacing 10.16 mm (400 mils) +THT DIP DIL PDIP 2.54mm 10.16mm 400mil +0 +16 +16 +Package_DIP +DIP-16_W10.16mm_LongPads +16-lead though-hole mounted DIP package, row spacing 10.16 mm (400 mils), LongPads +THT DIP DIL PDIP 2.54mm 10.16mm 400mil LongPads +0 +16 +16 +Package_DIP +DIP-18_W7.62mm +18-lead though-hole mounted DIP package, row spacing 7.62 mm (300 mils) +THT DIP DIL PDIP 2.54mm 7.62mm 300mil +0 +18 +18 +Package_DIP +DIP-18_W7.62mm_LongPads +18-lead though-hole mounted DIP package, row spacing 7.62 mm (300 mils), LongPads +THT DIP DIL PDIP 2.54mm 7.62mm 300mil LongPads +0 +18 +18 +Package_DIP +DIP-18_W7.62mm_SMDSocket_SmallPads +18-lead though-hole mounted DIP package, row spacing 7.62 mm (300 mils), SMDSocket, SmallPads +THT DIP DIL PDIP 2.54mm 7.62mm 300mil SMDSocket SmallPads +0 +18 +18 +Package_DIP +DIP-18_W7.62mm_Socket +18-lead though-hole mounted DIP package, row spacing 7.62 mm (300 mils), Socket +THT DIP DIL PDIP 2.54mm 7.62mm 300mil Socket +0 +18 +18 +Package_DIP +DIP-18_W7.62mm_Socket_LongPads +18-lead though-hole mounted DIP package, row spacing 7.62 mm (300 mils), Socket, LongPads +THT DIP DIL PDIP 2.54mm 7.62mm 300mil Socket LongPads +0 +18 +18 +Package_DIP +DIP-18_W8.89mm_SMDSocket_LongPads +18-lead though-hole mounted DIP package, row spacing 8.89 mm (350 mils), SMDSocket, LongPads +THT DIP DIL PDIP 2.54mm 8.89mm 350mil SMDSocket LongPads +0 +18 +18 +Package_DIP +DIP-20_W7.62mm +20-lead though-hole mounted DIP package, row spacing 7.62 mm (300 mils) +THT DIP DIL PDIP 2.54mm 7.62mm 300mil +0 +20 +20 +Package_DIP +DIP-20_W7.62mm_LongPads +20-lead though-hole mounted DIP package, row spacing 7.62 mm (300 mils), LongPads +THT DIP DIL PDIP 2.54mm 7.62mm 300mil LongPads +0 +20 +20 +Package_DIP +DIP-20_W7.62mm_SMDSocket_SmallPads +20-lead though-hole mounted DIP package, row spacing 7.62 mm (300 mils), SMDSocket, SmallPads +THT DIP DIL PDIP 2.54mm 7.62mm 300mil SMDSocket SmallPads +0 +20 +20 +Package_DIP +DIP-20_W7.62mm_Socket +20-lead though-hole mounted DIP package, row spacing 7.62 mm (300 mils), Socket +THT DIP DIL PDIP 2.54mm 7.62mm 300mil Socket +0 +20 +20 +Package_DIP +DIP-20_W7.62mm_Socket_LongPads +20-lead though-hole mounted DIP package, row spacing 7.62 mm (300 mils), Socket, LongPads +THT DIP DIL PDIP 2.54mm 7.62mm 300mil Socket LongPads +0 +20 +20 +Package_DIP +DIP-20_W8.89mm_SMDSocket_LongPads +20-lead though-hole mounted DIP package, row spacing 8.89 mm (350 mils), SMDSocket, LongPads +THT DIP DIL PDIP 2.54mm 8.89mm 350mil SMDSocket LongPads +0 +20 +20 +Package_DIP +DIP-22_W7.62mm +22-lead though-hole mounted DIP package, row spacing 7.62 mm (300 mils) +THT DIP DIL PDIP 2.54mm 7.62mm 300mil +0 +22 +22 +Package_DIP +DIP-22_W7.62mm_LongPads +22-lead though-hole mounted DIP package, row spacing 7.62 mm (300 mils), LongPads +THT DIP DIL PDIP 2.54mm 7.62mm 300mil LongPads +0 +22 +22 +Package_DIP +DIP-22_W7.62mm_SMDSocket_SmallPads +22-lead though-hole mounted DIP package, row spacing 7.62 mm (300 mils), SMDSocket, SmallPads +THT DIP DIL PDIP 2.54mm 7.62mm 300mil SMDSocket SmallPads +0 +22 +22 +Package_DIP +DIP-22_W7.62mm_Socket +22-lead though-hole mounted DIP package, row spacing 7.62 mm (300 mils), Socket +THT DIP DIL PDIP 2.54mm 7.62mm 300mil Socket +0 +22 +22 +Package_DIP +DIP-22_W7.62mm_Socket_LongPads +22-lead though-hole mounted DIP package, row spacing 7.62 mm (300 mils), Socket, LongPads +THT DIP DIL PDIP 2.54mm 7.62mm 300mil Socket LongPads +0 +22 +22 +Package_DIP +DIP-22_W8.89mm_SMDSocket_LongPads +22-lead though-hole mounted DIP package, row spacing 8.89 mm (350 mils), SMDSocket, LongPads +THT DIP DIL PDIP 2.54mm 8.89mm 350mil SMDSocket LongPads +0 +22 +22 +Package_DIP +DIP-22_W10.16mm +22-lead though-hole mounted DIP package, row spacing 10.16 mm (400 mils) +THT DIP DIL PDIP 2.54mm 10.16mm 400mil +0 +22 +22 +Package_DIP +DIP-22_W10.16mm_LongPads +22-lead though-hole mounted DIP package, row spacing 10.16 mm (400 mils), LongPads +THT DIP DIL PDIP 2.54mm 10.16mm 400mil LongPads +0 +22 +22 +Package_DIP +DIP-22_W10.16mm_SMDSocket_SmallPads +22-lead though-hole mounted DIP package, row spacing 10.16 mm (400 mils), SMDSocket, SmallPads +THT DIP DIL PDIP 2.54mm 10.16mm 400mil SMDSocket SmallPads +0 +22 +22 +Package_DIP +DIP-22_W10.16mm_Socket +22-lead though-hole mounted DIP package, row spacing 10.16 mm (400 mils), Socket +THT DIP DIL PDIP 2.54mm 10.16mm 400mil Socket +0 +22 +22 +Package_DIP +DIP-22_W10.16mm_Socket_LongPads +22-lead though-hole mounted DIP package, row spacing 10.16 mm (400 mils), Socket, LongPads +THT DIP DIL PDIP 2.54mm 10.16mm 400mil Socket LongPads +0 +22 +22 +Package_DIP +DIP-22_W11.43mm_SMDSocket_LongPads +22-lead though-hole mounted DIP package, row spacing 11.43 mm (450 mils), SMDSocket, LongPads +THT DIP DIL PDIP 2.54mm 11.43mm 450mil SMDSocket LongPads +0 +22 +22 +Package_DIP +DIP-24_W7.62mm +24-lead though-hole mounted DIP package, row spacing 7.62 mm (300 mils) +THT DIP DIL PDIP 2.54mm 7.62mm 300mil +0 +24 +24 +Package_DIP +DIP-24_W7.62mm_LongPads +24-lead though-hole mounted DIP package, row spacing 7.62 mm (300 mils), LongPads +THT DIP DIL PDIP 2.54mm 7.62mm 300mil LongPads +0 +24 +24 +Package_DIP +DIP-24_W7.62mm_SMDSocket_SmallPads +24-lead though-hole mounted DIP package, row spacing 7.62 mm (300 mils), SMDSocket, SmallPads +THT DIP DIL PDIP 2.54mm 7.62mm 300mil SMDSocket SmallPads +0 +24 +24 +Package_DIP +DIP-24_W7.62mm_Socket +24-lead though-hole mounted DIP package, row spacing 7.62 mm (300 mils), Socket +THT DIP DIL PDIP 2.54mm 7.62mm 300mil Socket +0 +24 +24 +Package_DIP +DIP-24_W7.62mm_Socket_LongPads +24-lead though-hole mounted DIP package, row spacing 7.62 mm (300 mils), Socket, LongPads +THT DIP DIL PDIP 2.54mm 7.62mm 300mil Socket LongPads +0 +24 +24 +Package_DIP +DIP-24_W8.89mm_SMDSocket_LongPads +24-lead though-hole mounted DIP package, row spacing 8.89 mm (350 mils), SMDSocket, LongPads +THT DIP DIL PDIP 2.54mm 8.89mm 350mil SMDSocket LongPads +0 +24 +24 +Package_DIP +DIP-24_W10.16mm +24-lead though-hole mounted DIP package, row spacing 10.16 mm (400 mils) +THT DIP DIL PDIP 2.54mm 10.16mm 400mil +0 +24 +24 +Package_DIP +DIP-24_W10.16mm_LongPads +24-lead though-hole mounted DIP package, row spacing 10.16 mm (400 mils), LongPads +THT DIP DIL PDIP 2.54mm 10.16mm 400mil LongPads +0 +24 +24 +Package_DIP +DIP-24_W10.16mm_SMDSocket_SmallPads +24-lead though-hole mounted DIP package, row spacing 10.16 mm (400 mils), SMDSocket, SmallPads +THT DIP DIL PDIP 2.54mm 10.16mm 400mil SMDSocket SmallPads +0 +24 +24 +Package_DIP +DIP-24_W10.16mm_Socket +24-lead though-hole mounted DIP package, row spacing 10.16 mm (400 mils), Socket +THT DIP DIL PDIP 2.54mm 10.16mm 400mil Socket +0 +24 +24 +Package_DIP +DIP-24_W10.16mm_Socket_LongPads +24-lead though-hole mounted DIP package, row spacing 10.16 mm (400 mils), Socket, LongPads +THT DIP DIL PDIP 2.54mm 10.16mm 400mil Socket LongPads +0 +24 +24 +Package_DIP +DIP-24_W11.43mm_SMDSocket_LongPads +24-lead though-hole mounted DIP package, row spacing 11.43 mm (450 mils), SMDSocket, LongPads +THT DIP DIL PDIP 2.54mm 11.43mm 450mil SMDSocket LongPads +0 +24 +24 +Package_DIP +DIP-24_W15.24mm +24-lead though-hole mounted DIP package, row spacing 15.24 mm (600 mils) +THT DIP DIL PDIP 2.54mm 15.24mm 600mil +0 +24 +24 +Package_DIP +DIP-24_W15.24mm_LongPads +24-lead though-hole mounted DIP package, row spacing 15.24 mm (600 mils), LongPads +THT DIP DIL PDIP 2.54mm 15.24mm 600mil LongPads +0 +24 +24 +Package_DIP +DIP-24_W15.24mm_SMDSocket_SmallPads +24-lead though-hole mounted DIP package, row spacing 15.24 mm (600 mils), SMDSocket, SmallPads +THT DIP DIL PDIP 2.54mm 15.24mm 600mil SMDSocket SmallPads +0 +24 +24 +Package_DIP +DIP-24_W15.24mm_Socket +24-lead though-hole mounted DIP package, row spacing 15.24 mm (600 mils), Socket +THT DIP DIL PDIP 2.54mm 15.24mm 600mil Socket +0 +24 +24 +Package_DIP +DIP-24_W15.24mm_Socket_LongPads +24-lead though-hole mounted DIP package, row spacing 15.24 mm (600 mils), Socket, LongPads +THT DIP DIL PDIP 2.54mm 15.24mm 600mil Socket LongPads +0 +24 +24 +Package_DIP +DIP-24_W16.51mm_SMDSocket_LongPads +24-lead though-hole mounted DIP package, row spacing 16.51 mm (650 mils), SMDSocket, LongPads +THT DIP DIL PDIP 2.54mm 16.51mm 650mil SMDSocket LongPads +0 +24 +24 +Package_DIP +DIP-28_W7.62mm +28-lead though-hole mounted DIP package, row spacing 7.62 mm (300 mils) +THT DIP DIL PDIP 2.54mm 7.62mm 300mil +0 +28 +28 +Package_DIP +DIP-28_W7.62mm_LongPads +28-lead though-hole mounted DIP package, row spacing 7.62 mm (300 mils), LongPads +THT DIP DIL PDIP 2.54mm 7.62mm 300mil LongPads +0 +28 +28 +Package_DIP +DIP-28_W7.62mm_SMDSocket_SmallPads +28-lead though-hole mounted DIP package, row spacing 7.62 mm (300 mils), SMDSocket, SmallPads +THT DIP DIL PDIP 2.54mm 7.62mm 300mil SMDSocket SmallPads +0 +28 +28 +Package_DIP +DIP-28_W7.62mm_Socket +28-lead though-hole mounted DIP package, row spacing 7.62 mm (300 mils), Socket +THT DIP DIL PDIP 2.54mm 7.62mm 300mil Socket +0 +28 +28 +Package_DIP +DIP-28_W7.62mm_Socket_LongPads +28-lead though-hole mounted DIP package, row spacing 7.62 mm (300 mils), Socket, LongPads +THT DIP DIL PDIP 2.54mm 7.62mm 300mil Socket LongPads +0 +28 +28 +Package_DIP +DIP-28_W8.89mm_SMDSocket_LongPads +28-lead though-hole mounted DIP package, row spacing 8.89 mm (350 mils), SMDSocket, LongPads +THT DIP DIL PDIP 2.54mm 8.89mm 350mil SMDSocket LongPads +0 +28 +28 +Package_DIP +DIP-28_W15.24mm +28-lead though-hole mounted DIP package, row spacing 15.24 mm (600 mils) +THT DIP DIL PDIP 2.54mm 15.24mm 600mil +0 +28 +28 +Package_DIP +DIP-28_W15.24mm_LongPads +28-lead though-hole mounted DIP package, row spacing 15.24 mm (600 mils), LongPads +THT DIP DIL PDIP 2.54mm 15.24mm 600mil LongPads +0 +28 +28 +Package_DIP +DIP-28_W15.24mm_SMDSocket_SmallPads +28-lead though-hole mounted DIP package, row spacing 15.24 mm (600 mils), SMDSocket, SmallPads +THT DIP DIL PDIP 2.54mm 15.24mm 600mil SMDSocket SmallPads +0 +28 +28 +Package_DIP +DIP-28_W15.24mm_Socket +28-lead though-hole mounted DIP package, row spacing 15.24 mm (600 mils), Socket +THT DIP DIL PDIP 2.54mm 15.24mm 600mil Socket +0 +28 +28 +Package_DIP +DIP-28_W15.24mm_Socket_LongPads +28-lead though-hole mounted DIP package, row spacing 15.24 mm (600 mils), Socket, LongPads +THT DIP DIL PDIP 2.54mm 15.24mm 600mil Socket LongPads +0 +28 +28 +Package_DIP +DIP-28_W16.51mm_SMDSocket_LongPads +28-lead though-hole mounted DIP package, row spacing 16.51 mm (650 mils), SMDSocket, LongPads +THT DIP DIL PDIP 2.54mm 16.51mm 650mil SMDSocket LongPads +0 +28 +28 +Package_DIP +DIP-32_W7.62mm +32-lead dip package, row spacing 7.62 mm (300 mils) +DIL DIP PDIP 2.54mm 7.62mm 300mil +0 +32 +32 +Package_DIP +DIP-32_W15.24mm +32-lead though-hole mounted DIP package, row spacing 15.24 mm (600 mils) +THT DIP DIL PDIP 2.54mm 15.24mm 600mil +0 +32 +32 +Package_DIP +DIP-32_W15.24mm_LongPads +32-lead though-hole mounted DIP package, row spacing 15.24 mm (600 mils), LongPads +THT DIP DIL PDIP 2.54mm 15.24mm 600mil LongPads +0 +32 +32 +Package_DIP +DIP-32_W15.24mm_SMDSocket_SmallPads +32-lead though-hole mounted DIP package, row spacing 15.24 mm (600 mils), SMDSocket, SmallPads +THT DIP DIL PDIP 2.54mm 15.24mm 600mil SMDSocket SmallPads +0 +32 +32 +Package_DIP +DIP-32_W15.24mm_Socket +32-lead though-hole mounted DIP package, row spacing 15.24 mm (600 mils), Socket +THT DIP DIL PDIP 2.54mm 15.24mm 600mil Socket +0 +32 +32 +Package_DIP +DIP-32_W15.24mm_Socket_LongPads +32-lead though-hole mounted DIP package, row spacing 15.24 mm (600 mils), Socket, LongPads +THT DIP DIL PDIP 2.54mm 15.24mm 600mil Socket LongPads +0 +32 +32 +Package_DIP +DIP-32_W16.51mm_SMDSocket_LongPads +32-lead though-hole mounted DIP package, row spacing 16.51 mm (650 mils), SMDSocket, LongPads +THT DIP DIL PDIP 2.54mm 16.51mm 650mil SMDSocket LongPads +0 +32 +32 +Package_DIP +DIP-40_W15.24mm +40-lead though-hole mounted DIP package, row spacing 15.24 mm (600 mils) +THT DIP DIL PDIP 2.54mm 15.24mm 600mil +0 +40 +40 +Package_DIP +DIP-40_W15.24mm_LongPads +40-lead though-hole mounted DIP package, row spacing 15.24 mm (600 mils), LongPads +THT DIP DIL PDIP 2.54mm 15.24mm 600mil LongPads +0 +40 +40 +Package_DIP +DIP-40_W15.24mm_SMDSocket_SmallPads +40-lead though-hole mounted DIP package, row spacing 15.24 mm (600 mils), SMDSocket, SmallPads +THT DIP DIL PDIP 2.54mm 15.24mm 600mil SMDSocket SmallPads +0 +40 +40 +Package_DIP +DIP-40_W15.24mm_Socket +40-lead though-hole mounted DIP package, row spacing 15.24 mm (600 mils), Socket +THT DIP DIL PDIP 2.54mm 15.24mm 600mil Socket +0 +40 +40 +Package_DIP +DIP-40_W15.24mm_Socket_LongPads +40-lead though-hole mounted DIP package, row spacing 15.24 mm (600 mils), Socket, LongPads +THT DIP DIL PDIP 2.54mm 15.24mm 600mil Socket LongPads +0 +40 +40 +Package_DIP +DIP-40_W16.51mm_SMDSocket_LongPads +40-lead though-hole mounted DIP package, row spacing 16.51 mm (650 mils), SMDSocket, LongPads +THT DIP DIL PDIP 2.54mm 16.51mm 650mil SMDSocket LongPads +0 +40 +40 +Package_DIP +DIP-40_W25.4mm +40-lead though-hole mounted DIP package, row spacing 25.4 mm (1000 mils) +THT DIP DIL PDIP 2.54mm 25.4mm 1000mil +0 +40 +40 +Package_DIP +DIP-40_W25.4mm_LongPads +40-lead though-hole mounted DIP package, row spacing 25.4 mm (1000 mils), LongPads +THT DIP DIL PDIP 2.54mm 25.4mm 1000mil LongPads +0 +40 +40 +Package_DIP +DIP-40_W25.4mm_SMDSocket_SmallPads +40-lead though-hole mounted DIP package, row spacing 25.4 mm (1000 mils), SMDSocket, SmallPads +THT DIP DIL PDIP 2.54mm 25.4mm 1000mil SMDSocket SmallPads +0 +40 +40 +Package_DIP +DIP-40_W25.4mm_Socket +40-lead though-hole mounted DIP package, row spacing 25.4 mm (1000 mils), Socket +THT DIP DIL PDIP 2.54mm 25.4mm 1000mil Socket +0 +40 +40 +Package_DIP +DIP-40_W25.4mm_Socket_LongPads +40-lead though-hole mounted DIP package, row spacing 25.4 mm (1000 mils), Socket, LongPads +THT DIP DIL PDIP 2.54mm 25.4mm 1000mil Socket LongPads +0 +40 +40 +Package_DIP +DIP-40_W26.67mm_SMDSocket_LongPads +40-lead though-hole mounted DIP package, row spacing 26.67 mm (1050 mils), SMDSocket, LongPads +THT DIP DIL PDIP 2.54mm 26.669999999999998mm 1050mil SMDSocket LongPads +0 +40 +40 +Package_DIP +DIP-42_W15.24mm +42-lead though-hole mounted DIP package, row spacing 15.24 mm (600 mils) +THT DIP DIL PDIP 2.54mm 15.24mm 600mil +0 +42 +42 +Package_DIP +DIP-42_W15.24mm_LongPads +42-lead though-hole mounted DIP package, row spacing 15.24 mm (600 mils), LongPads +THT DIP DIL PDIP 2.54mm 15.24mm 600mil LongPads +0 +42 +42 +Package_DIP +DIP-42_W15.24mm_SMDSocket_SmallPads +42-lead though-hole mounted DIP package, row spacing 15.24 mm (600 mils), SMDSocket, SmallPads +THT DIP DIL PDIP 2.54mm 15.24mm 600mil SMDSocket SmallPads +0 +42 +42 +Package_DIP +DIP-42_W15.24mm_Socket +42-lead though-hole mounted DIP package, row spacing 15.24 mm (600 mils), Socket +THT DIP DIL PDIP 2.54mm 15.24mm 600mil Socket +0 +42 +42 +Package_DIP +DIP-42_W15.24mm_Socket_LongPads +42-lead though-hole mounted DIP package, row spacing 15.24 mm (600 mils), Socket, LongPads +THT DIP DIL PDIP 2.54mm 15.24mm 600mil Socket LongPads +0 +42 +42 +Package_DIP +DIP-42_W16.51mm_SMDSocket_LongPads +42-lead though-hole mounted DIP package, row spacing 16.51 mm (650 mils), SMDSocket, LongPads +THT DIP DIL PDIP 2.54mm 16.51mm 650mil SMDSocket LongPads +0 +42 +42 +Package_DIP +DIP-48_W15.24mm +48-lead though-hole mounted DIP package, row spacing 15.24 mm (600 mils) +THT DIP DIL PDIP 2.54mm 15.24mm 600mil +0 +48 +48 +Package_DIP +DIP-48_W15.24mm_LongPads +48-lead though-hole mounted DIP package, row spacing 15.24 mm (600 mils), LongPads +THT DIP DIL PDIP 2.54mm 15.24mm 600mil LongPads +0 +48 +48 +Package_DIP +DIP-48_W15.24mm_SMDSocket_SmallPads +48-lead though-hole mounted DIP package, row spacing 15.24 mm (600 mils), SMDSocket, SmallPads +THT DIP DIL PDIP 2.54mm 15.24mm 600mil SMDSocket SmallPads +0 +48 +48 +Package_DIP +DIP-48_W15.24mm_Socket +48-lead though-hole mounted DIP package, row spacing 15.24 mm (600 mils), Socket +THT DIP DIL PDIP 2.54mm 15.24mm 600mil Socket +0 +48 +48 +Package_DIP +DIP-48_W15.24mm_Socket_LongPads +48-lead though-hole mounted DIP package, row spacing 15.24 mm (600 mils), Socket, LongPads +THT DIP DIL PDIP 2.54mm 15.24mm 600mil Socket LongPads +0 +48 +48 +Package_DIP +DIP-48_W16.51mm_SMDSocket_LongPads +48-lead though-hole mounted DIP package, row spacing 16.51 mm (650 mils), SMDSocket, LongPads +THT DIP DIL PDIP 2.54mm 16.51mm 650mil SMDSocket LongPads +0 +48 +48 +Package_DIP +DIP-64_W15.24mm +64-lead though-hole mounted DIP package, row spacing 15.24 mm (600 mils) +THT DIP DIL PDIP 2.54mm 15.24mm 600mil +0 +64 +64 +Package_DIP +DIP-64_W15.24mm_LongPads +64-lead though-hole mounted DIP package, row spacing 15.24 mm (600 mils), LongPads +THT DIP DIL PDIP 2.54mm 15.24mm 600mil LongPads +0 +64 +64 +Package_DIP +DIP-64_W15.24mm_SMDSocket_SmallPads +64-lead though-hole mounted DIP package, row spacing 15.24 mm (600 mils), SMDSocket, SmallPads +THT DIP DIL PDIP 2.54mm 15.24mm 600mil SMDSocket SmallPads +0 +64 +64 +Package_DIP +DIP-64_W15.24mm_Socket +64-lead though-hole mounted DIP package, row spacing 15.24 mm (600 mils), Socket +THT DIP DIL PDIP 2.54mm 15.24mm 600mil Socket +0 +64 +64 +Package_DIP +DIP-64_W15.24mm_Socket_LongPads +64-lead though-hole mounted DIP package, row spacing 15.24 mm (600 mils), Socket, LongPads +THT DIP DIL PDIP 2.54mm 15.24mm 600mil Socket LongPads +0 +64 +64 +Package_DIP +DIP-64_W16.51mm_SMDSocket_LongPads +64-lead though-hole mounted DIP package, row spacing 16.51 mm (650 mils), SMDSocket, LongPads +THT DIP DIL PDIP 2.54mm 16.51mm 650mil SMDSocket LongPads +0 +64 +64 +Package_DIP +DIP-64_W22.86mm +64-lead though-hole mounted DIP package, row spacing 22.86 mm (900 mils) +THT DIP DIL PDIP 2.54mm 22.86mm 900mil +0 +64 +64 +Package_DIP +DIP-64_W22.86mm_LongPads +64-lead though-hole mounted DIP package, row spacing 22.86 mm (900 mils), LongPads +THT DIP DIL PDIP 2.54mm 22.86mm 900mil LongPads +0 +64 +64 +Package_DIP +DIP-64_W22.86mm_SMDSocket_SmallPads +64-lead though-hole mounted DIP package, row spacing 22.86 mm (900 mils), SMDSocket, SmallPads +THT DIP DIL PDIP 2.54mm 22.86mm 900mil SMDSocket SmallPads +0 +64 +64 +Package_DIP +DIP-64_W22.86mm_Socket +64-lead though-hole mounted DIP package, row spacing 22.86 mm (900 mils), Socket +THT DIP DIL PDIP 2.54mm 22.86mm 900mil Socket +0 +64 +64 +Package_DIP +DIP-64_W22.86mm_Socket_LongPads +64-lead though-hole mounted DIP package, row spacing 22.86 mm (900 mils), Socket, LongPads +THT DIP DIL PDIP 2.54mm 22.86mm 900mil Socket LongPads +0 +64 +64 +Package_DIP +DIP-64_W24.13mm_SMDSocket_LongPads +64-lead though-hole mounted DIP package, row spacing 24.13 mm (950 mils), SMDSocket, LongPads +THT DIP DIL PDIP 2.54mm 24.13mm 950mil SMDSocket LongPads +0 +64 +64 +Package_DIP +DIP-64_W25.4mm +64-lead though-hole mounted DIP package, row spacing 25.4 mm (1000 mils) +THT DIP DIL PDIP 2.54mm 25.4mm 1000mil +0 +64 +64 +Package_DIP +DIP-64_W25.4mm_LongPads +64-lead though-hole mounted DIP package, row spacing 25.4 mm (1000 mils), LongPads +THT DIP DIL PDIP 2.54mm 25.4mm 1000mil LongPads +0 +64 +64 +Package_DIP +DIP-64_W25.4mm_SMDSocket_SmallPads +64-lead though-hole mounted DIP package, row spacing 25.4 mm (1000 mils), SMDSocket, SmallPads +THT DIP DIL PDIP 2.54mm 25.4mm 1000mil SMDSocket SmallPads +0 +64 +64 +Package_DIP +DIP-64_W25.4mm_Socket +64-lead though-hole mounted DIP package, row spacing 25.4 mm (1000 mils), Socket +THT DIP DIL PDIP 2.54mm 25.4mm 1000mil Socket +0 +64 +64 +Package_DIP +DIP-64_W25.4mm_Socket_LongPads +64-lead though-hole mounted DIP package, row spacing 25.4 mm (1000 mils), Socket, LongPads +THT DIP DIL PDIP 2.54mm 25.4mm 1000mil Socket LongPads +0 +64 +64 +Package_DIP +DIP-64_W26.67mm_SMDSocket_LongPads +64-lead though-hole mounted DIP package, row spacing 26.67 mm (1050 mils), SMDSocket, LongPads +THT DIP DIL PDIP 2.54mm 26.669999999999998mm 1050mil SMDSocket LongPads +0 +64 +64 +Package_DIP +Fairchild_LSOP-8 +8-Lead, 300\" Wide, Surface Mount Package (https://www.fairchildsemi.com/package-drawings/ML/MLSOP08A.pdf) +LSOP 2.54mm 300mil +0 +8 +8 +Package_DIP +PowerIntegrations_eDIP-12B +Power Integrations eDIP-12B, see https://www.power.com/sites/default/files/product-docs/linkswitch-pl_family_datasheet.pdf +THT DIP DIL PDIP 2.54mm 7.62mm 300mil +0 +11 +11 +Package_DIP +PowerIntegrations_PDIP-8B +Power Integrations variant of 8-lead though-hole mounted DIP package, row spacing 7.62 mm (300 mils), LongPads, see https://www.power.com/sites/default/files/product-docs/lnk520.pdf +THT DIP DIL PDIP 2.54mm 7.62mm 300mil LongPads +0 +7 +7 +Package_DIP +PowerIntegrations_PDIP-8C +Power Integrations variant of 8-lead though-hole mounted DIP package, row spacing 7.62 mm (300 mils), LongPads, see https://ac-dc.power.com/sites/default/files/product-docs/tinyswitch-iii_family_datasheet.pdf +THT DIP DIL PDIP 2.54mm 7.62mm 300mil LongPads +0 +7 +7 +Package_DIP +PowerIntegrations_SDIP-10C +PowerIntegrations variant of 10-lead though-hole mounted DIP package, row spacing 7.62 mm (300 mils), LongPads, see https://www.power.com/sites/default/files/product-docs/tophx_family_datasheet.pdf +THT DIP DIL PDIP 2.54mm 7.62mm 300mil LongPads +0 +9 +9 +Package_DIP +PowerIntegrations_SMD-8 +PowerIntegrations variant of 8-lead surface-mounted (SMD) DIP package, row spacing 7.62 mm (300 mils), see https://www.power.com/sites/default/files/product-docs/lnk520.pdf +SMD DIP DIL PDIP SMDIP 2.54mm 7.62mm 300mil +0 +8 +8 +Package_DIP +PowerIntegrations_SMD-8B +PowerIntegrations variant of 8-lead surface-mounted (SMD) DIP package, row spacing 7.62 mm (300 mils), see https://www.power.com/sites/default/files/product-docs/lnk520.pdf +SMD DIP DIL PDIP SMDIP 2.54mm 7.62mm 300mil +0 +7 +7 +Package_DIP +PowerIntegrations_SMD-8C +PowerIntegrations variant of 8-lead surface-mounted (SMD) DIP package, row spacing 7.62 mm (300 mils), see https://ac-dc.power.com/sites/default/files/product-docs/tinyswitch-iii_family_datasheet.pdf +SMD DIP DIL PDIP SMDIP 2.54mm 7.62mm 300mil +0 +7 +7 +Package_DIP +SMDIP-4_W7.62mm +4-lead surface-mounted (SMD) DIP package, row spacing 7.62 mm (300 mils) +SMD DIP DIL PDIP SMDIP 2.54mm 7.62mm 300mil +0 +4 +4 +Package_DIP +SMDIP-4_W9.53mm +4-lead surface-mounted (SMD) DIP package, row spacing 9.53 mm (375 mils) +SMD DIP DIL PDIP SMDIP 2.54mm 9.53mm 375mil +0 +4 +4 +Package_DIP +SMDIP-4_W9.53mm_Clearance8mm +4-lead surface-mounted (SMD) DIP package, row spacing 9.53 mm (375 mils), Clearance8mm +SMD DIP DIL PDIP SMDIP 2.54mm 9.53mm 375mil Clearance8mm +0 +4 +4 +Package_DIP +SMDIP-4_W11.48mm +4-lead surface-mounted (SMD) DIP package, row spacing 11.48 mm (451 mils) +SMD DIP DIL PDIP SMDIP 2.54mm 11.48mm 451mil +0 +4 +4 +Package_DIP +SMDIP-6_W7.62mm +6-lead surface-mounted (SMD) DIP package, row spacing 7.62 mm (300 mils) +SMD DIP DIL PDIP SMDIP 2.54mm 7.62mm 300mil +0 +6 +6 +Package_DIP +SMDIP-6_W9.53mm +6-lead surface-mounted (SMD) DIP package, row spacing 9.53 mm (375 mils) +SMD DIP DIL PDIP SMDIP 2.54mm 9.53mm 375mil +0 +6 +6 +Package_DIP +SMDIP-6_W9.53mm_Clearance8mm +6-lead surface-mounted (SMD) DIP package, row spacing 9.53 mm (375 mils), Clearance8mm +SMD DIP DIL PDIP SMDIP 2.54mm 9.53mm 375mil Clearance8mm +0 +6 +6 +Package_DIP +SMDIP-6_W11.48mm +6-lead surface-mounted (SMD) DIP package, row spacing 11.48 mm (451 mils) +SMD DIP DIL PDIP SMDIP 2.54mm 11.48mm 451mil +0 +6 +6 +Package_DIP +SMDIP-8_W7.62mm +8-lead surface-mounted (SMD) DIP package, row spacing 7.62 mm (300 mils) +SMD DIP DIL PDIP SMDIP 2.54mm 7.62mm 300mil +0 +8 +8 +Package_DIP +SMDIP-8_W9.53mm +8-lead surface-mounted (SMD) DIP package, row spacing 9.53 mm (375 mils) +SMD DIP DIL PDIP SMDIP 2.54mm 9.53mm 375mil +0 +8 +8 +Package_DIP +SMDIP-8_W9.53mm_Clearance8mm +8-lead surface-mounted (SMD) DIP package, row spacing 9.53 mm (375 mils), Clearance8mm +SMD DIP DIL PDIP SMDIP 2.54mm 9.53mm 375mil Clearance8mm +0 +8 +8 +Package_DIP +SMDIP-8_W11.48mm +8-lead surface-mounted (SMD) DIP package, row spacing 11.48 mm (451 mils) +SMD DIP DIL PDIP SMDIP 2.54mm 11.48mm 451mil +0 +8 +8 +Package_DIP +SMDIP-10_W7.62mm +10-lead surface-mounted (SMD) DIP package, row spacing 7.62 mm (300 mils) +SMD DIP DIL PDIP SMDIP 2.54mm 7.62mm 300mil +0 +10 +10 +Package_DIP +SMDIP-10_W9.53mm +10-lead surface-mounted (SMD) DIP package, row spacing 9.53 mm (375 mils) +SMD DIP DIL PDIP SMDIP 2.54mm 9.53mm 375mil +0 +10 +10 +Package_DIP +SMDIP-10_W9.53mm_Clearance8mm +10-lead surface-mounted (SMD) DIP package, row spacing 9.53 mm (375 mils), Clearance8mm +SMD DIP DIL PDIP SMDIP 2.54mm 9.53mm 375mil Clearance8mm +0 +10 +10 +Package_DIP +SMDIP-10_W11.48mm +10-lead surface-mounted (SMD) DIP package, row spacing 11.48 mm (451 mils) +SMD DIP DIL PDIP SMDIP 2.54mm 11.48mm 451mil +0 +10 +10 +Package_DIP +SMDIP-12_W7.62mm +12-lead surface-mounted (SMD) DIP package, row spacing 7.62 mm (300 mils) +SMD DIP DIL PDIP SMDIP 2.54mm 7.62mm 300mil +0 +12 +12 +Package_DIP +SMDIP-12_W9.53mm +12-lead surface-mounted (SMD) DIP package, row spacing 9.53 mm (375 mils) +SMD DIP DIL PDIP SMDIP 2.54mm 9.53mm 375mil +0 +12 +12 +Package_DIP +SMDIP-12_W9.53mm_Clearance8mm +12-lead surface-mounted (SMD) DIP package, row spacing 9.53 mm (375 mils), Clearance8mm +SMD DIP DIL PDIP SMDIP 2.54mm 9.53mm 375mil Clearance8mm +0 +12 +12 +Package_DIP +SMDIP-12_W11.48mm +12-lead surface-mounted (SMD) DIP package, row spacing 11.48 mm (451 mils) +SMD DIP DIL PDIP SMDIP 2.54mm 11.48mm 451mil +0 +12 +12 +Package_DIP +SMDIP-14_W7.62mm +14-lead surface-mounted (SMD) DIP package, row spacing 7.62 mm (300 mils) +SMD DIP DIL PDIP SMDIP 2.54mm 7.62mm 300mil +0 +14 +14 +Package_DIP +SMDIP-14_W9.53mm +14-lead surface-mounted (SMD) DIP package, row spacing 9.53 mm (375 mils) +SMD DIP DIL PDIP SMDIP 2.54mm 9.53mm 375mil +0 +14 +14 +Package_DIP +SMDIP-14_W9.53mm_Clearance8mm +14-lead surface-mounted (SMD) DIP package, row spacing 9.53 mm (375 mils), Clearance8mm +SMD DIP DIL PDIP SMDIP 2.54mm 9.53mm 375mil Clearance8mm +0 +14 +14 +Package_DIP +SMDIP-14_W11.48mm +14-lead surface-mounted (SMD) DIP package, row spacing 11.48 mm (451 mils) +SMD DIP DIL PDIP SMDIP 2.54mm 11.48mm 451mil +0 +14 +14 +Package_DIP +SMDIP-16_W7.62mm +16-lead surface-mounted (SMD) DIP package, row spacing 7.62 mm (300 mils) +SMD DIP DIL PDIP SMDIP 2.54mm 7.62mm 300mil +0 +16 +16 +Package_DIP +SMDIP-16_W9.53mm +16-lead surface-mounted (SMD) DIP package, row spacing 9.53 mm (375 mils) +SMD DIP DIL PDIP SMDIP 2.54mm 9.53mm 375mil +0 +16 +16 +Package_DIP +SMDIP-16_W9.53mm_Clearance8mm +16-lead surface-mounted (SMD) DIP package, row spacing 9.53 mm (375 mils), Clearance8mm +SMD DIP DIL PDIP SMDIP 2.54mm 9.53mm 375mil Clearance8mm +0 +16 +16 +Package_DIP +SMDIP-16_W11.48mm +16-lead surface-mounted (SMD) DIP package, row spacing 11.48 mm (451 mils) +SMD DIP DIL PDIP SMDIP 2.54mm 11.48mm 451mil +0 +16 +16 +Package_DIP +SMDIP-18_W7.62mm +18-lead surface-mounted (SMD) DIP package, row spacing 7.62 mm (300 mils) +SMD DIP DIL PDIP SMDIP 2.54mm 7.62mm 300mil +0 +18 +18 +Package_DIP +SMDIP-18_W9.53mm +18-lead surface-mounted (SMD) DIP package, row spacing 9.53 mm (375 mils) +SMD DIP DIL PDIP SMDIP 2.54mm 9.53mm 375mil +0 +18 +18 +Package_DIP +SMDIP-18_W9.53mm_Clearance8mm +18-lead surface-mounted (SMD) DIP package, row spacing 9.53 mm (375 mils), Clearance8mm +SMD DIP DIL PDIP SMDIP 2.54mm 9.53mm 375mil Clearance8mm +0 +18 +18 +Package_DIP +SMDIP-18_W11.48mm +18-lead surface-mounted (SMD) DIP package, row spacing 11.48 mm (451 mils) +SMD DIP DIL PDIP SMDIP 2.54mm 11.48mm 451mil +0 +18 +18 +Package_DIP +SMDIP-20_W7.62mm +20-lead surface-mounted (SMD) DIP package, row spacing 7.62 mm (300 mils) +SMD DIP DIL PDIP SMDIP 2.54mm 7.62mm 300mil +0 +20 +20 +Package_DIP +SMDIP-20_W9.53mm +20-lead surface-mounted (SMD) DIP package, row spacing 9.53 mm (375 mils) +SMD DIP DIL PDIP SMDIP 2.54mm 9.53mm 375mil +0 +20 +20 +Package_DIP +SMDIP-20_W9.53mm_Clearance8mm +20-lead surface-mounted (SMD) DIP package, row spacing 9.53 mm (375 mils), Clearance8mm +SMD DIP DIL PDIP SMDIP 2.54mm 9.53mm 375mil Clearance8mm +0 +20 +20 +Package_DIP +SMDIP-20_W11.48mm +20-lead surface-mounted (SMD) DIP package, row spacing 11.48 mm (451 mils) +SMD DIP DIL PDIP SMDIP 2.54mm 11.48mm 451mil +0 +20 +20 +Package_DIP +SMDIP-22_W7.62mm +22-lead surface-mounted (SMD) DIP package, row spacing 7.62 mm (300 mils) +SMD DIP DIL PDIP SMDIP 2.54mm 7.62mm 300mil +0 +22 +22 +Package_DIP +SMDIP-22_W9.53mm +22-lead surface-mounted (SMD) DIP package, row spacing 9.53 mm (375 mils) +SMD DIP DIL PDIP SMDIP 2.54mm 9.53mm 375mil +0 +22 +22 +Package_DIP +SMDIP-22_W9.53mm_Clearance8mm +22-lead surface-mounted (SMD) DIP package, row spacing 9.53 mm (375 mils), Clearance8mm +SMD DIP DIL PDIP SMDIP 2.54mm 9.53mm 375mil Clearance8mm +0 +22 +22 +Package_DIP +SMDIP-22_W11.48mm +22-lead surface-mounted (SMD) DIP package, row spacing 11.48 mm (451 mils) +SMD DIP DIL PDIP SMDIP 2.54mm 11.48mm 451mil +0 +22 +22 +Package_DIP +SMDIP-24_W7.62mm +24-lead surface-mounted (SMD) DIP package, row spacing 7.62 mm (300 mils) +SMD DIP DIL PDIP SMDIP 2.54mm 7.62mm 300mil +0 +24 +24 +Package_DIP +SMDIP-24_W9.53mm +24-lead surface-mounted (SMD) DIP package, row spacing 9.53 mm (375 mils) +SMD DIP DIL PDIP SMDIP 2.54mm 9.53mm 375mil +0 +24 +24 +Package_DIP +SMDIP-24_W11.48mm +24-lead surface-mounted (SMD) DIP package, row spacing 11.48 mm (451 mils) +SMD DIP DIL PDIP SMDIP 2.54mm 11.48mm 451mil +0 +24 +24 +Package_DIP +SMDIP-24_W15.24mm +24-lead surface-mounted (SMD) DIP package, row spacing 15.24 mm (600 mils) +SMD DIP DIL PDIP SMDIP 2.54mm 15.24mm 600mil +0 +24 +24 +Package_DIP +SMDIP-28_W15.24mm +28-lead surface-mounted (SMD) DIP package, row spacing 15.24 mm (600 mils) +SMD DIP DIL PDIP SMDIP 2.54mm 15.24mm 600mil +0 +28 +28 +Package_DIP +SMDIP-32_W7.62mm +32-lead surface-mounted (SMD) DIP package, row spacing 7.62 mm (300 mils) +SMD DIP DIL PDIP SMDIP 2.54mm 7.62mm 300mil +0 +32 +32 +Package_DIP +SMDIP-32_W9.53mm +32-lead surface-mounted (SMD) DIP package, row spacing 9.53 mm (375 mils) +SMD DIP DIL PDIP SMDIP 2.54mm 9.53mm 375mil +0 +32 +32 +Package_DIP +SMDIP-32_W11.48mm +32-lead surface-mounted (SMD) DIP package, row spacing 11.48 mm (451 mils) +SMD DIP DIL PDIP SMDIP 2.54mm 11.48mm 451mil +0 +32 +32 +Package_DIP +SMDIP-32_W15.24mm +32-lead surface-mounted (SMD) DIP package, row spacing 15.24 mm (600 mils) +SMD DIP DIL PDIP SMDIP 2.54mm 15.24mm 600mil +0 +32 +32 +Package_DIP +SMDIP-40_W15.24mm +40-lead surface-mounted (SMD) DIP package, row spacing 15.24 mm (600 mils) +SMD DIP DIL PDIP SMDIP 2.54mm 15.24mm 600mil +0 +40 +40 +Package_DIP +SMDIP-40_W25.24mm +40-lead surface-mounted (SMD) DIP package, row spacing 25.24 mm (993 mils) +SMD DIP DIL PDIP SMDIP 2.54mm 25.24mm 993mil +0 +40 +40 +Package_DIP +SMDIP-42_W15.24mm +42-lead surface-mounted (SMD) DIP package, row spacing 15.24 mm (600 mils) +SMD DIP DIL PDIP SMDIP 2.54mm 15.24mm 600mil +0 +42 +42 +Package_DIP +SMDIP-48_W15.24mm +48-lead surface-mounted (SMD) DIP package, row spacing 15.24 mm (600 mils) +SMD DIP DIL PDIP SMDIP 2.54mm 15.24mm 600mil +0 +48 +48 +Package_DIP +SMDIP-64_W15.24mm +64-lead surface-mounted (SMD) DIP package, row spacing 15.24 mm (600 mils) +SMD DIP DIL PDIP SMDIP 2.54mm 15.24mm 600mil +0 +64 +64 +Package_DIP +Toshiba_11-7A9 +Toshiba 11-7A9 package, like 6-lead dip package with missing pin 5, row spacing 7.62 mm (300 mils), https://toshiba.semicon-storage.com/info/docget.jsp?did=1421&prodName=TLP3021(S) +Toshiba 11-7A9 DIL DIP PDIP 2.54mm 7.62mm 300mil +0 +5 +5 +Package_DIP +Vishay_HVM-DIP-3_W7.62mm +3-lead though-hole mounted high-volatge DIP package (based on standard DIP-4), row spacing 7.62 mm (300 mils), see https://www.vishay.com/docs/91361/hexdip.pdf +THT DIP DIL PDIP 2.54mm 7.62mm 300mil Vishay HVMDIP HEXDIP +0 +4 +3 +Package_QFP +EQFP-144-1EP_20x20mm_P0.5mm_EP4x4mm +EQFP, 144 Pin (https://www.intel.com/content/dam/www/programmable/us/en/pdfs/literature/packaging/04r00482-02.pdf), generated with kicad-footprint-generator ipc_gullwing_generator.py +EQFP QFP +0 +154 +145 +Package_QFP +EQFP-144-1EP_20x20mm_P0.5mm_EP4x4mm_ThermalVias +EQFP, 144 Pin (https://www.intel.com/content/dam/www/programmable/us/en/pdfs/literature/packaging/04r00482-02.pdf), generated with kicad-footprint-generator ipc_gullwing_generator.py +EQFP QFP +0 +171 +145 +Package_QFP +EQFP-144-1EP_20x20mm_P0.5mm_EP5x5mm +EQFP, 144 Pin (https://www.intel.com/content/dam/www/programmable/us/en/pdfs/literature/packaging/04r00476-02.pdf), generated with kicad-footprint-generator ipc_gullwing_generator.py +EQFP QFP +0 +161 +145 +Package_QFP +EQFP-144-1EP_20x20mm_P0.5mm_EP5x5mm_ThermalVias +EQFP, 144 Pin (https://www.intel.com/content/dam/www/programmable/us/en/pdfs/literature/packaging/04r00476-02.pdf), generated with kicad-footprint-generator ipc_gullwing_generator.py +EQFP QFP +0 +187 +145 +Package_QFP +EQFP-144-1EP_20x20mm_P0.5mm_EP6.61x5.615mm +EQFP, 144 Pin (https://www.intel.com/content/dam/www/programmable/us/en/pdfs/literature/packaging/04r00485-02.pdf), generated with kicad-footprint-generator ipc_gullwing_generator.py +EQFP QFP +0 +165 +145 +Package_QFP +EQFP-144-1EP_20x20mm_P0.5mm_EP6.61x5.615mm_ThermalVias +EQFP, 144 Pin (https://www.intel.com/content/dam/www/programmable/us/en/pdfs/literature/packaging/04r00485-02.pdf), generated with kicad-footprint-generator ipc_gullwing_generator.py +EQFP QFP +0 +196 +145 +Package_QFP +EQFP-144-1EP_20x20mm_P0.5mm_EP7.2x6.35mm +EQFP, 144 Pin (https://www.intel.com/content/dam/www/programmable/us/en/pdfs/literature/packaging/04r00487-01.pdf), generated with kicad-footprint-generator ipc_gullwing_generator.py +EQFP QFP +0 +175 +145 +Package_QFP +EQFP-144-1EP_20x20mm_P0.5mm_EP7.2x6.35mm_ThermalVias +EQFP, 144 Pin (https://www.intel.com/content/dam/www/programmable/us/en/pdfs/literature/packaging/04r00487-01.pdf), generated with kicad-footprint-generator ipc_gullwing_generator.py +EQFP QFP +0 +218 +145 +Package_QFP +EQFP-144-1EP_20x20mm_P0.5mm_EP8.93x8.7mm +EQFP, 144 Pin (https://www.intel.com/content/dam/www/programmable/us/en/pdfs/literature/packaging/04r00479-02.pdf), generated with kicad-footprint-generator ipc_gullwing_generator.py +EQFP QFP +0 +194 +145 +Package_QFP +EQFP-144-1EP_20x20mm_P0.5mm_EP8.93x8.7mm_ThermalVias +EQFP, 144 Pin (https://www.intel.com/content/dam/www/programmable/us/en/pdfs/literature/packaging/04r00479-02.pdf), generated with kicad-footprint-generator ipc_gullwing_generator.py +EQFP QFP +0 +259 +145 +Package_QFP +HTQFP-64-1EP_10x10mm_P0.5mm_EP8x8mm +64-Lead Plastic Thin Quad Flatpack (PT) - 10x10x1 mm Body, 2.00 mm Footprint [HTQFP] thermal pad +HTQFP-64 Pitch 0.5 +0 +69 +65 +Package_QFP +HTQFP-64-1EP_10x10mm_P0.5mm_EP8x8mm_Mask4.4x4.4mm_ThermalVias +64-Lead Plastic Thin Quad Flatpack (PT) - 10x10x1 mm Body, 2.00 mm Footprint [HTQFP] thermal pad +HTQFP-64 Pitch 0.5 +0 +135 +65 +Package_QFP +LQFP-32_5x5mm_P0.5mm +LQFP, 32 Pin (https://www.nxp.com/docs/en/package-information/SOT401-1.pdf), generated with kicad-footprint-generator ipc_gullwing_generator.py +LQFP QFP +0 +32 +32 +Package_QFP +LQFP-32_7x7mm_P0.8mm +LQFP, 32 Pin (https://www.nxp.com/docs/en/package-information/SOT358-1.pdf), generated with kicad-footprint-generator ipc_gullwing_generator.py +LQFP QFP +0 +32 +32 +Package_QFP +LQFP-36_7x7mm_P0.65mm +LQFP, 36 Pin (https://www.onsemi.com/pub/Collateral/561AV.PDF), generated with kicad-footprint-generator ipc_gullwing_generator.py +LQFP QFP +0 +36 +36 +Package_QFP +LQFP-44_10x10mm_P0.8mm +LQFP, 44 Pin (https://www.nxp.com/files-static/shared/doc/package_info/98ASS23225W.pdf?&fsrch=1), generated with kicad-footprint-generator ipc_gullwing_generator.py +LQFP QFP +0 +44 +44 +Package_QFP +LQFP-48-1EP_7x7mm_P0.5mm_EP3.6x3.6mm +LQFP, 48 Pin (http://www.analog.com/media/en/technical-documentation/data-sheets/LTC7810.pdf), generated with kicad-footprint-generator ipc_qfp_generator.py +LQFP QFP +0 +58 +49 +Package_QFP +LQFP-48-1EP_7x7mm_P0.5mm_EP3.6x3.6mm_ThermalVias +LQFP, 48 Pin (http://www.analog.com/media/en/technical-documentation/data-sheets/LTC7810.pdf), generated with kicad-footprint-generator ipc_qfp_generator.py +LQFP QFP +0 +75 +49 +Package_QFP +LQFP-48_7x7mm_P0.5mm +LQFP, 48 Pin (https://www.analog.com/media/en/technical-documentation/data-sheets/ltc2358-16.pdf), generated with kicad-footprint-generator ipc_gullwing_generator.py +LQFP QFP +0 +48 +48 +Package_QFP +LQFP-52-1EP_10x10mm_P0.65mm_EP4.8x4.8mm +LQFP, 52 Pin (https://www.onsemi.com/pub/Collateral/848H-01.PDF), generated with kicad-footprint-generator ipc_gullwing_generator.py +LQFP QFP +0 +62 +53 +Package_QFP +LQFP-52-1EP_10x10mm_P0.65mm_EP4.8x4.8mm_ThermalVias +LQFP, 52 Pin (https://www.onsemi.com/pub/Collateral/848H-01.PDF), generated with kicad-footprint-generator ipc_gullwing_generator.py +LQFP QFP +0 +95 +53 +Package_QFP +LQFP-52_10x10mm_P0.65mm +LQFP, 52 Pin (https://www.nxp.com/docs/en/package-information/98ARL10526D.pdf), generated with kicad-footprint-generator ipc_gullwing_generator.py +LQFP QFP +0 +52 +52 +Package_QFP +LQFP-52_14x14mm_P1mm +LQFP, 52 Pin (http://www.holtek.com/documents/10179/116711/HT1632Cv170.pdf), generated with kicad-footprint-generator ipc_gullwing_generator.py +LQFP QFP +0 +52 +52 +Package_QFP +LQFP-64-1EP_10x10mm_P0.5mm_EP6.5x6.5mm +LQFP, 64 Pin (https://www.nxp.com/files-static/shared/doc/package_info/98ARH98426A.pdf), generated with kicad-footprint-generator ipc_gullwing_generator.py +LQFP QFP +0 +90 +65 +Package_QFP +LQFP-64-1EP_10x10mm_P0.5mm_EP6.5x6.5mm_ThermalVias +LQFP, 64 Pin (https://www.nxp.com/files-static/shared/doc/package_info/98ARH98426A.pdf), generated with kicad-footprint-generator ipc_gullwing_generator.py +LQFP QFP +0 +127 +65 +Package_QFP +LQFP-64_7x7mm_P0.4mm +LQFP, 64 Pin (https://www.nxp.com/docs/en/package-information/SOT414-1.pdf), generated with kicad-footprint-generator ipc_gullwing_generator.py +LQFP QFP +0 +64 +64 +Package_QFP +LQFP-64_10x10mm_P0.5mm +LQFP, 64 Pin (https://www.analog.com/media/en/technical-documentation/data-sheets/ad7606_7606-6_7606-4.pdf), generated with kicad-footprint-generator ipc_gullwing_generator.py +LQFP QFP +0 +64 +64 +Package_QFP +LQFP-64_14x14mm_P0.8mm +LQFP, 64 Pin (https://www.nxp.com/docs/en/package-information/SOT791-1.pdf), generated with kicad-footprint-generator ipc_gullwing_generator.py +LQFP QFP +0 +64 +64 +Package_QFP +LQFP-80_10x10mm_P0.4mm +LQFP, 80 Pin (https://www.renesas.com/eu/en/package-image/pdf/outdrawing/q80.10x10.pdf), generated with kicad-footprint-generator ipc_gullwing_generator.py +LQFP QFP +0 +80 +80 +Package_QFP +LQFP-80_12x12mm_P0.5mm +LQFP, 80 Pin (https://www.nxp.com/docs/en/package-information/SOT315-1.pdf), generated with kicad-footprint-generator ipc_gullwing_generator.py +LQFP QFP +0 +80 +80 +Package_QFP +LQFP-80_14x14mm_P0.65mm +LQFP, 80 Pin (https://www.analog.com/media/en/technical-documentation/data-sheets/AD9852.pdf), generated with kicad-footprint-generator ipc_gullwing_generator.py +LQFP QFP +0 +80 +80 +Package_QFP +LQFP-100_14x14mm_P0.5mm +LQFP, 100 Pin (https://www.nxp.com/docs/en/package-information/SOT407-1.pdf), generated with kicad-footprint-generator ipc_gullwing_generator.py +LQFP QFP +0 +100 +100 +Package_QFP +LQFP-128_14x14mm_P0.4mm +LQFP, 128 Pin (https://www.renesas.com/eu/en/package-image/pdf/outdrawing/q128.14x14.pdf), generated with kicad-footprint-generator ipc_gullwing_generator.py +LQFP QFP +0 +128 +128 +Package_QFP +LQFP-128_14x20mm_P0.5mm +LQFP, 128 Pin (https://www.nxp.com/docs/en/package-information/SOT425-1.pdf), generated with kicad-footprint-generator ipc_gullwing_generator.py +LQFP QFP +0 +128 +128 +Package_QFP +LQFP-144_20x20mm_P0.5mm +LQFP, 144 Pin (http://ww1.microchip.com/downloads/en/PackagingSpec/00000049BQ.pdf#page=425), generated with kicad-footprint-generator ipc_gullwing_generator.py +LQFP QFP +0 +144 +144 +Package_QFP +LQFP-160_24x24mm_P0.5mm +LQFP, 160 Pin (https://www.nxp.com/docs/en/package-information/SOT435-1.pdf), generated with kicad-footprint-generator ipc_gullwing_generator.py +LQFP QFP +0 +160 +160 +Package_QFP +LQFP-176_20x20mm_P0.4mm +LQFP, 176 Pin (https://www.onsemi.com/pub/Collateral/566DB.PDF), generated with kicad-footprint-generator ipc_gullwing_generator.py +LQFP QFP +0 +176 +176 +Package_QFP +LQFP-176_24x24mm_P0.5mm +LQFP, 176 Pin (https://www.st.com/resource/en/datasheet/stm32f207vg.pdf#page=163), generated with kicad-footprint-generator ipc_gullwing_generator.py +LQFP QFP +0 +176 +176 +Package_QFP +LQFP-208_28x28mm_P0.5mm +LQFP, 208 Pin (https://www.nxp.com/docs/en/package-information/SOT459-1.pdf), generated with kicad-footprint-generator ipc_gullwing_generator.py +LQFP QFP +0 +208 +208 +Package_QFP +LQFP-216_24x24mm_P0.4mm +LQFP, 216 Pin (https://www.onsemi.com/pub/Collateral/561BE.PDF), generated with kicad-footprint-generator ipc_gullwing_generator.py +LQFP QFP +0 +216 +216 +Package_QFP +MQFP-44_10x10mm_P0.8mm +MQFP, 44 Pin (https://www.analog.com/media/en/technical-documentation/data-sheets/ad7722.pdf), generated with kicad-footprint-generator ipc_gullwing_generator.py +MQFP QFP +0 +44 +44 +Package_QFP +PQFP-44_10x10mm_P0.8mm +44-Lead Plastic Quad Flatpack - 10x10x2.5mm Body (http://www.onsemi.com/pub/Collateral/122BK.PDF) +PQFP 0.8 +0 +44 +44 +Package_QFP +PQFP-80_14x20mm_P0.8mm +PQFP80 14x20 / QIP80E CASE 122BS (see ON Semiconductor 122BS.PDF) +QFP 0.8 +0 +80 +80 +Package_QFP +PQFP-100_14x20mm_P0.65mm +PQFP, 100 Pin (http://www.microsemi.com/index.php?option=com_docman&task=doc_download&gid=131095), generated with kicad-footprint-generator ipc_qfp_generator.py +PQFP QFP +0 +100 +100 +Package_QFP +PQFP-112_20x20mm_P0.65mm +PQFP, 112 pins, 20mm sq body, 0.65mm pitch (http://cache.freescale.com/files/shared/doc/package_info/98ASS23330W.pdf, http://www.nxp.com/docs/en/application-note/AN4388.pdf) +PQFP 112 +0 +112 +112 +Package_QFP +PQFP-132_24x24mm_P0.635mm +PQFP, 132 pins, 24mm sq body, 0.635mm pitch (https://www.intel.com/content/dam/www/public/us/en/documents/packaging-databooks/packaging-chapter-02-databook.pdf, http://www.nxp.com/docs/en/application-note/AN4388.pdf) +PQFP 132 +0 +132 +132 +Package_QFP +PQFP-132_24x24mm_P0.635mm_i386 +PQFP, 132 pins, 24mm sq body, 0.635mm pitch, Intel 386EX (https://www.intel.com/content/dam/www/public/us/en/documents/packaging-databooks/packaging-chapter-02-databook.pdf, http://www.nxp.com/docs/en/application-note/AN4388.pdf) +PQFP 132 Intel 386EX +0 +132 +132 +Package_QFP +PQFP-144_28x28mm_P0.65mm +PQFP, 144 Pin (http://www.microsemi.com/index.php?option=com_docman&task=doc_download&gid=131095), generated with kicad-footprint-generator ipc_qfp_generator.py +PQFP QFP +0 +144 +144 +Package_QFP +PQFP-160_28x28mm_P0.65mm +PQFP, 160 Pin (http://www.microsemi.com/index.php?option=com_docman&task=doc_download&gid=131095), generated with kicad-footprint-generator ipc_qfp_generator.py +PQFP QFP +0 +160 +160 +Package_QFP +PQFP-208_28x28mm_P0.5mm +PQFP, 208 Pin (http://www.microsemi.com/index.php?option=com_docman&task=doc_download&gid=131095), generated with kicad-footprint-generator ipc_qfp_generator.py +PQFP QFP +0 +208 +208 +Package_QFP +PQFP-240_32.1x32.1mm_P0.5mm +PQFP, 240 Pin (http://www.microsemi.com/index.php?option=com_docman&task=doc_download&gid=131095), generated with kicad-footprint-generator ipc_qfp_generator.py +PQFP QFP +0 +240 +240 +Package_QFP +PQFP-256_28x28mm_P0.4mm +PQFP256 28x28 / QFP256J CASE 122BX (see ON Semiconductor 122BX.PDF) +QFP 0.4 +0 +256 +256 +Package_QFP +TQFP-32_7x7mm_P0.8mm +32-Lead Plastic Thin Quad Flatpack (PT) - 7x7x1.0 mm Body, 2.00 mm [TQFP] (see Microchip Packaging Specification 00000049BS.pdf) +QFP 0.8 +0 +32 +32 +Package_QFP +TQFP-44-1EP_10x10mm_P0.8mm_EP4.5x4.5mm +44-Lead Plastic Thin Quad Flatpack (MW) - 10x10x1.0 mm Body [TQFP] With 4.5x4.5 mm Exposed Pad (see Microchip Packaging Specification 00000049BS.pdf) +QFP 0.8 +0 +54 +45 +Package_QFP +TQFP-44_10x10mm_P0.8mm +44-Lead Plastic Thin Quad Flatpack (PT) - 10x10x1.0 mm Body [TQFP] (see Microchip Packaging Specification 00000049BS.pdf) +QFP 0.8 +0 +44 +44 +Package_QFP +TQFP-48-1EP_7x7mm_P0.5mm_EP3.5x3.5mm +48-Lead Thin Quad Flatpack (PT) - 7x7x1.0 mm Body [TQFP] With Exposed Pad (see Microchip Packaging Specification 00000049BS.pdf) +QFP 0.5 +0 +53 +49 +Package_QFP +TQFP-48-1EP_7x7mm_P0.5mm_EP5x5mm +TQFP, 48 Pin (https://www.trinamic.com/fileadmin/assets/Products/ICs_Documents/TMC2100_datasheet_Rev1.08.pdf (page 45)), generated with kicad-footprint-generator ipc_qfp_generator.py +TQFP QFP +0 +65 +49 +Package_QFP +TQFP-48-1EP_7x7mm_P0.5mm_EP5x5mm_ThermalVias +TQFP, 48 Pin (https://www.trinamic.com/fileadmin/assets/Products/ICs_Documents/TMC2100_datasheet_Rev1.08.pdf (page 45)), generated with kicad-footprint-generator ipc_qfp_generator.py +TQFP QFP +0 +91 +49 +Package_QFP +TQFP-48_7x7mm_P0.5mm +48 LEAD TQFP 7x7mm (see MICREL TQFP7x7-48LD-PL-1.pdf) +QFP 0.5 +0 +48 +48 +Package_QFP +TQFP-52-1EP_10x10mm_P0.65mm_EP6.5x6.5mm +TQFP, 52 Pin (http://www.analog.com/media/en/package-pcb-resources/package/pkg_pdf/tqfp_edsv/sv_52_1.pdf), generated with kicad-footprint-generator ipc_qfp_generator.py +TQFP QFP +0 +78 +53 +Package_QFP +TQFP-52-1EP_10x10mm_P0.65mm_EP6.5x6.5mm_ThermalVias +TQFP, 52 Pin (http://www.analog.com/media/en/package-pcb-resources/package/pkg_pdf/tqfp_edsv/sv_52_1.pdf), generated with kicad-footprint-generator ipc_qfp_generator.py +TQFP QFP +0 +79 +53 +Package_QFP +TQFP-64-1EP_10x10mm_P0.5mm_EP8x8mm +64-Lead Plastic Thin Quad Flatpack (PT) - 10x10x1 mm Body, 2.00 mm Footprint [TQFP] thermal pad +QFP 0.5 +0 +90 +65 +Package_QFP +TQFP-64_7x7mm_P0.4mm +TQFP64 7x7, 0.4P CASE 932BH (see ON Semiconductor 932BH.PDF) +QFP 0.4 +0 +64 +64 +Package_QFP +TQFP-64_10x10mm_P0.5mm +TQFP, 64 Pin (http://www.microsemi.com/index.php?option=com_docman&task=doc_download&gid=131095), generated with kicad-footprint-generator ipc_qfp_generator.py +TQFP QFP +0 +64 +64 +Package_QFP +TQFP-64_14x14mm_P0.8mm +64-Lead Plastic Thin Quad Flatpack (PF) - 14x14x1 mm Body, 2.00 mm [TQFP] (see Microchip Packaging Specification 00000049BS.pdf) +QFP 0.8 +0 +64 +64 +Package_QFP +TQFP-80-1EP_14x14mm_P0.65mm_EP9.5x9.5mm +80-Lead Plastic Thin Quad Flatpack (PF) - 14x14mm body, 9.5mm sq thermal pad (http://www.analog.com/media/en/technical-documentation/data-sheets/AD9852.pdf) +QFP 0.65 +0 +85 +81 +Package_QFP +TQFP-80_12x12mm_P0.5mm +80-Lead Plastic Thin Quad Flatpack (PT) - 12x12x1 mm Body, 2.00 mm [TQFP] (see Microchip Packaging Specification 00000049BS.pdf) +QFP 0.5 +0 +80 +80 +Package_QFP +TQFP-80_14x14mm_P0.65mm +80-Lead Plastic Thin Quad Flatpack (PF) - 14x14x1 mm Body, 2.00 mm [TQFP] (see Microchip Packaging Specification 00000049BS.pdf) +QFP 0.65 +0 +80 +80 +Package_QFP +TQFP-100-1EP_14x14mm_P0.5mm_EP5x5mm +100-Lead Plastic Thin Quad Flatpack (PF) - 14x14x1 mm Body 2.00 mm Footprint with Exposed Pad [TQFP] (see Microchip Packaging Specification 00000049BS.pdf) +QFP 0.5 +0 +117 +101 +Package_QFP +TQFP-100_12x12mm_P0.4mm +100-Lead Plastic Thin Quad Flatpack (PT) - 12x12x1 mm Body, 2.00 mm [TQFP] (see Microchip Packaging Specification 00000049BS.pdf) +QFP 0.4 +0 +100 +100 +Package_QFP +TQFP-100_14x14mm_P0.5mm +TQFP, 100 Pin (http://www.microsemi.com/index.php?option=com_docman&task=doc_download&gid=131095), generated with kicad-footprint-generator ipc_qfp_generator.py +TQFP QFP +0 +100 +100 +Package_QFP +TQFP-120_14x14mm_P0.4mm +TQFP120 14x14 / TQFP120 CASE 932AZ (see ON Semiconductor 932AZ.PDF) +QFP 0.4 +0 +120 +120 +Package_QFP +TQFP-128_14x14mm_P0.4mm +TQFP128 14x14 / TQFP128 CASE 932BB (see ON Semiconductor 932BB.PDF) +QFP 0.4 +0 +128 +128 +Package_QFP +TQFP-144_16x16mm_P0.4mm +144-Lead Plastic Thin Quad Flatpack (PH) - 16x16x1 mm Body, 2.00 mm Footprint [TQFP] (see Microchip Packaging Specification 00000049BS.pdf) +QFP 0.4 +0 +144 +144 +Package_QFP +TQFP-144_20x20mm_P0.5mm +TQFP, 144 Pin (http://www.microsemi.com/index.php?option=com_docman&task=doc_download&gid=131095), generated with kicad-footprint-generator ipc_qfp_generator.py +TQFP QFP +0 +144 +144 +Package_QFP +TQFP-176_24x24mm_P0.5mm +TQFP, 176 Pin (http://www.microsemi.com/index.php?option=com_docman&task=doc_download&gid=131095), generated with kicad-footprint-generator ipc_qfp_generator.py +TQFP QFP +0 +176 +176 +Package_QFP +VQFP-80_14x14mm_P0.65mm +VQFP, 80 Pin (http://www.microsemi.com/index.php?option=com_docman&task=doc_download&gid=131095), generated with kicad-footprint-generator ipc_qfp_generator.py +VQFP QFP +0 +80 +80 +Package_QFP +VQFP-100_14x14mm_P0.5mm +VQFP, 100 Pin (http://www.microsemi.com/index.php?option=com_docman&task=doc_download&gid=131095), generated with kicad-footprint-generator ipc_qfp_generator.py +VQFP QFP +0 +100 +100 +Package_QFP +VQFP-128_14x14mm_P0.4mm +VQFP, 128 Pin (http://www.microsemi.com/index.php?option=com_docman&task=doc_download&gid=131095), generated with kicad-footprint-generator ipc_qfp_generator.py +VQFP QFP +0 +128 +128 +Package_QFP +VQFP-176_20x20mm_P0.4mm +VQFP, 176 Pin (http://www.microsemi.com/index.php?option=com_docman&task=doc_download&gid=131095), generated with kicad-footprint-generator ipc_qfp_generator.py +VQFP QFP +0 +176 +176 +Package_SO +Diodes_PSOP-8 +8-Lead Plastic PSOP, Exposed Die Pad (see https://www.diodes.com/assets/Datasheets/AP2204.pdf) +SSOP 0.50 exposed pad +0 +12 +9 +Package_SO +Diodes_SO-8EP +8-Lead Plastic SO, Exposed Die Pad (see https://www.diodes.com/assets/Package-Files/SO-8EP.pdf) +SO exposed pad +0 +9 +9 +Package_SO +ETSSOP-20-1EP_4.4x6.5mm_P0.65mm_EP3x4.2mm +20-Lead Plastic Thin Shrink Small Outline (ST)-4.4 mm Body with Exposed Pad [eTSSOP] (see Microchip Packaging Specification 00000049BS.pdf) +SSOP 0.65 +0 +27 +21 +Package_SO +HSOP-8-1EP_3.9x4.9mm_P1.27mm_EP2.41x3.1mm +HSOP, 8 Pin (https://www.st.com/resource/en/datasheet/l5973d.pdf), generated with kicad-footprint-generator ipc_gullwing_generator.py +HSOP SO +0 +13 +9 +Package_SO +HSOP-8-1EP_3.9x4.9mm_P1.27mm_EP2.41x3.1mm_ThermalVias +HSOP, 8 Pin (https://www.st.com/resource/en/datasheet/l5973d.pdf), generated with kicad-footprint-generator ipc_gullwing_generator.py +HSOP SO +0 +20 +9 +Package_SO +HSOP-20-1EP_11.0x15.9mm_P1.27mm_SlugDown +HSOP 11.0x15.9mm Pitch 1.27mm Slug Down (PowerSO-20) [JEDEC MO-166] (http://www.st.com/resource/en/datasheet/tda7266d.pdf, www.st.com/resource/en/application_note/cd00003801.pdf) +HSOP 11.0 x 15.9mm Pitch 1.27mm +0 +23 +21 +Package_SO +HSOP-20-1EP_11.0x15.9mm_P1.27mm_SlugDown_ThermalVias +HSOP 11.0x15.9mm Pitch 1.27mm Slug Down Thermal Vias (PowerSO-20) [JEDEC MO-166] (http://www.st.com/resource/en/datasheet/tda7266d.pdf, www.st.com/resource/en/application_note/cd00003801.pdf) +HSOP 11.0 x 15.9mm Pitch 1.27mm +0 +45 +21 +Package_SO +HSOP-20-1EP_11.0x15.9mm_P1.27mm_SlugUp +HSOP 11.0x15.9mm Pitch 1.27mm Slug Up (PowerSO-20) [JEDEC MO-166] (http://www.st.com/resource/en/datasheet/tda7266d.pdf, www.st.com/resource/en/application_note/cd00003801.pdf) +HSOP 11.0 x 15.9mm Pitch 1.27mm +0 +20 +20 +Package_SO +HSOP-36-1EP_11.0x15.9mm_P0.65mm_SlugDown +HSOP 11.0x15.9mm Pitch 0.65mm Slug Down (PowerSO-36) [JEDEC MO-166] (http://www.st.com/resource/en/datasheet/vn808cm-32-e.pdf, http://www.st.com/resource/en/application_note/cd00003801.pdf) +HSOP 11.0 x 15.9mm Pitch 0.65mm +0 +39 +37 +Package_SO +HSOP-36-1EP_11.0x15.9mm_P0.65mm_SlugDown_ThermalVias +HSOP 11.0x15.9mm Pitch 0.65mm Slug Down Thermal Vias (PowerSO-36) [JEDEC MO-166] (http://www.st.com/resource/en/datasheet/vn808cm-32-e.pdf, http://www.st.com/resource/en/application_note/cd00003801.pdf) +HSOP 11.0 x 15.9mm Pitch 0.65mm +0 +61 +37 +Package_SO +HSOP-36-1EP_11.0x15.9mm_P0.65mm_SlugUp +HSOP 11.0x15.9mm Pitch 0.65mm Slug Up (PowerSO-36) [JEDEC MO-166] (http://www.st.com/resource/en/datasheet/vn808cm-32-e.pdf, http://www.st.com/resource/en/application_note/cd00003801.pdf) +HSOP 11.0 x 15.9mm Pitch 0.65mm +0 +36 +36 +Package_SO +HTSOP-8-1EP_3.9x4.9mm_P1.27mm_EP2.4x3.2mm +HTSOP, 8 Pin (https://media.digikey.com/pdf/Data%20Sheets/Rohm%20PDFs/BD9G341EFJ.pdf), generated with kicad-footprint-generator ipc_gullwing_generator.py +HTSOP SO +0 +13 +9 +Package_SO +HTSOP-8-1EP_3.9x4.9mm_P1.27mm_EP2.4x3.2mm_ThermalVias +HTSOP, 8 Pin (https://media.digikey.com/pdf/Data%20Sheets/Rohm%20PDFs/BD9G341EFJ.pdf), generated with kicad-footprint-generator ipc_gullwing_generator.py +HTSOP SO +0 +20 +9 +Package_SO +HTSSOP-16-1EP_4.4x5mm_P0.65mm_EP3.4x5mm +16-Lead Plastic HTSSOP (4.4x5x1.2mm); Thermal pad; (http://www.ti.com/lit/ds/symlink/drv8833.pdf) +SSOP 0.65 +0 +29 +17 +Package_SO +HTSSOP-16-1EP_4.4x5mm_P0.65mm_EP3.4x5mm_Mask2.46x2.31mm_ThermalVias +16-Lead Plastic HTSSOP (4.4x5x1.2mm); Thermal pad with vias; (http://www.ti.com/lit/ds/symlink/drv8833.pdf) +SSOP 0.65 +0 +27 +17 +Package_SO +HTSSOP-16-1EP_4.4x5mm_P0.65mm_EP3.4x5mm_Mask3x3mm_ThermalVias +16-Lead Plastic HTSSOP (4.4x5x1.2mm); Thermal pad with vias; (http://www.ti.com/lit/ds/symlink/drv8800.pdf) +SSOP 0.65 +0 +46 +17 +Package_SO +HTSSOP-16-1EP_4.4x5mm_P0.65mm_EP3x3mm +HTSSOP, 16 Pin (https://www.st.com/resource/en/datasheet/stp08cp05.pdf#page=20), generated with kicad-footprint-generator ipc_gullwing_generator.py +HTSSOP SO +0 +21 +17 +Package_SO +HTSSOP-20-1EP_4.4x6.5mm_P0.65mm_EP3.4x6.5mm +20-Lead Plastic Thin Shrink Small Outline (ST)-4.4 mm Body [HTSSOP], with thermal pad with vias +HTSSOP 0.65 +0 +29 +21 +Package_SO +HTSSOP-20-1EP_4.4x6.5mm_P0.65mm_EP3.4x6.5mm_Mask2.4x3.7mm +HTSSOP, 20 Pin (http://www.ti.com/lit/ds/symlink/bq24006.pdf), generated with kicad-footprint-generator ipc_gullwing_generator.py +HTSSOP SO +0 +24 +21 +Package_SO +HTSSOP-20-1EP_4.4x6.5mm_P0.65mm_EP3.4x6.5mm_Mask2.75x3.43mm +HTSSOP, 20 Pin (http://www.ti.com/lit/ds/symlink/tlc5971.pdf#page=37&zoom=160,-90,3), generated with kicad-footprint-generator ipc_gullwing_generator.py +HTSSOP SO +0 +26 +21 +Package_SO +HTSSOP-20-1EP_4.4x6.5mm_P0.65mm_EP3.4x6.5mm_Mask2.75x3.43mm_ThermalVias +HTSSOP, 20 Pin (http://www.ti.com/lit/ds/symlink/tlc5971.pdf#page=37&zoom=160,-90,3), generated with kicad-footprint-generator ipc_gullwing_generator.py +HTSSOP SO +0 +42 +21 +Package_SO +HTSSOP-20-1EP_4.4x6.5mm_P0.65mm_EP3.4x6.5mm_Mask2.75x3.43mm_ThermalVias_HandSolder +HTSSOP, 20 Pin (http://www.ti.com/lit/ds/symlink/tlc5971.pdf#page=37&zoom=160,-90,3), generated with kicad-footprint-generator ipc_gullwing_generator.py +HTSSOP SO +0 +42 +21 +Package_SO +HTSSOP-20-1EP_4.4x6.5mm_P0.65mm_EP3.4x6.5mm_ThermalVias +20-Lead Plastic Thin Shrink Small Outline (ST)-4.4 mm Body [HTSSOP], with thermal pad with vias +HTSSOP 0.65 +0 +45 +21 +Package_SO +HTSSOP-24-1EP_4.4x7.8mm_P0.65mm_EP3.2x5mm +HTSSOP, 24 Pin (https://www.st.com/resource/en/datasheet/stp16cp05.pdf#page=25), generated with kicad-footprint-generator ipc_gullwing_generator.py +HTSSOP SO +0 +31 +25 +Package_SO +HTSSOP-24-1EP_4.4x7.8mm_P0.65mm_EP3.4x7.8mm_Mask2.4x4.68mm +HTSSOP, 24 Pin (http://www.ti.com/lit/ds/symlink/tps703.pdf), generated with kicad-footprint-generator ipc_gullwing_generator.py +HTSSOP SO +0 +28 +25 +Package_SO +HTSSOP-24-1EP_4.4x7.8mm_P0.65mm_EP3.4x7.8mm_Mask2.4x4.68mm_ThermalVias +HTSSOP, 24 Pin (http://www.ti.com/lit/ds/symlink/tps703.pdf), generated with kicad-footprint-generator ipc_gullwing_generator.py +HTSSOP SO +0 +47 +25 +Package_SO +HTSSOP-28-1EP_4.4x9.7mm_P0.65mm_EP3.4x9.5mm +HTSSOP28: plastic thin shrink small outline package; 28 leads; body width 4.4 mm; thermal pad +TSSOP HTSSOP 0.65 thermal pad +0 +39 +29 +Package_SO +HTSSOP-28-1EP_4.4x9.7mm_P0.65mm_EP3.4x9.5mm_Mask2.4x6.17mm +HTSSOP28: plastic thin shrink small outline package; 28 leads; body width 4.4 mm; thermal pad +TSSOP HTSSOP 0.65 thermal pad +0 +40 +29 +Package_SO +HTSSOP-28-1EP_4.4x9.7mm_P0.65mm_EP3.4x9.5mm_Mask2.4x6.17mm_ThermalVias +HTSSOP28: plastic thin shrink small outline package; 28 leads; body width 4.4 mm; thermal pad +TSSOP HTSSOP 0.65 thermal pad +0 +55 +29 +Package_SO +HTSSOP-28-1EP_4.4x9.7mm_P0.65mm_EP3.4x9.5mm_ThermalVias +HTSSOP28: plastic thin shrink small outline package; 28 leads; body width 4.4 mm; thermal pad +TSSOP HTSSOP 0.65 thermal pad +0 +58 +29 +Package_SO +HTSSOP-32-1EP_6.1x11mm_P0.65mm_EP5.2x11mm_Mask4.11x4.36mm +HTSSOP32: plastic thin shrink small outline package; 32 leads; body width 6.1 mm; lead pitch 0.65 mm (see NXP SSOP-TSSOP-VSO-REFLOW.pdf and sot487-1_po.pdf) +SSOP 0.65 PowerPAD +0 +43 +33 +Package_SO +HTSSOP-32-1EP_6.1x11mm_P0.65mm_EP5.2x11mm_Mask4.11x4.36mm_ThermalVias +HTSSOP32: plastic thin shrink small outline package; 32 leads; body width 6.1 mm; lead pitch 0.65 mm (see NXP SSOP-TSSOP-VSO-REFLOW.pdf and sot487-1_po.pdf) +SSOP 0.65 PowerPAD +0 +83 +33 +Package_SO +HTSSOP-38-1EP_6.1x12.5mm_P0.65mm_EP5.2x12.5mm_Mask3.39x6.35mm +HTSSOP, 38 Pin (http://www.ti.com/lit/ds/symlink/tlc5951.pdf#page=47&zoom=140,-67,15), generated with kicad-footprint-generator ipc_gullwing_generator.py +HTSSOP SO +0 +46 +39 +Package_SO +HTSSOP-38-1EP_6.1x12.5mm_P0.65mm_EP5.2x12.5mm_Mask3.39x6.35mm_ThermalVias +HTSSOP, 38 Pin (http://www.ti.com/lit/ds/symlink/tlc5951.pdf#page=47&zoom=140,-67,15), generated with kicad-footprint-generator ipc_gullwing_generator.py +HTSSOP SO +0 +87 +39 +Package_SO +HTSSOP-56-1EP_6.1x14mm_P0.5mm_EP3.61x6.35mm +HTSSOP56: plastic thin shrink small outline package http://www.ti.com/lit/ds/symlink/drv8301.pdf +HTSSOP 0.5 +0 +72 +57 +Package_SO +Infineon_PG-DSO-8-43 +Infineon_PG-DSO-8-43 +DSO DSO-8 SOIC SOIC-8 +0 +12 +9 +Package_SO +Infineon_PG-DSO-12-9 +Infineon PG-DSO 12 pin, exposed pad: 4.5x8.1mm, with thermal vias (https://www.infineon.com/cms/en/product/packages/PG-DSO/PG-DSO-12-9/) +PG-DSO +0 +23 +13 +Package_SO +Infineon_PG-DSO-12-9_ThermalVias +Infineon PG-DSO 12 pin, exposed pad: 4.5x8.1mm, with thermal vias (https://www.infineon.com/cms/en/product/packages/PG-DSO/PG-DSO-12-9/) +PG-DSO +0 +42 +13 +Package_SO +Infineon_PG-DSO-12-11 +Infineon PG-DSO 12 pin, exposed pad: 4.5x8.1mm, with thermal vias (https://www.infineon.com/cms/en/product/packages/PG-DSO/PG-DSO-12-11/) +PG-DSO +0 +23 +13 +Package_SO +Infineon_PG-DSO-12-11_ThermalVias +Infineon PG-DSO 12 pin, exposed pad: 4.5x8.1mm, with thermal vias (https://www.infineon.com/cms/en/product/packages/PG-DSO/PG-DSO-12-11/) +PG-DSO +0 +42 +13 +Package_SO +Infineon_PG-DSO-20-30 +Infineon SO package 20pin, exposed pad 4.5x7mm (https://www.infineon.com/cms/en/product/packages/PG-DSO/PG-DSO-20-71/) +DSO-20 +0 +31 +21 +Package_SO +Infineon_PG-DSO-20-30_ThermalVias +Infineon SO package 20pin, exposed pad 4.5x7mm (https://www.infineon.com/cms/en/product/packages/PG-DSO/PG-DSO-20-71/) +DSO-20 +0 +45 +21 +Package_SO +Infineon_PG-DSO-20-32 +Infineon SO package 20pin without exposed pad (https://www.infineon.com/cms/en/product/packages/PG-DSO/PG-DSO-20-32/) +DSO-20 +0 +20 +20 +Package_SO +Infineon_PG-TSDSO-14-22 +Infineon_PG-TSDSO-14-22 +Infineon TSDSO 14-22 +0 +17 +15 +Package_SO +Linear_MSOP-12-16-1EP_3x4mm_P0.5mm +12-Lead Plastic Micro Small Outline Package (MS) [MSOP], variant of MSOP-16 (see http://cds.linear.com/docs/en/datasheet/3630fd.pdf) +SSOP 0.5 +0 +15 +13 +Package_SO +Linear_MSOP-12-16_3x4mm_P0.5mm +12-Lead Plastic Micro Small Outline Package (MS) [MSOP], variant of MSOP-16 (see https://www.analog.com/media/en/technical-documentation/data-sheets/3748fb.pdf) +SSOP 0.5 +0 +12 +12 +Package_SO +MFSOP6-4_4.4x3.6mm_P1.27mm +https://toshiba.semicon-storage.com/ap-en/design-support/package/detail.4pin%20MFSOP6.html +MFSOP 4 pin SMD +0 +4 +4 +Package_SO +MFSOP6-5_4.4x3.6mm_P1.27mm +https://toshiba.semicon-storage.com/ap-en/design-support/package/detail.5pin%20MFSOP6.html +MFSOP 4 pin SMD +0 +5 +5 +Package_SO +MSOP-8-1EP_3x3mm_P0.65mm_EP1.68x1.88mm +MS8E Package; 8-Lead Plastic MSOP, Exposed Die Pad (see Linear Technology 05081662_K_MS8E.pdf) +SSOP 0.65 +0 +13 +9 +Package_SO +MSOP-8-1EP_3x3mm_P0.65mm_EP1.73x1.85mm +MSOP, 8 Pin (http://www.ti.com/lit/ds/symlink/lm25085.pdf#page=32), generated with kicad-footprint-generator ipc_gullwing_generator.py +MSOP SO +0 +13 +9 +Package_SO +MSOP-8-1EP_3x3mm_P0.65mm_EP1.73x1.85mm_ThermalVias +MSOP, 8 Pin (http://www.ti.com/lit/ds/symlink/lm25085.pdf#page=32), generated with kicad-footprint-generator ipc_gullwing_generator.py +MSOP SO +0 +18 +9 +Package_SO +MSOP-8-1EP_3x3mm_P0.65mm_EP1.95x2.15mm +MSOP, 8 Pin (http://www.st.com/resource/en/datasheet/pm8834.pdf), generated with kicad-footprint-generator ipc_gullwing_generator.py +MSOP SO +0 +13 +9 +Package_SO +MSOP-8-1EP_3x3mm_P0.65mm_EP1.95x2.15mm_ThermalVias +MSOP, 8 Pin (http://www.st.com/resource/en/datasheet/pm8834.pdf), generated with kicad-footprint-generator ipc_gullwing_generator.py +MSOP SO +0 +18 +9 +Package_SO +MSOP-8-1EP_3x3mm_P0.65mm_EP2.5x3mm_Mask1.73x2.36mm +MSOP, 8 Pin (http://ww1.microchip.com/downloads/en/DeviceDoc/mic5355_6.pdf#page=15), generated with kicad-footprint-generator ipc_gullwing_generator.py +MSOP SO +0 +14 +9 +Package_SO +MSOP-8-1EP_3x3mm_P0.65mm_EP2.5x3mm_Mask1.73x2.36mm_ThermalVias +MSOP, 8 Pin (http://ww1.microchip.com/downloads/en/DeviceDoc/mic5355_6.pdf#page=15), generated with kicad-footprint-generator ipc_gullwing_generator.py +MSOP SO +0 +19 +9 +Package_SO +MSOP-8_3x3mm_P0.65mm +8-Lead Plastic Micro Small Outline Package (MS) [MSOP] (see Microchip Packaging Specification 00000049BS.pdf) +SSOP 0.65 +0 +8 +8 +Package_SO +MSOP-10-1EP_3x3mm_P0.5mm_EP1.68x1.88mm +MSOP, 10 Pin (https://www.analog.com/media/en/technical-documentation/data-sheets/3805fg.pdf#page=18), generated with kicad-footprint-generator ipc_gullwing_generator.py +MSOP SO +0 +15 +11 +Package_SO +MSOP-10-1EP_3x3mm_P0.5mm_EP1.68x1.88mm_ThermalVias +MSOP, 10 Pin (https://www.analog.com/media/en/technical-documentation/data-sheets/3805fg.pdf#page=18), generated with kicad-footprint-generator ipc_gullwing_generator.py +MSOP SO +0 +20 +11 +Package_SO +MSOP-10-1EP_3x3mm_P0.5mm_EP1.73x1.98mm +MSOP, 10 Pin (www.allegromicro.com/~/media/Files/Datasheets/A4952-3-Datasheet.ashx?la=en#page=10), generated with kicad-footprint-generator ipc_gullwing_generator.py +MSOP SO +0 +15 +11 +Package_SO +MSOP-10-1EP_3x3mm_P0.5mm_EP1.73x1.98mm_ThermalVias +MSOP, 10 Pin (www.allegromicro.com/~/media/Files/Datasheets/A4952-3-Datasheet.ashx?la=en#page=10), generated with kicad-footprint-generator ipc_gullwing_generator.py +MSOP SO +0 +20 +11 +Package_SO +MSOP-10_3x3mm_P0.5mm +10-Lead Plastic Micro Small Outline Package (MS) [MSOP] (see Microchip Packaging Specification 00000049BS.pdf) +SSOP 0.5 +0 +10 +10 +Package_SO +MSOP-12-1EP_3x4mm_P0.65mm_EP1.65x2.85mm +MSOP, 12 Pin (https://www.analog.com/media/en/technical-documentation/data-sheets/3652fe.pdf#page=24), generated with kicad-footprint-generator ipc_gullwing_generator.py +MSOP SO +0 +17 +13 +Package_SO +MSOP-12-1EP_3x4mm_P0.65mm_EP1.65x2.85mm_ThermalVias +MSOP, 12 Pin (https://www.analog.com/media/en/technical-documentation/data-sheets/3652fe.pdf#page=24), generated with kicad-footprint-generator ipc_gullwing_generator.py +MSOP SO +0 +24 +13 +Package_SO +MSOP-12-16-1EP_3x4mm_P0.5mm_EP1.65x2.85mm +10-Lead Plastic Micro Small Outline Package (MS) [MSOP] (see Microchip Packaging Specification 00000049BS.pdf) +SSOP 0.5 +0 +19 +13 +Package_SO +MSOP-12-16-1EP_3x4mm_P0.5mm_EP1.65x2.85mm_ThermalVias +10-Lead Plastic Micro Small Outline Package (MS) [MSOP] (see Microchip Packaging Specification 00000049BS.pdf) +SSOP 0.5 +0 +25 +13 +Package_SO +MSOP-12-16_3x4mm_P0.5mm +10-Lead Plastic Micro Small Outline Package (MS) [MSOP] (see Microchip Packaging Specification 00000049BS.pdf) +SSOP 0.5 +0 +12 +12 +Package_SO +MSOP-12_3x4mm_P0.65mm +MSOP, 12 Pin (https://www.analog.com/media/en/technical-documentation/data-sheets/6957fb.pdf#page=36), generated with kicad-footprint-generator ipc_gullwing_generator.py +MSOP SO +0 +12 +12 +Package_SO +MSOP-16-1EP_3x4mm_P0.5mm_EP1.65x2.85mm +MSOP, 16 Pin (http://cds.linear.com/docs/en/datasheet/37551fd.pdf#page=23), generated with kicad-footprint-generator ipc_gullwing_generator.py +MSOP SO +0 +21 +17 +Package_SO +MSOP-16-1EP_3x4mm_P0.5mm_EP1.65x2.85mm_ThermalVias +MSOP, 16 Pin (http://cds.linear.com/docs/en/datasheet/37551fd.pdf#page=23), generated with kicad-footprint-generator ipc_gullwing_generator.py +MSOP SO +0 +28 +17 +Package_SO +MSOP-16_3x4mm_P0.5mm +MSOP, 16 Pin (https://www.analog.com/media/en/technical-documentation/data-sheets/436412f.pdf#page=22), generated with kicad-footprint-generator ipc_gullwing_generator.py +MSOP SO +0 +16 +16 +Package_SO +OnSemi_Micro8 +ON Semiconductor Micro8 (Case846A-02): https://www.onsemi.com/pub/Collateral/846A-02.PDF +micro8 +0 +8 +8 +Package_SO +PowerIntegrations_eSOP-12B +eSOP-12B SMT Flat Package with Heatsink Tab, see https://ac-dc.power.com/sites/default/files/product-docs/topswitch-jx_family_datasheet.pdf +Power Integrations K Package +0 +12 +12 +Package_SO +PowerIntegrations_SO-8 +Power-Integrations variant of 8-Lead Plastic Small Outline (SN) - Narrow, 3.90 mm Body [SOIC], see https://ac-dc.power.com/sites/default/files/product-docs/senzero_family_datasheet.pdf +SOIC 1.27 +0 +8 +8 +Package_SO +PowerIntegrations_SO-8B +Power-Integrations variant of 8-Lead Plastic Small Outline (SN) - Narrow, 3.90 mm Body [SOIC], see https://www.mouser.com/ds/2/328/linkswitch-pl_family_datasheet-12517.pdf +SOIC 1.27 +0 +7 +7 +Package_SO +PowerIntegrations_SO-8C +Power-Integrations variant of 8-Lead Plastic Small Outline (SN) - Narrow, 3.90 mm Body [SOIC], see https://www.mouser.com/ds/2/328/linkswitch-pl_family_datasheet-12517.pdf +SOIC 1.27 +0 +7 +7 +Package_SO +PowerPAK_SO-8_Dual +PowerPAK SO-8 Dual (https://www.vishay.com/docs/71655/powerpak.pdf, https://www.vishay.com/docs/72600/72600.pdf) +PowerPAK SO-8 Dual +0 +10 +6 +Package_SO +PowerPAK_SO-8_Single +PowerPAK SO-8 Single (https://www.vishay.com/docs/71655/powerpak.pdf, https://www.vishay.com/docs/72599/72599.pdf) +PowerPAK SO-8 Single +0 +9 +5 +Package_SO +PSOP-44_16.9x27.17mm_P1.27mm +PSOP44: plastic thin shrink small outline package; 44 leads; body width 16.90 mm +PSOP 1.27 +0 +44 +44 +Package_SO +QSOP-16_3.9x4.9mm_P0.635mm +16-Lead Plastic Shrink Small Outline Narrow Body (QR)-.150" Body [QSOP] (see Microchip Packaging Specification 00000049BS.pdf) +SSOP 0.635 +0 +16 +16 +Package_SO +QSOP-20_3.9x8.7mm_P0.635mm +20-Lead Plastic Shrink Small Outline Narrow Body (http://www.analog.com/media/en/technical-documentation/data-sheets/ADuM7640_7641_7642_7643.pdf) +QSOP 0.635 +0 +20 +20 +Package_SO +QSOP-24_3.9x8.7mm_P0.635mm +24-Lead Plastic Shrink Small Outline Narrow Body (QR)-.150" Body [QSOP] (see Microchip Packaging Specification 00000049CH.pdf) +QSOP 0.635 +0 +24 +24 +Package_SO +SO-4_4.4x2.3mm_P1.27mm +4-Lead Plastic Small Outline (SO), see http://datasheet.octopart.com/OPIA403BTRE-Optek-datasheet-5328560.pdf +SO SOIC 1.27 +0 +4 +4 +Package_SO +SO-4_4.4x3.6mm_P2.54mm +4-Lead Plastic Small Outline (SO), see https://www.elpro.org/de/index.php?controller=attachment&id_attachment=339 +SO SOIC 2.54 +0 +4 +4 +Package_SO +SO-4_4.4x4.3mm_P2.54mm +4-Lead Plastic Small Outline (SO), see https://docs.broadcom.com/docs/AV02-0173EN +SO SOIC 2.54 +0 +4 +4 +Package_SO +SO-4_7.6x3.6mm_P2.54mm +4-Lead Plastic Small Outline (SO) (http://www.everlight.com/file/ProductFile/201407061745083848.pdf) +SO SOIC 2.54 +0 +4 +4 +Package_SO +SO-5_4.4x3.6mm_P1.27mm +5-Lead Plastic Small Outline (SO), see https://docs.broadcom.com/cs/Satellite?blobcol=urldata&blobheader=application%2Fpdf&blobheadername1=Content-Disposition&blobheadername2=Content-Type&blobheadername3=MDT-Type&blobheadervalue1=attachment%3Bfilename%3DIPD-Selection-Guide_AV00-0254EN_030617.pdf&blobheadervalue2=application%2Fx-download&blobheadervalue3=abinary%253B%2Bcharset%253DUTF-8&blobkey=id&blobnocache=true&blobtable=MungoBlobs&blobwhere=1430884105675&ssbinary=true +SO SOIC 1.27 +0 +5 +5 +Package_SO +SO-6L_10x3.84mm_P1.27mm +6-pin plasic small outline 7,5mm long https://toshiba.semicon-storage.com/info/docget.jsp?did=53548&prodName=TLP2770 +SO-6L +0 +6 +6 +Package_SO +SO-6_4.4x3.6mm_P1.27mm +6-Lead Plastic Small Outline (SO), see https://docs.broadcom.com/cs/Satellite?blobcol=urldata&blobheader=application%2Fpdf&blobheadername1=Content-Disposition&blobheadername2=Content-Type&blobheadername3=MDT-Type&blobheadervalue1=attachment%3Bfilename%3DIPD-Selection-Guide_AV00-0254EN_030617.pdf&blobheadervalue2=application%2Fx-download&blobheadervalue3=abinary%253B%2Bcharset%253DUTF-8&blobkey=id&blobnocache=true&blobtable=MungoBlobs&blobwhere=1430884105675&ssbinary=true +SO SOIC 1.27 +0 +6 +6 +Package_SO +SO-8_3.9x4.9mm_P1.27mm +SO, 8 Pin (https://www.nxp.com/docs/en/data-sheet/PCF8523.pdf), generated with kicad-footprint-generator ipc_gullwing_generator.py +SO SO +0 +8 +8 +Package_SO +SO-8_5.3x6.2mm_P1.27mm +8-Lead Plastic Small Outline, 5.3x6.2mm Body (http://www.ti.com.cn/cn/lit/ds/symlink/tl7705a.pdf) +SOIC 1.27 +0 +8 +8 +Package_SO +SO-20_12.8x7.5mm_P1.27mm +SO-20, 12.8x7.5mm, https://www.nxp.com/docs/en/data-sheet/SA605.pdf +S0-20 +0 +20 +20 +Package_SO +SOIC-4_4.55x2.6mm_P1.27mm +SOIC, 4 Pin (https://toshiba.semicon-storage.com/info/docget.jsp?did=12884&prodName=TLP291), generated with kicad-footprint-generator ipc_gullwing_generator.py +SOIC SO +0 +4 +4 +Package_SO +SOIC-4_4.55x3.7mm_P2.54mm +SOIC, 6 Pin (https://toshiba.semicon-storage.com/info/docget.jsp?did=11791&prodName=TLP185), generated with kicad-footprint-generator ipc_gullwing_generator.py +SOIC SO +0 +4 +4 +Package_SO +SOIC-8-1EP_3.9x4.9mm_P1.27mm_EP2.29x3mm +SOIC, 8 Pin (https://www.analog.com/media/en/technical-documentation/data-sheets/ada4898-1_4898-2.pdf#page=29), generated with kicad-footprint-generator ipc_gullwing_generator.py +SOIC SO +0 +13 +9 +Package_SO +SOIC-8-1EP_3.9x4.9mm_P1.27mm_EP2.29x3mm_ThermalVias +SOIC, 8 Pin (https://www.analog.com/media/en/technical-documentation/data-sheets/ada4898-1_4898-2.pdf#page=29), generated with kicad-footprint-generator ipc_gullwing_generator.py +SOIC SO +0 +20 +9 +Package_SO +SOIC-8-1EP_3.9x4.9mm_P1.27mm_EP2.41x3.3mm +SOIC, 8 Pin (http://www.allegromicro.com/~/media/Files/Datasheets/A4950-Datasheet.ashx#page=8), generated with kicad-footprint-generator ipc_gullwing_generator.py +SOIC SO +0 +13 +9 +Package_SO +SOIC-8-1EP_3.9x4.9mm_P1.27mm_EP2.41x3.3mm_ThermalVias +SOIC, 8 Pin (http://www.allegromicro.com/~/media/Files/Datasheets/A4950-Datasheet.ashx#page=8), generated with kicad-footprint-generator ipc_gullwing_generator.py +SOIC SO +0 +20 +9 +Package_SO +SOIC-8-1EP_3.9x4.9mm_P1.27mm_EP2.41x3.81mm +SOIC, 8 Pin (https://www.analog.com/media/en/technical-documentation/data-sheets/ada4898-1_4898-2.pdf#page=29), generated with kicad-footprint-generator ipc_gullwing_generator.py +SOIC SO +0 +13 +9 +Package_SO +SOIC-8-1EP_3.9x4.9mm_P1.27mm_EP2.41x3.81mm_ThermalVias +SOIC, 8 Pin (https://www.analog.com/media/en/technical-documentation/data-sheets/ada4898-1_4898-2.pdf#page=29), generated with kicad-footprint-generator ipc_gullwing_generator.py +SOIC SO +0 +20 +9 +Package_SO +SOIC-8-1EP_3.9x4.9mm_P1.27mm_EP2.95x4.9mm_Mask2.71x3.4mm +SOIC, 8 Pin (http://www.ti.com/lit/ds/symlink/lm5017.pdf#page=31), generated with kicad-footprint-generator ipc_gullwing_generator.py +SOIC SO +0 +14 +9 +Package_SO +SOIC-8-1EP_3.9x4.9mm_P1.27mm_EP2.95x4.9mm_Mask2.71x3.4mm_ThermalVias +SOIC, 8 Pin (http://www.ti.com/lit/ds/symlink/lm5017.pdf#page=31), generated with kicad-footprint-generator ipc_gullwing_generator.py +SOIC SO +0 +23 +9 +Package_SO +SOIC-8-1EP_3.9x4.9mm_P1.27mm_EP2.514x3.2mm +SOIC, 8 Pin (https://www.renesas.com/eu/en/www/doc/datasheet/hip2100.pdf#page=13), generated with kicad-footprint-generator ipc_gullwing_generator.py +SOIC SO +0 +13 +9 +Package_SO +SOIC-8-1EP_3.9x4.9mm_P1.27mm_EP2.514x3.2mm_ThermalVias +SOIC, 8 Pin (https://www.renesas.com/eu/en/www/doc/datasheet/hip2100.pdf#page=13), generated with kicad-footprint-generator ipc_gullwing_generator.py +SOIC SO +0 +20 +9 +Package_SO +SOIC-8-N7_3.9x4.9mm_P1.27mm +8-Lead Plastic Small Outline (SN) - Narrow, 3.90 mm Body [SOIC], pin 7 removed (Microchip Packaging Specification 00000049BS.pdf, http://www.onsemi.com/pub/Collateral/NCP1207B.PDF) +SOIC 1.27 +0 +7 +7 +Package_SO +SOIC-8_3.9x4.9mm_P1.27mm +8-Lead Plastic Small Outline (SN) - Narrow, 3.90 mm Body [SOIC] (see Microchip Packaging Specification http://ww1.microchip.com/downloads/en/PackagingSpec/00000049BQ.pdf) +SOIC 1.27 +0 +8 +8 +Package_SO +SOIC-14W_7.5x9.0mm_P1.27mm +14-Lead Plastic Small Outline (SO) - Wide, 7.50 mm Body (http://www.ti.com/lit/ds/symlink/lm1877.pdf) +SOIC 1.27 +0 +14 +14 +Package_SO +SOIC-14_3.9x8.7mm_P1.27mm +14-Lead Plastic Small Outline (SL) - Narrow, 3.90 mm Body [SOIC] (see Microchip Packaging Specification 00000049BS.pdf) +SOIC 1.27 +0 +14 +14 +Package_SO +SOIC-16W-12_7.5x10.3mm_P1.27mm +SOIC-16 With 12 Pin Placed - Wide, 7.50 mm Body [SOIC] (https://docs.broadcom.com/docs/AV02-0169EN) +SOIC 1.27 16 12 Wide +0 +12 +12 +Package_SO +SOIC-16W_5.3x10.2mm_P1.27mm +16-Lead Plastic Small Outline (SO) - Wide, 5.3 mm Body (http://www.ti.com/lit/ml/msop002a/msop002a.pdf) +SOIC 1.27 +0 +16 +16 +Package_SO +SOIC-16W_7.5x10.3mm_P1.27mm +16-Lead Plastic Small Outline (SO) - Wide, 7.50 mm Body [SOIC] (see Microchip Packaging Specification 00000049BS.pdf) +SOIC 1.27 +0 +16 +16 +Package_SO +SOIC-16W_7.5x12.8mm_P1.27mm +16-Lead Plastic Small Outline (SO) - Wide, 7.50 mm x 12.8 mm Body (http://www.analog.com/media/en/technical-documentation/data-sheets/ADuM6000.PDF) +SOIC 1.27 +0 +16 +16 +Package_SO +SOIC-16_3.9x9.9mm_P1.27mm +16-Lead Plastic Small Outline (SL) - Narrow, 3.90 mm Body [SOIC] (see Microchip Packaging Specification 00000049BS.pdf) +SOIC 1.27 +0 +16 +16 +Package_SO +SOIC-16_4.55x10.3mm_P1.27mm +SOIC, 16 Pin (https://toshiba.semicon-storage.com/info/docget.jsp?did=12858&prodName=TLP291-4), generated with kicad-footprint-generator ipc_gullwing_generator.py +SOIC SO +0 +16 +16 +Package_SO +SOIC-18W_7.5x11.6mm_P1.27mm +18-Lead Plastic Small Outline (SO) - Wide, 7.50 mm Body [SOIC] (see Microchip Packaging Specification 00000049BS.pdf) +SOIC 1.27 +0 +18 +18 +Package_SO +SOIC-20W_7.5x12.8mm_P1.27mm +20-Lead Plastic Small Outline (SO) - Wide, 7.50 mm Body [SOIC] (see Microchip Packaging Specification 00000049BS.pdf) +SOIC 1.27 +0 +20 +20 +Package_SO +SOIC-24W_7.5x15.4mm_P1.27mm +24-Lead Plastic Small Outline (SO) - Wide, 7.50 mm Body [SOIC] (see Microchip Packaging Specification 00000049BS.pdf) +SOIC 1.27 +0 +24 +24 +Package_SO +SOIC-28W_7.5x17.9mm_P1.27mm +28-Lead Plastic Small Outline (SO) - Wide, 7.50 mm Body [SOIC] (see Microchip Packaging Specification 00000049BS.pdf) +SOIC 1.27 +0 +28 +28 +Package_SO +SOIC-28W_7.5x18.7mm_P1.27mm +28-Lead Plastic Small Outline (SO) - Wide, 7.50 mm X 18.7 mm Body [SOIC] (https://www.akm.com/akm/en/file/datasheet/AK5394AVS.pdf) +SOIC 1.27 +0 +28 +28 +Package_SO +SOIJ-8_5.3x5.3mm_P1.27mm +8-Lead Plastic Small Outline (SM) - Medium, 5.28 mm Body [SOIC] (see Microchip Packaging Specification 00000049BS.pdf) +SOIC 1.27 +0 +8 +8 +Package_SO +SOJ-36_10.16x23.49mm_P1.27mm +SOJ, 36 Pin (http://www.issi.com/WW/pdf/61-64C5128AL.pdf), generated with kicad-footprint-generator ipc_gullwing_generator.py +SOJ SO +0 +36 +36 +Package_SO +SOP-4_3.8x4.1mm_P2.54mm +SOP, 4 Pin (http://www.ixysic.com/home/pdfs.nsf/www/CPC1017N.pdf/$file/CPC1017N.pdf), generated with kicad-footprint-generator ipc_gullwing_generator.py +SOP SO +0 +4 +4 +Package_SO +SOP-4_4.4x2.6mm_P1.27mm +SOP, 4 Pin (http://www.vishay.com/docs/83510/tcmt1100.pdf), generated with kicad-footprint-generator ipc_gullwing_generator.py +SOP SO +0 +4 +4 +Package_SO +SOP-8_3.76x4.96mm_P1.27mm +SOP, 8 Pin (https://ww2.minicircuits.com/case_style/XX211.pdf), generated with kicad-footprint-generator ipc_gullwing_generator.py +SOP SO +0 +8 +8 +Package_SO +SOP-8_6.62x9.15mm_P2.54mm +SOP, 8 Pin (http://www.ti.com/lit/ds/symlink/iso1050.pdf), generated with kicad-footprint-generator ipc_gullwing_generator.py +SOP SO +0 +8 +8 +Package_SO +SOP-16_4.4x10.4mm_P1.27mm +16-Lead Plastic Small Outline http://www.vishay.com/docs/49633/sg2098.pdf +SOP 1.27 +0 +16 +16 +Package_SO +SOP-16_4.55x10.3mm_P1.27mm +SOP, 16 Pin (https://toshiba.semicon-storage.com/info/docget.jsp?did=12855&prodName=TLP290-4), generated with kicad-footprint-generator ipc_gullwing_generator.py +SOP SO +0 +16 +16 +Package_SO +SOP-18_7x12.5mm_P1.27mm +SOP, 18 Pin (https://toshiba.semicon-storage.com/info/docget.jsp?did=30523), generated with kicad-footprint-generator ipc_gullwing_generator.py +SOP SO +0 +18 +18 +Package_SO +SSO-4_6.7x5.1mm_P2.54mm_Clearance8mm +4-Lead Plastic Stretched Small Outline (SSO/Stretched SO), see https://www.vishay.com/docs/84299/vor1142b4.pdf +SSO Stretched SO SOIC 2.54 +0 +4 +4 +Package_SO +SSO-6_6.8x4.6mm_P1.27mm_Clearance7mm +8-Lead Plastic Stretched Small Outline (SSO/Stretched SO), see https://docs.broadcom.com/cs/Satellite?blobcol=urldata&blobheader=application%2Fpdf&blobheadername1=Content-Disposition&blobheadername2=Content-Type&blobheadername3=MDT-Type&blobheadervalue1=attachment%3Bfilename%3DIPD-Selection-Guide_AV00-0254EN_030617.pdf&blobheadervalue2=application%2Fx-download&blobheadervalue3=abinary%253B%2Bcharset%253DUTF-8&blobkey=id&blobnocache=true&blobtable=MungoBlobs&blobwhere=1430884105675&ssbinary=true +SSO Stretched SO SOIC 1.27 +0 +6 +6 +Package_SO +SSO-6_6.8x4.6mm_P1.27mm_Clearance8mm +8-Lead Plastic Stretched Small Outline (SSO/Stretched SO), see https://docs.broadcom.com/cs/Satellite?blobcol=urldata&blobheader=application%2Fpdf&blobheadername1=Content-Disposition&blobheadername2=Content-Type&blobheadername3=MDT-Type&blobheadervalue1=attachment%3Bfilename%3DIPD-Selection-Guide_AV00-0254EN_030617.pdf&blobheadervalue2=application%2Fx-download&blobheadervalue3=abinary%253B%2Bcharset%253DUTF-8&blobkey=id&blobnocache=true&blobtable=MungoBlobs&blobwhere=1430884105675&ssbinary=true +SSO Stretched SO SOIC 1.27 +0 +6 +6 +Package_SO +SSO-8_6.7x9.8mm_P2.54mm_Clearance8mm +8-Lead Plastic Stretched Small Outline (SSO/Stretched SO), see https://www.vishay.com/docs/83831/lh1533ab.pdf +SSO Stretched SO SOIC Pitch 2.54 +0 +8 +8 +Package_SO +SSO-8_6.8x5.9mm_P1.27mm_Clearance7mm +8-Lead Plastic Stretched Small Outline (SSO/Stretched SO), see https://docs.broadcom.com/cs/Satellite?blobcol=urldata&blobheader=application%2Fpdf&blobheadername1=Content-Disposition&blobheadername2=Content-Type&blobheadername3=MDT-Type&blobheadervalue1=attachment%3Bfilename%3DIPD-Selection-Guide_AV00-0254EN_030617.pdf&blobheadervalue2=application%2Fx-download&blobheadervalue3=abinary%253B%2Bcharset%253DUTF-8&blobkey=id&blobnocache=true&blobtable=MungoBlobs&blobwhere=1430884105675&ssbinary=true +SSO Stretched SO SOIC Pitch 1.27 +0 +8 +8 +Package_SO +SSO-8_6.8x5.9mm_P1.27mm_Clearance8mm +8-Lead Plastic Stretched Small Outline (SSO/Stretched SO), see https://docs.broadcom.com/cs/Satellite?blobcol=urldata&blobheader=application%2Fpdf&blobheadername1=Content-Disposition&blobheadername2=Content-Type&blobheadername3=MDT-Type&blobheadervalue1=attachment%3Bfilename%3DIPD-Selection-Guide_AV00-0254EN_030617.pdf&blobheadervalue2=application%2Fx-download&blobheadervalue3=abinary%253B%2Bcharset%253DUTF-8&blobkey=id&blobnocache=true&blobtable=MungoBlobs&blobwhere=1430884105675&ssbinary=true +SSO Stretched SO SOIC Pitch 1.27 +0 +8 +8 +Package_SO +SSO-8_9.6x6.3mm_P1.27mm_Clearance10.5mm +8-Lead Plastic Stretched Small Outline (SSO/Stretched SO), see https://docs.broadcom.com/cs/Satellite?blobcol=urldata&blobheader=application%2Fpdf&blobheadername1=Content-Disposition&blobheadername2=Content-Type&blobheadername3=MDT-Type&blobheadervalue1=attachment%3Bfilename%3DIPD-Selection-Guide_AV00-0254EN_030617.pdf&blobheadervalue2=application%2Fx-download&blobheadervalue3=abinary%253B%2Bcharset%253DUTF-8&blobkey=id&blobnocache=true&blobtable=MungoBlobs&blobwhere=1430884105675&ssbinary=true +SSO Stretched SO SOIC Pitch 1.27 +0 +8 +8 +Package_SO +SSO-8_13.6x6.3mm_P1.27mm_Clearance14.2mm +8-Lead Plastic Stretched Small Outline (SSO/Stretched SO), see https://docs.broadcom.com/cs/Satellite?blobcol=urldata&blobheader=application%2Fpdf&blobheadername1=Content-Disposition&blobheadername2=Content-Type&blobheadername3=MDT-Type&blobheadervalue1=attachment%3Bfilename%3DIPD-Selection-Guide_AV00-0254EN_030617.pdf&blobheadervalue2=application%2Fx-download&blobheadervalue3=abinary%253B%2Bcharset%253DUTF-8&blobkey=id&blobnocache=true&blobtable=MungoBlobs&blobwhere=1430884105675&ssbinary=true +SSO Stretched SO SOIC Pitch 1.27 +0 +8 +8 +Package_SO +SSOP-8_2.95x2.8mm_P0.65mm +SSOP-8 2.9 x2.8mm Pitch 0.65mm +SSOP-8 2.95x2.8mm Pitch 0.65mm +0 +8 +8 +Package_SO +SSOP-8_3.9x5.05mm_P1.27mm +SSOP, 8 Pin (http://www.fujitsu.com/downloads/MICRO/fsa/pdf/products/memory/fram/MB85RS16-DS501-00014-6v0-E.pdf), generated with kicad-footprint-generator ipc_gullwing_generator.py +SSOP SO +0 +8 +8 +Package_SO +SSOP-8_3.95x5.21x3.27mm_P1.27mm +SSOP-8 3.95x5.21x3.27mm Pitch 1.27mm +SSOP-8 3.95x5.21x3.27mm 1.27mm +0 +8 +8 +Package_SO +SSOP-8_5.25x5.24mm_P1.27mm +SSOP, 8 Pin (http://www.fujitsu.com/ca/en/Images/MB85RS2MT-DS501-00023-1v0-E.pdf), generated with kicad-footprint-generator ipc_gullwing_generator.py +SSOP SO +0 +8 +8 +Package_SO +SSOP-10_3.9x4.9mm_P1.00mm +10-Lead SSOP, 3.9 x 4.9mm body, 1.00mm pitch (http://www.st.com/resource/en/datasheet/viper01.pdf) +SSOP 3.9 4.9 1.00 +0 +10 +10 +Package_SO +SSOP-14_5.3x6.2mm_P0.65mm +SSOP14: plastic shrink small outline package; 14 leads; body width 5.3 mm; (see NXP SSOP-TSSOP-VSO-REFLOW.pdf and sot337-1_po.pdf) +SSOP 0.65 +0 +14 +14 +Package_SO +SSOP-16_3.9x4.9mm_P0.635mm +SSOP16: plastic shrink small outline package; 16 leads; body width 3.9 mm; lead pitch 0.635; (see NXP SSOP-TSSOP-VSO-REFLOW.pdf and sot519-1_po.pdf) +SSOP 0.635 +0 +16 +16 +Package_SO +SSOP-16_4.4x5.2mm_P0.65mm +SSOP16: plastic shrink small outline package; 16 leads; body width 4.4 mm; (see NXP SSOP-TSSOP-VSO-REFLOW.pdf and sot369-1_po.pdf) +SSOP 0.65 +0 +16 +16 +Package_SO +SSOP-16_5.3x6.2mm_P0.65mm +SSOP16: plastic shrink small outline package; 16 leads; body width 5.3 mm; (see NXP SSOP-TSSOP-VSO-REFLOW.pdf and sot338-1_po.pdf) +SSOP 0.65 +0 +16 +16 +Package_SO +SSOP-18_4.4x6.5mm_P0.65mm +SSOP18: plastic shrink small outline package; 18 leads; body width 4.4 mm (http://toshiba.semicon-storage.com/info/docget.jsp?did=30523&prodName=TBD62783APG) +SSOP 0.65 +0 +18 +18 +Package_SO +SSOP-20_3.9x8.7mm_P0.635mm +SSOP20: plastic shrink small outline package; 24 leads; body width 3.9 mm; lead pitch 0.635; (see http://www.ftdichip.com/Support/Documents/DataSheets/ICs/DS_FT231X.pdf) +SSOP 0.635 +0 +20 +20 +Package_SO +SSOP-20_4.4x6.5mm_P0.65mm +SSOP20: plastic shrink small outline package; 20 leads; body width 4.4 mm; (see NXP SSOP-TSSOP-VSO-REFLOW.pdf and sot266-1_po.pdf) +SSOP 0.65 +0 +20 +20 +Package_SO +SSOP-20_5.3x7.2mm_P0.65mm +20-Lead Plastic Shrink Small Outline (SS)-5.30 mm Body [SSOP] (see Microchip Packaging Specification 00000049BS.pdf) +SSOP 0.65 +0 +20 +20 +Package_SO +SSOP-24_3.9x8.7mm_P0.635mm +SSOP24: plastic shrink small outline package; 24 leads; body width 3.9 mm; lead pitch 0.635; (see NXP SSOP-TSSOP-VSO-REFLOW.pdf and sot556-1_po.pdf) +SSOP 0.635 +0 +24 +24 +Package_SO +SSOP-24_5.3x8.2mm_P0.65mm +24-Lead Plastic Shrink Small Outline (SS)-5.30 mm Body [SSOP] (see Microchip Packaging Specification 00000049BS.pdf) +SSOP 0.65 +0 +24 +24 +Package_SO +SSOP-28_3.9x9.9mm_P0.635mm +SSOP28: plastic shrink small outline package; 28 leads; body width 3.9 mm; lead pitch 0.635; (see http://cds.linear.com/docs/en/datasheet/38901fb.pdf) +SSOP 0.635 +0 +28 +28 +Package_SO +SSOP-28_5.3x10.2mm_P0.65mm +28-Lead Plastic Shrink Small Outline (SS)-5.30 mm Body [SSOP] (see Microchip Packaging Specification 00000049BS.pdf) +SSOP 0.65 +0 +28 +28 +Package_SO +SSOP-32_11.305x20.495mm_P1.27mm +SSOP, 32 Pin (http://www.issi.com/WW/pdf/61-64C5128AL.pdf), generated with kicad-footprint-generator ipc_gullwing_generator.py +SSOP SO +0 +32 +32 +Package_SO +SSOP-44_5.3x12.8mm_P0.5mm +44-Lead Plastic Shrink Small Outline (SS)-5.30 mm Body [SSOP] (http://cds.linear.com/docs/en/datasheet/680313fa.pdf) +SSOP 0.5 +0 +44 +44 +Package_SO +SSOP-48_7.5x15.9mm_P0.635mm +SSOP48: plastic shrink small outline package; 48 leads; body width 7.5 mm; (see NXP SSOP-TSSOP-VSO-REFLOW.pdf and sot370-1_po.pdf) +SSOP 0.635 +0 +48 +48 +Package_SO +SSOP-56_7.5x18.5mm_P0.635mm +SSOP56: plastic shrink small outline package; 56 leads; body width 7.5 mm; (see NXP SSOP-TSSOP-VSO-REFLOW.pdf and sot371-1_po.pdf) +SSOP 0.635 +0 +56 +56 +Package_SO +ST_MultiPowerSO-30 +MultiPowerSO-30 3EP 16.0x17.2mm Pitch 1mm (http://www.st.com/resource/en/datasheet/vnh2sp30-e.pdf) +MultiPowerSO-30 3EP 16.0x17.2mm Pitch 1mm +0 +33 +33 +Package_SO +ST_PowerSSO-24_SlugDown +ST PowerSSO-24 1EP 7.5x10.3mm Pitch 0.8mm [JEDEC MO-271] (http://www.st.com/resource/en/datasheet/tda7266p.pdf, http://freedatasheets.com/downloads/Technical%20Note%20Powersso24%20TN0054.pdf) +ST PowerSSO-24 1EP 7.5x10.3mm Pitch 0.8mm +0 +25 +25 +Package_SO +ST_PowerSSO-24_SlugDown_ThermalVias +ST PowerSSO-24 1EP 7.5x10.3mm Pitch 0.8mm [JEDEC MO-271] (http://www.st.com/resource/en/datasheet/tda7266p.pdf, http://freedatasheets.com/downloads/Technical%20Note%20Powersso24%20TN0054.pdf) +ST PowerSSO-24 1EP 7.5x10.3mm Pitch 0.8mm +0 +38 +25 +Package_SO +ST_PowerSSO-24_SlugUp +ST PowerSSO-24 1EP 7.5x10.3mm Pitch 0.8mm [JEDEC MO-271] (http://www.st.com/resource/en/datasheet/tda7266p.pdf, http://freedatasheets.com/downloads/Technical%20Note%20Powersso24%20TN0054.pdf) +ST PowerSSO-24 1EP 7.5x10.3mm Pitch 0.8mm +0 +24 +24 +Package_SO +ST_PowerSSO-36_SlugDown +ST PowerSSO-36 1EP 7.5x10.3mm Pitch 0.8mm [JEDEC MO-271] (http://www.st.com/resource/en/datasheet/tda7492p.pdf, http://freedatasheets.com/downloads/Technical%20Note%20Powersso24%20TN0054.pdf) +ST PowerSSO-36 1EP 7.5x10.3mm Pitch 0.8mm +0 +37 +37 +Package_SO +ST_PowerSSO-36_SlugDown_ThermalVias +ST PowerSSO-36 1EP 7.5x10.3mm Pitch 0.8mm [JEDEC MO-271] (http://www.st.com/resource/en/datasheet/tda7492p.pdf, http://freedatasheets.com/downloads/Technical%20Note%20Powersso24%20TN0054.pdf) +ST PowerSSO-36 1EP 7.5x10.3mm Pitch 0.8mm +0 +50 +37 +Package_SO +ST_PowerSSO-36_SlugUp +ST PowerSSO-36 1EP 7.5x10.3mm Pitch 0.8mm [JEDEC MO-271] (http://www.st.com/resource/en/datasheet/tda7492p.pdf, http://freedatasheets.com/downloads/Technical%20Note%20Powersso24%20TN0054.pdf) +ST PowerSSO-36 1EP 7.5x10.3mm Pitch 0.8mm +0 +36 +36 +Package_SO +Texas_HSOP-8-1EP_3.9x4.9mm_P1.27mm +Texas Instruments HSOP 9, 1.27mm pitch, 3.9x4.9mm body, exposed pad, DDA0008J (http://www.ti.com/lit/ds/symlink/tps5430.pdf) +HSOP 1.27 +0 +11 +9 +Package_SO +Texas_HSOP-8-1EP_3.9x4.9mm_P1.27mm_ThermalVias +Texas Instruments HSOP 9, 1.27mm pitch, 3.9x4.9mm body, exposed pad, thermal vias, DDA0008J (http://www.ti.com/lit/ds/symlink/tps5430.pdf) +HSOP 1.27 +0 +20 +9 +Package_SO +Texas_HTSOP-8-1EP_3.9x4.9mm_P1.27mm_EP2.95x4.9mm_Mask2.4x3.1mm_ThermalVias +8-pin HTSOP package with 1.27mm pin pitch, compatible with SOIC-8, 3.9x4.9mm body, exposed pad, thermal vias, http://www.ti.com/lit/ds/symlink/drv8870.pdf +HTSOP 1.27 +0 +18 +9 +Package_SO +Texas_PWP0020A +20-Pin Thermally Enhanced Thin Shrink Small-Outline Package, Body 4.4x6.5x1.1mm, Pad 3.0x4.2mm, Texas Instruments (see http://www.ti.com/lit/ds/symlink/lm5118.pdf) +PWP HTSSOP 0.65mm +0 +25 +21 +Package_SO +Texas_R-PDSO-G8_EP2.95x4.9mm_Mask2.4x3.1mm +HSOIC, 8 Pin (http://www.ti.com/lit/ds/symlink/lmr14030.pdf#page=28, http://www.ti.com/lit/ml/msoi002j/msoi002j.pdf), generated with kicad-footprint-generator ipc_gullwing_generator.py +HSOIC SO +0 +16 +9 +Package_SO +Texas_R-PDSO-G8_EP2.95x4.9mm_Mask2.4x3.1mm_ThermalVias +HSOIC, 8 Pin (http://www.ti.com/lit/ds/symlink/lmr14030.pdf#page=28, http://www.ti.com/lit/ml/msoi002j/msoi002j.pdf), generated with kicad-footprint-generator ipc_gullwing_generator.py +HSOIC SO +0 +23 +9 +Package_SO +Texas_R-PDSO-N5 +Plastic Small outline http://www.ti.com/lit/ml/mpds158c/mpds158c.pdf +SOT23 R-PDSO-N5 +0 +5 +5 +Package_SO +TI_SO-PowerPAD-8 +8-Lead Plastic PSOP, Exposed Die Pad (TI DDA0008B, see http://www.ti.com/lit/ds/symlink/lm3404.pdf) +SSOP 0.50 exposed pad +0 +12 +9 +Package_SO +TI_SO-PowerPAD-8_ThermalVias +8-pin HTSOP package with 1.27mm pin pitch, compatible with SOIC-8, 3.9x4.9mm² body, exposed pad, thermal vias with large copper area, as proposed in http://www.ti.com/lit/ds/symlink/tps5430.pdf +HTSOP 1.27 +0 +19 +9 +Package_SO +TSOP-5_1.65x3.05mm_P0.95mm +TSOP-5 package (comparable to TSOT-23), https://www.vishay.com/docs/71200/71200.pdf +Jedec MO-193C TSOP-5L +0 +5 +5 +Package_SO +TSOP-6_1.65x3.05mm_P0.95mm +TSOP-6 package (comparable to TSOT-23), https://www.vishay.com/docs/71200/71200.pdf +Jedec MO-193C TSOP-6L +0 +6 +6 +Package_SO +TSOP-I-28_11.8x8mm_P0.55mm +TSOP I, 28 pins, 18.8x8mm body, 0.55mm pitch, IPC-calculated pads (http://ww1.microchip.com/downloads/en/devicedoc/doc0807.pdf) +TSOP I 28 pins +0 +28 +28 +Package_SO +TSOP-I-32_11.8x8mm_P0.5mm +TSOP-I, 32 Pin (http://www.issi.com/WW/pdf/61-64C5128AL.pdf), generated with kicad-footprint-generator ipc_gullwing_generator.py +TSOP-I SO +0 +32 +32 +Package_SO +TSOP-I-32_18.4x8mm_P0.5mm +TSOP I, 32 pins, 18.4x8mm body (https://www.micron.com/~/media/documents/products/technical-note/nor-flash/tn1225_land_pad_design.pdf, http://www.fujitsu.com/downloads/MICRO/fma/pdfmcu/f32pm25.pdf) +TSOP I 32 +0 +32 +32 +Package_SO +TSOP-I-32_18.4x8mm_P0.5mm_Reverse +TSOP I, 32 pins, 18.4x8mm body (http://www.futurlec.com/Datasheet/Memory/628128.pdf), reverse mount +TSOP I 32 reverse +0 +32 +32 +Package_SO +TSOP-I-48_18.4x12mm_P0.5mm +TSOP I, 32 pins, 18.4x8mm body (https://www.micron.com/~/media/documents/products/technical-note/nor-flash/tn1225_land_pad_design.pdf) +TSOP I 32 +0 +48 +48 +Package_SO +TSOP-I-56_18.4x14mm_P0.5mm +TSOP I, 32 pins, 18.4x8mm body (https://www.micron.com/~/media/documents/products/technical-note/nor-flash/tn1225_land_pad_design.pdf) +TSOP I 32 +0 +56 +56 +Package_SO +TSOP-II-32_21.0x10.2mm_P1.27mm +32-lead plastic TSOP; Type II +TSOP-II 32 +0 +32 +32 +Package_SO +TSOP-II-44_10.16x18.41mm_P0.8mm +TSOP-II, 44 Pin (http://www.issi.com/WW/pdf/61-64C5128AL.pdf), generated with kicad-footprint-generator ipc_gullwing_generator.py +TSOP-II SO +0 +44 +44 +Package_SO +TSOP-II-54_22.2x10.16mm_P0.8mm +54-lead TSOP typ II package +TSOPII TSOP2 +0 +54 +54 +Package_SO +TSSOP-8_3x3mm_P0.65mm +TSSOP8: plastic thin shrink small outline package; 8 leads; body width 3 mm; (see NXP SSOP-TSSOP-VSO-REFLOW.pdf and sot505-1_po.pdf) +SSOP 0.65 +0 +8 +8 +Package_SO +TSSOP-8_4.4x3mm_P0.65mm +8-Lead Plastic Thin Shrink Small Outline (ST)-4.4 mm Body [TSSOP] (see Microchip Packaging Specification 00000049BS.pdf) +SSOP 0.65 +0 +8 +8 +Package_SO +TSSOP-10_3x3mm_P0.5mm +TSSOP10: plastic thin shrink small outline package; 10 leads; body width 3 mm; (see NXP SSOP-TSSOP-VSO-REFLOW.pdf and sot552-1_po.pdf) +SSOP 0.5 +0 +10 +10 +Package_SO +TSSOP-14-1EP_4.4x5mm_P0.65mm +14-Lead Plastic Thin Shrink Small Outline (ST)-4.4 mm Body [TSSOP] with exposed pad (http://cds.linear.com/docs/en/datasheet/34301fa.pdf) +SSOP 0.65 exposed pad +0 +18 +15 +Package_SO +TSSOP-14_4.4x5mm_P0.65mm +14-Lead Plastic Thin Shrink Small Outline (ST)-4.4 mm Body [TSSOP] (see Microchip Packaging Specification 00000049BS.pdf) +SSOP 0.65 +0 +14 +14 +Package_SO +TSSOP-16-1EP_4.4x5mm_P0.65mm +FE Package; 16-Lead Plastic TSSOP (4.4mm); Exposed Pad Variation BB; (see Linear Technology 1956f.pdf) +SSOP 0.65 +0 +24 +17 +Package_SO +TSSOP-16_4.4x5mm_P0.65mm +16-Lead Plastic Thin Shrink Small Outline (ST)-4.4 mm Body [TSSOP] (see Microchip Packaging Specification 00000049BS.pdf) +SSOP 0.65 +0 +16 +16 +Package_SO +TSSOP-20_4.4x6.5mm_P0.65mm +20-Lead Plastic Thin Shrink Small Outline (ST)-4.4 mm Body [TSSOP] (see Microchip Packaging Specification 00000049BS.pdf) +SSOP 0.65 +0 +20 +20 +Package_SO +TSSOP-24_4.4x7.8mm_P0.65mm +TSSOP24: plastic thin shrink small outline package; 24 leads; body width 4.4 mm; (see NXP SSOP-TSSOP-VSO-REFLOW.pdf and sot355-1_po.pdf) +SSOP 0.65 +0 +24 +24 +Package_SO +TSSOP-28-1EP_4.4x9.7mm_P0.65mm +TSSOP28: plastic thin shrink small outline package; 28 leads; body width 4.4 mm; Exposed Pad Variation; (see NXP SSOP-TSSOP-VSO-REFLOW.pdf and sot361-1_po.pdf) +SSOP 0.65 +0 +36 +29 +Package_SO +TSSOP-28_4.4x9.7mm_P0.65mm +TSSOP28: plastic thin shrink small outline package; 28 leads; body width 4.4 mm; (see NXP SSOP-TSSOP-VSO-REFLOW.pdf and sot361-1_po.pdf) +SSOP 0.65 +0 +28 +28 +Package_SO +TSSOP-30_4.4x7.8mm_P0.5mm +TSSOP30: plastic thin shrink small outline package; 30 leads; body width 4.4 mm (http://www.ti.com/lit/ds/symlink/bq78350.pdf) +SSOP 0.5 +0 +30 +30 +Package_SO +TSSOP-32_6.1x11mm_P0.65mm +TSSOP32: plastic thin shrink small outline package; 32 leads; body width 6.1 mm; lead pitch 0.65 mm (see NXP SSOP-TSSOP-VSO-REFLOW.pdf and sot487-1_po.pdf) +SSOP 0.65 +0 +32 +32 +Package_SO +TSSOP-38_4.4x9.7mm_P0.5mm +TSSOP38: plastic thin shrink small outline package; 38 leads; body width 4.4 mm (see NXP SSOP-TSSOP-VSO-REFLOW.pdf and sot510-1_po.pdf) +SSOP 0.5 +0 +38 +38 +Package_SO +TSSOP-38_6.1x12.5mm_P0.65mm +TSSOP38: plastic thin shrink small outline package; 38 leads; body width 6.1 mm (http://www.ti.com/lit/ds/symlink/msp430g2744.pdf) +SSOP 0.65 +0 +38 +38 +Package_SO +TSSOP-44_4.4x11.2mm_P0.5mm +TSSOP44: plastic thin shrink small outline package; 44 leads; body width 4.4 mm (see NXP SSOP-TSSOP-VSO-REFLOW.pdf and sot510-1_po.pdf) +SSOP 0.5 +0 +44 +44 +Package_SO +TSSOP-48_6.1x12.5mm_P0.5mm +TSSOP48: plastic thin shrink small outline package; 48 leads; body width 6.1 mm (see NXP SSOP-TSSOP-VSO-REFLOW.pdf and sot362-1_po.pdf) +SSOP 0.5 +0 +48 +48 +Package_SO +TSSOP-56_6.1x14mm_P0.5mm +TSSOP56: plastic thin shrink small outline package; 56 leads; body width 6.1 mm (see NXP SSOP-TSSOP-VSO-REFLOW.pdf and sot364-1_po.pdf) +SSOP 0.5 +0 +56 +56 +Package_SO +Vishay_PowerPAK_1212-8_Dual +PowerPAK 1212-8 Dual (https://www.vishay.com/docs/71656/ppak12128.pdf, https://www.vishay.com/docs/72598/72598.pdf) +Vishay_PowerPAK_1212-8_Dual +0 +6 +6 +Package_SO +Vishay_PowerPAK_1212-8_Single +PowerPAK 1212-8 Single (https://www.vishay.com/docs/71656/ppak12128.pdf, https://www.vishay.com/docs/72597/72597.pdf) +Vishay PowerPAK 1212-8 Single +0 +5 +5 +Package_SO +VSO-40_7.6x15.4mm_P0.762mm +VSO40: plastic very small outline package; 40 leads (see NXP SSOP-TSSOP-VSO-REFLOW.pdf and sot158-1_po.pdf) +SSOP 0.762 +0 +40 +40 +Package_SO +VSO-56_11.1x21.5mm_P0.75mm +VSO56: plastic very small outline package; 56 leads (see NXP SSOP-TSSOP-VSO-REFLOW.pdf and sot190-1_po.pdf) +SSOP 0.75 +0 +56 +56 +Package_SO +VSSOP-8_2.3x2mm_P0.5mm +VSSOP-8 2.3x2mm Pitch 0.5mm +VSSOP-8 2.3x2mm Pitch 0.5mm +0 +8 +8 +Package_SO +VSSOP-8_2.4x2.1mm_P0.5mm +http://www.ti.com/lit/ml/mpds050d/mpds050d.pdf +VSSOP DCU R-PDSO-G8 Pitch0.5mm +0 +8 +8 +Package_SO +VSSOP-8_3.0x3.0mm_P0.65mm +VSSOP-8 3.0 x 3.0, http://www.ti.com/lit/ds/symlink/lm75b.pdf +VSSOP-8 3.0 x 3.0 +0 +8 +8 +Package_SO +VSSOP-10_3x3mm_P0.5mm +VSSOP, 10 Pin (http://www.ti.com/lit/ds/symlink/ads1115.pdf), generated with kicad-footprint-generator ipc_gullwing_generator.py +VSSOP SO +0 +10 +10 +Package_SO +Zetex_SM8 +Zetex, SMD, 8 pin package (http://datasheet.octopart.com/ZDT6758TA-Zetex-datasheet-68057.pdf) +Zetex SM8 +0 +8 +8 +Resistor_SMD +R_0201_0603Metric +Resistor SMD 0201 (0603 Metric), square (rectangular) end terminal, IPC_7351 nominal, (Body size source: https://www.vishay.com/docs/20052/crcw0201e3.pdf), generated with kicad-footprint-generator +resistor +0 +4 +2 +Resistor_SMD +R_0402_1005Metric +Resistor SMD 0402 (1005 Metric), square (rectangular) end terminal, IPC_7351 nominal, (Body size source: http://www.tortai-tech.com/upload/download/2011102023233369053.pdf), generated with kicad-footprint-generator +resistor +0 +2 +2 +Resistor_SMD +R_0603_1608Metric +Resistor SMD 0603 (1608 Metric), square (rectangular) end terminal, IPC_7351 nominal, (Body size source: http://www.tortai-tech.com/upload/download/2011102023233369053.pdf), generated with kicad-footprint-generator +resistor +0 +2 +2 +Resistor_SMD +R_0603_1608Metric_Pad1.05x0.95mm_HandSolder +Resistor SMD 0603 (1608 Metric), square (rectangular) end terminal, IPC_7351 nominal with elongated pad for handsoldering. (Body size source: http://www.tortai-tech.com/upload/download/2011102023233369053.pdf), generated with kicad-footprint-generator +resistor handsolder +0 +2 +2 +Resistor_SMD +R_0612_1632Metric +Resistor SMD 0612 (1632 Metric), square (rectangular) end terminal, IPC_7351 nominal, (Body size source: https://www.vishay.com/docs/20019/rcwe.pdf), generated with kicad-footprint-generator +resistor +0 +2 +2 +Resistor_SMD +R_0612_1632Metric_Pad1.18x3.40mm_HandSolder +Resistor SMD 0612 (1632 Metric), square (rectangular) end terminal, IPC_7351 nominal with elongated pad for handsoldering. (Body size source: https://www.vishay.com/docs/20019/rcwe.pdf), generated with kicad-footprint-generator +resistor handsolder +0 +2 +2 +Resistor_SMD +R_0805_2012Metric +Resistor SMD 0805 (2012 Metric), square (rectangular) end terminal, IPC_7351 nominal, (Body size source: https://docs.google.com/spreadsheets/d/1BsfQQcO9C6DZCsRaXUlFlo91Tg2WpOkGARC1WS5S8t0/edit?usp=sharing), generated with kicad-footprint-generator +resistor +0 +2 +2 +Resistor_SMD +R_0805_2012Metric_Pad1.15x1.40mm_HandSolder +Resistor SMD 0805 (2012 Metric), square (rectangular) end terminal, IPC_7351 nominal with elongated pad for handsoldering. (Body size source: https://docs.google.com/spreadsheets/d/1BsfQQcO9C6DZCsRaXUlFlo91Tg2WpOkGARC1WS5S8t0/edit?usp=sharing), generated with kicad-footprint-generator +resistor handsolder +0 +2 +2 +Resistor_SMD +R_0815_2038Metric +Resistor SMD 0815 (2038 Metric), square (rectangular) end terminal, IPC_7351 nominal, (Body size source: http://www.yageo.com/documents/recent/PYu-PRPFPH_521_RoHS_L_0.pdf), generated with kicad-footprint-generator +resistor +0 +2 +2 +Resistor_SMD +R_0815_2038Metric_Pad1.53x4.00mm_HandSolder +Resistor SMD 0815 (2038 Metric), square (rectangular) end terminal, IPC_7351 nominal with elongated pad for handsoldering. (Body size source: http://www.yageo.com/documents/recent/PYu-PRPFPH_521_RoHS_L_0.pdf), generated with kicad-footprint-generator +resistor handsolder +0 +2 +2 +Resistor_SMD +R_01005_0402Metric +Resistor SMD 01005 (0402 Metric), square (rectangular) end terminal, IPC_7351 nominal, (Body size source: http://www.vishay.com/docs/20056/crcw01005e3.pdf), generated with kicad-footprint-generator +resistor +0 +4 +2 +Resistor_SMD +R_1020_2550Metric +Resistor SMD 1020 (2550 Metric), square (rectangular) end terminal, IPC_7351 nominal, (Body size source: https://www.vishay.com/docs/20019/rcwe.pdf), generated with kicad-footprint-generator +resistor +0 +2 +2 +Resistor_SMD +R_1020_2550Metric_Pad1.33x5.20mm_HandSolder +Resistor SMD 1020 (2550 Metric), square (rectangular) end terminal, IPC_7351 nominal with elongated pad for handsoldering. (Body size source: https://www.vishay.com/docs/20019/rcwe.pdf), generated with kicad-footprint-generator +resistor handsolder +0 +2 +2 +Resistor_SMD +R_1206_3216Metric +Resistor SMD 1206 (3216 Metric), square (rectangular) end terminal, IPC_7351 nominal, (Body size source: http://www.tortai-tech.com/upload/download/2011102023233369053.pdf), generated with kicad-footprint-generator +resistor +0 +2 +2 +Resistor_SMD +R_1206_3216Metric_Pad1.42x1.75mm_HandSolder +Resistor SMD 1206 (3216 Metric), square (rectangular) end terminal, IPC_7351 nominal with elongated pad for handsoldering. (Body size source: http://www.tortai-tech.com/upload/download/2011102023233369053.pdf), generated with kicad-footprint-generator +resistor handsolder +0 +2 +2 +Resistor_SMD +R_1210_3225Metric +Resistor SMD 1210 (3225 Metric), square (rectangular) end terminal, IPC_7351 nominal, (Body size source: http://www.tortai-tech.com/upload/download/2011102023233369053.pdf), generated with kicad-footprint-generator +resistor +0 +2 +2 +Resistor_SMD +R_1210_3225Metric_Pad1.42x2.65mm_HandSolder +Resistor SMD 1210 (3225 Metric), square (rectangular) end terminal, IPC_7351 nominal with elongated pad for handsoldering. (Body size source: http://www.tortai-tech.com/upload/download/2011102023233369053.pdf), generated with kicad-footprint-generator +resistor handsolder +0 +2 +2 +Resistor_SMD +R_1218_3246Metric +Resistor SMD 1218 (3246 Metric), square (rectangular) end terminal, IPC_7351 nominal, (Body size source: https://www.vishay.com/docs/20035/dcrcwe3.pdf), generated with kicad-footprint-generator +resistor +0 +2 +2 +Resistor_SMD +R_1218_3246Metric_Pad1.22x4.75mm_HandSolder +Resistor SMD 1218 (3246 Metric), square (rectangular) end terminal, IPC_7351 nominal with elongated pad for handsoldering. (Body size source: https://www.vishay.com/docs/20035/dcrcwe3.pdf), generated with kicad-footprint-generator +resistor handsolder +0 +2 +2 +Resistor_SMD +R_1806_4516Metric +Resistor SMD 1806 (4516 Metric), square (rectangular) end terminal, IPC_7351 nominal, (Body size source: https://www.modelithics.com/models/Vendor/MuRata/BLM41P.pdf), generated with kicad-footprint-generator +resistor +0 +2 +2 +Resistor_SMD +R_1806_4516Metric_Pad1.57x1.80mm_HandSolder +Resistor SMD 1806 (4516 Metric), square (rectangular) end terminal, IPC_7351 nominal with elongated pad for handsoldering. (Body size source: https://www.modelithics.com/models/Vendor/MuRata/BLM41P.pdf), generated with kicad-footprint-generator +resistor handsolder +0 +2 +2 +Resistor_SMD +R_1812_4532Metric +Resistor SMD 1812 (4532 Metric), square (rectangular) end terminal, IPC_7351 nominal, (Body size source: https://www.nikhef.nl/pub/departments/mt/projects/detectorR_D/dtddice/ERJ2G.pdf), generated with kicad-footprint-generator +resistor +0 +2 +2 +Resistor_SMD +R_1812_4532Metric_Pad1.30x3.40mm_HandSolder +Resistor SMD 1812 (4532 Metric), square (rectangular) end terminal, IPC_7351 nominal with elongated pad for handsoldering. (Body size source: https://www.nikhef.nl/pub/departments/mt/projects/detectorR_D/dtddice/ERJ2G.pdf), generated with kicad-footprint-generator +resistor handsolder +0 +2 +2 +Resistor_SMD +R_2010_5025Metric +Resistor SMD 2010 (5025 Metric), square (rectangular) end terminal, IPC_7351 nominal, (Body size source: http://www.tortai-tech.com/upload/download/2011102023233369053.pdf), generated with kicad-footprint-generator +resistor +0 +2 +2 +Resistor_SMD +R_2010_5025Metric_Pad1.52x2.65mm_HandSolder +Resistor SMD 2010 (5025 Metric), square (rectangular) end terminal, IPC_7351 nominal with elongated pad for handsoldering. (Body size source: http://www.tortai-tech.com/upload/download/2011102023233369053.pdf), generated with kicad-footprint-generator +resistor handsolder +0 +2 +2 +Resistor_SMD +R_2512_6332Metric +Resistor SMD 2512 (6332 Metric), square (rectangular) end terminal, IPC_7351 nominal, (Body size source: http://www.tortai-tech.com/upload/download/2011102023233369053.pdf), generated with kicad-footprint-generator +resistor +0 +2 +2 +Resistor_SMD +R_2512_6332Metric_Pad1.52x3.35mm_HandSolder +Resistor SMD 2512 (6332 Metric), square (rectangular) end terminal, IPC_7351 nominal with elongated pad for handsoldering. (Body size source: http://www.tortai-tech.com/upload/download/2011102023233369053.pdf), generated with kicad-footprint-generator +resistor handsolder +0 +2 +2 +Resistor_SMD +R_2816_7142Metric +Resistor SMD 2816 (7142 Metric), square (rectangular) end terminal, IPC_7351 nominal, (Body size from: https://www.vishay.com/docs/30100/wsl.pdf), generated with kicad-footprint-generator +resistor +0 +2 +2 +Resistor_SMD +R_2816_7142Metric_Pad3.20x4.45mm_HandSolder +Resistor SMD 2816 (7142 Metric), square (rectangular) end terminal, IPC_7351 nominal with elongated pad for handsoldering. (Body size from: https://www.vishay.com/docs/30100/wsl.pdf), generated with kicad-footprint-generator +resistor handsolder +0 +2 +2 +Resistor_SMD +R_4020_10251Metric +Resistor SMD 4020 (10251 Metric), square (rectangular) end terminal, IPC_7351 nominal, (Body size source: http://datasheet.octopart.com/HVC0603T5004FET-Ohmite-datasheet-26699797.pdf), generated with kicad-footprint-generator +resistor +0 +2 +2 +Resistor_SMD +R_4020_10251Metric_Pad1.65x5.30mm_HandSolder +Resistor SMD 4020 (10251 Metric), square (rectangular) end terminal, IPC_7351 nominal with elongated pad for handsoldering. (Body size source: http://datasheet.octopart.com/HVC0603T5004FET-Ohmite-datasheet-26699797.pdf), generated with kicad-footprint-generator +resistor handsolder +0 +2 +2 +Resistor_SMD +R_Array_Concave_2x0603 +Thick Film Chip Resistor Array, Wave soldering, Vishay CRA06P (see cra06p.pdf) +resistor array +0 +4 +4 +Resistor_SMD +R_Array_Concave_4x0402 +Thick Film Chip Resistor Array, Wave soldering, Vishay CRA04P (see cra04p.pdf) +resistor array +0 +8 +8 +Resistor_SMD +R_Array_Concave_4x0603 +Thick Film Chip Resistor Array, Wave soldering, Vishay CRA06P (see cra06p.pdf) +resistor array +0 +8 +8 +Resistor_SMD +R_Array_Convex_2x0402 +Chip Resistor Network, ROHM MNR02 (see mnr_g.pdf) +resistor array +0 +4 +4 +Resistor_SMD +R_Array_Convex_2x0603 +Chip Resistor Network, ROHM MNR12 (see mnr_g.pdf) +resistor array +0 +4 +4 +Resistor_SMD +R_Array_Convex_2x0606 +Precision Thin Film Chip Resistor Array, VISHAY (see http://www.vishay.com/docs/28770/acasat.pdf) +resistor array +0 +4 +4 +Resistor_SMD +R_Array_Convex_2x1206 +Chip Resistor Network, ROHM MNR32 (see mnr_g.pdf) +resistor array +0 +4 +4 +Resistor_SMD +R_Array_Convex_4x0402 +Chip Resistor Network, ROHM MNR04 (see mnr_g.pdf) +resistor array +0 +8 +8 +Resistor_SMD +R_Array_Convex_4x0603 +Chip Resistor Network, ROHM MNR14 (see mnr_g.pdf) +resistor array +0 +8 +8 +Resistor_SMD +R_Array_Convex_4x0612 +Precision Thin Film Chip Resistor Array, VISHAY (see http://www.vishay.com/docs/28770/acasat.pdf) +resistor array +0 +8 +8 +Resistor_SMD +R_Array_Convex_4x1206 +Chip Resistor Network, ROHM MNR34 (see mnr_g.pdf) +resistor array +0 +8 +8 +Resistor_SMD +R_Array_Convex_5x0603 +Chip Resistor Network, ROHM MNR15 (see mnr_g.pdf) +resistor array +0 +10 +10 +Resistor_SMD +R_Array_Convex_5x1206 +Chip Resistor Network, ROHM MNR35 (see mnr_g.pdf) +resistor array +0 +10 +10 +Resistor_SMD +R_Array_Convex_8x0602 +Chip Resistor Network, ROHM MNR18 (see mnr_g.pdf) +resistor array +0 +16 +16 +Resistor_SMD +R_Cat16-2 +SMT resistor net, Bourns CAT16 series, 2 way +SMT resistor net Bourns CAT16 series 2 way +0 +4 +4 +Resistor_SMD +R_Cat16-4 +SMT resistor net, Bourns CAT16 series, 4 way +SMT resistor net Bourns CAT16 series 4 way +0 +8 +8 +Resistor_SMD +R_Cat16-8 +SMT resistor net, Bourns CAT16 series, 8 way +SMT resistor net Bourns CAT16 series 8 way +0 +16 +16 +Resistor_SMD +R_MELF_MMB-0207 +Resistor, MELF, MMB-0207, http://www.vishay.com/docs/28713/melfprof.pdf +MELF Resistor +0 +2 +2 +Resistor_SMD +R_MicroMELF_MMU-0102 +Resistor, MicroMELF, MMU-0102, http://www.vishay.com/docs/28713/melfprof.pdf +MicroMELF Resistor +0 +2 +2 +Resistor_SMD +R_MiniMELF_MMA-0204 +Resistor, MiniMELF, MMA-0204, http://www.vishay.com/docs/28713/melfprof.pdf +MiniMELF Resistor +0 +2 +2 +Resistor_SMD +R_Shunt_Ohmite_LVK12 +4 contact shunt resistor +shunt resistor 4 contacts +0 +4 +4 +Resistor_SMD +R_Shunt_Ohmite_LVK20 +4 contacts shunt resistor, https://www.ohmite.com/assets/docs/res_lvk.pdf +4 contacts resistor smd +0 +4 +4 +Resistor_SMD +R_Shunt_Ohmite_LVK24 +4 contacts shunt resistor,https://www.ohmite.com/assets/docs/res_lvk.pdf +4 contacts resistor smd +0 +4 +4 +Resistor_SMD +R_Shunt_Ohmite_LVK25 +4 contacts shunt resistor,https://www.ohmite.com/assets/docs/res_lvk.pdf +4 contacts resistor smd +0 +4 +4 +Resistor_SMD +R_Shunt_Vishay_WSK2512_6332Metric_T1.19mm +Shunt Resistor SMD 2512 (6332 Metric), 2.6mm thick, Vishay WKS2512, Terminal length (T) 1.19mm, 5 to 200 milli Ohm (http://http://www.vishay.com/docs/30108/wsk.pdf) +resistor shunt WSK2512 +0 +4 +4 +Resistor_SMD +R_Shunt_Vishay_WSK2512_6332Metric_T2.21mm +Shunt Resistor SMD 2512 (6332 Metric), 2.6mm thick, Vishay WKS2512, Terminal length (T) 2.21mm, 1 to 4.9 milli Ohm (http://http://www.vishay.com/docs/30108/wsk.pdf) +resistor shunt WSK2512 +0 +4 +4 +Resistor_SMD +R_Shunt_Vishay_WSK2512_6332Metric_T2.66mm +Shunt Resistor SMD 2512 (6332 Metric), 2.6mm thick, Vishay WKS2512, Terminal length (T) 2.66mm, 0.5 to 0.99 milli Ohm (http://http://www.vishay.com/docs/30108/wsk.pdf) +resistor shunt WSK2512 +0 +4 +4 +Resistor_SMD +R_Shunt_Vishay_WSKW0612 +https://www.vishay.com/docs/30332/wskw0612.pdf +4-Terminal SMD Shunt +0 +4 +4 +Resistor_SMD +R_Shunt_Vishay_WSR2_WSR3 +Power Metal Strip Resistors 0.005 to 0.2, https://www.vishay.com/docs/30101/wsr.pdf +SMD Shunt Resistor +0 +2 +2 +Resistor_SMD +R_Shunt_Vishay_WSR2_WSR3_KelvinConnection +Power Metal Strip Resistors 0.005 to 0.2, https://www.vishay.com/docs/30101/wsr.pdf +SMD Shunt Resistor +0 +4 +2 +Resistor_THT +R_Array_SIP4 +4-pin Resistor SIP pack +R +0 +4 +4 +Resistor_THT +R_Array_SIP5 +5-pin Resistor SIP pack +R +0 +5 +5 +Resistor_THT +R_Array_SIP6 +6-pin Resistor SIP pack +R +0 +6 +6 +Resistor_THT +R_Array_SIP7 +7-pin Resistor SIP pack +R +0 +7 +7 +Resistor_THT +R_Array_SIP8 +8-pin Resistor SIP pack +R +0 +8 +8 +Resistor_THT +R_Array_SIP9 +9-pin Resistor SIP pack +R +0 +9 +9 +Resistor_THT +R_Array_SIP10 +10-pin Resistor SIP pack +R +0 +10 +10 +Resistor_THT +R_Array_SIP11 +11-pin Resistor SIP pack +R +0 +11 +11 +Resistor_THT +R_Array_SIP12 +12-pin Resistor SIP pack +R +0 +12 +12 +Resistor_THT +R_Array_SIP13 +13-pin Resistor SIP pack +R +0 +13 +13 +Resistor_THT +R_Array_SIP14 +14-pin Resistor SIP pack +R +0 +14 +14 +Resistor_THT +R_Axial_DIN0204_L3.6mm_D1.6mm_P1.90mm_Vertical +Resistor, Axial_DIN0204 series, Axial, Vertical, pin pitch=1.9mm, 0.167W, length*diameter=3.6*1.6mm^2, http://cdn-reichelt.de/documents/datenblatt/B400/1_4W%23YAG.pdf +Resistor Axial_DIN0204 series Axial Vertical pin pitch 1.9mm 0.167W length 3.6mm diameter 1.6mm +0 +2 +2 +Resistor_THT +R_Axial_DIN0204_L3.6mm_D1.6mm_P2.54mm_Vertical +Resistor, Axial_DIN0204 series, Axial, Vertical, pin pitch=2.54mm, 0.167W, length*diameter=3.6*1.6mm^2, http://cdn-reichelt.de/documents/datenblatt/B400/1_4W%23YAG.pdf +Resistor Axial_DIN0204 series Axial Vertical pin pitch 2.54mm 0.167W length 3.6mm diameter 1.6mm +0 +2 +2 +Resistor_THT +R_Axial_DIN0204_L3.6mm_D1.6mm_P5.08mm_Horizontal +Resistor, Axial_DIN0204 series, Axial, Horizontal, pin pitch=5.08mm, 0.167W, length*diameter=3.6*1.6mm^2, http://cdn-reichelt.de/documents/datenblatt/B400/1_4W%23YAG.pdf +Resistor Axial_DIN0204 series Axial Horizontal pin pitch 5.08mm 0.167W length 3.6mm diameter 1.6mm +0 +2 +2 +Resistor_THT +R_Axial_DIN0204_L3.6mm_D1.6mm_P5.08mm_Vertical +Resistor, Axial_DIN0204 series, Axial, Vertical, pin pitch=5.08mm, 0.167W, length*diameter=3.6*1.6mm^2, http://cdn-reichelt.de/documents/datenblatt/B400/1_4W%23YAG.pdf +Resistor Axial_DIN0204 series Axial Vertical pin pitch 5.08mm 0.167W length 3.6mm diameter 1.6mm +0 +2 +2 +Resistor_THT +R_Axial_DIN0204_L3.6mm_D1.6mm_P7.62mm_Horizontal +Resistor, Axial_DIN0204 series, Axial, Horizontal, pin pitch=7.62mm, 0.167W, length*diameter=3.6*1.6mm^2, http://cdn-reichelt.de/documents/datenblatt/B400/1_4W%23YAG.pdf +Resistor Axial_DIN0204 series Axial Horizontal pin pitch 7.62mm 0.167W length 3.6mm diameter 1.6mm +0 +2 +2 +Resistor_THT +R_Axial_DIN0207_L6.3mm_D2.5mm_P2.54mm_Vertical +Resistor, Axial_DIN0207 series, Axial, Vertical, pin pitch=2.54mm, 0.25W = 1/4W, length*diameter=6.3*2.5mm^2, http://cdn-reichelt.de/documents/datenblatt/B400/1_4W%23YAG.pdf +Resistor Axial_DIN0207 series Axial Vertical pin pitch 2.54mm 0.25W = 1/4W length 6.3mm diameter 2.5mm +0 +2 +2 +Resistor_THT +R_Axial_DIN0207_L6.3mm_D2.5mm_P5.08mm_Vertical +Resistor, Axial_DIN0207 series, Axial, Vertical, pin pitch=5.08mm, 0.25W = 1/4W, length*diameter=6.3*2.5mm^2, http://cdn-reichelt.de/documents/datenblatt/B400/1_4W%23YAG.pdf +Resistor Axial_DIN0207 series Axial Vertical pin pitch 5.08mm 0.25W = 1/4W length 6.3mm diameter 2.5mm +0 +2 +2 +Resistor_THT +R_Axial_DIN0207_L6.3mm_D2.5mm_P7.62mm_Horizontal +Resistor, Axial_DIN0207 series, Axial, Horizontal, pin pitch=7.62mm, 0.25W = 1/4W, length*diameter=6.3*2.5mm^2, http://cdn-reichelt.de/documents/datenblatt/B400/1_4W%23YAG.pdf +Resistor Axial_DIN0207 series Axial Horizontal pin pitch 7.62mm 0.25W = 1/4W length 6.3mm diameter 2.5mm +0 +2 +2 +Resistor_THT +R_Axial_DIN0207_L6.3mm_D2.5mm_P10.16mm_Horizontal +Resistor, Axial_DIN0207 series, Axial, Horizontal, pin pitch=10.16mm, 0.25W = 1/4W, length*diameter=6.3*2.5mm^2, http://cdn-reichelt.de/documents/datenblatt/B400/1_4W%23YAG.pdf +Resistor Axial_DIN0207 series Axial Horizontal pin pitch 10.16mm 0.25W = 1/4W length 6.3mm diameter 2.5mm +0 +2 +2 +Resistor_THT +R_Axial_DIN0207_L6.3mm_D2.5mm_P15.24mm_Horizontal +Resistor, Axial_DIN0207 series, Axial, Horizontal, pin pitch=15.24mm, 0.25W = 1/4W, length*diameter=6.3*2.5mm^2, http://cdn-reichelt.de/documents/datenblatt/B400/1_4W%23YAG.pdf +Resistor Axial_DIN0207 series Axial Horizontal pin pitch 15.24mm 0.25W = 1/4W length 6.3mm diameter 2.5mm +0 +2 +2 +Resistor_THT +R_Axial_DIN0309_L9.0mm_D3.2mm_P2.54mm_Vertical +Resistor, Axial_DIN0309 series, Axial, Vertical, pin pitch=2.54mm, 0.5W = 1/2W, length*diameter=9*3.2mm^2, http://cdn-reichelt.de/documents/datenblatt/B400/1_4W%23YAG.pdf +Resistor Axial_DIN0309 series Axial Vertical pin pitch 2.54mm 0.5W = 1/2W length 9mm diameter 3.2mm +0 +2 +2 +Resistor_THT +R_Axial_DIN0309_L9.0mm_D3.2mm_P5.08mm_Vertical +Resistor, Axial_DIN0309 series, Axial, Vertical, pin pitch=5.08mm, 0.5W = 1/2W, length*diameter=9*3.2mm^2, http://cdn-reichelt.de/documents/datenblatt/B400/1_4W%23YAG.pdf +Resistor Axial_DIN0309 series Axial Vertical pin pitch 5.08mm 0.5W = 1/2W length 9mm diameter 3.2mm +0 +2 +2 +Resistor_THT +R_Axial_DIN0309_L9.0mm_D3.2mm_P12.70mm_Horizontal +Resistor, Axial_DIN0309 series, Axial, Horizontal, pin pitch=12.7mm, 0.5W = 1/2W, length*diameter=9*3.2mm^2, http://cdn-reichelt.de/documents/datenblatt/B400/1_4W%23YAG.pdf +Resistor Axial_DIN0309 series Axial Horizontal pin pitch 12.7mm 0.5W = 1/2W length 9mm diameter 3.2mm +0 +2 +2 +Resistor_THT +R_Axial_DIN0309_L9.0mm_D3.2mm_P15.24mm_Horizontal +Resistor, Axial_DIN0309 series, Axial, Horizontal, pin pitch=15.24mm, 0.5W = 1/2W, length*diameter=9*3.2mm^2, http://cdn-reichelt.de/documents/datenblatt/B400/1_4W%23YAG.pdf +Resistor Axial_DIN0309 series Axial Horizontal pin pitch 15.24mm 0.5W = 1/2W length 9mm diameter 3.2mm +0 +2 +2 +Resistor_THT +R_Axial_DIN0309_L9.0mm_D3.2mm_P20.32mm_Horizontal +Resistor, Axial_DIN0309 series, Axial, Horizontal, pin pitch=20.32mm, 0.5W = 1/2W, length*diameter=9*3.2mm^2, http://cdn-reichelt.de/documents/datenblatt/B400/1_4W%23YAG.pdf +Resistor Axial_DIN0309 series Axial Horizontal pin pitch 20.32mm 0.5W = 1/2W length 9mm diameter 3.2mm +0 +2 +2 +Resistor_THT +R_Axial_DIN0309_L9.0mm_D3.2mm_P25.40mm_Horizontal +Resistor, Axial_DIN0309 series, Axial, Horizontal, pin pitch=25.4mm, 0.5W = 1/2W, length*diameter=9*3.2mm^2, http://cdn-reichelt.de/documents/datenblatt/B400/1_4W%23YAG.pdf +Resistor Axial_DIN0309 series Axial Horizontal pin pitch 25.4mm 0.5W = 1/2W length 9mm diameter 3.2mm +0 +2 +2 +Resistor_THT +R_Axial_DIN0411_L9.9mm_D3.6mm_P5.08mm_Vertical +Resistor, Axial_DIN0411 series, Axial, Vertical, pin pitch=5.08mm, 1W, length*diameter=9.9*3.6mm^2 +Resistor Axial_DIN0411 series Axial Vertical pin pitch 5.08mm 1W length 9.9mm diameter 3.6mm +0 +2 +2 +Resistor_THT +R_Axial_DIN0411_L9.9mm_D3.6mm_P7.62mm_Vertical +Resistor, Axial_DIN0411 series, Axial, Vertical, pin pitch=7.62mm, 1W, length*diameter=9.9*3.6mm^2 +Resistor Axial_DIN0411 series Axial Vertical pin pitch 7.62mm 1W length 9.9mm diameter 3.6mm +0 +2 +2 +Resistor_THT +R_Axial_DIN0411_L9.9mm_D3.6mm_P12.70mm_Horizontal +Resistor, Axial_DIN0411 series, Axial, Horizontal, pin pitch=12.7mm, 1W, length*diameter=9.9*3.6mm^2 +Resistor Axial_DIN0411 series Axial Horizontal pin pitch 12.7mm 1W length 9.9mm diameter 3.6mm +0 +2 +2 +Resistor_THT +R_Axial_DIN0411_L9.9mm_D3.6mm_P15.24mm_Horizontal +Resistor, Axial_DIN0411 series, Axial, Horizontal, pin pitch=15.24mm, 1W, length*diameter=9.9*3.6mm^2 +Resistor Axial_DIN0411 series Axial Horizontal pin pitch 15.24mm 1W length 9.9mm diameter 3.6mm +0 +2 +2 +Resistor_THT +R_Axial_DIN0411_L9.9mm_D3.6mm_P20.32mm_Horizontal +Resistor, Axial_DIN0411 series, Axial, Horizontal, pin pitch=20.32mm, 1W, length*diameter=9.9*3.6mm^2 +Resistor Axial_DIN0411 series Axial Horizontal pin pitch 20.32mm 1W length 9.9mm diameter 3.6mm +0 +2 +2 +Resistor_THT +R_Axial_DIN0411_L9.9mm_D3.6mm_P25.40mm_Horizontal +Resistor, Axial_DIN0411 series, Axial, Horizontal, pin pitch=25.4mm, 1W, length*diameter=9.9*3.6mm^2 +Resistor Axial_DIN0411 series Axial Horizontal pin pitch 25.4mm 1W length 9.9mm diameter 3.6mm +0 +2 +2 +Resistor_THT +R_Axial_DIN0414_L11.9mm_D4.5mm_P5.08mm_Vertical +Resistor, Axial_DIN0414 series, Axial, Vertical, pin pitch=5.08mm, 2W, length*diameter=11.9*4.5mm^2, http://www.vishay.com/docs/20128/wkxwrx.pdf +Resistor Axial_DIN0414 series Axial Vertical pin pitch 5.08mm 2W length 11.9mm diameter 4.5mm +0 +2 +2 +Resistor_THT +R_Axial_DIN0414_L11.9mm_D4.5mm_P7.62mm_Vertical +Resistor, Axial_DIN0414 series, Axial, Vertical, pin pitch=7.62mm, 2W, length*diameter=11.9*4.5mm^2, http://www.vishay.com/docs/20128/wkxwrx.pdf +Resistor Axial_DIN0414 series Axial Vertical pin pitch 7.62mm 2W length 11.9mm diameter 4.5mm +0 +2 +2 +Resistor_THT +R_Axial_DIN0414_L11.9mm_D4.5mm_P15.24mm_Horizontal +Resistor, Axial_DIN0414 series, Axial, Horizontal, pin pitch=15.24mm, 2W, length*diameter=11.9*4.5mm^2, http://www.vishay.com/docs/20128/wkxwrx.pdf +Resistor Axial_DIN0414 series Axial Horizontal pin pitch 15.24mm 2W length 11.9mm diameter 4.5mm +0 +2 +2 +Resistor_THT +R_Axial_DIN0414_L11.9mm_D4.5mm_P20.32mm_Horizontal +Resistor, Axial_DIN0414 series, Axial, Horizontal, pin pitch=20.32mm, 2W, length*diameter=11.9*4.5mm^2, http://www.vishay.com/docs/20128/wkxwrx.pdf +Resistor Axial_DIN0414 series Axial Horizontal pin pitch 20.32mm 2W length 11.9mm diameter 4.5mm +0 +2 +2 +Resistor_THT +R_Axial_DIN0414_L11.9mm_D4.5mm_P25.40mm_Horizontal +Resistor, Axial_DIN0414 series, Axial, Horizontal, pin pitch=25.4mm, 2W, length*diameter=11.9*4.5mm^2, http://www.vishay.com/docs/20128/wkxwrx.pdf +Resistor Axial_DIN0414 series Axial Horizontal pin pitch 25.4mm 2W length 11.9mm diameter 4.5mm +0 +2 +2 +Resistor_THT +R_Axial_DIN0516_L15.5mm_D5.0mm_P5.08mm_Vertical +Resistor, Axial_DIN0516 series, Axial, Vertical, pin pitch=5.08mm, 2W, length*diameter=15.5*5mm^2, http://cdn-reichelt.de/documents/datenblatt/B400/1_4W%23YAG.pdf +Resistor Axial_DIN0516 series Axial Vertical pin pitch 5.08mm 2W length 15.5mm diameter 5mm +0 +2 +2 +Resistor_THT +R_Axial_DIN0516_L15.5mm_D5.0mm_P7.62mm_Vertical +Resistor, Axial_DIN0516 series, Axial, Vertical, pin pitch=7.62mm, 2W, length*diameter=15.5*5mm^2, http://cdn-reichelt.de/documents/datenblatt/B400/1_4W%23YAG.pdf +Resistor Axial_DIN0516 series Axial Vertical pin pitch 7.62mm 2W length 15.5mm diameter 5mm +0 +2 +2 +Resistor_THT +R_Axial_DIN0516_L15.5mm_D5.0mm_P20.32mm_Horizontal +Resistor, Axial_DIN0516 series, Axial, Horizontal, pin pitch=20.32mm, 2W, length*diameter=15.5*5mm^2, http://cdn-reichelt.de/documents/datenblatt/B400/1_4W%23YAG.pdf +Resistor Axial_DIN0516 series Axial Horizontal pin pitch 20.32mm 2W length 15.5mm diameter 5mm +0 +2 +2 +Resistor_THT +R_Axial_DIN0516_L15.5mm_D5.0mm_P25.40mm_Horizontal +Resistor, Axial_DIN0516 series, Axial, Horizontal, pin pitch=25.4mm, 2W, length*diameter=15.5*5mm^2, http://cdn-reichelt.de/documents/datenblatt/B400/1_4W%23YAG.pdf +Resistor Axial_DIN0516 series Axial Horizontal pin pitch 25.4mm 2W length 15.5mm diameter 5mm +0 +2 +2 +Resistor_THT +R_Axial_DIN0516_L15.5mm_D5.0mm_P30.48mm_Horizontal +Resistor, Axial_DIN0516 series, Axial, Horizontal, pin pitch=30.48mm, 2W, length*diameter=15.5*5mm^2, http://cdn-reichelt.de/documents/datenblatt/B400/1_4W%23YAG.pdf +Resistor Axial_DIN0516 series Axial Horizontal pin pitch 30.48mm 2W length 15.5mm diameter 5mm +0 +2 +2 +Resistor_THT +R_Axial_DIN0614_L14.3mm_D5.7mm_P5.08mm_Vertical +Resistor, Axial_DIN0614 series, Axial, Vertical, pin pitch=5.08mm, 1.5W, length*diameter=14.3*5.7mm^2 +Resistor Axial_DIN0614 series Axial Vertical pin pitch 5.08mm 1.5W length 14.3mm diameter 5.7mm +0 +2 +2 +Resistor_THT +R_Axial_DIN0614_L14.3mm_D5.7mm_P7.62mm_Vertical +Resistor, Axial_DIN0614 series, Axial, Vertical, pin pitch=7.62mm, 1.5W, length*diameter=14.3*5.7mm^2 +Resistor Axial_DIN0614 series Axial Vertical pin pitch 7.62mm 1.5W length 14.3mm diameter 5.7mm +0 +2 +2 +Resistor_THT +R_Axial_DIN0614_L14.3mm_D5.7mm_P15.24mm_Horizontal +Resistor, Axial_DIN0614 series, Axial, Horizontal, pin pitch=15.24mm, 1.5W, length*diameter=14.3*5.7mm^2 +Resistor Axial_DIN0614 series Axial Horizontal pin pitch 15.24mm 1.5W length 14.3mm diameter 5.7mm +0 +2 +2 +Resistor_THT +R_Axial_DIN0614_L14.3mm_D5.7mm_P20.32mm_Horizontal +Resistor, Axial_DIN0614 series, Axial, Horizontal, pin pitch=20.32mm, 1.5W, length*diameter=14.3*5.7mm^2 +Resistor Axial_DIN0614 series Axial Horizontal pin pitch 20.32mm 1.5W length 14.3mm diameter 5.7mm +0 +2 +2 +Resistor_THT +R_Axial_DIN0614_L14.3mm_D5.7mm_P25.40mm_Horizontal +Resistor, Axial_DIN0614 series, Axial, Horizontal, pin pitch=25.4mm, 1.5W, length*diameter=14.3*5.7mm^2 +Resistor Axial_DIN0614 series Axial Horizontal pin pitch 25.4mm 1.5W length 14.3mm diameter 5.7mm +0 +2 +2 +Resistor_THT +R_Axial_DIN0617_L17.0mm_D6.0mm_P5.08mm_Vertical +Resistor, Axial_DIN0617 series, Axial, Vertical, pin pitch=5.08mm, 2W, length*diameter=17*6mm^2, http://www.vishay.com/docs/20128/wkxwrx.pdf +Resistor Axial_DIN0617 series Axial Vertical pin pitch 5.08mm 2W length 17mm diameter 6mm +0 +2 +2 +Resistor_THT +R_Axial_DIN0617_L17.0mm_D6.0mm_P7.62mm_Vertical +Resistor, Axial_DIN0617 series, Axial, Vertical, pin pitch=7.62mm, 2W, length*diameter=17*6mm^2, http://www.vishay.com/docs/20128/wkxwrx.pdf +Resistor Axial_DIN0617 series Axial Vertical pin pitch 7.62mm 2W length 17mm diameter 6mm +0 +2 +2 +Resistor_THT +R_Axial_DIN0617_L17.0mm_D6.0mm_P20.32mm_Horizontal +Resistor, Axial_DIN0617 series, Axial, Horizontal, pin pitch=20.32mm, 2W, length*diameter=17*6mm^2, http://www.vishay.com/docs/20128/wkxwrx.pdf +Resistor Axial_DIN0617 series Axial Horizontal pin pitch 20.32mm 2W length 17mm diameter 6mm +0 +2 +2 +Resistor_THT +R_Axial_DIN0617_L17.0mm_D6.0mm_P25.40mm_Horizontal +Resistor, Axial_DIN0617 series, Axial, Horizontal, pin pitch=25.4mm, 2W, length*diameter=17*6mm^2, http://www.vishay.com/docs/20128/wkxwrx.pdf +Resistor Axial_DIN0617 series Axial Horizontal pin pitch 25.4mm 2W length 17mm diameter 6mm +0 +2 +2 +Resistor_THT +R_Axial_DIN0617_L17.0mm_D6.0mm_P30.48mm_Horizontal +Resistor, Axial_DIN0617 series, Axial, Horizontal, pin pitch=30.48mm, 2W, length*diameter=17*6mm^2, http://www.vishay.com/docs/20128/wkxwrx.pdf +Resistor Axial_DIN0617 series Axial Horizontal pin pitch 30.48mm 2W length 17mm diameter 6mm +0 +2 +2 +Resistor_THT +R_Axial_DIN0918_L18.0mm_D9.0mm_P7.62mm_Vertical +Resistor, Axial_DIN0918 series, Axial, Vertical, pin pitch=7.62mm, 4W, length*diameter=18*9mm^2 +Resistor Axial_DIN0918 series Axial Vertical pin pitch 7.62mm 4W length 18mm diameter 9mm +0 +2 +2 +Resistor_THT +R_Axial_DIN0918_L18.0mm_D9.0mm_P22.86mm_Horizontal +Resistor, Axial_DIN0918 series, Axial, Horizontal, pin pitch=22.86mm, 4W, length*diameter=18*9mm^2 +Resistor Axial_DIN0918 series Axial Horizontal pin pitch 22.86mm 4W length 18mm diameter 9mm +0 +2 +2 +Resistor_THT +R_Axial_DIN0918_L18.0mm_D9.0mm_P25.40mm_Horizontal +Resistor, Axial_DIN0918 series, Axial, Horizontal, pin pitch=25.4mm, 4W, length*diameter=18*9mm^2 +Resistor Axial_DIN0918 series Axial Horizontal pin pitch 25.4mm 4W length 18mm diameter 9mm +0 +2 +2 +Resistor_THT +R_Axial_DIN0918_L18.0mm_D9.0mm_P30.48mm_Horizontal +Resistor, Axial_DIN0918 series, Axial, Horizontal, pin pitch=30.48mm, 4W, length*diameter=18*9mm^2 +Resistor Axial_DIN0918 series Axial Horizontal pin pitch 30.48mm 4W length 18mm diameter 9mm +0 +2 +2 +Resistor_THT +R_Axial_DIN0922_L20.0mm_D9.0mm_P7.62mm_Vertical +Resistor, Axial_DIN0922 series, Axial, Vertical, pin pitch=7.62mm, 5W, length*diameter=20*9mm^2, http://www.vishay.com/docs/20128/wkxwrx.pdf +Resistor Axial_DIN0922 series Axial Vertical pin pitch 7.62mm 5W length 20mm diameter 9mm +0 +2 +2 +Resistor_THT +R_Axial_DIN0922_L20.0mm_D9.0mm_P25.40mm_Horizontal +Resistor, Axial_DIN0922 series, Axial, Horizontal, pin pitch=25.4mm, 5W, length*diameter=20*9mm^2, http://www.vishay.com/docs/20128/wkxwrx.pdf +Resistor Axial_DIN0922 series Axial Horizontal pin pitch 25.4mm 5W length 20mm diameter 9mm +0 +2 +2 +Resistor_THT +R_Axial_DIN0922_L20.0mm_D9.0mm_P30.48mm_Horizontal +Resistor, Axial_DIN0922 series, Axial, Horizontal, pin pitch=30.48mm, 5W, length*diameter=20*9mm^2, http://www.vishay.com/docs/20128/wkxwrx.pdf +Resistor Axial_DIN0922 series Axial Horizontal pin pitch 30.48mm 5W length 20mm diameter 9mm +0 +2 +2 +Resistor_THT +R_Axial_Power_L20.0mm_W6.4mm_P5.08mm_Vertical +Resistor, Axial_Power series, Axial, Vertical, pin pitch=5.08mm, 4W, length*width*height=20*6.4*6.4mm^3, http://cdn-reichelt.de/documents/datenblatt/B400/5WAXIAL_9WAXIAL_11WAXIAL_17WAXIAL%23YAG.pdf +Resistor Axial_Power series Axial Vertical pin pitch 5.08mm 4W length 20mm width 6.4mm height 6.4mm +0 +2 +2 +Resistor_THT +R_Axial_Power_L20.0mm_W6.4mm_P7.62mm_Vertical +Resistor, Axial_Power series, Axial, Vertical, pin pitch=7.62mm, 4W, length*width*height=20*6.4*6.4mm^3, http://cdn-reichelt.de/documents/datenblatt/B400/5WAXIAL_9WAXIAL_11WAXIAL_17WAXIAL%23YAG.pdf +Resistor Axial_Power series Axial Vertical pin pitch 7.62mm 4W length 20mm width 6.4mm height 6.4mm +0 +2 +2 +Resistor_THT +R_Axial_Power_L20.0mm_W6.4mm_P22.40mm +Resistor, Axial_Power series, Box, pin pitch=22.4mm, 4W, length*width*height=20*6.4*6.4mm^3, http://cdn-reichelt.de/documents/datenblatt/B400/5WAXIAL_9WAXIAL_11WAXIAL_17WAXIAL%23YAG.pdf +Resistor Axial_Power series Box pin pitch 22.4mm 4W length 20mm width 6.4mm height 6.4mm +0 +2 +2 +Resistor_THT +R_Axial_Power_L20.0mm_W6.4mm_P25.40mm +Resistor, Axial_Power series, Box, pin pitch=25.4mm, 4W, length*width*height=20*6.4*6.4mm^3, http://cdn-reichelt.de/documents/datenblatt/B400/5WAXIAL_9WAXIAL_11WAXIAL_17WAXIAL%23YAG.pdf +Resistor Axial_Power series Box pin pitch 25.4mm 4W length 20mm width 6.4mm height 6.4mm +0 +2 +2 +Resistor_THT +R_Axial_Power_L20.0mm_W6.4mm_P30.48mm +Resistor, Axial_Power series, Box, pin pitch=30.48mm, 4W, length*width*height=20*6.4*6.4mm^3, http://cdn-reichelt.de/documents/datenblatt/B400/5WAXIAL_9WAXIAL_11WAXIAL_17WAXIAL%23YAG.pdf +Resistor Axial_Power series Box pin pitch 30.48mm 4W length 20mm width 6.4mm height 6.4mm +0 +2 +2 +Resistor_THT +R_Axial_Power_L25.0mm_W6.4mm_P27.94mm +Resistor, Axial_Power series, Box, pin pitch=27.94mm, 5W, length*width*height=25*6.4*6.4mm^3, http://cdn-reichelt.de/documents/datenblatt/B400/5WAXIAL_9WAXIAL_11WAXIAL_17WAXIAL%23YAG.pdf +Resistor Axial_Power series Box pin pitch 27.94mm 5W length 25mm width 6.4mm height 6.4mm +0 +2 +2 +Resistor_THT +R_Axial_Power_L25.0mm_W6.4mm_P30.48mm +Resistor, Axial_Power series, Box, pin pitch=30.48mm, 5W, length*width*height=25*6.4*6.4mm^3, http://cdn-reichelt.de/documents/datenblatt/B400/5WAXIAL_9WAXIAL_11WAXIAL_17WAXIAL%23YAG.pdf +Resistor Axial_Power series Box pin pitch 30.48mm 5W length 25mm width 6.4mm height 6.4mm +0 +2 +2 +Resistor_THT +R_Axial_Power_L25.0mm_W9.0mm_P7.62mm_Vertical +Resistor, Axial_Power series, Axial, Vertical, pin pitch=7.62mm, 7W, length*width*height=25*9*9mm^3, http://cdn-reichelt.de/documents/datenblatt/B400/5WAXIAL_9WAXIAL_11WAXIAL_17WAXIAL%23YAG.pdf +Resistor Axial_Power series Axial Vertical pin pitch 7.62mm 7W length 25mm width 9mm height 9mm +0 +2 +2 +Resistor_THT +R_Axial_Power_L25.0mm_W9.0mm_P10.16mm_Vertical +Resistor, Axial_Power series, Axial, Vertical, pin pitch=10.16mm, 7W, length*width*height=25*9*9mm^3, http://cdn-reichelt.de/documents/datenblatt/B400/5WAXIAL_9WAXIAL_11WAXIAL_17WAXIAL%23YAG.pdf +Resistor Axial_Power series Axial Vertical pin pitch 10.16mm 7W length 25mm width 9mm height 9mm +0 +2 +2 +Resistor_THT +R_Axial_Power_L25.0mm_W9.0mm_P27.94mm +Resistor, Axial_Power series, Box, pin pitch=27.94mm, 7W, length*width*height=25*9*9mm^3, http://cdn-reichelt.de/documents/datenblatt/B400/5WAXIAL_9WAXIAL_11WAXIAL_17WAXIAL%23YAG.pdf +Resistor Axial_Power series Box pin pitch 27.94mm 7W length 25mm width 9mm height 9mm +0 +2 +2 +Resistor_THT +R_Axial_Power_L25.0mm_W9.0mm_P30.48mm +Resistor, Axial_Power series, Box, pin pitch=30.48mm, 7W, length*width*height=25*9*9mm^3, http://cdn-reichelt.de/documents/datenblatt/B400/5WAXIAL_9WAXIAL_11WAXIAL_17WAXIAL%23YAG.pdf +Resistor Axial_Power series Box pin pitch 30.48mm 7W length 25mm width 9mm height 9mm +0 +2 +2 +Resistor_THT +R_Axial_Power_L38.0mm_W6.4mm_P40.64mm +Resistor, Axial_Power series, Box, pin pitch=40.64mm, 7W, length*width*height=38*6.4*6.4mm^3, http://cdn-reichelt.de/documents/datenblatt/B400/5WAXIAL_9WAXIAL_11WAXIAL_17WAXIAL%23YAG.pdf +Resistor Axial_Power series Box pin pitch 40.64mm 7W length 38mm width 6.4mm height 6.4mm +0 +2 +2 +Resistor_THT +R_Axial_Power_L38.0mm_W6.4mm_P45.72mm +Resistor, Axial_Power series, Box, pin pitch=45.72mm, 7W, length*width*height=38*6.4*6.4mm^3, http://cdn-reichelt.de/documents/datenblatt/B400/5WAXIAL_9WAXIAL_11WAXIAL_17WAXIAL%23YAG.pdf +Resistor Axial_Power series Box pin pitch 45.72mm 7W length 38mm width 6.4mm height 6.4mm +0 +2 +2 +Resistor_THT +R_Axial_Power_L38.0mm_W9.0mm_P40.64mm +Resistor, Axial_Power series, Box, pin pitch=40.64mm, 9W, length*width*height=38*9*9mm^3, http://cdn-reichelt.de/documents/datenblatt/B400/5WAXIAL_9WAXIAL_11WAXIAL_17WAXIAL%23YAG.pdf +Resistor Axial_Power series Box pin pitch 40.64mm 9W length 38mm width 9mm height 9mm +0 +2 +2 +Resistor_THT +R_Axial_Power_L38.0mm_W9.0mm_P45.72mm +Resistor, Axial_Power series, Box, pin pitch=45.72mm, 9W, length*width*height=38*9*9mm^3, http://cdn-reichelt.de/documents/datenblatt/B400/5WAXIAL_9WAXIAL_11WAXIAL_17WAXIAL%23YAG.pdf +Resistor Axial_Power series Box pin pitch 45.72mm 9W length 38mm width 9mm height 9mm +0 +2 +2 +Resistor_THT +R_Axial_Power_L48.0mm_W12.5mm_P7.62mm_Vertical +Resistor, Axial_Power series, Axial, Vertical, pin pitch=7.62mm, 15W, length*width*height=48*12.5*12.5mm^3, http://cdn-reichelt.de/documents/datenblatt/B400/5WAXIAL_9WAXIAL_11WAXIAL_17WAXIAL%23YAG.pdf +Resistor Axial_Power series Axial Vertical pin pitch 7.62mm 15W length 48mm width 12.5mm height 12.5mm +0 +2 +2 +Resistor_THT +R_Axial_Power_L48.0mm_W12.5mm_P10.16mm_Vertical +Resistor, Axial_Power series, Axial, Vertical, pin pitch=10.16mm, 15W, length*width*height=48*12.5*12.5mm^3, http://cdn-reichelt.de/documents/datenblatt/B400/5WAXIAL_9WAXIAL_11WAXIAL_17WAXIAL%23YAG.pdf +Resistor Axial_Power series Axial Vertical pin pitch 10.16mm 15W length 48mm width 12.5mm height 12.5mm +0 +2 +2 +Resistor_THT +R_Axial_Power_L48.0mm_W12.5mm_P55.88mm +Resistor, Axial_Power series, Box, pin pitch=55.88mm, 15W, length*width*height=48*12.5*12.5mm^3, http://cdn-reichelt.de/documents/datenblatt/B400/5WAXIAL_9WAXIAL_11WAXIAL_17WAXIAL%23YAG.pdf +Resistor Axial_Power series Box pin pitch 55.88mm 15W length 48mm width 12.5mm height 12.5mm +0 +2 +2 +Resistor_THT +R_Axial_Power_L48.0mm_W12.5mm_P60.96mm +Resistor, Axial_Power series, Box, pin pitch=60.96mm, 15W, length*width*height=48*12.5*12.5mm^3, http://cdn-reichelt.de/documents/datenblatt/B400/5WAXIAL_9WAXIAL_11WAXIAL_17WAXIAL%23YAG.pdf +Resistor Axial_Power series Box pin pitch 60.96mm 15W length 48mm width 12.5mm height 12.5mm +0 +2 +2 +Resistor_THT +R_Axial_Power_L50.0mm_W9.0mm_P55.88mm +Resistor, Axial_Power series, Box, pin pitch=55.88mm, 11W, length*width*height=50*9*9mm^3, http://cdn-reichelt.de/documents/datenblatt/B400/5WAXIAL_9WAXIAL_11WAXIAL_17WAXIAL%23YAG.pdf +Resistor Axial_Power series Box pin pitch 55.88mm 11W length 50mm width 9mm height 9mm +0 +2 +2 +Resistor_THT +R_Axial_Power_L50.0mm_W9.0mm_P60.96mm +Resistor, Axial_Power series, Box, pin pitch=60.96mm, 11W, length*width*height=50*9*9mm^3, http://cdn-reichelt.de/documents/datenblatt/B400/5WAXIAL_9WAXIAL_11WAXIAL_17WAXIAL%23YAG.pdf +Resistor Axial_Power series Box pin pitch 60.96mm 11W length 50mm width 9mm height 9mm +0 +2 +2 +Resistor_THT +R_Axial_Power_L60.0mm_W14.0mm_P10.16mm_Vertical +Resistor, Axial_Power series, Axial, Vertical, pin pitch=10.16mm, 25W, length*width*height=60*14*14mm^3, http://cdn-reichelt.de/documents/datenblatt/B400/5WAXIAL_9WAXIAL_11WAXIAL_17WAXIAL%23YAG.pdf +Resistor Axial_Power series Axial Vertical pin pitch 10.16mm 25W length 60mm width 14mm height 14mm +0 +2 +2 +Resistor_THT +R_Axial_Power_L60.0mm_W14.0mm_P66.04mm +Resistor, Axial_Power series, Box, pin pitch=66.04mm, 25W, length*width*height=60*14*14mm^3, http://cdn-reichelt.de/documents/datenblatt/B400/5WAXIAL_9WAXIAL_11WAXIAL_17WAXIAL%23YAG.pdf +Resistor Axial_Power series Box pin pitch 66.04mm 25W length 60mm width 14mm height 14mm +0 +2 +2 +Resistor_THT +R_Axial_Power_L60.0mm_W14.0mm_P71.12mm +Resistor, Axial_Power series, Box, pin pitch=71.12mm, 25W, length*width*height=60*14*14mm^3, http://cdn-reichelt.de/documents/datenblatt/B400/5WAXIAL_9WAXIAL_11WAXIAL_17WAXIAL%23YAG.pdf +Resistor Axial_Power series Box pin pitch 71.12mm 25W length 60mm width 14mm height 14mm +0 +2 +2 +Resistor_THT +R_Axial_Power_L75.0mm_W9.0mm_P81.28mm +Resistor, Axial_Power series, Box, pin pitch=81.28mm, 17W, length*width*height=75*9*9mm^3, http://cdn-reichelt.de/documents/datenblatt/B400/5WAXIAL_9WAXIAL_11WAXIAL_17WAXIAL%23YAG.pdf +Resistor Axial_Power series Box pin pitch 81.28mm 17W length 75mm width 9mm height 9mm +0 +2 +2 +Resistor_THT +R_Axial_Power_L75.0mm_W9.0mm_P86.36mm +Resistor, Axial_Power series, Box, pin pitch=86.36mm, 17W, length*width*height=75*9*9mm^3, http://cdn-reichelt.de/documents/datenblatt/B400/5WAXIAL_9WAXIAL_11WAXIAL_17WAXIAL%23YAG.pdf +Resistor Axial_Power series Box pin pitch 86.36mm 17W length 75mm width 9mm height 9mm +0 +2 +2 +Resistor_THT +R_Axial_Shunt_L22.2mm_W8.0mm_PS14.30mm_P25.40mm +Resistor, Axial_Shunt series, Box, pin pitch=25.4mm, 3W, length*width*height=22.2*8*8mm^3, shunt pin pitch = 14.30mm, http://www.vishay.com/docs/30217/cpsl.pdf +Resistor Axial_Shunt series Box pin pitch 25.4mm 3W length 22.2mm width 8mm height 8mm shunt pin pitch 14.30mm +0 +4 +4 +Resistor_THT +R_Axial_Shunt_L22.2mm_W9.5mm_PS14.30mm_P25.40mm +Resistor, Axial_Shunt series, Box, pin pitch=25.4mm, 5W, length*width*height=22.2*9.5*9.5mm^3, shunt pin pitch = 14.30mm, http://www.vishay.com/docs/30217/cpsl.pdf +Resistor Axial_Shunt series Box pin pitch 25.4mm 5W length 22.2mm width 9.5mm height 9.5mm shunt pin pitch 14.30mm +0 +4 +4 +Resistor_THT +R_Axial_Shunt_L35.3mm_W9.5mm_PS25.40mm_P38.10mm +Resistor, Axial_Shunt series, Box, pin pitch=38.1mm, 7W, length*width*height=35.3*9.5*9.5mm^3, shunt pin pitch = 25.40mm, http://www.vishay.com/docs/30217/cpsl.pdf +Resistor Axial_Shunt series Box pin pitch 38.1mm 7W length 35.3mm width 9.5mm height 9.5mm shunt pin pitch 25.40mm +0 +4 +4 +Resistor_THT +R_Axial_Shunt_L47.6mm_W9.5mm_PS34.93mm_P50.80mm +Resistor, Axial_Shunt series, Box, pin pitch=50.8mm, 10W, length*width*height=47.6*9.5*9.5mm^3, shunt pin pitch = 34.93mm, http://www.vishay.com/docs/30217/cpsl.pdf +Resistor Axial_Shunt series Box pin pitch 50.8mm 10W length 47.6mm width 9.5mm height 9.5mm shunt pin pitch 34.93mm +0 +4 +4 +Resistor_THT +R_Axial_Shunt_L47.6mm_W12.7mm_PS34.93mm_P50.80mm +Resistor, Axial_Shunt series, Box, pin pitch=50.8mm, 15W, length*width*height=47.6*12.7*12.7mm^3, shunt pin pitch = 34.93mm, http://www.vishay.com/docs/30217/cpsl.pdf +Resistor Axial_Shunt series Box pin pitch 50.8mm 15W length 47.6mm width 12.7mm height 12.7mm shunt pin pitch 34.93mm +0 +4 +4 +Resistor_THT +R_Bare_Metal_Element_L12.4mm_W4.8mm_P11.40mm +Resistor, Bare_Metal_Element series, Bare Metal Strip/Wire, Horizontal, pin pitch=11.4mm, 1W, length*width=12.4*4.8mm^2, https://www.bourns.com/pdfs/PWR4412-2S.pdf +Resistor Bare_Metal_Element series Bare Metal Strip Wire Horizontal pin pitch 11.4mm 1W length 12.4mm width 4.8mm +0 +2 +2 +Resistor_THT +R_Bare_Metal_Element_L16.3mm_W4.8mm_P15.30mm +Resistor, Bare_Metal_Element series, Bare Metal Strip/Wire, Horizontal, pin pitch=15.3mm, 3W, length*width=16.3*4.8mm^2, https://www.bourns.com/pdfs/PWR4412-2S.pdf +Resistor Bare_Metal_Element series Bare Metal Strip Wire Horizontal pin pitch 15.3mm 3W length 16.3mm width 4.8mm +0 +2 +2 +Resistor_THT +R_Bare_Metal_Element_L21.3mm_W4.8mm_P20.30mm +Resistor, Bare_Metal_Element series, Bare Metal Strip/Wire, Horizontal, pin pitch=20.3mm, 5W, length*width=21.3*4.8mm^2, https://www.bourns.com/pdfs/PWR4412-2S.pdf +Resistor Bare_Metal_Element series Bare Metal Strip Wire Horizontal pin pitch 20.3mm 5W length 21.3mm width 4.8mm +0 +2 +2 +Resistor_THT +R_Box_L8.4mm_W2.5mm_P5.08mm +Resistor, Box series, Radial, pin pitch=5.08mm, 0.5W = 1/2W, length*width=8.38*2.54mm^2, http://www.vishay.com/docs/60051/cns020.pdf +Resistor Box series Radial pin pitch 5.08mm 0.5W = 1/2W length 8.38mm width 2.54mm +0 +2 +2 +Resistor_THT +R_Box_L13.0mm_W4.0mm_P9.00mm +Resistor, Box series, Radial, pin pitch=9.00mm, 2W, length*width=13.0*4.0mm^2, http://www.produktinfo.conrad.com/datenblaetter/425000-449999/443860-da-01-de-METALLBAND_WIDERSTAND_0_1_OHM_5W_5Pr.pdf +Resistor Box series Radial pin pitch 9.00mm 2W length 13.0mm width 4.0mm +0 +2 +2 +Resistor_THT +R_Box_L14.0mm_W5.0mm_P9.00mm +Resistor, Box series, Radial, pin pitch=9.00mm, 5W, length*width=14.0*5.0mm^2, http://www.produktinfo.conrad.com/datenblaetter/425000-449999/443860-da-01-de-METALLBAND_WIDERSTAND_0_1_OHM_5W_5Pr.pdf +Resistor Box series Radial pin pitch 9.00mm 5W length 14.0mm width 5.0mm +0 +2 +2 +Resistor_THT +R_Box_L26.0mm_W5.0mm_P20.00mm +Resistor, Box series, Radial, pin pitch=20.00mm, 10W, length*width=26.0*5.0mm^2, http://www.produktinfo.conrad.com/datenblaetter/425000-449999/443860-da-01-de-METALLBAND_WIDERSTAND_0_1_OHM_5W_5Pr.pdf +Resistor Box series Radial pin pitch 20.00mm 10W length 26.0mm width 5.0mm +0 +2 +2 +Resistor_THT +R_Radial_Power_L7.0mm_W8.0mm_Px2.40mm_Py2.30mm +Resistor, Radial_Power series, Radial, pin pitch=2.40*2.30mm^2, 7W, length*width=7*8mm^2, http://www.vitrohm.com/content/files/vitrohm_series_kv_-_201601.pdf +Resistor Radial_Power series Radial pin pitch 2.40*2.30mm^2 7W length 7mm width 8mm +0 +2 +2 +Resistor_THT +R_Radial_Power_L9.0mm_W10.0mm_Px2.70mm_Py2.30mm +Resistor, Radial_Power series, Radial, pin pitch=2.70*2.30mm^2, 17W, length*width=9*10mm^2, http://www.vitrohm.com/content/files/vitrohm_series_kv_-_201601.pdf +Resistor Radial_Power series Radial pin pitch 2.70*2.30mm^2 17W length 9mm width 10mm +0 +2 +2 +Resistor_THT +R_Radial_Power_L11.0mm_W7.0mm_P5.00mm +Resistor, Radial_Power series, Radial, pin pitch=5.00mm, 2W, length*width=11.0*7.0mm^2, http://www.vishay.com/docs/30218/cpcx.pdf +Resistor Radial_Power series Radial pin pitch 5.00mm 2W length 11.0mm width 7.0mm +0 +2 +2 +Resistor_THT +R_Radial_Power_L12.0mm_W8.0mm_P5.00mm +Resistor, Radial_Power series, Radial, pin pitch=5.00mm, 3W, length*width=12.0*8.0mm^2, http://www.vishay.com/docs/30218/cpcx.pdf +Resistor Radial_Power series Radial pin pitch 5.00mm 3W length 12.0mm width 8.0mm +0 +2 +2 +Resistor_THT +R_Radial_Power_L13.0mm_W9.0mm_P5.00mm +Resistor, Radial_Power series, Radial, pin pitch=5.00mm, 7W, length*width=13.0*9.0mm^2, http://www.vishay.com/docs/30218/cpcx.pdf +Resistor Radial_Power series Radial pin pitch 5.00mm 7W length 13.0mm width 9.0mm +0 +2 +2 +Resistor_THT +R_Radial_Power_L16.1mm_W9.0mm_P7.37mm +Resistor, Radial_Power series, Radial, pin pitch=7.37mm, 10W, length*width=16.1*9mm^2, http://www.vishay.com/docs/30218/cpcx.pdf +Resistor Radial_Power series Radial pin pitch 7.37mm 10W length 16.1mm width 9mm +0 +2 +2 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_MKDS-1,5-2-5.08_1x02_P5.08mm_Horizontal +Terminal Block Phoenix MKDS-1,5-2-5.08, 2 pins, pitch 5.08mm, size 10.2x9.8mm^2, drill diamater 1.3mm, pad diameter 2.6mm, see http://www.farnell.com/datasheets/100425.pdf, script-generated using https://github.com/pointhi/kicad-footprint-generator/scripts/TerminalBlock_Phoenix +THT Terminal Block Phoenix MKDS-1,5-2-5.08 pitch 5.08mm size 10.2x9.8mm^2 drill 1.3mm pad 2.6mm +0 +2 +2 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_MKDS-1,5-2_1x02_P5.00mm_Horizontal +Terminal Block Phoenix MKDS-1,5-2, 2 pins, pitch 5mm, size 10x9.8mm^2, drill diamater 1.3mm, pad diameter 2.6mm, see http://www.farnell.com/datasheets/100425.pdf, script-generated using https://github.com/pointhi/kicad-footprint-generator/scripts/TerminalBlock_Phoenix +THT Terminal Block Phoenix MKDS-1,5-2 pitch 5mm size 10x9.8mm^2 drill 1.3mm pad 2.6mm +0 +2 +2 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_MKDS-1,5-3-5.08_1x03_P5.08mm_Horizontal +Terminal Block Phoenix MKDS-1,5-3-5.08, 3 pins, pitch 5.08mm, size 15.2x9.8mm^2, drill diamater 1.3mm, pad diameter 2.6mm, see http://www.farnell.com/datasheets/100425.pdf, script-generated using https://github.com/pointhi/kicad-footprint-generator/scripts/TerminalBlock_Phoenix +THT Terminal Block Phoenix MKDS-1,5-3-5.08 pitch 5.08mm size 15.2x9.8mm^2 drill 1.3mm pad 2.6mm +0 +3 +3 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_MKDS-1,5-3_1x03_P5.00mm_Horizontal +Terminal Block Phoenix MKDS-1,5-3, 3 pins, pitch 5mm, size 15x9.8mm^2, drill diamater 1.3mm, pad diameter 2.6mm, see http://www.farnell.com/datasheets/100425.pdf, script-generated using https://github.com/pointhi/kicad-footprint-generator/scripts/TerminalBlock_Phoenix +THT Terminal Block Phoenix MKDS-1,5-3 pitch 5mm size 15x9.8mm^2 drill 1.3mm pad 2.6mm +0 +3 +3 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_MKDS-1,5-4-5.08_1x04_P5.08mm_Horizontal +Terminal Block Phoenix MKDS-1,5-4-5.08, 4 pins, pitch 5.08mm, size 20.3x9.8mm^2, drill diamater 1.3mm, pad diameter 2.6mm, see http://www.farnell.com/datasheets/100425.pdf, script-generated using https://github.com/pointhi/kicad-footprint-generator/scripts/TerminalBlock_Phoenix +THT Terminal Block Phoenix MKDS-1,5-4-5.08 pitch 5.08mm size 20.3x9.8mm^2 drill 1.3mm pad 2.6mm +0 +4 +4 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_MKDS-1,5-4_1x04_P5.00mm_Horizontal +Terminal Block Phoenix MKDS-1,5-4, 4 pins, pitch 5mm, size 20x9.8mm^2, drill diamater 1.3mm, pad diameter 2.6mm, see http://www.farnell.com/datasheets/100425.pdf, script-generated using https://github.com/pointhi/kicad-footprint-generator/scripts/TerminalBlock_Phoenix +THT Terminal Block Phoenix MKDS-1,5-4 pitch 5mm size 20x9.8mm^2 drill 1.3mm pad 2.6mm +0 +4 +4 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_MKDS-1,5-5-5.08_1x05_P5.08mm_Horizontal +Terminal Block Phoenix MKDS-1,5-5-5.08, 5 pins, pitch 5.08mm, size 25.4x9.8mm^2, drill diamater 1.3mm, pad diameter 2.6mm, see http://www.farnell.com/datasheets/100425.pdf, script-generated using https://github.com/pointhi/kicad-footprint-generator/scripts/TerminalBlock_Phoenix +THT Terminal Block Phoenix MKDS-1,5-5-5.08 pitch 5.08mm size 25.4x9.8mm^2 drill 1.3mm pad 2.6mm +0 +5 +5 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_MKDS-1,5-5_1x05_P5.00mm_Horizontal +Terminal Block Phoenix MKDS-1,5-5, 5 pins, pitch 5mm, size 25x9.8mm^2, drill diamater 1.3mm, pad diameter 2.6mm, see http://www.farnell.com/datasheets/100425.pdf, script-generated using https://github.com/pointhi/kicad-footprint-generator/scripts/TerminalBlock_Phoenix +THT Terminal Block Phoenix MKDS-1,5-5 pitch 5mm size 25x9.8mm^2 drill 1.3mm pad 2.6mm +0 +5 +5 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_MKDS-1,5-6-5.08_1x06_P5.08mm_Horizontal +Terminal Block Phoenix MKDS-1,5-6-5.08, 6 pins, pitch 5.08mm, size 30.5x9.8mm^2, drill diamater 1.3mm, pad diameter 2.6mm, see http://www.farnell.com/datasheets/100425.pdf, script-generated using https://github.com/pointhi/kicad-footprint-generator/scripts/TerminalBlock_Phoenix +THT Terminal Block Phoenix MKDS-1,5-6-5.08 pitch 5.08mm size 30.5x9.8mm^2 drill 1.3mm pad 2.6mm +0 +6 +6 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_MKDS-1,5-6_1x06_P5.00mm_Horizontal +Terminal Block Phoenix MKDS-1,5-6, 6 pins, pitch 5mm, size 30x9.8mm^2, drill diamater 1.3mm, pad diameter 2.6mm, see http://www.farnell.com/datasheets/100425.pdf, script-generated using https://github.com/pointhi/kicad-footprint-generator/scripts/TerminalBlock_Phoenix +THT Terminal Block Phoenix MKDS-1,5-6 pitch 5mm size 30x9.8mm^2 drill 1.3mm pad 2.6mm +0 +6 +6 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_MKDS-1,5-7-5.08_1x07_P5.08mm_Horizontal +Terminal Block Phoenix MKDS-1,5-7-5.08, 7 pins, pitch 5.08mm, size 35.6x9.8mm^2, drill diamater 1.3mm, pad diameter 2.6mm, see http://www.farnell.com/datasheets/100425.pdf, script-generated using https://github.com/pointhi/kicad-footprint-generator/scripts/TerminalBlock_Phoenix +THT Terminal Block Phoenix MKDS-1,5-7-5.08 pitch 5.08mm size 35.6x9.8mm^2 drill 1.3mm pad 2.6mm +0 +7 +7 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_MKDS-1,5-7_1x07_P5.00mm_Horizontal +Terminal Block Phoenix MKDS-1,5-7, 7 pins, pitch 5mm, size 35x9.8mm^2, drill diamater 1.3mm, pad diameter 2.6mm, see http://www.farnell.com/datasheets/100425.pdf, script-generated using https://github.com/pointhi/kicad-footprint-generator/scripts/TerminalBlock_Phoenix +THT Terminal Block Phoenix MKDS-1,5-7 pitch 5mm size 35x9.8mm^2 drill 1.3mm pad 2.6mm +0 +7 +7 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_MKDS-1,5-8-5.08_1x08_P5.08mm_Horizontal +Terminal Block Phoenix MKDS-1,5-8-5.08, 8 pins, pitch 5.08mm, size 40.6x9.8mm^2, drill diamater 1.3mm, pad diameter 2.6mm, see http://www.farnell.com/datasheets/100425.pdf, script-generated using https://github.com/pointhi/kicad-footprint-generator/scripts/TerminalBlock_Phoenix +THT Terminal Block Phoenix MKDS-1,5-8-5.08 pitch 5.08mm size 40.6x9.8mm^2 drill 1.3mm pad 2.6mm +0 +8 +8 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_MKDS-1,5-8_1x08_P5.00mm_Horizontal +Terminal Block Phoenix MKDS-1,5-8, 8 pins, pitch 5mm, size 40x9.8mm^2, drill diamater 1.3mm, pad diameter 2.6mm, see http://www.farnell.com/datasheets/100425.pdf, script-generated using https://github.com/pointhi/kicad-footprint-generator/scripts/TerminalBlock_Phoenix +THT Terminal Block Phoenix MKDS-1,5-8 pitch 5mm size 40x9.8mm^2 drill 1.3mm pad 2.6mm +0 +8 +8 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_MKDS-1,5-9-5.08_1x09_P5.08mm_Horizontal +Terminal Block Phoenix MKDS-1,5-9-5.08, 9 pins, pitch 5.08mm, size 45.7x9.8mm^2, drill diamater 1.3mm, pad diameter 2.6mm, see http://www.farnell.com/datasheets/100425.pdf, script-generated using https://github.com/pointhi/kicad-footprint-generator/scripts/TerminalBlock_Phoenix +THT Terminal Block Phoenix MKDS-1,5-9-5.08 pitch 5.08mm size 45.7x9.8mm^2 drill 1.3mm pad 2.6mm +0 +9 +9 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_MKDS-1,5-9_1x09_P5.00mm_Horizontal +Terminal Block Phoenix MKDS-1,5-9, 9 pins, pitch 5mm, size 45x9.8mm^2, drill diamater 1.3mm, pad diameter 2.6mm, see http://www.farnell.com/datasheets/100425.pdf, script-generated using https://github.com/pointhi/kicad-footprint-generator/scripts/TerminalBlock_Phoenix +THT Terminal Block Phoenix MKDS-1,5-9 pitch 5mm size 45x9.8mm^2 drill 1.3mm pad 2.6mm +0 +9 +9 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_MKDS-1,5-10-5.08_1x10_P5.08mm_Horizontal +Terminal Block Phoenix MKDS-1,5-10-5.08, 10 pins, pitch 5.08mm, size 50.8x9.8mm^2, drill diamater 1.3mm, pad diameter 2.6mm, see http://www.farnell.com/datasheets/100425.pdf, script-generated using https://github.com/pointhi/kicad-footprint-generator/scripts/TerminalBlock_Phoenix +THT Terminal Block Phoenix MKDS-1,5-10-5.08 pitch 5.08mm size 50.8x9.8mm^2 drill 1.3mm pad 2.6mm +0 +10 +10 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_MKDS-1,5-10_1x10_P5.00mm_Horizontal +Terminal Block Phoenix MKDS-1,5-10, 10 pins, pitch 5mm, size 50x9.8mm^2, drill diamater 1.3mm, pad diameter 2.6mm, see http://www.farnell.com/datasheets/100425.pdf, script-generated using https://github.com/pointhi/kicad-footprint-generator/scripts/TerminalBlock_Phoenix +THT Terminal Block Phoenix MKDS-1,5-10 pitch 5mm size 50x9.8mm^2 drill 1.3mm pad 2.6mm +0 +10 +10 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_MKDS-1,5-11-5.08_1x11_P5.08mm_Horizontal +Terminal Block Phoenix MKDS-1,5-11-5.08, 11 pins, pitch 5.08mm, size 55.9x9.8mm^2, drill diamater 1.3mm, pad diameter 2.6mm, see http://www.farnell.com/datasheets/100425.pdf, script-generated using https://github.com/pointhi/kicad-footprint-generator/scripts/TerminalBlock_Phoenix +THT Terminal Block Phoenix MKDS-1,5-11-5.08 pitch 5.08mm size 55.9x9.8mm^2 drill 1.3mm pad 2.6mm +0 +11 +11 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_MKDS-1,5-11_1x11_P5.00mm_Horizontal +Terminal Block Phoenix MKDS-1,5-11, 11 pins, pitch 5mm, size 55x9.8mm^2, drill diamater 1.3mm, pad diameter 2.6mm, see http://www.farnell.com/datasheets/100425.pdf, script-generated using https://github.com/pointhi/kicad-footprint-generator/scripts/TerminalBlock_Phoenix +THT Terminal Block Phoenix MKDS-1,5-11 pitch 5mm size 55x9.8mm^2 drill 1.3mm pad 2.6mm +0 +11 +11 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_MKDS-1,5-12-5.08_1x12_P5.08mm_Horizontal +Terminal Block Phoenix MKDS-1,5-12-5.08, 12 pins, pitch 5.08mm, size 61x9.8mm^2, drill diamater 1.3mm, pad diameter 2.6mm, see http://www.farnell.com/datasheets/100425.pdf, script-generated using https://github.com/pointhi/kicad-footprint-generator/scripts/TerminalBlock_Phoenix +THT Terminal Block Phoenix MKDS-1,5-12-5.08 pitch 5.08mm size 61x9.8mm^2 drill 1.3mm pad 2.6mm +0 +12 +12 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_MKDS-1,5-12_1x12_P5.00mm_Horizontal +Terminal Block Phoenix MKDS-1,5-12, 12 pins, pitch 5mm, size 60x9.8mm^2, drill diamater 1.3mm, pad diameter 2.6mm, see http://www.farnell.com/datasheets/100425.pdf, script-generated using https://github.com/pointhi/kicad-footprint-generator/scripts/TerminalBlock_Phoenix +THT Terminal Block Phoenix MKDS-1,5-12 pitch 5mm size 60x9.8mm^2 drill 1.3mm pad 2.6mm +0 +12 +12 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_MKDS-1,5-13-5.08_1x13_P5.08mm_Horizontal +Terminal Block Phoenix MKDS-1,5-13-5.08, 13 pins, pitch 5.08mm, size 66x9.8mm^2, drill diamater 1.3mm, pad diameter 2.6mm, see http://www.farnell.com/datasheets/100425.pdf, script-generated using https://github.com/pointhi/kicad-footprint-generator/scripts/TerminalBlock_Phoenix +THT Terminal Block Phoenix MKDS-1,5-13-5.08 pitch 5.08mm size 66x9.8mm^2 drill 1.3mm pad 2.6mm +0 +13 +13 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_MKDS-1,5-13_1x13_P5.00mm_Horizontal +Terminal Block Phoenix MKDS-1,5-13, 13 pins, pitch 5mm, size 65x9.8mm^2, drill diamater 1.3mm, pad diameter 2.6mm, see http://www.farnell.com/datasheets/100425.pdf, script-generated using https://github.com/pointhi/kicad-footprint-generator/scripts/TerminalBlock_Phoenix +THT Terminal Block Phoenix MKDS-1,5-13 pitch 5mm size 65x9.8mm^2 drill 1.3mm pad 2.6mm +0 +13 +13 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_MKDS-1,5-14-5.08_1x14_P5.08mm_Horizontal +Terminal Block Phoenix MKDS-1,5-14-5.08, 14 pins, pitch 5.08mm, size 71.1x9.8mm^2, drill diamater 1.3mm, pad diameter 2.6mm, see http://www.farnell.com/datasheets/100425.pdf, script-generated using https://github.com/pointhi/kicad-footprint-generator/scripts/TerminalBlock_Phoenix +THT Terminal Block Phoenix MKDS-1,5-14-5.08 pitch 5.08mm size 71.1x9.8mm^2 drill 1.3mm pad 2.6mm +0 +14 +14 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_MKDS-1,5-14_1x14_P5.00mm_Horizontal +Terminal Block Phoenix MKDS-1,5-14, 14 pins, pitch 5mm, size 70x9.8mm^2, drill diamater 1.3mm, pad diameter 2.6mm, see http://www.farnell.com/datasheets/100425.pdf, script-generated using https://github.com/pointhi/kicad-footprint-generator/scripts/TerminalBlock_Phoenix +THT Terminal Block Phoenix MKDS-1,5-14 pitch 5mm size 70x9.8mm^2 drill 1.3mm pad 2.6mm +0 +14 +14 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_MKDS-1,5-15-5.08_1x15_P5.08mm_Horizontal +Terminal Block Phoenix MKDS-1,5-15-5.08, 15 pins, pitch 5.08mm, size 76.2x9.8mm^2, drill diamater 1.3mm, pad diameter 2.6mm, see http://www.farnell.com/datasheets/100425.pdf, script-generated using https://github.com/pointhi/kicad-footprint-generator/scripts/TerminalBlock_Phoenix +THT Terminal Block Phoenix MKDS-1,5-15-5.08 pitch 5.08mm size 76.2x9.8mm^2 drill 1.3mm pad 2.6mm +0 +15 +15 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_MKDS-1,5-15_1x15_P5.00mm_Horizontal +Terminal Block Phoenix MKDS-1,5-15, 15 pins, pitch 5mm, size 75x9.8mm^2, drill diamater 1.3mm, pad diameter 2.6mm, see http://www.farnell.com/datasheets/100425.pdf, script-generated using https://github.com/pointhi/kicad-footprint-generator/scripts/TerminalBlock_Phoenix +THT Terminal Block Phoenix MKDS-1,5-15 pitch 5mm size 75x9.8mm^2 drill 1.3mm pad 2.6mm +0 +15 +15 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_MKDS-1,5-16-5.08_1x16_P5.08mm_Horizontal +Terminal Block Phoenix MKDS-1,5-16-5.08, 16 pins, pitch 5.08mm, size 81.3x9.8mm^2, drill diamater 1.3mm, pad diameter 2.6mm, see http://www.farnell.com/datasheets/100425.pdf, script-generated using https://github.com/pointhi/kicad-footprint-generator/scripts/TerminalBlock_Phoenix +THT Terminal Block Phoenix MKDS-1,5-16-5.08 pitch 5.08mm size 81.3x9.8mm^2 drill 1.3mm pad 2.6mm +0 +16 +16 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_MKDS-1,5-16_1x16_P5.00mm_Horizontal +Terminal Block Phoenix MKDS-1,5-16, 16 pins, pitch 5mm, size 80x9.8mm^2, drill diamater 1.3mm, pad diameter 2.6mm, see http://www.farnell.com/datasheets/100425.pdf, script-generated using https://github.com/pointhi/kicad-footprint-generator/scripts/TerminalBlock_Phoenix +THT Terminal Block Phoenix MKDS-1,5-16 pitch 5mm size 80x9.8mm^2 drill 1.3mm pad 2.6mm +0 +16 +16 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_MKDS-3-2-5.08_1x02_P5.08mm_Horizontal +Terminal Block Phoenix MKDS-3-2-5.08, 2 pins, pitch 5.08mm, size 10.2x11.2mm^2, drill diamater 1.3mm, pad diameter 2.6mm, see http://www.farnell.com/datasheets/2138224.pdf, script-generated using https://github.com/pointhi/kicad-footprint-generator/scripts/TerminalBlock_Phoenix +THT Terminal Block Phoenix MKDS-3-2-5.08 pitch 5.08mm size 10.2x11.2mm^2 drill 1.3mm pad 2.6mm +0 +2 +2 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_MKDS-3-3-5.08_1x03_P5.08mm_Horizontal +Terminal Block Phoenix MKDS-3-3-5.08, 3 pins, pitch 5.08mm, size 15.2x11.2mm^2, drill diamater 1.3mm, pad diameter 2.6mm, see http://www.farnell.com/datasheets/2138224.pdf, script-generated using https://github.com/pointhi/kicad-footprint-generator/scripts/TerminalBlock_Phoenix +THT Terminal Block Phoenix MKDS-3-3-5.08 pitch 5.08mm size 15.2x11.2mm^2 drill 1.3mm pad 2.6mm +0 +3 +3 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_MKDS-3-4-5.08_1x04_P5.08mm_Horizontal +Terminal Block Phoenix MKDS-3-4-5.08, 4 pins, pitch 5.08mm, size 20.3x11.2mm^2, drill diamater 1.3mm, pad diameter 2.6mm, see http://www.farnell.com/datasheets/2138224.pdf, script-generated using https://github.com/pointhi/kicad-footprint-generator/scripts/TerminalBlock_Phoenix +THT Terminal Block Phoenix MKDS-3-4-5.08 pitch 5.08mm size 20.3x11.2mm^2 drill 1.3mm pad 2.6mm +0 +4 +4 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_MKDS-3-5-5.08_1x05_P5.08mm_Horizontal +Terminal Block Phoenix MKDS-3-5-5.08, 5 pins, pitch 5.08mm, size 25.4x11.2mm^2, drill diamater 1.3mm, pad diameter 2.6mm, see http://www.farnell.com/datasheets/2138224.pdf, script-generated using https://github.com/pointhi/kicad-footprint-generator/scripts/TerminalBlock_Phoenix +THT Terminal Block Phoenix MKDS-3-5-5.08 pitch 5.08mm size 25.4x11.2mm^2 drill 1.3mm pad 2.6mm +0 +5 +5 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_MKDS-3-6-5.08_1x06_P5.08mm_Horizontal +Terminal Block Phoenix MKDS-3-6-5.08, 6 pins, pitch 5.08mm, size 30.5x11.2mm^2, drill diamater 1.3mm, pad diameter 2.6mm, see http://www.farnell.com/datasheets/2138224.pdf, script-generated using https://github.com/pointhi/kicad-footprint-generator/scripts/TerminalBlock_Phoenix +THT Terminal Block Phoenix MKDS-3-6-5.08 pitch 5.08mm size 30.5x11.2mm^2 drill 1.3mm pad 2.6mm +0 +6 +6 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_MKDS-3-7-5.08_1x07_P5.08mm_Horizontal +Terminal Block Phoenix MKDS-3-7-5.08, 7 pins, pitch 5.08mm, size 35.6x11.2mm^2, drill diamater 1.3mm, pad diameter 2.6mm, see http://www.farnell.com/datasheets/2138224.pdf, script-generated using https://github.com/pointhi/kicad-footprint-generator/scripts/TerminalBlock_Phoenix +THT Terminal Block Phoenix MKDS-3-7-5.08 pitch 5.08mm size 35.6x11.2mm^2 drill 1.3mm pad 2.6mm +0 +7 +7 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_MKDS-3-8-5.08_1x08_P5.08mm_Horizontal +Terminal Block Phoenix MKDS-3-8-5.08, 8 pins, pitch 5.08mm, size 40.6x11.2mm^2, drill diamater 1.3mm, pad diameter 2.6mm, see http://www.farnell.com/datasheets/2138224.pdf, script-generated using https://github.com/pointhi/kicad-footprint-generator/scripts/TerminalBlock_Phoenix +THT Terminal Block Phoenix MKDS-3-8-5.08 pitch 5.08mm size 40.6x11.2mm^2 drill 1.3mm pad 2.6mm +0 +8 +8 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_MKDS-3-9-5.08_1x09_P5.08mm_Horizontal +Terminal Block Phoenix MKDS-3-9-5.08, 9 pins, pitch 5.08mm, size 45.7x11.2mm^2, drill diamater 1.3mm, pad diameter 2.6mm, see http://www.farnell.com/datasheets/2138224.pdf, script-generated using https://github.com/pointhi/kicad-footprint-generator/scripts/TerminalBlock_Phoenix +THT Terminal Block Phoenix MKDS-3-9-5.08 pitch 5.08mm size 45.7x11.2mm^2 drill 1.3mm pad 2.6mm +0 +9 +9 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_MKDS-3-10-5.08_1x10_P5.08mm_Horizontal +Terminal Block Phoenix MKDS-3-10-5.08, 10 pins, pitch 5.08mm, size 50.8x11.2mm^2, drill diamater 1.3mm, pad diameter 2.6mm, see http://www.farnell.com/datasheets/2138224.pdf, script-generated using https://github.com/pointhi/kicad-footprint-generator/scripts/TerminalBlock_Phoenix +THT Terminal Block Phoenix MKDS-3-10-5.08 pitch 5.08mm size 50.8x11.2mm^2 drill 1.3mm pad 2.6mm +0 +10 +10 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_MKDS-3-11-5.08_1x11_P5.08mm_Horizontal +Terminal Block Phoenix MKDS-3-11-5.08, 11 pins, pitch 5.08mm, size 55.9x11.2mm^2, drill diamater 1.3mm, pad diameter 2.6mm, see http://www.farnell.com/datasheets/2138224.pdf, script-generated using https://github.com/pointhi/kicad-footprint-generator/scripts/TerminalBlock_Phoenix +THT Terminal Block Phoenix MKDS-3-11-5.08 pitch 5.08mm size 55.9x11.2mm^2 drill 1.3mm pad 2.6mm +0 +11 +11 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_MKDS-3-12-5.08_1x12_P5.08mm_Horizontal +Terminal Block Phoenix MKDS-3-12-5.08, 12 pins, pitch 5.08mm, size 61x11.2mm^2, drill diamater 1.3mm, pad diameter 2.6mm, see http://www.farnell.com/datasheets/2138224.pdf, script-generated using https://github.com/pointhi/kicad-footprint-generator/scripts/TerminalBlock_Phoenix +THT Terminal Block Phoenix MKDS-3-12-5.08 pitch 5.08mm size 61x11.2mm^2 drill 1.3mm pad 2.6mm +0 +12 +12 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_MKDS-3-13-5.08_1x13_P5.08mm_Horizontal +Terminal Block Phoenix MKDS-3-13-5.08, 13 pins, pitch 5.08mm, size 66x11.2mm^2, drill diamater 1.3mm, pad diameter 2.6mm, see http://www.farnell.com/datasheets/2138224.pdf, script-generated using https://github.com/pointhi/kicad-footprint-generator/scripts/TerminalBlock_Phoenix +THT Terminal Block Phoenix MKDS-3-13-5.08 pitch 5.08mm size 66x11.2mm^2 drill 1.3mm pad 2.6mm +0 +13 +13 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_MKDS-3-14-5.08_1x14_P5.08mm_Horizontal +Terminal Block Phoenix MKDS-3-14-5.08, 14 pins, pitch 5.08mm, size 71.1x11.2mm^2, drill diamater 1.3mm, pad diameter 2.6mm, see http://www.farnell.com/datasheets/2138224.pdf, script-generated using https://github.com/pointhi/kicad-footprint-generator/scripts/TerminalBlock_Phoenix +THT Terminal Block Phoenix MKDS-3-14-5.08 pitch 5.08mm size 71.1x11.2mm^2 drill 1.3mm pad 2.6mm +0 +14 +14 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_MKDS-3-15-5.08_1x15_P5.08mm_Horizontal +Terminal Block Phoenix MKDS-3-15-5.08, 15 pins, pitch 5.08mm, size 76.2x11.2mm^2, drill diamater 1.3mm, pad diameter 2.6mm, see http://www.farnell.com/datasheets/2138224.pdf, script-generated using https://github.com/pointhi/kicad-footprint-generator/scripts/TerminalBlock_Phoenix +THT Terminal Block Phoenix MKDS-3-15-5.08 pitch 5.08mm size 76.2x11.2mm^2 drill 1.3mm pad 2.6mm +0 +15 +15 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_MKDS-3-16-5.08_1x16_P5.08mm_Horizontal +Terminal Block Phoenix MKDS-3-16-5.08, 16 pins, pitch 5.08mm, size 81.3x11.2mm^2, drill diamater 1.3mm, pad diameter 2.6mm, see http://www.farnell.com/datasheets/2138224.pdf, script-generated using https://github.com/pointhi/kicad-footprint-generator/scripts/TerminalBlock_Phoenix +THT Terminal Block Phoenix MKDS-3-16-5.08 pitch 5.08mm size 81.3x11.2mm^2 drill 1.3mm pad 2.6mm +0 +16 +16 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_MPT-0,5-2-2.54_1x02_P2.54mm_Horizontal +Terminal Block Phoenix MPT-0,5-2-2.54, 2 pins, pitch 2.54mm, size 5.54x6.2mm^2, drill diamater 1.1mm, pad diameter 2.2mm, see http://www.mouser.com/ds/2/324/ItemDetail_1725656-920552.pdf, script-generated using https://github.com/pointhi/kicad-footprint-generator/scripts/TerminalBlock_Phoenix +THT Terminal Block Phoenix MPT-0,5-2-2.54 pitch 2.54mm size 5.54x6.2mm^2 drill 1.1mm pad 2.2mm +0 +2 +2 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_MPT-0,5-3-2.54_1x03_P2.54mm_Horizontal +Terminal Block Phoenix MPT-0,5-3-2.54, 3 pins, pitch 2.54mm, size 8.08x6.2mm^2, drill diamater 1.1mm, pad diameter 2.2mm, see http://www.mouser.com/ds/2/324/ItemDetail_1725656-920552.pdf, script-generated using https://github.com/pointhi/kicad-footprint-generator/scripts/TerminalBlock_Phoenix +THT Terminal Block Phoenix MPT-0,5-3-2.54 pitch 2.54mm size 8.08x6.2mm^2 drill 1.1mm pad 2.2mm +0 +3 +3 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_MPT-0,5-4-2.54_1x04_P2.54mm_Horizontal +Terminal Block Phoenix MPT-0,5-4-2.54, 4 pins, pitch 2.54mm, size 10.6x6.2mm^2, drill diamater 1.1mm, pad diameter 2.2mm, see http://www.mouser.com/ds/2/324/ItemDetail_1725672-916605.pdf, script-generated using https://github.com/pointhi/kicad-footprint-generator/scripts/TerminalBlock_Phoenix +THT Terminal Block Phoenix MPT-0,5-4-2.54 pitch 2.54mm size 10.6x6.2mm^2 drill 1.1mm pad 2.2mm +0 +4 +4 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_MPT-0,5-5-2.54_1x05_P2.54mm_Horizontal +Terminal Block Phoenix MPT-0,5-5-2.54, 5 pins, pitch 2.54mm, size 13.2x6.2mm^2, drill diamater 1.1mm, pad diameter 2.2mm, see http://www.mouser.com/ds/2/324/ItemDetail_1725672-916605.pdf, script-generated using https://github.com/pointhi/kicad-footprint-generator/scripts/TerminalBlock_Phoenix +THT Terminal Block Phoenix MPT-0,5-5-2.54 pitch 2.54mm size 13.2x6.2mm^2 drill 1.1mm pad 2.2mm +0 +5 +5 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_MPT-0,5-6-2.54_1x06_P2.54mm_Horizontal +Terminal Block Phoenix MPT-0,5-6-2.54, 6 pins, pitch 2.54mm, size 15.7x6.2mm^2, drill diamater 1.1mm, pad diameter 2.2mm, see http://www.mouser.com/ds/2/324/ItemDetail_1725672-916605.pdf, script-generated using https://github.com/pointhi/kicad-footprint-generator/scripts/TerminalBlock_Phoenix +THT Terminal Block Phoenix MPT-0,5-6-2.54 pitch 2.54mm size 15.7x6.2mm^2 drill 1.1mm pad 2.2mm +0 +6 +6 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_MPT-0,5-7-2.54_1x07_P2.54mm_Horizontal +Terminal Block Phoenix MPT-0,5-7-2.54, 7 pins, pitch 2.54mm, size 18.2x6.2mm^2, drill diamater 1.1mm, pad diameter 2.2mm, see http://www.mouser.com/ds/2/324/ItemDetail_1725672-916605.pdf, script-generated using https://github.com/pointhi/kicad-footprint-generator/scripts/TerminalBlock_Phoenix +THT Terminal Block Phoenix MPT-0,5-7-2.54 pitch 2.54mm size 18.2x6.2mm^2 drill 1.1mm pad 2.2mm +0 +7 +7 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_MPT-0,5-8-2.54_1x08_P2.54mm_Horizontal +Terminal Block Phoenix MPT-0,5-8-2.54, 8 pins, pitch 2.54mm, size 20.8x6.2mm^2, drill diamater 1.1mm, pad diameter 2.2mm, see http://www.mouser.com/ds/2/324/ItemDetail_1725672-916605.pdf, script-generated using https://github.com/pointhi/kicad-footprint-generator/scripts/TerminalBlock_Phoenix +THT Terminal Block Phoenix MPT-0,5-8-2.54 pitch 2.54mm size 20.8x6.2mm^2 drill 1.1mm pad 2.2mm +0 +8 +8 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_MPT-0,5-9-2.54_1x09_P2.54mm_Horizontal +Terminal Block Phoenix MPT-0,5-9-2.54, 9 pins, pitch 2.54mm, size 23.3x6.2mm^2, drill diamater 1.1mm, pad diameter 2.2mm, see http://www.mouser.com/ds/2/324/ItemDetail_1725672-916605.pdf, script-generated using https://github.com/pointhi/kicad-footprint-generator/scripts/TerminalBlock_Phoenix +THT Terminal Block Phoenix MPT-0,5-9-2.54 pitch 2.54mm size 23.3x6.2mm^2 drill 1.1mm pad 2.2mm +0 +9 +9 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_MPT-0,5-10-2.54_1x10_P2.54mm_Horizontal +Terminal Block Phoenix MPT-0,5-10-2.54, 10 pins, pitch 2.54mm, size 25.9x6.2mm^2, drill diamater 1.1mm, pad diameter 2.2mm, see http://www.mouser.com/ds/2/324/ItemDetail_1725672-916605.pdf, script-generated using https://github.com/pointhi/kicad-footprint-generator/scripts/TerminalBlock_Phoenix +THT Terminal Block Phoenix MPT-0,5-10-2.54 pitch 2.54mm size 25.9x6.2mm^2 drill 1.1mm pad 2.2mm +0 +10 +10 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_MPT-0,5-11-2.54_1x11_P2.54mm_Horizontal +Terminal Block Phoenix MPT-0,5-11-2.54, 11 pins, pitch 2.54mm, size 28.4x6.2mm^2, drill diamater 1.1mm, pad diameter 2.2mm, see http://www.mouser.com/ds/2/324/ItemDetail_1725672-916605.pdf, script-generated using https://github.com/pointhi/kicad-footprint-generator/scripts/TerminalBlock_Phoenix +THT Terminal Block Phoenix MPT-0,5-11-2.54 pitch 2.54mm size 28.4x6.2mm^2 drill 1.1mm pad 2.2mm +0 +11 +11 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_MPT-0,5-12-2.54_1x12_P2.54mm_Horizontal +Terminal Block Phoenix MPT-0,5-12-2.54, 12 pins, pitch 2.54mm, size 30.9x6.2mm^2, drill diamater 1.1mm, pad diameter 2.2mm, see http://www.mouser.com/ds/2/324/ItemDetail_1725672-916605.pdf, script-generated using https://github.com/pointhi/kicad-footprint-generator/scripts/TerminalBlock_Phoenix +THT Terminal Block Phoenix MPT-0,5-12-2.54 pitch 2.54mm size 30.9x6.2mm^2 drill 1.1mm pad 2.2mm +0 +12 +12 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_PT-1,5-2-3.5-H_1x02_P3.50mm_Horizontal +Terminal Block Phoenix PT-1,5-2-3.5-H, 2 pins, pitch 3.5mm, size 7x7.6mm^2, drill diamater 1.2mm, pad diameter 2.4mm, see , script-generated using https://github.com/pointhi/kicad-footprint-generator/scripts/TerminalBlock_Phoenix +THT Terminal Block Phoenix PT-1,5-2-3.5-H pitch 3.5mm size 7x7.6mm^2 drill 1.2mm pad 2.4mm +0 +2 +2 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_PT-1,5-2-5.0-H_1x02_P5.00mm_Horizontal +Terminal Block Phoenix PT-1,5-2-5.0-H, 2 pins, pitch 5mm, size 10x9mm^2, drill diamater 1.3mm, pad diameter 2.6mm, see http://www.mouser.com/ds/2/324/ItemDetail_1935161-922578.pdf, script-generated using https://github.com/pointhi/kicad-footprint-generator/scripts/TerminalBlock_Phoenix +THT Terminal Block Phoenix PT-1,5-2-5.0-H pitch 5mm size 10x9mm^2 drill 1.3mm pad 2.6mm +0 +2 +2 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_PT-1,5-3-3.5-H_1x03_P3.50mm_Horizontal +Terminal Block Phoenix PT-1,5-3-3.5-H, 3 pins, pitch 3.5mm, size 10.5x7.6mm^2, drill diamater 1.2mm, pad diameter 2.4mm, see , script-generated using https://github.com/pointhi/kicad-footprint-generator/scripts/TerminalBlock_Phoenix +THT Terminal Block Phoenix PT-1,5-3-3.5-H pitch 3.5mm size 10.5x7.6mm^2 drill 1.2mm pad 2.4mm +0 +3 +3 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_PT-1,5-3-5.0-H_1x03_P5.00mm_Horizontal +Terminal Block Phoenix PT-1,5-3-5.0-H, 3 pins, pitch 5mm, size 15x9mm^2, drill diamater 1.3mm, pad diameter 2.6mm, see http://www.mouser.com/ds/2/324/ItemDetail_1935161-922578.pdf, script-generated using https://github.com/pointhi/kicad-footprint-generator/scripts/TerminalBlock_Phoenix +THT Terminal Block Phoenix PT-1,5-3-5.0-H pitch 5mm size 15x9mm^2 drill 1.3mm pad 2.6mm +0 +3 +3 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_PT-1,5-4-3.5-H_1x04_P3.50mm_Horizontal +Terminal Block Phoenix PT-1,5-4-3.5-H, 4 pins, pitch 3.5mm, size 14x7.6mm^2, drill diamater 1.2mm, pad diameter 2.4mm, see , script-generated using https://github.com/pointhi/kicad-footprint-generator/scripts/TerminalBlock_Phoenix +THT Terminal Block Phoenix PT-1,5-4-3.5-H pitch 3.5mm size 14x7.6mm^2 drill 1.2mm pad 2.4mm +0 +4 +4 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_PT-1,5-4-5.0-H_1x04_P5.00mm_Horizontal +Terminal Block Phoenix PT-1,5-4-5.0-H, 4 pins, pitch 5mm, size 20x9mm^2, drill diamater 1.3mm, pad diameter 2.6mm, see http://www.mouser.com/ds/2/324/ItemDetail_1935161-922578.pdf, script-generated using https://github.com/pointhi/kicad-footprint-generator/scripts/TerminalBlock_Phoenix +THT Terminal Block Phoenix PT-1,5-4-5.0-H pitch 5mm size 20x9mm^2 drill 1.3mm pad 2.6mm +0 +4 +4 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_PT-1,5-5-3.5-H_1x05_P3.50mm_Horizontal +Terminal Block Phoenix PT-1,5-5-3.5-H, 5 pins, pitch 3.5mm, size 17.5x7.6mm^2, drill diamater 1.2mm, pad diameter 2.4mm, see , script-generated using https://github.com/pointhi/kicad-footprint-generator/scripts/TerminalBlock_Phoenix +THT Terminal Block Phoenix PT-1,5-5-3.5-H pitch 3.5mm size 17.5x7.6mm^2 drill 1.2mm pad 2.4mm +0 +5 +5 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_PT-1,5-5-5.0-H_1x05_P5.00mm_Horizontal +Terminal Block Phoenix PT-1,5-5-5.0-H, 5 pins, pitch 5mm, size 25x9mm^2, drill diamater 1.3mm, pad diameter 2.6mm, see http://www.mouser.com/ds/2/324/ItemDetail_1935161-922578.pdf, script-generated using https://github.com/pointhi/kicad-footprint-generator/scripts/TerminalBlock_Phoenix +THT Terminal Block Phoenix PT-1,5-5-5.0-H pitch 5mm size 25x9mm^2 drill 1.3mm pad 2.6mm +0 +5 +5 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_PT-1,5-6-3.5-H_1x06_P3.50mm_Horizontal +Terminal Block Phoenix PT-1,5-6-3.5-H, 6 pins, pitch 3.5mm, size 21x7.6mm^2, drill diamater 1.2mm, pad diameter 2.4mm, see , script-generated using https://github.com/pointhi/kicad-footprint-generator/scripts/TerminalBlock_Phoenix +THT Terminal Block Phoenix PT-1,5-6-3.5-H pitch 3.5mm size 21x7.6mm^2 drill 1.2mm pad 2.4mm +0 +6 +6 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_PT-1,5-6-5.0-H_1x06_P5.00mm_Horizontal +Terminal Block Phoenix PT-1,5-6-5.0-H, 6 pins, pitch 5mm, size 30x9mm^2, drill diamater 1.3mm, pad diameter 2.6mm, see http://www.mouser.com/ds/2/324/ItemDetail_1935161-922578.pdf, script-generated using https://github.com/pointhi/kicad-footprint-generator/scripts/TerminalBlock_Phoenix +THT Terminal Block Phoenix PT-1,5-6-5.0-H pitch 5mm size 30x9mm^2 drill 1.3mm pad 2.6mm +0 +6 +6 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_PT-1,5-7-3.5-H_1x07_P3.50mm_Horizontal +Terminal Block Phoenix PT-1,5-7-3.5-H, 7 pins, pitch 3.5mm, size 24.5x7.6mm^2, drill diamater 1.2mm, pad diameter 2.4mm, see , script-generated using https://github.com/pointhi/kicad-footprint-generator/scripts/TerminalBlock_Phoenix +THT Terminal Block Phoenix PT-1,5-7-3.5-H pitch 3.5mm size 24.5x7.6mm^2 drill 1.2mm pad 2.4mm +0 +7 +7 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_PT-1,5-7-5.0-H_1x07_P5.00mm_Horizontal +Terminal Block Phoenix PT-1,5-7-5.0-H, 7 pins, pitch 5mm, size 35x9mm^2, drill diamater 1.3mm, pad diameter 2.6mm, see http://www.mouser.com/ds/2/324/ItemDetail_1935161-922578.pdf, script-generated using https://github.com/pointhi/kicad-footprint-generator/scripts/TerminalBlock_Phoenix +THT Terminal Block Phoenix PT-1,5-7-5.0-H pitch 5mm size 35x9mm^2 drill 1.3mm pad 2.6mm +0 +7 +7 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_PT-1,5-8-3.5-H_1x08_P3.50mm_Horizontal +Terminal Block Phoenix PT-1,5-8-3.5-H, 8 pins, pitch 3.5mm, size 28x7.6mm^2, drill diamater 1.2mm, pad diameter 2.4mm, see , script-generated using https://github.com/pointhi/kicad-footprint-generator/scripts/TerminalBlock_Phoenix +THT Terminal Block Phoenix PT-1,5-8-3.5-H pitch 3.5mm size 28x7.6mm^2 drill 1.2mm pad 2.4mm +0 +8 +8 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_PT-1,5-8-5.0-H_1x08_P5.00mm_Horizontal +Terminal Block Phoenix PT-1,5-8-5.0-H, 8 pins, pitch 5mm, size 40x9mm^2, drill diamater 1.3mm, pad diameter 2.6mm, see http://www.mouser.com/ds/2/324/ItemDetail_1935161-922578.pdf, script-generated using https://github.com/pointhi/kicad-footprint-generator/scripts/TerminalBlock_Phoenix +THT Terminal Block Phoenix PT-1,5-8-5.0-H pitch 5mm size 40x9mm^2 drill 1.3mm pad 2.6mm +0 +8 +8 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_PT-1,5-9-3.5-H_1x09_P3.50mm_Horizontal +Terminal Block Phoenix PT-1,5-9-3.5-H, 9 pins, pitch 3.5mm, size 31.5x7.6mm^2, drill diamater 1.2mm, pad diameter 2.4mm, see , script-generated using https://github.com/pointhi/kicad-footprint-generator/scripts/TerminalBlock_Phoenix +THT Terminal Block Phoenix PT-1,5-9-3.5-H pitch 3.5mm size 31.5x7.6mm^2 drill 1.2mm pad 2.4mm +0 +9 +9 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_PT-1,5-9-5.0-H_1x09_P5.00mm_Horizontal +Terminal Block Phoenix PT-1,5-9-5.0-H, 9 pins, pitch 5mm, size 45x9mm^2, drill diamater 1.3mm, pad diameter 2.6mm, see http://www.mouser.com/ds/2/324/ItemDetail_1935161-922578.pdf, script-generated using https://github.com/pointhi/kicad-footprint-generator/scripts/TerminalBlock_Phoenix +THT Terminal Block Phoenix PT-1,5-9-5.0-H pitch 5mm size 45x9mm^2 drill 1.3mm pad 2.6mm +0 +9 +9 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_PT-1,5-10-3.5-H_1x10_P3.50mm_Horizontal +Terminal Block Phoenix PT-1,5-10-3.5-H, 10 pins, pitch 3.5mm, size 35x7.6mm^2, drill diamater 1.2mm, pad diameter 2.4mm, see , script-generated using https://github.com/pointhi/kicad-footprint-generator/scripts/TerminalBlock_Phoenix +THT Terminal Block Phoenix PT-1,5-10-3.5-H pitch 3.5mm size 35x7.6mm^2 drill 1.2mm pad 2.4mm +0 +10 +10 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_PT-1,5-10-5.0-H_1x10_P5.00mm_Horizontal +Terminal Block Phoenix PT-1,5-10-5.0-H, 10 pins, pitch 5mm, size 50x9mm^2, drill diamater 1.3mm, pad diameter 2.6mm, see http://www.mouser.com/ds/2/324/ItemDetail_1935161-922578.pdf, script-generated using https://github.com/pointhi/kicad-footprint-generator/scripts/TerminalBlock_Phoenix +THT Terminal Block Phoenix PT-1,5-10-5.0-H pitch 5mm size 50x9mm^2 drill 1.3mm pad 2.6mm +0 +10 +10 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_PT-1,5-11-3.5-H_1x11_P3.50mm_Horizontal +Terminal Block Phoenix PT-1,5-11-3.5-H, 11 pins, pitch 3.5mm, size 38.5x7.6mm^2, drill diamater 1.2mm, pad diameter 2.4mm, see , script-generated using https://github.com/pointhi/kicad-footprint-generator/scripts/TerminalBlock_Phoenix +THT Terminal Block Phoenix PT-1,5-11-3.5-H pitch 3.5mm size 38.5x7.6mm^2 drill 1.2mm pad 2.4mm +0 +11 +11 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_PT-1,5-11-5.0-H_1x11_P5.00mm_Horizontal +Terminal Block Phoenix PT-1,5-11-5.0-H, 11 pins, pitch 5mm, size 55x9mm^2, drill diamater 1.3mm, pad diameter 2.6mm, see http://www.mouser.com/ds/2/324/ItemDetail_1935161-922578.pdf, script-generated using https://github.com/pointhi/kicad-footprint-generator/scripts/TerminalBlock_Phoenix +THT Terminal Block Phoenix PT-1,5-11-5.0-H pitch 5mm size 55x9mm^2 drill 1.3mm pad 2.6mm +0 +11 +11 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_PT-1,5-12-3.5-H_1x12_P3.50mm_Horizontal +Terminal Block Phoenix PT-1,5-12-3.5-H, 12 pins, pitch 3.5mm, size 42x7.6mm^2, drill diamater 1.2mm, pad diameter 2.4mm, see , script-generated using https://github.com/pointhi/kicad-footprint-generator/scripts/TerminalBlock_Phoenix +THT Terminal Block Phoenix PT-1,5-12-3.5-H pitch 3.5mm size 42x7.6mm^2 drill 1.2mm pad 2.4mm +0 +12 +12 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_PT-1,5-12-5.0-H_1x12_P5.00mm_Horizontal +Terminal Block Phoenix PT-1,5-12-5.0-H, 12 pins, pitch 5mm, size 60x9mm^2, drill diamater 1.3mm, pad diameter 2.6mm, see http://www.mouser.com/ds/2/324/ItemDetail_1935161-922578.pdf, script-generated using https://github.com/pointhi/kicad-footprint-generator/scripts/TerminalBlock_Phoenix +THT Terminal Block Phoenix PT-1,5-12-5.0-H pitch 5mm size 60x9mm^2 drill 1.3mm pad 2.6mm +0 +12 +12 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_PT-1,5-13-3.5-H_1x13_P3.50mm_Horizontal +Terminal Block Phoenix PT-1,5-13-3.5-H, 13 pins, pitch 3.5mm, size 45.5x7.6mm^2, drill diamater 1.2mm, pad diameter 2.4mm, see , script-generated using https://github.com/pointhi/kicad-footprint-generator/scripts/TerminalBlock_Phoenix +THT Terminal Block Phoenix PT-1,5-13-3.5-H pitch 3.5mm size 45.5x7.6mm^2 drill 1.2mm pad 2.4mm +0 +13 +13 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_PT-1,5-13-5.0-H_1x13_P5.00mm_Horizontal +Terminal Block Phoenix PT-1,5-13-5.0-H, 13 pins, pitch 5mm, size 65x9mm^2, drill diamater 1.3mm, pad diameter 2.6mm, see http://www.mouser.com/ds/2/324/ItemDetail_1935161-922578.pdf, script-generated using https://github.com/pointhi/kicad-footprint-generator/scripts/TerminalBlock_Phoenix +THT Terminal Block Phoenix PT-1,5-13-5.0-H pitch 5mm size 65x9mm^2 drill 1.3mm pad 2.6mm +0 +13 +13 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_PT-1,5-14-3.5-H_1x14_P3.50mm_Horizontal +Terminal Block Phoenix PT-1,5-14-3.5-H, 14 pins, pitch 3.5mm, size 49x7.6mm^2, drill diamater 1.2mm, pad diameter 2.4mm, see , script-generated using https://github.com/pointhi/kicad-footprint-generator/scripts/TerminalBlock_Phoenix +THT Terminal Block Phoenix PT-1,5-14-3.5-H pitch 3.5mm size 49x7.6mm^2 drill 1.2mm pad 2.4mm +0 +14 +14 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_PT-1,5-14-5.0-H_1x14_P5.00mm_Horizontal +Terminal Block Phoenix PT-1,5-14-5.0-H, 14 pins, pitch 5mm, size 70x9mm^2, drill diamater 1.3mm, pad diameter 2.6mm, see http://www.mouser.com/ds/2/324/ItemDetail_1935161-922578.pdf, script-generated using https://github.com/pointhi/kicad-footprint-generator/scripts/TerminalBlock_Phoenix +THT Terminal Block Phoenix PT-1,5-14-5.0-H pitch 5mm size 70x9mm^2 drill 1.3mm pad 2.6mm +0 +14 +14 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_PT-1,5-15-3.5-H_1x15_P3.50mm_Horizontal +Terminal Block Phoenix PT-1,5-15-3.5-H, 15 pins, pitch 3.5mm, size 52.5x7.6mm^2, drill diamater 1.2mm, pad diameter 2.4mm, see , script-generated using https://github.com/pointhi/kicad-footprint-generator/scripts/TerminalBlock_Phoenix +THT Terminal Block Phoenix PT-1,5-15-3.5-H pitch 3.5mm size 52.5x7.6mm^2 drill 1.2mm pad 2.4mm +0 +15 +15 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_PT-1,5-15-5.0-H_1x15_P5.00mm_Horizontal +Terminal Block Phoenix PT-1,5-15-5.0-H, 15 pins, pitch 5mm, size 75x9mm^2, drill diamater 1.3mm, pad diameter 2.6mm, see http://www.mouser.com/ds/2/324/ItemDetail_1935161-922578.pdf, script-generated using https://github.com/pointhi/kicad-footprint-generator/scripts/TerminalBlock_Phoenix +THT Terminal Block Phoenix PT-1,5-15-5.0-H pitch 5mm size 75x9mm^2 drill 1.3mm pad 2.6mm +0 +15 +15 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_PT-1,5-16-3.5-H_1x16_P3.50mm_Horizontal +Terminal Block Phoenix PT-1,5-16-3.5-H, 16 pins, pitch 3.5mm, size 56x7.6mm^2, drill diamater 1.2mm, pad diameter 2.4mm, see , script-generated using https://github.com/pointhi/kicad-footprint-generator/scripts/TerminalBlock_Phoenix +THT Terminal Block Phoenix PT-1,5-16-3.5-H pitch 3.5mm size 56x7.6mm^2 drill 1.2mm pad 2.4mm +0 +16 +16 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_PT-1,5-16-5.0-H_1x16_P5.00mm_Horizontal +Terminal Block Phoenix PT-1,5-16-5.0-H, 16 pins, pitch 5mm, size 80x9mm^2, drill diamater 1.3mm, pad diameter 2.6mm, see http://www.mouser.com/ds/2/324/ItemDetail_1935161-922578.pdf, script-generated using https://github.com/pointhi/kicad-footprint-generator/scripts/TerminalBlock_Phoenix +THT Terminal Block Phoenix PT-1,5-16-5.0-H pitch 5mm size 80x9mm^2 drill 1.3mm pad 2.6mm +0 +16 +16 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_PTSM-0,5-2-2,5-V-SMD_1x02-1MP_P2.50mm_Vertical +PhoenixContact PTSM0,5 2 2,5mm vertical SMD spring clamp terminal block connector http://www.phoenixcontact.com/us/products/1814702/pdf +PhoenixContact PTSM0.5 2 2.5mm vertical SMD spring clamp terminal block connector +0 +4 +3 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_PTSM-0,5-2-2.5-H-THR_1x02_P2.50mm_Horizontal +Terminal Block Phoenix PTSM-0,5-2-2.5-H-THR, 2 pins, pitch 2.5mm, size 7.2x10mm^2, drill diamater 1.2mm, pad diameter 3mm, see http://www.produktinfo.conrad.com/datenblaetter/550000-574999/556441-da-01-de-LEITERPLATTENKL__PTSM_0_5__8_2_5_H_THR.pdf, script-generated using https://github.com/pointhi/kicad-footprint-generator/scripts/TerminalBlock_Phoenix +THT Terminal Block Phoenix PTSM-0,5-2-2.5-H-THR pitch 2.5mm size 7.2x10mm^2 drill 1.2mm pad 3mm +0 +4 +2 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_PTSM-0,5-2-2.5-V-THR_1x02_P2.50mm_Vertical +Terminal Block Phoenix PTSM-0,5-2-2.5-V-THR, vertical (cable from top), 2 pins, pitch 2.5mm, size 5.5x5mm^2, drill diamater 1.2mm, pad diameter 2mm, see http://www.produktinfo.conrad.com/datenblaetter/550000-574999/556444-da-01-de-LEITERPLATTENKL__PTSM_0_5__4_2_5_V_THR.pdf, script-generated with , script-generated using https://github.com/pointhi/kicad-footprint-generator/scripts/TerminalBlock_Phoenix +THT Terminal Block Phoenix PTSM-0,5-2-2.5-V-THR vertical pitch 2.5mm size 5.5x5mm^2 drill 1.2mm pad 2mm +0 +4 +2 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_PTSM-0,5-2-HV-2.5-SMD_1x02-1MP_P2.50mm_Vertical +PhoenixContact PTSM0,5 2 HV 2,5mm vertical SMD spring clamp terminal block connector http://www.phoenixcontact.com/us/products/1778696/pdf +2.5mm vertical SMD spring clamp terminal block connector +0 +4 +3 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_PTSM-0,5-3-2,5-V-SMD_1x03-1MP_P2.50mm_Vertical +PhoenixContact PTSM0,5 3 2,5mm vertical SMD spring clamp terminal block connector http://www.phoenixcontact.com/us/products/1814715/pdf +PhoenixContact PTSM0.5 3 2.5mm vertical SMD spring clamp terminal block connector +0 +5 +4 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_PTSM-0,5-3-2.5-H-THR_1x03_P2.50mm_Horizontal +Terminal Block Phoenix PTSM-0,5-3-2.5-H-THR, 3 pins, pitch 2.5mm, size 9.7x10mm^2, drill diamater 1.2mm, pad diameter 3mm, see http://www.produktinfo.conrad.com/datenblaetter/550000-574999/556441-da-01-de-LEITERPLATTENKL__PTSM_0_5__8_2_5_H_THR.pdf, script-generated using https://github.com/pointhi/kicad-footprint-generator/scripts/TerminalBlock_Phoenix +THT Terminal Block Phoenix PTSM-0,5-3-2.5-H-THR pitch 2.5mm size 9.7x10mm^2 drill 1.2mm pad 3mm +0 +6 +3 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_PTSM-0,5-3-2.5-V-THR_1x03_P2.50mm_Vertical +Terminal Block Phoenix PTSM-0,5-3-2.5-V-THR, vertical (cable from top), 3 pins, pitch 2.5mm, size 8x5mm^2, drill diamater 1.2mm, pad diameter 2mm, see http://www.produktinfo.conrad.com/datenblaetter/550000-574999/556444-da-01-de-LEITERPLATTENKL__PTSM_0_5__4_2_5_V_THR.pdf, script-generated with , script-generated using https://github.com/pointhi/kicad-footprint-generator/scripts/TerminalBlock_Phoenix +THT Terminal Block Phoenix PTSM-0,5-3-2.5-V-THR vertical pitch 2.5mm size 8x5mm^2 drill 1.2mm pad 2mm +0 +6 +3 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_PTSM-0,5-3-HV-2.5-SMD_1x03-1MP_P2.50mm_Vertical +PhoenixContact PTSM0,5 3 HV 2,5mm vertical SMD spring clamp terminal block connector http://www.phoenixcontact.com/us/products/1778706/pdf +2.5mm vertical SMD spring clamp terminal block connector +0 +5 +4 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_PTSM-0,5-4-2,5-V-SMD_1x04-1MP_P2.50mm_Vertical +PhoenixContact PTSM0,5 4 2,5mm vertical SMD spring clamp terminal block connector http://www.phoenixcontact.com/us/products/1814728/pdf +PhoenixContact PTSM0.5 4 2.5mm vertical SMD spring clamp terminal block connector +0 +6 +5 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_PTSM-0,5-4-2.5-H-THR_1x04_P2.50mm_Horizontal +Terminal Block Phoenix PTSM-0,5-4-2.5-H-THR, 4 pins, pitch 2.5mm, size 12.2x10mm^2, drill diamater 1.2mm, pad diameter 3mm, see http://www.produktinfo.conrad.com/datenblaetter/550000-574999/556441-da-01-de-LEITERPLATTENKL__PTSM_0_5__8_2_5_H_THR.pdf, script-generated using https://github.com/pointhi/kicad-footprint-generator/scripts/TerminalBlock_Phoenix +THT Terminal Block Phoenix PTSM-0,5-4-2.5-H-THR pitch 2.5mm size 12.2x10mm^2 drill 1.2mm pad 3mm +0 +8 +4 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_PTSM-0,5-4-2.5-V-THR_1x04_P2.50mm_Vertical +Terminal Block Phoenix PTSM-0,5-4-2.5-V-THR, vertical (cable from top), 4 pins, pitch 2.5mm, size 10.5x5mm^2, drill diamater 1.2mm, pad diameter 2mm, see http://www.produktinfo.conrad.com/datenblaetter/550000-574999/556444-da-01-de-LEITERPLATTENKL__PTSM_0_5__4_2_5_V_THR.pdf, script-generated with , script-generated using https://github.com/pointhi/kicad-footprint-generator/scripts/TerminalBlock_Phoenix +THT Terminal Block Phoenix PTSM-0,5-4-2.5-V-THR vertical pitch 2.5mm size 10.5x5mm^2 drill 1.2mm pad 2mm +0 +8 +4 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_PTSM-0,5-4-HV-2.5-SMD_1x04-1MP_P2.50mm_Vertical +PhoenixContact PTSM0,5 4 HV 2,5mm vertical SMD spring clamp terminal block connector http://www.phoenixcontact.com/us/products/1778719/pdf +2.5mm vertical SMD spring clamp terminal block connector +0 +4 +3 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_PTSM-0,5-5-2,5-V-SMD_1x05-1MP_P2.50mm_Vertical +PhoenixContact PTSM0,5 5 2,5mm vertical SMD spring clamp terminal block connector http://www.phoenixcontact.com/us/products/1814731/pdf +PhoenixContact PTSM0.5 5 2.5mm vertical SMD spring clamp terminal block connector +0 +7 +6 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_PTSM-0,5-5-2.5-H-THR_1x05_P2.50mm_Horizontal +Terminal Block Phoenix PTSM-0,5-5-2.5-H-THR, 5 pins, pitch 2.5mm, size 14.7x10mm^2, drill diamater 1.2mm, pad diameter 3mm, see http://www.produktinfo.conrad.com/datenblaetter/550000-574999/556441-da-01-de-LEITERPLATTENKL__PTSM_0_5__8_2_5_H_THR.pdf, script-generated using https://github.com/pointhi/kicad-footprint-generator/scripts/TerminalBlock_Phoenix +THT Terminal Block Phoenix PTSM-0,5-5-2.5-H-THR pitch 2.5mm size 14.7x10mm^2 drill 1.2mm pad 3mm +0 +10 +5 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_PTSM-0,5-5-2.5-V-THR_1x05_P2.50mm_Vertical +Terminal Block Phoenix PTSM-0,5-5-2.5-V-THR, vertical (cable from top), 5 pins, pitch 2.5mm, size 13x5mm^2, drill diamater 1.2mm, pad diameter 2mm, see http://www.produktinfo.conrad.com/datenblaetter/550000-574999/556444-da-01-de-LEITERPLATTENKL__PTSM_0_5__4_2_5_V_THR.pdf, script-generated with , script-generated using https://github.com/pointhi/kicad-footprint-generator/scripts/TerminalBlock_Phoenix +THT Terminal Block Phoenix PTSM-0,5-5-2.5-V-THR vertical pitch 2.5mm size 13x5mm^2 drill 1.2mm pad 2mm +0 +10 +5 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_PTSM-0,5-5-HV-2.5-SMD_1x05-1MP_P2.50mm_Vertical +PhoenixContact PTSM0,5 5 HV 2,5mm vertical SMD spring clamp terminal block connector http://www.phoenixcontact.com/us/products/1778722/pdf +2.5mm vertical SMD spring clamp terminal block connector +0 +7 +6 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_PTSM-0,5-6-2,5-V-SMD_1x06-1MP_P2.50mm_Vertical +PhoenixContact PTSM0,5 6 2,5mm vertical SMD spring clamp terminal block connector http://www.phoenixcontact.com/us/products/1814744/pdf +PhoenixContact PTSM0.5 6 2.5mm vertical SMD spring clamp terminal block connector +0 +8 +7 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_PTSM-0,5-6-2.5-H-THR_1x06_P2.50mm_Horizontal +Terminal Block Phoenix PTSM-0,5-6-2.5-H-THR, 6 pins, pitch 2.5mm, size 17.2x10mm^2, drill diamater 1.2mm, pad diameter 3mm, see http://www.produktinfo.conrad.com/datenblaetter/550000-574999/556441-da-01-de-LEITERPLATTENKL__PTSM_0_5__8_2_5_H_THR.pdf, script-generated using https://github.com/pointhi/kicad-footprint-generator/scripts/TerminalBlock_Phoenix +THT Terminal Block Phoenix PTSM-0,5-6-2.5-H-THR pitch 2.5mm size 17.2x10mm^2 drill 1.2mm pad 3mm +0 +12 +6 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_PTSM-0,5-6-2.5-V-THR_1x06_P2.50mm_Vertical +Terminal Block Phoenix PTSM-0,5-6-2.5-V-THR, vertical (cable from top), 6 pins, pitch 2.5mm, size 15.5x5mm^2, drill diamater 1.2mm, pad diameter 2mm, see http://www.produktinfo.conrad.com/datenblaetter/550000-574999/556444-da-01-de-LEITERPLATTENKL__PTSM_0_5__4_2_5_V_THR.pdf, script-generated with , script-generated using https://github.com/pointhi/kicad-footprint-generator/scripts/TerminalBlock_Phoenix +THT Terminal Block Phoenix PTSM-0,5-6-2.5-V-THR vertical pitch 2.5mm size 15.5x5mm^2 drill 1.2mm pad 2mm +0 +12 +6 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_PTSM-0,5-6-HV-2.5-SMD_1x06-1MP_P2.50mm_Vertical +PhoenixContact PTSM0,5 6 HV 2,5mm vertical SMD spring clamp terminal block connector http://www.phoenixcontact.com/us/products/1778735/pdf +2.5mm vertical SMD spring clamp terminal block connector +0 +8 +7 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_PTSM-0,5-7-2,5-V-SMD_1x07-1MP_P2.50mm_Vertical +PhoenixContact PTSM0,5 7 2,5mm vertical SMD spring clamp terminal block connector http://www.phoenixcontact.com/us/products/1814757/pdf +PhoenixContact PTSM0.5 7 2.5mm vertical SMD spring clamp terminal block connector +0 +9 +8 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_PTSM-0,5-7-2.5-H-THR_1x07_P2.50mm_Horizontal +Terminal Block Phoenix PTSM-0,5-7-2.5-H-THR, 7 pins, pitch 2.5mm, size 19.7x10mm^2, drill diamater 1.2mm, pad diameter 3mm, see http://www.produktinfo.conrad.com/datenblaetter/550000-574999/556441-da-01-de-LEITERPLATTENKL__PTSM_0_5__8_2_5_H_THR.pdf, script-generated using https://github.com/pointhi/kicad-footprint-generator/scripts/TerminalBlock_Phoenix +THT Terminal Block Phoenix PTSM-0,5-7-2.5-H-THR pitch 2.5mm size 19.7x10mm^2 drill 1.2mm pad 3mm +0 +14 +7 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_PTSM-0,5-7-2.5-V-THR_1x07_P2.50mm_Vertical +Terminal Block Phoenix PTSM-0,5-7-2.5-V-THR, vertical (cable from top), 7 pins, pitch 2.5mm, size 18x5mm^2, drill diamater 1.2mm, pad diameter 2mm, see http://www.produktinfo.conrad.com/datenblaetter/550000-574999/556444-da-01-de-LEITERPLATTENKL__PTSM_0_5__4_2_5_V_THR.pdf, script-generated with , script-generated using https://github.com/pointhi/kicad-footprint-generator/scripts/TerminalBlock_Phoenix +THT Terminal Block Phoenix PTSM-0,5-7-2.5-V-THR vertical pitch 2.5mm size 18x5mm^2 drill 1.2mm pad 2mm +0 +14 +7 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_PTSM-0,5-7-HV-2.5-SMD_1x07-1MP_P2.50mm_Vertical +PhoenixContact PTSM0,5 7 HV 2,5mm vertical SMD spring clamp terminal block connector http://www.phoenixcontact.com/us/products/1778748/pdf +2.5mm vertical SMD spring clamp terminal block connector +0 +9 +8 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_PTSM-0,5-8-2,5-V-SMD_1x08-1MP_P2.50mm_Vertical +PhoenixContact PTSM0,5 8 2,5mm vertical SMD spring clamp terminal block connector http://www.phoenixcontact.com/us/products/1814760/pdf +PhoenixContact PTSM0.5 8 2.5mm vertical SMD spring clamp terminal block connector +0 +10 +9 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_PTSM-0,5-8-2.5-H-THR_1x08_P2.50mm_Horizontal +Terminal Block Phoenix PTSM-0,5-8-2.5-H-THR, 8 pins, pitch 2.5mm, size 22.2x10mm^2, drill diamater 1.2mm, pad diameter 3mm, see http://www.produktinfo.conrad.com/datenblaetter/550000-574999/556441-da-01-de-LEITERPLATTENKL__PTSM_0_5__8_2_5_H_THR.pdf, script-generated using https://github.com/pointhi/kicad-footprint-generator/scripts/TerminalBlock_Phoenix +THT Terminal Block Phoenix PTSM-0,5-8-2.5-H-THR pitch 2.5mm size 22.2x10mm^2 drill 1.2mm pad 3mm +0 +16 +8 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_PTSM-0,5-8-2.5-V-THR_1x08_P2.50mm_Vertical +Terminal Block Phoenix PTSM-0,5-8-2.5-V-THR, vertical (cable from top), 8 pins, pitch 2.5mm, size 20.5x5mm^2, drill diamater 1.2mm, pad diameter 2mm, see http://www.produktinfo.conrad.com/datenblaetter/550000-574999/556444-da-01-de-LEITERPLATTENKL__PTSM_0_5__4_2_5_V_THR.pdf, script-generated with , script-generated using https://github.com/pointhi/kicad-footprint-generator/scripts/TerminalBlock_Phoenix +THT Terminal Block Phoenix PTSM-0,5-8-2.5-V-THR vertical pitch 2.5mm size 20.5x5mm^2 drill 1.2mm pad 2mm +0 +16 +8 +TerminalBlock_Phoenix +TerminalBlock_Phoenix_PTSM-0,5-8-HV-2.5-SMD_1x08-1MP_P2.50mm_Vertical +PhoenixContact PTSM0,5 8 HV 2,5mm vertical SMD spring clamp terminal block connector http://www.phoenixcontact.com/us/products/1778751/pdf +2.5mm vertical SMD spring clamp terminal block connector +0 +10 +9 +TO_SOT_Packages_SMD +Analog_KS-4 +Analog Devices KS-4, http://www.analog.com/media/en/package-pcb-resources/package/pkg_pdf/sc70ks/ks_4.pdf +Analog Devices KS-4 (like EIAJ SC-82) +0 +4 +4 +TO_SOT_Packages_SMD +ATPAK-2 +ATPAK SMD package, http://www.onsemi.com/pub/Collateral/ENA2192-D.PDF +ATPAK +0 +7 +3 +TO_SOT_Packages_SMD +Diodes_SOT-553 +Diodes SOT-553, https://www.diodes.com/assets/Package-Files/SOT553.pdf +SOT-553 +0 +5 +5 +TO_SOT_Packages_SMD +HVSOF5 +HVSOF5, http://rohmfs.rohm.com/en/techdata_basic/ic/package/hvsof5_1-e.pdf +HVSOF5 +0 +9 +5 +TO_SOT_Packages_SMD +HVSOF6 +HVSOF6, http://rohmfs.rohm.com/en/techdata_basic/ic/package/hvsof6_1-e.pdf, http://rohmfs.rohm.com/en/products/databook/datasheet/ic/audio_video/video_amplifier/bh76106hfv-e.pdf +HVSOF6 +0 +7 +7 +TO_SOT_Packages_SMD +Infineon_PG-HDSOP-10-1 +Infineon PG-HDSOP-10-1 (DDPAK), 20.96x6.5x2.3mm, slug up (https://www.infineon.com/cms/en/product/packages/PG-HDSOP/PG-HDSOP-10-1/) +hdsop 10 ddpak +0 +10 +10 +TO_SOT_Packages_SMD +Infineon_PG-HSOF-8-1 +Infineon HSOF-8-1 power mosfet http://www.infineon.com/cms/en/product/packages/PG-HSOF/PG-HSOF-8-1/ +mosfet hsof +0 +54 +3 +TO_SOT_Packages_SMD +Infineon_PG-HSOF-8-1_ThermalVias +HSOF-8-1 power mosfet http://www.infineon.com/cms/en/product/packages/PG-HSOF/PG-HSOF-8-1/ +mosfet hsof thermal vias +0 +57 +3 +TO_SOT_Packages_SMD +Infineon_PG-TO-220-7Lead_TabPin8 +Infineon PG-TO-220-7, Tab as Pin 8, see e.g. https://www.infineon.com/dgdl/Infineon-BTS50055-1TMC-DS-v01_00-EN.pdf?fileId=5546d4625a888733015aa9b0007235e9 +Infineon PG-TO-220-7 +0 +12 +8 +TO_SOT_Packages_SMD +LFPAK33 +LFPAK33 SOT-1210 https://assets.nexperia.com/documents/outline-drawing/SOT1210.pdf +LFPAK33 SOT-1210 +0 +21 +5 +TO_SOT_Packages_SMD +LFPAK56 +LFPAK56 https://assets.nexperia.com/documents/outline-drawing/SOT669.pdf +LFPAK56 SOT-669 Power-SO8 +0 +19 +5 +TO_SOT_Packages_SMD +LFPAK56_ThermalVias-1 +LFPAK56 https://assets.nexperia.com/documents/outline-drawing/SOT669.pdf +LFPAK56 SOT669 Thermal Vias 0.4mm Power-SO8 +0 +63 +5 +TO_SOT_Packages_SMD +LFPAK56_ThermalVias-2 +LFPAK56 https://assets.nexperia.com/documents/outline-drawing/SOT669.pdf +LFPAK56 SOT669 Thermical Vias Power-SO8 +0 +30 +5 +TO_SOT_Packages_SMD +OnSemi_ECH8 +On Semiconductor ECH8, https://www.onsemi.com/pub/Collateral/318BF.PDF +ECH8 SOT28-FL SOT-28-FL +0 +8 +8 +TO_SOT_Packages_SMD +PowerMacro_M234_NoHole +TO-50-4 Power Macro Package Style M234 +TO-50-4 Power Macro Package Style M234 +0 +4 +4 +TO_SOT_Packages_SMD +PowerMacro_M234_WithHole +TO-50-4 Power Macro Package Style M234 +TO-50-4 Power Macro Package Style M234 +0 +4 +4 +TO_SOT_Packages_SMD +PQFN_8x8 +Low profile 8x8mm PQFN package e.g. https://www.fairchildsemi.com/datasheets/FD/FDMT80080DC.pdf +pqfn vdfn mosfet +0 +16 +3 +TO_SOT_Packages_SMD +Rohm_HRP7 +Rohm HRP7 SMD package, http://rohmfs.rohm.com/en/techdata_basic/ic/package/hrp7_1-e.pdf, http://rohmfs.rohm.com/en/products/databook/datasheet/ic/motor/dc/bd621x-e.pdf +Rohm HRP7 SMD +0 +69 +7 +TO_SOT_Packages_SMD +SC-59 +SC-59, https://lib.chipdip.ru/images/import_diod/original/SOT-23_SC-59.jpg +SC-59 +0 +3 +3 +TO_SOT_Packages_SMD +SC-59_Handsoldering +SC-59, hand-soldering varaint, https://lib.chipdip.ru/images/import_diod/original/SOT-23_SC-59.jpg +SC-59 hand-soldering +0 +3 +3 +TO_SOT_Packages_SMD +SC-70-8 +SC70-8 +SC70-8 +0 +8 +8 +TO_SOT_Packages_SMD +SC-70-8_Handsoldering +SC70-8, Handsoldering +SC70-8 Handsoldering +0 +8 +8 +TO_SOT_Packages_SMD +SC-82AA +SC-82AA +SC-82AA +0 +4 +4 +TO_SOT_Packages_SMD +SC-82AA_Handsoldering +SC-82AA +SC-82AA +0 +4 +4 +TO_SOT_Packages_SMD +SC-82AB +SC-82AB +SC-82AB +0 +4 +4 +TO_SOT_Packages_SMD +SC-82AB_Handsoldering +SC-82AB +SC-82AB +0 +4 +4 +TO_SOT_Packages_SMD +SOT-23 +SOT-23, Standard +SOT-23 +0 +3 +3 +TO_SOT_Packages_SMD +SOT-23-5 +5-pin SOT23 package +SOT-23-5 +0 +5 +5 +TO_SOT_Packages_SMD +SOT-23-5_HandSoldering +5-pin SOT23 package +SOT-23-5 hand-soldering +0 +5 +5 +TO_SOT_Packages_SMD +SOT-23-6 +6-pin SOT-23 package +SOT-23-6 +0 +6 +6 +TO_SOT_Packages_SMD +SOT-23-6_Handsoldering +6-pin SOT-23 package, Handsoldering +SOT-23-6 Handsoldering +0 +6 +6 +TO_SOT_Packages_SMD +SOT-23-8 +8-pin SOT-23 package, http://www.analog.com/media/en/package-pcb-resources/package/pkg_pdf/sot-23rj/rj_8.pdf +SOT-23-8 +0 +8 +8 +TO_SOT_Packages_SMD +SOT-23-8_Handsoldering +8-pin SOT-23 package, Handsoldering, http://www.analog.com/media/en/package-pcb-resources/package/pkg_pdf/sot-23rj/rj_8.pdf +SOT-23-8 Handsoldering +0 +8 +8 +TO_SOT_Packages_SMD +SOT-23W +SOT-23W http://www.allegromicro.com/~/media/Files/Datasheets/A112x-Datasheet.ashx?la=en&hash=7BC461E058CC246E0BAB62433B2F1ECA104CA9D3 +SOT-23W +0 +3 +3 +TO_SOT_Packages_SMD +SOT-23W_Handsoldering +SOT-23W http://www.allegromicro.com/~/media/Files/Datasheets/A112x-Datasheet.ashx?la=en&hash=7BC461E058CC246E0BAB62433B2F1ECA104CA9D3 +SOT-23W for handsoldering +0 +3 +3 +TO_SOT_Packages_SMD +SOT-23_Handsoldering +SOT-23, Handsoldering +SOT-23 +0 +3 +3 +TO_SOT_Packages_SMD +SOT-89-3 +SOT-89-3 +SOT-89-3 +0 +6 +3 +TO_SOT_Packages_SMD +SOT-89-3_Handsoldering +SOT-89-3 Handsoldering +SOT-89-3 Handsoldering +0 +5 +3 +TO_SOT_Packages_SMD +SOT-89-5 +SOT-89-5, Housing,http://www.e-devices.ricoh.co.jp/en/products/product_power/pkg/sot-89-5.pdf +SOT-89-5 Housing +0 +9 +5 +TO_SOT_Packages_SMD +SOT-89-5_Handsoldering +SOT89-5, Housing,http://www.e-devices.ricoh.co.jp/en/products/product_power/pkg/sot-89-5.pdf +SOT89-5 Housing +0 +9 +5 +TO_SOT_Packages_SMD +SOT-143 +SOT-143 +SOT-143 +0 +4 +4 +TO_SOT_Packages_SMD +SOT-143R_Reverse +SOT-143R Reverse +SOT-143R Reverse +0 +4 +4 +TO_SOT_Packages_SMD +SOT-143R_Reverse_Handsoldering +SOT-143R Reverse Handsoldering +SOT-143 Reverse Handsoldering +0 +4 +4 +TO_SOT_Packages_SMD +SOT-143_Handsoldering +SOT-143 Handsoldering +SOT-143 Handsoldering +0 +4 +4 +TO_SOT_Packages_SMD +SOT-223 +module CMS SOT223 4 pins +CMS SOT +0 +4 +4 +TO_SOT_Packages_SMD +SOT-223-3_TabPin2 +module CMS SOT223 4 pins +CMS SOT +0 +4 +3 +TO_SOT_Packages_SMD +SOT-223-5 +module CMS SOT223 5 pins, http://ww1.microchip.com/downloads/en/DeviceDoc/51751a.pdf +CMS SOT +0 +5 +5 +TO_SOT_Packages_SMD +SOT-223-6 +module CMS SOT223 6 pins, http://www.ti.com/lit/ds/symlink/tps737.pdf +CMS SOT +0 +6 +6 +TO_SOT_Packages_SMD +SOT-223-6_TabPin3 +module CMS SOT223 6 pins, http://www.ti.com/lit/ds/symlink/tps737.pdf +CMS SOT +0 +6 +5 +TO_SOT_Packages_SMD +SOT-223-8 +module CMS SOT223 8 pins, https://www.diodes.com/assets/Datasheets/ZXSBMR16PT8.pdf +CMS SOT +0 +8 +8 +TO_SOT_Packages_SMD +SOT-323_SC-70 +SOT-323, SC-70 +SOT-323 SC-70 +0 +3 +3 +TO_SOT_Packages_SMD +SOT-323_SC-70_Handsoldering +SOT-323, SC-70 Handsoldering +SOT-323 SC-70 Handsoldering +0 +3 +3 +TO_SOT_Packages_SMD +SOT-343_SC-70-4 +SOT-343, SC-70-4 +SOT-343 SC-70-4 +0 +4 +4 +TO_SOT_Packages_SMD +SOT-343_SC-70-4_Handsoldering +SOT-343, SC-70-4, Handsoldering +SOT-343 SC-70-4 Handsoldering +0 +4 +4 +TO_SOT_Packages_SMD +SOT-353_SC-70-5 +SOT-353, SC-70-5 +SOT-353 SC-70-5 +0 +5 +5 +TO_SOT_Packages_SMD +SOT-353_SC-70-5_Handsoldering +SOT-353, SC-70-5, Handsoldering +SOT-353 SC-70-5 Handsoldering +0 +5 +5 +TO_SOT_Packages_SMD +SOT-363_SC-70-6 +SOT-363, SC-70-6 +SOT-363 SC-70-6 +0 +6 +6 +TO_SOT_Packages_SMD +SOT-363_SC-70-6_Handsoldering +SOT-363, SC-70-6, Handsoldering +SOT-363 SC-70-6 Handsoldering +0 +6 +6 +TO_SOT_Packages_SMD +SOT-383F +8-pin SOT-383F, http://www.mouser.com/ds/2/80/CPDVR085V0C-HF-RevB-10783.pdf +SOT-383F +0 +9 +9 +TO_SOT_Packages_SMD +SOT-383FL +8-pin SOT-383FL package, http://www.onsemi.com/pub_link/Collateral/ENA2267-D.PDF +SOT-383FL +0 +8 +8 +TO_SOT_Packages_SMD +SOT-416 +SOT-416, https://www.nxp.com/docs/en/package-information/SOT416.pdf +SOT-416 +0 +3 +3 +TO_SOT_Packages_SMD +SOT-543 +SOT-543 4 lead surface package +SOT-543 SC-107A EMD4 +0 +4 +4 +TO_SOT_Packages_SMD +SOT-553 +SOT553 +SOT-553 +0 +5 +5 +TO_SOT_Packages_SMD +SOT-563 +SOT563 +SOT-563 +0 +6 +6 +TO_SOT_Packages_SMD +SOT-665 +SOT665 +SOT-665 +0 +5 +5 +TO_SOT_Packages_SMD +SOT-666 +SOT666 +SOT-666 +0 +6 +6 +TO_SOT_Packages_SMD +SOT-723 +http://toshiba.semicon-storage.com/info/docget.jsp?did=5879&prodName=RN1104MFV +sot 723 +0 +3 +3 +TO_SOT_Packages_SMD +SOT-883 +SOT-883, https://assets.nexperia.com/documents/outline-drawing/SOT883.pdf +SOT-883 +0 +3 +3 +TO_SOT_Packages_SMD +SOT-886 +SOT-886 +SOT-886 +0 +6 +6 +TO_SOT_Packages_SMD +SOT-963 +SOT 963 6 pins package 1x0.8mm pitch 0.35mm +SOT 963 6 pins package 1x0.8mm pitch 0.35mm +0 +6 +6 +TO_SOT_Packages_SMD +SOT-1123 +SOT-1123 small outline transistor (see http://www.onsemi.com/pub/Collateral/NST3906F3-D.PDF) +SOT-1123 transistor +0 +3 +3 +TO_SOT_Packages_SMD +SOT-1333-1 +SOT-1333-1 +SOT-1333-1 +0 +9 +9 +TO_SOT_Packages_SMD +SOT-1334-1 +SOT-1334-1 +SOT-1334-1 +0 +14 +14 +TO_SOT_Packages_SMD +SuperSOT-3 +3-pin SuperSOT package https://www.fairchildsemi.com/package-drawings/MA/MA03B.pdf +SuperSOT-3 SSOT-3 +0 +3 +3 +TO_SOT_Packages_SMD +SuperSOT-6 +6-pin SuperSOT package http://www.mouser.com/ds/2/149/FMB5551-889214.pdf +SuperSOT-6 SSOT-6 +0 +6 +6 +TO_SOT_Packages_SMD +SuperSOT-8 +8-pin SuperSOT package, http://www.icbank.com/icbank_data/semi_package/ssot8_dim.pdf +SuperSOT-8 SSOT-8 +0 +8 +8 +TO_SOT_Packages_SMD +TDSON-8-1 +Power MOSFET package, TDSON-8-1, SuperS08, SON-8_5x6mm +tdson +0 +13 +5 +TO_SOT_Packages_SMD +TDSON-8-1_HandSoldering +Power MOSFET package, TDSON-8-1, SuperS08, SON-8_5x6mm +tdson +0 +13 +5 +TO_SOT_Packages_SMD +Texas_DRT-3 +Texas Instrument DRT-3 1x0.8mm Pitch 0.7mm http://www.ti.com/lit/ds/symlink/tpd2eusb30.pdf +DRT-3 1x0.8mm Pitch 0.7mm +0 +3 +3 +TO_SOT_Packages_SMD +Texas_R-PDSO-G6 +R-PDSO-G6, http://www.ti.com/lit/ds/slis144b/slis144b.pdf +R-PDSO-G6 SC-70-6 +0 +6 +6 +TO_SOT_Packages_SMD +TO-50-3_LongPad-NoHole_Housing +TO-50-3 Macro T Package Style M236 +TO-50-3 Macro T Package Style M236 +0 +3 +3 +TO_SOT_Packages_SMD +TO-50-3_LongPad-WithHole_Housing +TO-50-3 Macro T Package Style M236 +TO-50-3 Macro T Package Style M236 +0 +3 +3 +TO_SOT_Packages_SMD +TO-50-3_ShortPad-NoHole_Housing +TO-50-3 Macro T Package Style M236 +TO-50-3 Macro T Package Style M236 +0 +3 +3 +TO_SOT_Packages_SMD +TO-50-3_ShortPad-WithHole_Housing +TO-50-3 Macro T Package Style M236 +TO-50-3 Macro T Package Style M236 +0 +3 +3 +TO_SOT_Packages_SMD +TO-50-4_LongPad-NoHole_Housing +TO-50-4 Macro X Package Style M238 +TO-50-4 Macro X Package Style M238 +0 +4 +4 +TO_SOT_Packages_SMD +TO-50-4_LongPad-WithHole_Housing +TO-50-4 Macro X Package Style M238 +TO-50-4 Macro X Package Style M238 +0 +4 +4 +TO_SOT_Packages_SMD +TO-50-4_ShortPad-NoHole_Housing +TO-50-4 Macro X Package Style M238 +TO-50-4 Macro X Package Style M238 +0 +4 +4 +TO_SOT_Packages_SMD +TO-50-4_ShortPad-WithHole_Housing +TO-50-4 Macro X Package Style M238 +TO-50-4 Macro X Package Style M238 +0 +4 +4 +TO_SOT_Packages_SMD +TO-252-2 +TO-252 / DPAK SMD package, http://www.infineon.com/cms/en/product/packages/PG-TO252/PG-TO252-3-1/ +DPAK TO-252 DPAK-3 TO-252-3 SOT-428 +0 +7 +3 +TO_SOT_Packages_SMD +TO-252-2_TabPin1 +TO-252-2, tab to pin 1 https://www.wolfspeed.com/media/downloads/87/CSD01060.pdf +TO-252-2 diode +0 +7 +2 +TO_SOT_Packages_SMD +TO-252-3_TabPin2 +TO-252 / DPAK SMD package, http://www.infineon.com/cms/en/product/packages/PG-TO252/PG-TO252-3-1/ +DPAK TO-252 DPAK-3 TO-252-3 SOT-428 +0 +8 +3 +TO_SOT_Packages_SMD +TO-252-3_TabPin4 +TO-252 / DPAK SMD package, http://www.infineon.com/cms/en/product/packages/PG-TO252/PG-TO252-3-1/ +DPAK TO-252 DPAK-3 TO-252-3 SOT-428 +0 +8 +4 +TO_SOT_Packages_SMD +TO-252-4 +TO-252 / DPAK SMD package, http://www.infineon.com/cms/en/product/packages/PG-TO252/PG-TO252-5-11/ +DPAK TO-252 DPAK-5 TO-252-5 +0 +9 +5 +TO_SOT_Packages_SMD +TO-252-5_TabPin3 +TO-252 / DPAK SMD package, http://www.infineon.com/cms/en/product/packages/PG-TO252/PG-TO252-5-11/ +DPAK TO-252 DPAK-5 TO-252-5 +0 +10 +5 +TO_SOT_Packages_SMD +TO-252-5_TabPin6 +TO-252 / DPAK SMD package, http://www.infineon.com/cms/en/product/packages/PG-TO252/PG-TO252-5-11/ +DPAK TO-252 DPAK-5 TO-252-5 +0 +10 +6 +TO_SOT_Packages_SMD +TO-263-2 +TO-263 / D2PAK / DDPAK SMD package, http://www.infineon.com/cms/en/product/packages/PG-TO263/PG-TO263-3-1/ +D2PAK DDPAK TO-263 D2PAK-3 TO-263-3 SOT-404 +0 +7 +3 +TO_SOT_Packages_SMD +TO-263-2_TabPin1 +TO-263 / D2PAK / DDPAK SMD package, tab to pin 1, https://www.wolfspeed.com/media/downloads/137/C3D06060G.pdf +D2PAK DDPAK TO-263 D2PAK-3 TO-263-3 SOT-404 diode +0 +7 +2 +TO_SOT_Packages_SMD +TO-263-3_TabPin2 +TO-263 / D2PAK / DDPAK SMD package, http://www.infineon.com/cms/en/product/packages/PG-TO263/PG-TO263-3-1/ +D2PAK DDPAK TO-263 D2PAK-3 TO-263-3 SOT-404 +0 +8 +3 +TO_SOT_Packages_SMD +TO-263-3_TabPin4 +TO-263 / D2PAK / DDPAK SMD package, http://www.infineon.com/cms/en/product/packages/PG-TO263/PG-TO263-3-1/ +D2PAK DDPAK TO-263 D2PAK-3 TO-263-3 SOT-404 +0 +8 +4 +TO_SOT_Packages_SMD +TO-263-4 +TO-263 / D2PAK / DDPAK SMD package, http://www.infineon.com/cms/en/product/packages/PG-TO263/PG-TO263-5-1/ +D2PAK DDPAK TO-263 D2PAK-5 TO-263-5 SOT-426 +0 +9 +5 +TO_SOT_Packages_SMD +TO-263-5_TabPin3 +TO-263 / D2PAK / DDPAK SMD package, http://www.infineon.com/cms/en/product/packages/PG-TO263/PG-TO263-5-1/ +D2PAK DDPAK TO-263 D2PAK-5 TO-263-5 SOT-426 +0 +10 +5 +TO_SOT_Packages_SMD +TO-263-5_TabPin6 +TO-263 / D2PAK / DDPAK SMD package, http://www.infineon.com/cms/en/product/packages/PG-TO263/PG-TO263-5-1/ +D2PAK DDPAK TO-263 D2PAK-5 TO-263-5 SOT-426 +0 +10 +6 +TO_SOT_Packages_SMD +TO-263-6 +TO-263 / D2PAK / DDPAK SMD package, http://www.infineon.com/cms/en/product/packages/PG-TO263/PG-TO263-7-1/ +D2PAK DDPAK TO-263 D2PAK-7 TO-263-7 SOT-427 +0 +11 +7 +TO_SOT_Packages_SMD +TO-263-7_TabPin4 +TO-263 / D2PAK / DDPAK SMD package, http://www.infineon.com/cms/en/product/packages/PG-TO263/PG-TO263-7-1/ +D2PAK DDPAK TO-263 D2PAK-7 TO-263-7 SOT-427 +0 +12 +7 +TO_SOT_Packages_SMD +TO-263-7_TabPin8 +TO-263 / D2PAK / DDPAK SMD package, http://www.infineon.com/cms/en/product/packages/PG-TO263/PG-TO263-7-1/ +D2PAK DDPAK TO-263 D2PAK-7 TO-263-7 SOT-427 +0 +12 +8 +TO_SOT_Packages_SMD +TO-263-9_TabPin5 +TO-263 / D2PAK / DDPAK SMD package, http://www.ti.com/lit/ds/symlink/lm4755.pdf +D2PAK DDPAK TO-263 D2PAK-9 TO-263-9 +0 +14 +9 +TO_SOT_Packages_SMD +TO-263-9_TabPin10 +TO-263 / D2PAK / DDPAK SMD package, http://www.ti.com/lit/ds/symlink/lm4755.pdf +D2PAK DDPAK TO-263 D2PAK-9 TO-263-9 +0 +14 +10 +TO_SOT_Packages_SMD +TO-268-2 +TO-268/D3PAK SMD package, http://www.icbank.com/icbank_data/semi_package/to268aa_dim.pdf +D3PAK TO-268 D3PAK-3 TO-268-3 +0 +7 +3 +TO_SOT_Packages_SMD +TO-269AA +SMD package TO-269AA (e.g. diode bridge), see http://www.vishay.com/docs/88854/padlayouts.pdf +TO-269AA MBS diode bridge +0 +4 +4 +TO_SOT_Packages_SMD +TO-277A +Thermal enhanced ultra thin SMD package; 3 leads; body: 5.8 x 4.3 x 0.78 mm +TO-277A SOT-1289 +0 +12 +3 +TO_SOT_Packages_SMD +TO-277B +TO-227B https://media.digikey.com/pdf/Data%20Sheets/Littelfuse%20PDFs/DST2050S.pdf +TO-277B +0 +9 +3 +TO_SOT_Packages_SMD +TSOT-23 +3-pin TSOT23 package, http://www.analog.com.tw/pdf/All_In_One.pdf +TSOT-23 +0 +3 +3 +TO_SOT_Packages_SMD +TSOT-23-5 +5-pin TSOT23 package, http://cds.linear.com/docs/en/packaging/SOT_5_05-08-1635.pdf +TSOT-23-5 +0 +5 +5 +TO_SOT_Packages_SMD +TSOT-23-5_HandSoldering +5-pin TSOT23 package, http://cds.linear.com/docs/en/packaging/SOT_5_05-08-1635.pdf +TSOT-23-5 Hand-soldering +0 +5 +5 +TO_SOT_Packages_SMD +TSOT-23-6 +6-pin TSOT23 package, http://cds.linear.com/docs/en/packaging/SOT_6_05-08-1636.pdf +TSOT-23-6 MK06A TSOT-6 +0 +6 +6 +TO_SOT_Packages_SMD +TSOT-23-6_HandSoldering +6-pin TSOT23 package, http://cds.linear.com/docs/en/packaging/SOT_6_05-08-1636.pdf +TSOT-23-6 MK06A TSOT-6 Hand-soldering +0 +6 +6 +TO_SOT_Packages_SMD +TSOT-23-8 +8-pin TSOT23 package, http://cds.linear.com/docs/en/packaging/SOT_8_05-08-1637.pdf +TSOT-23-8 +0 +8 +8 +TO_SOT_Packages_SMD +TSOT-23-8_HandSoldering +8-pin TSOT23 package, http://cds.linear.com/docs/en/packaging/SOT_8_05-08-1637.pdf +TSOT-23-8 Hand-soldering +0 +8 +8 +TO_SOT_Packages_SMD +TSOT-23_HandSoldering +5-pin TSOT23 package, http://cds.linear.com/docs/en/packaging/SOT_5_05-08-1635.pdf +TSOT-23 Hand-soldering +0 +3 +3 +TO_SOT_Packages_SMD +Vishay_PowerPAK_SC70-6L_Dual +Vishay PowerPAK SC70 dual transistor package http://www.vishay.com/docs/70487/70487.pdf +powerpak sc70 sc-70 dual +0 +8 +6 +TO_SOT_Packages_SMD +Vishay_PowerPAK_SC70-6L_Single +Vishay PowerPAK SC70 single transistor package http://www.vishay.com/docs/70486/70486.pdf +powerpak sc70 sc-70 +0 +10 +3 +TO_SOT_Packages_SMD +VSOF5 +VSOF5 +VSOF5 +0 +5 +5 +TO_SOT_Packages_THT +Fairchild_TO-220F-6L +Fairchild TO-220F-6L, http://www.mouser.com/ds/2/149/FSL136MRT-113334.pdf +Fairchild TO-220F-6L +0 +6 +6 +TO_SOT_Packages_THT +Heraeus_TO-92-2 +TO-92 2-pin variant by Heraeus, drill 0.75mm (http://www.produktinfo.conrad.com/datenblaetter/175000-199999/181293-da-01-de-TO92_Temperatursensor_PT1000_32209225.pdf) +to-92 +0 +2 +2 +TO_SOT_Packages_THT +NEC_Molded_7x4x9mm +Molded Japan Transistor Package 7x4x9mm^3, http://rtellason.com/transdata/2sb734.pdf +Japan transistor +0 +3 +3 +TO_SOT_Packages_THT +PowerIntegrations_TO-220-7C +Non Isolated Modified TO-220 7pin Package, see http://www.farnell.com/datasheets/5793.pdf +Power Integration Y Package +0 +6 +6 +TO_SOT_Packages_THT +SIPAK-1EP_Horizontal_TabDown +SIPAK, Horizontal, RM 2.286mm +SIPAK Horizontal RM 2.286mm +0 +4 +4 +TO_SOT_Packages_THT +SIPAK_Vertical +SIPAK, Vertical, RM 2.286mm +SIPAK Vertical RM 2.286mm +0 +3 +3 +TO_SOT_Packages_THT +SOD-70_P2.54mm +Plastic near cylindrical package Sod-70 see: https://www.nxp.com/docs/en/data-sheet/KTY81_SER.pdf [StepUp generated footprint] +Sod-70 +0 +2 +2 +TO_SOT_Packages_THT +SOD-70_P5.08mm +Plastic near cylindrical package Sod-70 see: https://www.nxp.com/docs/en/data-sheet/KTY81_SER.pdf [StepUp generated footprint] +Sod-70 +0 +2 +2 +TO_SOT_Packages_THT +SOT-227 +SOT-227 / SOT-227B / ISOTOP, M4 mounting screws (https://www.vishay.com/docs/95423/sot227g2.pdf, https://www.vishay.com/docs/95793/vs-fc420sa10.pdf) +sot 227 isotop +0 +8 +4 +TO_SOT_Packages_THT +TO-3 +Transistor TO-3 +TR TO-3 TO3 TO-204 +0 +4 +3 +TO_SOT_Packages_THT +TO-3P-3_Horizontal_TabDown +TO-3P-3, Horizontal, RM 5.45mm, , see https://toshiba.semicon-storage.com/ap-en/design-support/package/detail.TO-3P(N).html +TO-3P-3 Horizontal RM 5.45mm +0 +3 +3 +TO_SOT_Packages_THT +TO-3P-3_Horizontal_TabUp +TO-3P-3, Horizontal, RM 5.45mm, , see https://toshiba.semicon-storage.com/ap-en/design-support/package/detail.TO-3P(N).html +TO-3P-3 Horizontal RM 5.45mm +0 +3 +3 +TO_SOT_Packages_THT +TO-3P-3_Vertical +TO-3P-3, Vertical, RM 5.45mm, , see https://toshiba.semicon-storage.com/ap-en/design-support/package/detail.TO-3P(N).html +TO-3P-3 Vertical RM 5.45mm +0 +3 +3 +TO_SOT_Packages_THT +TO-3PB-3_Horizontal_TabDown +TO-3PB-3, Horizontal, RM 5.45mm, , see http://www.onsemi.com/pub/Collateral/340AC.PDF +TO-3PB-3 Horizontal RM 5.45mm +0 +3 +3 +TO_SOT_Packages_THT +TO-3PB-3_Horizontal_TabUp +TO-3PB-3, Horizontal, RM 5.45mm, , see http://www.onsemi.com/pub/Collateral/340AC.PDF +TO-3PB-3 Horizontal RM 5.45mm +0 +3 +3 +TO_SOT_Packages_THT +TO-3PB-3_Vertical +TO-3PB-3, Vertical, RM 5.45mm, , see http://www.onsemi.com/pub/Collateral/340AC.PDF +TO-3PB-3 Vertical RM 5.45mm +0 +3 +3 +TO_SOT_Packages_THT +TO-5-2 +TO-5-2 +TO-5-2 +0 +2 +2 +TO_SOT_Packages_THT +TO-5-2_Window +TO-5-2_Window, Window +TO-5-2_Window Window +0 +2 +2 +TO_SOT_Packages_THT +TO-5-3 +TO-5-3 +TO-5-3 +0 +3 +3 +TO_SOT_Packages_THT +TO-5-3_Window +TO-5-3_Window, Window +TO-5-3_Window Window +0 +3 +3 +TO_SOT_Packages_THT +TO-5-4 +TO-5-4 +TO-5-4 +0 +4 +4 +TO_SOT_Packages_THT +TO-5-4_Window +TO-5-4_Window, Window +TO-5-4_Window Window +0 +4 +4 +TO_SOT_Packages_THT +TO-5-6 +TO-5-6 +TO-5-6 +0 +6 +6 +TO_SOT_Packages_THT +TO-5-6_Window +TO-5-6_Window, Window +TO-5-6_Window Window +0 +6 +6 +TO_SOT_Packages_THT +TO-5-8 +TO-5-8 +TO-5-8 +0 +8 +8 +TO_SOT_Packages_THT +TO-5-8_PD5.08 +TO-5-8_PD5.08 +TO-5-8_PD5.08 +0 +8 +8 +TO_SOT_Packages_THT +TO-5-8_PD5.08_Window +TO-5-8_PD5.08_Window, Window +TO-5-8_PD5.08_Window Window +0 +8 +8 +TO_SOT_Packages_THT +TO-5-8_Window +TO-5-8_Window, Window +TO-5-8_Window Window +0 +8 +8 +TO_SOT_Packages_THT +TO-5-10 +TO-5-10 +TO-5-10 +0 +10 +10 +TO_SOT_Packages_THT +TO-5-10_Window +TO-5-10_Window, Window +TO-5-10_Window Window +0 +10 +10 +TO_SOT_Packages_THT +TO-8-2 +TO-8-2 +TO-8-2 +0 +2 +2 +TO_SOT_Packages_THT +TO-8-2_Window +TO-8-2_Window, Window +TO-8-2_Window Window +0 +2 +2 +TO_SOT_Packages_THT +TO-8-3 +TO-8-3 +TO-8-3 +0 +3 +3 +TO_SOT_Packages_THT +TO-8-3_Window +TO-8-3_Window, Window +TO-8-3_Window Window +0 +3 +3 +TO_SOT_Packages_THT +TO-11-2 +TO-11-2 +TO-11-2 +0 +2 +2 +TO_SOT_Packages_THT +TO-11-2_Window +TO-11-2_Window, Window +TO-11-2_Window Window +0 +2 +2 +TO_SOT_Packages_THT +TO-11-3 +TO-11-3 +TO-11-3 +0 +3 +3 +TO_SOT_Packages_THT +TO-11-3_Window +TO-11-3_Window, Window +TO-11-3_Window Window +0 +3 +3 +TO_SOT_Packages_THT +TO-12-4 +TO-12-4 +TO-12-4 +0 +4 +4 +TO_SOT_Packages_THT +TO-12-4_Window +TO-12-4_Window, Window +TO-12-4_Window Window +0 +4 +4 +TO_SOT_Packages_THT +TO-17-4 +TO-17-4 +TO-17-4 +0 +4 +4 +TO_SOT_Packages_THT +TO-17-4_Window +TO-17-4_Window, Window +TO-17-4_Window Window +0 +4 +4 +TO_SOT_Packages_THT +TO-18-2 +TO-18-2 +TO-18-2 +0 +2 +2 +TO_SOT_Packages_THT +TO-18-2_Lens +TO-18-2_Lens, Lens +TO-18-2_Lens Lens +0 +2 +2 +TO_SOT_Packages_THT +TO-18-2_Window +TO-18-2_Window, Window +TO-18-2_Window Window +0 +2 +2 +TO_SOT_Packages_THT +TO-18-3 +TO-18-3 +TO-18-3 +0 +3 +3 +TO_SOT_Packages_THT +TO-18-3_Lens +TO-18-3_Lens, Lens +TO-18-3_Lens Lens +0 +3 +3 +TO_SOT_Packages_THT +TO-18-3_Window +TO-18-3_Window, Window +TO-18-3_Window Window +0 +3 +3 +TO_SOT_Packages_THT +TO-18-4 +TO-18-4 +TO-18-4 +0 +4 +4 +TO_SOT_Packages_THT +TO-18-4_Lens +TO-18-4_Lens, Lens +TO-18-4_Lens Lens +0 +4 +4 +TO_SOT_Packages_THT +TO-18-4_Window +TO-18-4_Window, Window +TO-18-4_Window Window +0 +4 +4 +TO_SOT_Packages_THT +TO-33-4 +TO-33-4 +TO-33-4 +0 +4 +4 +TO_SOT_Packages_THT +TO-33-4_Window +TO-33-4_Window, Window +TO-33-4_Window Window +0 +4 +4 +TO_SOT_Packages_THT +TO-38-2 +TO-38-2 +TO-38-2 +0 +2 +2 +TO_SOT_Packages_THT +TO-38-2_Window +TO-38-2_Window, Window +TO-38-2_Window Window +0 +2 +2 +TO_SOT_Packages_THT +TO-38-3 +TO-38-3 +TO-38-3 +0 +3 +3 +TO_SOT_Packages_THT +TO-38-3_Window +TO-38-3_Window, Window +TO-38-3_Window Window +0 +3 +3 +TO_SOT_Packages_THT +TO-39-2 +TO-39-2 +TO-39-2 +0 +2 +2 +TO_SOT_Packages_THT +TO-39-2_Window +TO-39-2_Window, Window +TO-39-2_Window Window +0 +2 +2 +TO_SOT_Packages_THT +TO-39-3 +TO-39-3 +TO-39-3 +0 +3 +3 +TO_SOT_Packages_THT +TO-39-3_Window +TO-39-3_Window, Window +TO-39-3_Window Window +0 +3 +3 +TO_SOT_Packages_THT +TO-39-4 +TO-39-4 +TO-39-4 +0 +4 +4 +TO_SOT_Packages_THT +TO-39-4_Window +TO-39-4_Window, Window +TO-39-4_Window Window +0 +4 +4 +TO_SOT_Packages_THT +TO-39-6 +TO-39-6 +TO-39-6 +0 +6 +6 +TO_SOT_Packages_THT +TO-39-6_Window +TO-39-6_Window, Window +TO-39-6_Window Window +0 +6 +6 +TO_SOT_Packages_THT +TO-39-8 +TO-39-8 +TO-39-8 +0 +8 +8 +TO_SOT_Packages_THT +TO-39-8_Window +TO-39-8_Window, Window +TO-39-8_Window Window +0 +8 +8 +TO_SOT_Packages_THT +TO-39-10 +TO-39-10 +TO-39-10 +0 +10 +10 +TO_SOT_Packages_THT +TO-39-10_Window +TO-39-10_Window, Window +TO-39-10_Window Window +0 +10 +10 +TO_SOT_Packages_THT +TO-46-2 +TO-46-2 +TO-46-2 +0 +2 +2 +TO_SOT_Packages_THT +TO-46-2_Pin2Center +TO-46-2, Pin2 at center of package, Thorlabs photodiodes +TO-46-2 Thorlabs +0 +2 +2 +TO_SOT_Packages_THT +TO-46-2_Pin2Center_Window +TO-46-2, Pin2 at center of package, Thorlabs photodiodes +TO-46-2 Thorlabs +0 +2 +2 +TO_SOT_Packages_THT +TO-46-2_Window +TO-46-2_Window, Window +TO-46-2_Window Window +0 +2 +2 +TO_SOT_Packages_THT +TO-46-3 +TO-46-3 +TO-46-3 +0 +3 +3 +TO_SOT_Packages_THT +TO-46-3_Pin2Center +TO-46-3, Pin2 at center of package, Thorlabs photodiodes, https://www.thorlabs.de/drawings/374b6862eb3b5a04-9360B5F6-5056-2306-D912111C06C3F830/FDGA05-SpecSheet.pdf +TO-46-3 Thorlabs +0 +3 +3 +TO_SOT_Packages_THT +TO-46-3_Pin2Center_Window +TO-46-3, Pin2 at center of package, Thorlabs photodiodes, https://www.thorlabs.de/drawings/374b6862eb3b5a04-9360B5F6-5056-2306-D912111C06C3F830/FDGA05-SpecSheet.pdf +TO-46-3 Thorlabs +0 +3 +3 +TO_SOT_Packages_THT +TO-46-3_Window +TO-46-3_Window, Window +TO-46-3_Window Window +0 +3 +3 +TO_SOT_Packages_THT +TO-46-4 +TO-46-4 +TO-46-4 +0 +4 +4 +TO_SOT_Packages_THT +TO-46-4_Window +TO-46-4_Window, Window +TO-46-4_Window Window +0 +4 +4 +TO_SOT_Packages_THT +TO-52-2 +TO-52-2 +TO-52-2 +0 +2 +2 +TO_SOT_Packages_THT +TO-52-2_Window +TO-52-2_Window, Window +TO-52-2_Window Window +0 +2 +2 +TO_SOT_Packages_THT +TO-52-3 +TO-52-3 +TO-52-3 +0 +3 +3 +TO_SOT_Packages_THT +TO-52-3_Window +TO-52-3_Window, Window +TO-52-3_Window Window +0 +3 +3 +TO_SOT_Packages_THT +TO-72-4 +TO-72-4 +TO-72-4 +0 +4 +4 +TO_SOT_Packages_THT +TO-72-4_Window +TO-72-4_Window, Window +TO-72-4_Window Window +0 +4 +4 +TO_SOT_Packages_THT +TO-75-6 +TO-75-6 +TO-75-6 +0 +6 +6 +TO_SOT_Packages_THT +TO-75-6_Window +TO-75-6_Window, Window +TO-75-6_Window Window +0 +6 +6 +TO_SOT_Packages_THT +TO-78-6 +TO-78-6 +TO-78-6 +0 +6 +6 +TO_SOT_Packages_THT +TO-78-6_Window +TO-78-6_Window, Window +TO-78-6_Window Window +0 +6 +6 +TO_SOT_Packages_THT +TO-78-8 +TO-78-8 +TO-78-8 +0 +8 +8 +TO_SOT_Packages_THT +TO-78-8_Window +TO-78-8_Window, Window +TO-78-8_Window Window +0 +8 +8 +TO_SOT_Packages_THT +TO-78-10 +TO-78-10 +TO-78-10 +0 +10 +10 +TO_SOT_Packages_THT +TO-78-10_Window +TO-78-10_Window, Window +TO-78-10_Window Window +0 +10 +10 +TO_SOT_Packages_THT +TO-92 +TO-92 leads molded, narrow, drill 0.75mm (see NXP sot054_po.pdf) +to-92 sc-43 sc-43a sot54 PA33 transistor +0 +3 +3 +TO_SOT_Packages_THT +TO-92-2 +TO-92 2-pin leads in-line, narrow, oval pads, drill 0.75mm (see NXP sot054_po.pdf) +to-92 sc-43 sc-43a sot54 PA33 diode SOD70 +0 +2 +2 +TO_SOT_Packages_THT +TO-92-2_Horizontal1 +2-pin TO-92 horizontal, leads molded, narrow, drill 0.75mm (see NXP sot054_po.pdf) +to-92 sc-43 sc-43a sot54 PA33 temperature sensor diode +0 +2 +2 +TO_SOT_Packages_THT +TO-92-2_Horizontal2 +2-pin TO-92 horizontal, leads molded, narrow, drill 0.75mm (see NXP sot054_po.pdf) +to-92 sc-43 sc-43a sot54 PA33 temperature sensor diode +0 +2 +2 +TO_SOT_Packages_THT +TO-92-2_W4.0mm_Horizontal_FlatSideDown +TO-92 horizontal, leads in-line, narrow, oval pads, drill 0.75mm (see NXP sot054_po.pdf) +to-92 sc-43 sc-43a sot54 PA33 transistor +0 +2 +2 +TO_SOT_Packages_THT +TO-92-2_W4.0mm_Horizontal_FlatSideUp +TO-92 horizontal, leads in-line, narrow, oval pads, drill 0.75mm (see NXP sot054_po.pdf) +to-92 sc-43 sc-43a sot54 PA33 transistor +0 +2 +2 +TO_SOT_Packages_THT +TO-92-2_Wide +TO-92 2-pin leads in-line, wide, drill 0.75mm +to-92 sc-43 sc-43a sot54 PA33 diode SOD70 +0 +2 +2 +TO_SOT_Packages_THT +TO-92Flat +TO-92Flat package, often used for hall sensors, drill 0.75mm (see e.g. http://www.ti.com/lit/ds/symlink/drv5023.pdf) +to-92Flat hall sensor +0 +3 +3 +TO_SOT_Packages_THT +TO-92L +TO-92L leads in-line (large body variant of TO-92), also known as TO-226, wide, drill 0.75mm (see https://www.diodes.com/assets/Package-Files/TO92L.pdf and http://www.ti.com/lit/an/snoa059/snoa059.pdf) +TO-92L Molded Narrow transistor +0 +3 +3 +TO_SOT_Packages_THT +TO-92L_HandSolder +TO-92L leads in-line (large body variant of TO-92), also known as TO-226, wide, drill 0.75mm, hand-soldering variant with enlarged pads (see https://www.diodes.com/assets/Package-Files/TO92L.pdf and http://www.ti.com/lit/an/snoa059/snoa059.pdf) +to-92 sc-43 sc-43a sot54 PA33 transistor +0 +3 +3 +TO_SOT_Packages_THT +TO-92L_Inline +TO-92L leads in-line (large body variant of TO-92), also known as TO-226, wide, drill 0.75mm (see https://www.diodes.com/assets/Package-Files/TO92L.pdf and http://www.ti.com/lit/an/snoa059/snoa059.pdf) +TO-92L Inline Wide transistor +0 +3 +3 +TO_SOT_Packages_THT +TO-92L_Inline_Wide +TO-92L leads in-line (large body variant of TO-92), also known as TO-226, wide, drill 0.75mm (see https://www.diodes.com/assets/Package-Files/TO92L.pdf and http://www.ti.com/lit/an/snoa059/snoa059.pdf) +TO-92L Inline Wide transistor +0 +3 +3 +TO_SOT_Packages_THT +TO-92L_Wide +TO-92L leads in-line (large body variant of TO-92), also known as TO-226, wide, drill 0.75mm (see https://www.diodes.com/assets/Package-Files/TO92L.pdf and http://www.ti.com/lit/an/snoa059/snoa059.pdf) +TO-92L Molded Wide transistor +0 +3 +3 +TO_SOT_Packages_THT +TO-92Mini-2 +TO-92Mini package, drill 0.6mm (https://media.digikey.com/pdf/Data%20Sheets/Infineon%20PDFs/KT,KTY.pdf) +to-92Mini transistor +0 +2 +2 +TO_SOT_Packages_THT +TO-92S +TO-92S package, drill 0.75mm (https://www.diodes.com/assets/Package-Files/TO92S%20(Type%20B).pdf) +to-92S transistor +0 +3 +3 +TO_SOT_Packages_THT +TO-92S-2 +TO-92S package, 2-pin, drill 0.75mm (https://www.diodes.com/assets/Package-Files/TO92S%20(Type%20B).pdf) +to-92S transistor +0 +2 +2 +TO_SOT_Packages_THT +TO-92S_Wide +TO-92S_Wide package, drill 0.75mm (https://www.diodes.com/assets/Package-Files/TO92S%20(Type%20B).pdf) +TO-92S_Wide transistor +0 +3 +3 +TO_SOT_Packages_THT +TO-92_HandSolder +TO-92 leads molded, narrow, drill 0.75mm, handsoldering variant with enlarged pads (see NXP sot054_po.pdf) +to-92 sc-43 sc-43a sot54 PA33 transistor +0 +3 +3 +TO_SOT_Packages_THT +TO-92_Horizontal1 +TO-92 horizontal, leads molded, narrow, drill 0.75mm (see NXP sot054_po.pdf) +to-92 sc-43 sc-43a sot54 PA33 transistor +0 +3 +3 +TO_SOT_Packages_THT +TO-92_Horizontal2 +TO-92 horizontal, leads molded, narrow, drill 0.75mm (see NXP sot054_po.pdf) +to-92 sc-43 sc-43a sot54 PA33 transistor +0 +3 +3 +TO_SOT_Packages_THT +TO-92_Inline +TO-92 leads in-line, narrow, oval pads, drill 0.75mm (see NXP sot054_po.pdf) +to-92 sc-43 sc-43a sot54 PA33 transistor +0 +3 +3 +TO_SOT_Packages_THT +TO-92_Inline_Horizontal1 +TO-92 horizontal, leads in-line, narrow, oval pads, drill 0.75mm (see NXP sot054_po.pdf) +to-92 sc-43 sc-43a sot54 PA33 transistor +0 +3 +3 +TO_SOT_Packages_THT +TO-92_Inline_Horizontal2 +TO-92 horizontal, leads in-line, narrow, oval pads, drill 0.75mm (see NXP sot054_po.pdf) +to-92 sc-43 sc-43a sot54 PA33 transistor +0 +3 +3 +TO_SOT_Packages_THT +TO-92_Inline_W4.0mm_Horizontal_FlatSideDown +TO-92 horizontal, leads in-line, narrow, oval pads, drill 0.75mm (see NXP sot054_po.pdf) +to-92 sc-43 sc-43a sot54 PA33 transistor +0 +3 +3 +TO_SOT_Packages_THT +TO-92_Inline_W4.0mm_Horizontal_FlatSideUp +TO-92 horizontal, leads in-line, narrow, oval pads, drill 0.75mm (see NXP sot054_po.pdf) +to-92 sc-43 sc-43a sot54 PA33 transistor +0 +3 +3 +TO_SOT_Packages_THT +TO-92_Inline_Wide +TO-92 leads in-line, wide, drill 0.75mm (see NXP sot054_po.pdf) +to-92 sc-43 sc-43a sot54 PA33 transistor +0 +3 +3 +TO_SOT_Packages_THT +TO-92_W4.0mm_StaggerEven_Horizontal_FlatSideDown +TO-92 horizontal, leads molded, narrow, drill 0.75mm (see NXP sot054_po.pdf) +to-92 sc-43 sc-43a sot54 PA33 transistor +0 +3 +3 +TO_SOT_Packages_THT +TO-92_W4.0mm_StaggerEven_Horizontal_FlatSideUp +TO-92 horizontal, leads molded, narrow, drill 0.75mm (see NXP sot054_po.pdf) +to-92 sc-43 sc-43a sot54 PA33 transistor +0 +3 +3 +TO_SOT_Packages_THT +TO-92_Wide +TO-92 leads molded, wide, drill 0.75mm (see NXP sot054_po.pdf) +to-92 sc-43 sc-43a sot54 PA33 transistor +0 +3 +3 +TO_SOT_Packages_THT +TO-99-6 +TO-99-6 +TO-99-6 +0 +6 +6 +TO_SOT_Packages_THT +TO-99-6_Window +TO-99-6_Window, Window +TO-99-6_Window Window +0 +6 +6 +TO_SOT_Packages_THT +TO-99-8 +TO-99-8 +TO-99-8 +0 +8 +8 +TO_SOT_Packages_THT +TO-99-8_Window +TO-99-8_Window, Window +TO-99-8_Window Window +0 +8 +8 +TO_SOT_Packages_THT +TO-100-10 +TO-100-10 +TO-100-10 +0 +10 +10 +TO_SOT_Packages_THT +TO-100-10_Window +TO-100-10_Window, Window +TO-100-10_Window Window +0 +10 +10 +TO_SOT_Packages_THT +TO-126-2_Horizontal_TabDown +TO-126-2, Horizontal, RM 5.08mm, see https://www.diodes.com/assets/Package-Files/TO126.pdf +TO-126-2 Horizontal RM 5.08mm +0 +2 +2 +TO_SOT_Packages_THT +TO-126-2_Horizontal_TabUp +TO-126-2, Horizontal, RM 5.08mm, see https://www.diodes.com/assets/Package-Files/TO126.pdf +TO-126-2 Horizontal RM 5.08mm +0 +2 +2 +TO_SOT_Packages_THT +TO-126-2_Vertical +TO-126-2, Vertical, RM 5.08mm, see https://www.diodes.com/assets/Package-Files/TO126.pdf +TO-126-2 Vertical RM 5.08mm +0 +2 +2 +TO_SOT_Packages_THT +TO-126-3_Horizontal_TabDown +TO-126-3, Horizontal, RM 2.54mm, see https://www.diodes.com/assets/Package-Files/TO126.pdf +TO-126-3 Horizontal RM 2.54mm +0 +3 +3 +TO_SOT_Packages_THT +TO-126-3_Horizontal_TabUp +TO-126-3, Horizontal, RM 2.54mm, see https://www.diodes.com/assets/Package-Files/TO126.pdf +TO-126-3 Horizontal RM 2.54mm +0 +3 +3 +TO_SOT_Packages_THT +TO-126-3_Vertical +TO-126-3, Vertical, RM 2.54mm, see https://www.diodes.com/assets/Package-Files/TO126.pdf +TO-126-3 Vertical RM 2.54mm +0 +3 +3 +TO_SOT_Packages_THT +TO-218-2_Horizontal_TabDown +TO-218-2, Horizontal, RM 10.95mm, SOT-93, see https://www.vishay.com/docs/95214/fto218.pdf +TO-218-2 Horizontal RM 10.95mm SOT-93 +0 +2 +2 +TO_SOT_Packages_THT +TO-218-2_Horizontal_TabUp +TO-218-2, Horizontal, RM 10.95mm, SOT-93, see https://www.vishay.com/docs/95214/fto218.pdf +TO-218-2 Horizontal RM 10.95mm SOT-93 +0 +2 +2 +TO_SOT_Packages_THT +TO-218-2_Vertical +TO-218-2, Vertical, RM 10.95mm, SOT-93, see https://www.vishay.com/docs/95214/fto218.pdf +TO-218-2 Vertical RM 10.95mm SOT-93 +0 +2 +2 +TO_SOT_Packages_THT +TO-218-3_Horizontal_TabDown +TO-218-3, Horizontal, RM 5.475mm, SOT-93, see https://www.vishay.com/docs/95214/fto218.pdf +TO-218-3 Horizontal RM 5.475mm SOT-93 +0 +3 +3 +TO_SOT_Packages_THT +TO-218-3_Horizontal_TabUp +TO-218-3, Horizontal, RM 5.475mm, SOT-93, see https://www.vishay.com/docs/95214/fto218.pdf +TO-218-3 Horizontal RM 5.475mm SOT-93 +0 +3 +3 +TO_SOT_Packages_THT +TO-218-3_Vertical +TO-218-3, Vertical, RM 5.475mm, SOT-93, see https://www.vishay.com/docs/95214/fto218.pdf +TO-218-3 Vertical RM 5.475mm SOT-93 +0 +3 +3 +TO_SOT_Packages_THT +TO-220-2_Horizontal_TabDown +TO-220-2, Horizontal, RM 5.08mm, see https://www.centralsemi.com/PDFS/CASE/TO-220-2PD.PDF +TO-220-2 Horizontal RM 5.08mm +0 +2 +2 +TO_SOT_Packages_THT +TO-220-2_Horizontal_TabUp +TO-220-2, Horizontal, RM 5.08mm, see https://www.centralsemi.com/PDFS/CASE/TO-220-2PD.PDF +TO-220-2 Horizontal RM 5.08mm +0 +2 +2 +TO_SOT_Packages_THT +TO-220-2_Vertical +TO-220-2, Vertical, RM 5.08mm, see https://www.centralsemi.com/PDFS/CASE/TO-220-2PD.PDF +TO-220-2 Vertical RM 5.08mm +0 +2 +2 +TO_SOT_Packages_THT +TO-220-3_Horizontal_TabDown +TO-220-3, Horizontal, RM 2.54mm, see https://www.vishay.com/docs/66542/to-220-1.pdf +TO-220-3 Horizontal RM 2.54mm +0 +3 +3 +TO_SOT_Packages_THT +TO-220-3_Horizontal_TabUp +TO-220-3, Horizontal, RM 2.54mm, see https://www.vishay.com/docs/66542/to-220-1.pdf +TO-220-3 Horizontal RM 2.54mm +0 +3 +3 +TO_SOT_Packages_THT +TO-220-3_Vertical +TO-220-3, Vertical, RM 2.54mm, see https://www.vishay.com/docs/66542/to-220-1.pdf +TO-220-3 Vertical RM 2.54mm +0 +3 +3 +TO_SOT_Packages_THT +TO-220-4_Horizontal_TabDown +TO-220-4, Horizontal, RM 2.54mm +TO-220-4 Horizontal RM 2.54mm +0 +4 +4 +TO_SOT_Packages_THT +TO-220-4_Horizontal_TabUp +TO-220-4, Horizontal, RM 2.54mm +TO-220-4 Horizontal RM 2.54mm +0 +4 +4 +TO_SOT_Packages_THT +TO-220-4_P5.08x2.54mm_StaggerEven_Lead3.8mm_Vertical +TO-220-4, Vertical, RM 2.54mm, staggered type-2 +TO-220-4 Vertical RM 2.54mm staggered type-2 +0 +4 +4 +TO_SOT_Packages_THT +TO-220-4_P5.08x2.54mm_StaggerEven_Lead5.84mm_TabDown +TO-220-4, Horizontal, RM 2.54mm, staggered type-2 +TO-220-4 Horizontal RM 2.54mm staggered type-2 +0 +4 +4 +TO_SOT_Packages_THT +TO-220-4_P5.08x2.54mm_StaggerOdd_Lead3.8mm_Vertical +TO-220-4, Vertical, RM 2.54mm, staggered type-1 +TO-220-4 Vertical RM 2.54mm staggered type-1 +0 +4 +4 +TO_SOT_Packages_THT +TO-220-4_P5.08x2.54mm_StaggerOdd_Lead5.84mm_TabDown +TO-220-4, Horizontal, RM 2.54mm, staggered type-1 +TO-220-4 Horizontal RM 2.54mm staggered type-1 +0 +4 +4 +TO_SOT_Packages_THT +TO-220-4_Vertical +TO-220-4, Vertical, RM 2.54mm +TO-220-4 Vertical RM 2.54mm +0 +4 +4 +TO_SOT_Packages_THT +TO-220-5_Horizontal_TabDown +TO-220-5, Horizontal, RM 1.7mm, Pentawatt, Multiwatt-5, see http://www.analog.com/media/en/package-pcb-resources/package/pkg_pdf/ltc-legacy-to-220/to-220_5_05-08-1421_straight_lead.pdf +TO-220-5 Horizontal RM 1.7mm Pentawatt Multiwatt-5 +0 +5 +5 +TO_SOT_Packages_THT +TO-220-5_Horizontal_TabUp +TO-220-5, Horizontal, RM 1.7mm, Pentawatt, Multiwatt-5, see http://www.analog.com/media/en/package-pcb-resources/package/pkg_pdf/ltc-legacy-to-220/to-220_5_05-08-1421_straight_lead.pdf +TO-220-5 Horizontal RM 1.7mm Pentawatt Multiwatt-5 +0 +5 +5 +TO_SOT_Packages_THT +TO-220-5_P3.4x3.7mm_StaggerEven_Lead3.8mm_Vertical +TO-220-5, Vertical, RM 1.7mm, Pentawatt, Multiwatt-5, staggered type-2, see http://www.analog.com/media/en/package-pcb-resources/package/pkg_pdf/ltc-legacy-to-220/to-220_5_05-08-1421.pdf?domain=www.linear.com, https://www.diodes.com/assets/Package-Files/TO220-5.pdf +TO-220-5 Vertical RM 1.7mm Pentawatt Multiwatt-5 staggered type-2 +0 +5 +5 +TO_SOT_Packages_THT +TO-220-5_P3.4x3.7mm_StaggerOdd_Lead3.8mm_Vertical +TO-220-5, Vertical, RM 1.7mm, Pentawatt, Multiwatt-5, staggered type-1, see http://www.analog.com/media/en/package-pcb-resources/package/pkg_pdf/ltc-legacy-to-220/to-220_5_05-08-1421.pdf?domain=www.linear.com, https://www.diodes.com/assets/Package-Files/TO220-5.pdf +TO-220-5 Vertical RM 1.7mm Pentawatt Multiwatt-5 staggered type-1 +0 +5 +5 +TO_SOT_Packages_THT +TO-220-5_P3.4x3.8mm_StaggerEven_Lead7.13mm_TabDown +TO-220-5, Horizontal, RM 1.7mm, Pentawatt, Multiwatt-5, staggered type-2, see http://www.analog.com/media/en/package-pcb-resources/package/pkg_pdf/ltc-legacy-to-220/to-220_5_05-08-1421.pdf?domain=www.linear.com, https://www.diodes.com/assets/Package-Files/TO220-5.pdf +TO-220-5 Horizontal RM 1.7mm Pentawatt Multiwatt-5 staggered type-2 +0 +5 +5 +TO_SOT_Packages_THT +TO-220-5_P3.4x3.8mm_StaggerOdd_Lead7.13mm_TabDown +TO-220-5, Horizontal, RM 1.7mm, Pentawatt, Multiwatt-5, staggered type-1, see http://www.analog.com/media/en/package-pcb-resources/package/pkg_pdf/ltc-legacy-to-220/to-220_5_05-08-1421.pdf?domain=www.linear.com, https://www.diodes.com/assets/Package-Files/TO220-5.pdf +TO-220-5 Horizontal RM 1.7mm Pentawatt Multiwatt-5 staggered type-1 +0 +5 +5 +TO_SOT_Packages_THT +TO-220-5_Vertical +TO-220-5, Vertical, RM 1.7mm, Pentawatt, Multiwatt-5, see http://www.analog.com/media/en/package-pcb-resources/package/pkg_pdf/ltc-legacy-to-220/to-220_5_05-08-1421_straight_lead.pdf +TO-220-5 Vertical RM 1.7mm Pentawatt Multiwatt-5 +0 +5 +5 +TO_SOT_Packages_THT +TO-220-7_P2.54x3.7mm_StaggerEven_Lead3.8mm_Vertical +TO-220-7, Vertical, RM 1.27mm, Multiwatt-7, staggered type-2 +TO-220-7 Vertical RM 1.27mm Multiwatt-7 staggered type-2 +0 +7 +7 +TO_SOT_Packages_THT +TO-220-7_P2.54x3.7mm_StaggerOdd_Lead3.8mm_Vertical +TO-220-7, Vertical, RM 1.27mm, Multiwatt-7, staggered type-1 +TO-220-7 Vertical RM 1.27mm Multiwatt-7 staggered type-1 +0 +7 +7 +TO_SOT_Packages_THT +TO-220-7_P2.54x3.8mm_StaggerEven_Lead5.85mm_TabDown +TO-220-7, Horizontal, RM 1.27mm, Multiwatt-7, staggered type-2 +TO-220-7 Horizontal RM 1.27mm Multiwatt-7 staggered type-2 +0 +7 +7 +TO_SOT_Packages_THT +TO-220-7_P2.54x3.8mm_StaggerOdd_Lead5.85mm_TabDown +TO-220-7, Horizontal, RM 1.27mm, Multiwatt-7, staggered type-1 +TO-220-7 Horizontal RM 1.27mm Multiwatt-7 staggered type-1 +0 +7 +7 +TO_SOT_Packages_THT +TO-220-8_Vertical +TO-220-8 (Multiwatt8), Vertical, 2.54mm Pitch (http://www.st.com/resource/en/datasheet/tda7264.pdf) +TO-220-9 Vertical 2.54mm Pitch Multiwatt 8 +0 +8 +8 +TO_SOT_Packages_THT +TO-220-9_P1.94x3.7mm_StaggerEven_Lead3.8mm_Vertical +TO-220-9, Vertical, RM 0.97mm, Multiwatt-9, staggered type-2 +TO-220-9 Vertical RM 0.97mm Multiwatt-9 staggered type-2 +0 +9 +9 +TO_SOT_Packages_THT +TO-220-9_P1.94x3.7mm_StaggerOdd_Lead3.8mm_Vertical +TO-220-9, Vertical, RM 0.97mm, Multiwatt-9, staggered type-1 +TO-220-9 Vertical RM 0.97mm Multiwatt-9 staggered type-1 +0 +9 +9 +TO_SOT_Packages_THT +TO-220-9_P1.94x3.8mm_StaggerEven_Lead5.85mm_TabDown +TO-220-9, Horizontal, RM 0.97mm, Multiwatt-9, staggered type-2 +TO-220-9 Horizontal RM 0.97mm Multiwatt-9 staggered type-2 +0 +9 +9 +TO_SOT_Packages_THT +TO-220-9_P1.94x3.8mm_StaggerOdd_Lead5.85mm_TabDown +TO-220-9, Horizontal, RM 0.97mm, Multiwatt-9, staggered type-1 +TO-220-9 Horizontal RM 0.97mm Multiwatt-9 staggered type-1 +0 +9 +9 +TO_SOT_Packages_THT +TO-220-11_P3.4x2.54mm_StaggerEven_Lead5.84mm_TabDown +TO-220-11, Horizontal, RM 1.7mm, staggered type-2, see http://www.st.com/resource/en/datasheet/tda7391lv.pdf +TO-220-11 Horizontal RM 1.7mm staggered type-2 +0 +11 +11 +TO_SOT_Packages_THT +TO-220-11_P3.4x2.54mm_StaggerOdd_Lead5.84mm_TabDown +TO-220-11, Horizontal, RM 1.7mm, staggered type-1, see http://www.st.com/resource/en/datasheet/tda7391lv.pdf +TO-220-11 Horizontal RM 1.7mm staggered type-1 +0 +11 +11 +TO_SOT_Packages_THT +TO-220-11_P3.4x5.08mm_StaggerEven_Lead4.58mm_Vertical +TO-220-11, Vertical, RM 1.7mm, staggered type-2, see http://www.st.com/resource/en/datasheet/tda7391lv.pdf +TO-220-11 Vertical RM 1.7mm staggered type-2 +0 +11 +11 +TO_SOT_Packages_THT +TO-220-11_P3.4x5.08mm_StaggerOdd_Lead4.85mm_Vertical +TO-220-11, Vertical, RM 1.7mm, staggered type-1, see http://www.st.com/resource/en/datasheet/tda7391lv.pdf +TO-220-11 Vertical RM 1.7mm staggered type-1 +0 +11 +11 +TO_SOT_Packages_THT +TO-220-11_P3.4x5.08mm_StaggerOdd_Lead8.45mm_TabDown +TO-220-11, Horizontal, RM 1.7mm, staggered type-1, see http://www.ti.com/lit/ds/symlink/lmd18200.pdf +TO-220-11 Horizontal RM 1.7mm staggered type-1 +0 +11 +11 +TO_SOT_Packages_THT +TO-220-15_P2.54x2.54mm_StaggerEven_Lead4.58mm_Vertical +TO-220-15, Vertical, RM 1.27mm, staggered type-2, see http://www.st.com/resource/en/datasheet/l298.pdf +TO-220-15 Vertical RM 1.27mm staggered type-2 +0 +15 +15 +TO_SOT_Packages_THT +TO-220-15_P2.54x2.54mm_StaggerEven_Lead5.84mm_TabDown +TO-220-15, Horizontal, RM 1.27mm, staggered type-2, see http://www.st.com/resource/en/datasheet/l298.pdf +TO-220-15 Horizontal RM 1.27mm staggered type-2 +0 +15 +15 +TO_SOT_Packages_THT +TO-220-15_P2.54x2.54mm_StaggerOdd_Lead4.58mm_Vertical +TO-220-15, Vertical, RM 1.27mm, staggered type-1, see http://www.st.com/resource/en/datasheet/l298.pdf +TO-220-15 Vertical RM 1.27mm staggered type-1 +0 +15 +15 +TO_SOT_Packages_THT +TO-220-15_P2.54x2.54mm_StaggerOdd_Lead5.84mm_TabDown +TO-220-15, Horizontal, RM 1.27mm, staggered type-1, see http://www.st.com/resource/en/datasheet/l298.pdf +TO-220-15 Horizontal RM 1.27mm staggered type-1 +0 +15 +15 +TO_SOT_Packages_THT +TO-220F-2_Horizontal_TabDown +TO-220F-2, Horizontal, RM 5.08mm, see http://www.onsemi.com/pub/Collateral/FFPF10F150S-D.pdf +TO-220F-2 Horizontal RM 5.08mm +0 +2 +2 +TO_SOT_Packages_THT +TO-220F-2_Horizontal_TabUp +TO-220F-2, Horizontal, RM 5.08mm, see http://www.onsemi.com/pub/Collateral/FFPF10F150S-D.pdf +TO-220F-2 Horizontal RM 5.08mm +0 +2 +2 +TO_SOT_Packages_THT +TO-220F-2_Vertical +TO-220F-2, Vertical, RM 5.08mm, see http://www.onsemi.com/pub/Collateral/FFPF10F150S-D.pdf +TO-220F-2 Vertical RM 5.08mm +0 +2 +2 +TO_SOT_Packages_THT +TO-220F-3_Horizontal_TabDown +TO-220F-3, Horizontal, RM 2.54mm, see http://www.st.com/resource/en/datasheet/stp20nm60.pdf +TO-220F-3 Horizontal RM 2.54mm +0 +3 +3 +TO_SOT_Packages_THT +TO-220F-3_Horizontal_TabUp +TO-220F-3, Horizontal, RM 2.54mm, see http://www.st.com/resource/en/datasheet/stp20nm60.pdf +TO-220F-3 Horizontal RM 2.54mm +0 +3 +3 +TO_SOT_Packages_THT +TO-220F-3_Vertical +TO-220F-3, Vertical, RM 2.54mm, see http://www.st.com/resource/en/datasheet/stp20nm60.pdf +TO-220F-3 Vertical RM 2.54mm +0 +3 +3 +TO_SOT_Packages_THT +TO-220F-4_Horizontal_TabDown +TO-220F-4, Horizontal, RM 2.54mm, see https://www.njr.com/semicon/PDF/package/TO-220F-4_E.pdf +TO-220F-4 Horizontal RM 2.54mm +0 +4 +4 +TO_SOT_Packages_THT +TO-220F-4_Horizontal_TabUp +TO-220F-4, Horizontal, RM 2.54mm, see https://www.njr.com/semicon/PDF/package/TO-220F-4_E.pdf +TO-220F-4 Horizontal RM 2.54mm +0 +4 +4 +TO_SOT_Packages_THT +TO-220F-4_P5.08x2.05mm_StaggerEven_Lead1.85mm_Vertical +TO-220F-4, Vertical, RM 2.54mm, staggered type-2, see https://www.njr.com/semicon/PDF/package/TO-220F-4_E.pdf +TO-220F-4 Vertical RM 2.54mm staggered type-2 +0 +4 +4 +TO_SOT_Packages_THT +TO-220F-4_P5.08x2.05mm_StaggerOdd_Lead1.85mm_Vertical +TO-220F-4, Vertical, RM 2.54mm, staggered type-1, see https://www.njr.com/semicon/PDF/package/TO-220F-4_E.pdf +TO-220F-4 Vertical RM 2.54mm staggered type-1 +0 +4 +4 +TO_SOT_Packages_THT +TO-220F-4_P5.08x3.7mm_StaggerEven_Lead3.5mm_Vertical +TO-220F-4, Vertical, RM 2.54mm, staggered type-2, see https://www.njr.com/semicon/PDF/package/TO-220F-4_E.pdf +TO-220F-4 Vertical RM 2.54mm staggered type-2 +0 +4 +4 +TO_SOT_Packages_THT +TO-220F-4_P5.08x3.7mm_StaggerOdd_Lead3.5mm_Vertical +TO-220F-4, Vertical, RM 2.54mm, staggered type-1, see https://www.njr.com/semicon/PDF/package/TO-220F-4_E.pdf +TO-220F-4 Vertical RM 2.54mm staggered type-1 +0 +4 +4 +TO_SOT_Packages_THT +TO-220F-4_Vertical +TO-220F-4, Vertical, RM 2.54mm, see https://www.njr.com/semicon/PDF/package/TO-220F-4_E.pdf +TO-220F-4 Vertical RM 2.54mm +0 +4 +4 +TO_SOT_Packages_THT +TO-220F-5_Horizontal_TabDown +TO-220F-5, Horizontal, RM 1.7mm, PentawattF-, MultiwattF-5 +TO-220F-5 Horizontal RM 1.7mm PentawattF- MultiwattF-5 +0 +5 +5 +TO_SOT_Packages_THT +TO-220F-5_Horizontal_TabUp +TO-220F-5, Horizontal, RM 1.7mm, PentawattF-, MultiwattF-5 +TO-220F-5 Horizontal RM 1.7mm PentawattF- MultiwattF-5 +0 +5 +5 +TO_SOT_Packages_THT +TO-220F-5_P3.4x2.06mm_StaggerEven_Lead1.86mm_Vertical +TO-220F-5, Vertical, RM 1.7mm, PentawattF-, MultiwattF-5, staggered type-2 +TO-220F-5 Vertical RM 1.7mm PentawattF- MultiwattF-5 staggered type-2 +0 +5 +5 +TO_SOT_Packages_THT +TO-220F-5_P3.4x2.06mm_StaggerOdd_Lead1.86mm_Vertical +TO-220F-5, Vertical, RM 1.7mm, PentawattF-, MultiwattF-5, staggered type-1 +TO-220F-5 Vertical RM 1.7mm PentawattF- MultiwattF-5 staggered type-1 +0 +5 +5 +TO_SOT_Packages_THT +TO-220F-5_P3.4x3.7mm_StaggerEven_Lead3.5mm_Vertical +TO-220F-5, Vertical, RM 1.7mm, PentawattF-, MultiwattF-5, staggered type-2 +TO-220F-5 Vertical RM 1.7mm PentawattF- MultiwattF-5 staggered type-2 +0 +5 +5 +TO_SOT_Packages_THT +TO-220F-5_P3.4x3.7mm_StaggerOdd_Lead3.5mm_Vertical +TO-220F-5, Vertical, RM 1.7mm, PentawattF-, MultiwattF-5, staggered type-1 +TO-220F-5 Vertical RM 1.7mm PentawattF- MultiwattF-5 staggered type-1 +0 +5 +5 +TO_SOT_Packages_THT +TO-220F-5_Vertical +TO-220F-5, Vertical, RM 1.7mm, PentawattF-, MultiwattF-5 +TO-220F-5 Vertical RM 1.7mm PentawattF- MultiwattF-5 +0 +5 +5 +TO_SOT_Packages_THT +TO-220F-7_P2.54x3.7mm_StaggerEven_Lead3.5mm_Vertical +TO-220F-7, Vertical, RM 1.27mm, staggered type-2 +TO-220F-7 Vertical RM 1.27mm staggered type-2 +0 +7 +7 +TO_SOT_Packages_THT +TO-220F-7_P2.54x3.7mm_StaggerOdd_Lead3.5mm_Vertical +TO-220F-7, Vertical, RM 1.27mm, staggered type-1 +TO-220F-7 Vertical RM 1.27mm staggered type-1 +0 +7 +7 +TO_SOT_Packages_THT +TO-220F-9_P1.8x3.7mm_StaggerEven_Lead3.5mm_Vertical +TO-220F-9, Vertical, RM 0.9mm, staggered type-2 +TO-220F-9 Vertical RM 0.9mm staggered type-2 +0 +9 +9 +TO_SOT_Packages_THT +TO-220F-9_P1.8x3.7mm_StaggerOdd_Lead3.5mm_Vertical +TO-220F-9, Vertical, RM 0.9mm, staggered type-1 +TO-220F-9 Vertical RM 0.9mm staggered type-1 +0 +9 +9 +TO_SOT_Packages_THT +TO-220F-11_P3.4x5.08mm_StaggerEven_Lead5.08mm_Vertical +TO-220F-11, Vertical, RM 1.7mm, MultiwattF-11, staggered type-2, see http://www.ti.com/lit/ds/symlink/lm3886.pdf +TO-220F-11 Vertical RM 1.7mm MultiwattF-11 staggered type-2 +0 +11 +11 +TO_SOT_Packages_THT +TO-220F-11_P3.4x5.08mm_StaggerOdd_Lead5.08mm_Vertical +TO-220F-11, Vertical, RM 1.7mm, MultiwattF-11, staggered type-1, see http://www.ti.com/lit/ds/symlink/lm3886.pdf +TO-220F-11 Vertical RM 1.7mm MultiwattF-11 staggered type-1 +0 +11 +11 +TO_SOT_Packages_THT +TO-220F-15_P2.54x5.08mm_StaggerEven_Lead5.08mm_Vertical +TO-220F-15, Vertical, RM 1.27mm, MultiwattF-15, staggered type-2 +TO-220F-15 Vertical RM 1.27mm MultiwattF-15 staggered type-2 +0 +15 +15 +TO_SOT_Packages_THT +TO-220F-15_P2.54x5.08mm_StaggerOdd_Lead5.08mm_Vertical +TO-220F-15, Vertical, RM 1.27mm, MultiwattF-15, staggered type-1 +TO-220F-15 Vertical RM 1.27mm MultiwattF-15 staggered type-1 +0 +15 +15 +TO_SOT_Packages_THT +TO-247-2_Horizontal_TabDown +TO-247-2, Horizontal, RM 10.9mm, see https://toshiba.semicon-storage.com/us/product/mosfet/to-247-4l.html +TO-247-2 Horizontal RM 10.9mm +0 +2 +2 +TO_SOT_Packages_THT +TO-247-2_Horizontal_TabUp +TO-247-2, Horizontal, RM 10.9mm, see https://toshiba.semicon-storage.com/us/product/mosfet/to-247-4l.html +TO-247-2 Horizontal RM 10.9mm +0 +2 +2 +TO_SOT_Packages_THT +TO-247-2_Vertical +TO-247-2, Vertical, RM 10.9mm, see https://toshiba.semicon-storage.com/us/product/mosfet/to-247-4l.html +TO-247-2 Vertical RM 10.9mm +0 +2 +2 +TO_SOT_Packages_THT +TO-247-3_Horizontal_TabDown +TO-247-3, Horizontal, RM 5.45mm, see https://toshiba.semicon-storage.com/us/product/mosfet/to-247-4l.html +TO-247-3 Horizontal RM 5.45mm +0 +3 +3 +TO_SOT_Packages_THT +TO-247-3_Horizontal_TabUp +TO-247-3, Horizontal, RM 5.45mm, see https://toshiba.semicon-storage.com/us/product/mosfet/to-247-4l.html +TO-247-3 Horizontal RM 5.45mm +0 +3 +3 +TO_SOT_Packages_THT +TO-247-3_Vertical +TO-247-3, Vertical, RM 5.45mm, see https://toshiba.semicon-storage.com/us/product/mosfet/to-247-4l.html +TO-247-3 Vertical RM 5.45mm +0 +3 +3 +TO_SOT_Packages_THT +TO-247-4_Horizontal_TabDown +TO-247-4, Horizontal, RM 2.54mm, see https://toshiba.semicon-storage.com/us/product/mosfet/to-247-4l.html +TO-247-4 Horizontal RM 2.54mm +0 +4 +4 +TO_SOT_Packages_THT +TO-247-4_Horizontal_TabUp +TO-247-4, Horizontal, RM 2.54mm, see https://toshiba.semicon-storage.com/us/product/mosfet/to-247-4l.html +TO-247-4 Horizontal RM 2.54mm +0 +4 +4 +TO_SOT_Packages_THT +TO-247-4_Vertical +TO-247-4, Vertical, RM 2.54mm, see https://toshiba.semicon-storage.com/us/product/mosfet/to-247-4l.html +TO-247-4 Vertical RM 2.54mm +0 +4 +4 +TO_SOT_Packages_THT +TO-247-5_Horizontal_TabDown +TO-247-5, Horizontal, RM 2.54mm, see http://ww1.microchip.com/downloads/en/DeviceDoc/20005685A.pdf +TO-247-5 Horizontal RM 2.54mm +0 +5 +5 +TO_SOT_Packages_THT +TO-247-5_Horizontal_TabUp +TO-247-5, Horizontal, RM 2.54mm, see http://ww1.microchip.com/downloads/en/DeviceDoc/20005685A.pdf +TO-247-5 Horizontal RM 2.54mm +0 +5 +5 +TO_SOT_Packages_THT +TO-247-5_Vertical +TO-247-5, Vertical, RM 2.54mm, see http://ww1.microchip.com/downloads/en/DeviceDoc/20005685A.pdf +TO-247-5 Vertical RM 2.54mm +0 +5 +5 +TO_SOT_Packages_THT +TO-251-2-1EP_Horizontal_TabDown +TO-251-2, Horizontal, RM 4.58mm, IPAK, see https://www.diodes.com/assets/Package-Files/TO251.pdf +TO-251-2 Horizontal RM 4.58mm IPAK +0 +3 +3 +TO_SOT_Packages_THT +TO-251-2_Vertical +TO-251-2, Vertical, RM 4.58mm, IPAK, see https://www.diodes.com/assets/Package-Files/TO251.pdf +TO-251-2 Vertical RM 4.58mm IPAK +0 +2 +2 +TO_SOT_Packages_THT +TO-251-3-1EP_Horizontal_TabDown +TO-251-3, Horizontal, RM 2.29mm, IPAK, see https://www.diodes.com/assets/Package-Files/TO251.pdf +TO-251-3 Horizontal RM 2.29mm IPAK +0 +4 +4 +TO_SOT_Packages_THT +TO-251-3_Vertical +TO-251-3, Vertical, RM 2.29mm, IPAK, see https://www.diodes.com/assets/Package-Files/TO251.pdf +TO-251-3 Vertical RM 2.29mm IPAK +0 +3 +3 +TO_SOT_Packages_THT +TO-262-3-1EP_Horizontal_TabDown +TO-262-3, Horizontal, RM 2.54mm, IIPAK, I2PAK, see http://www.onsemi.com/pub/Collateral/EN8586-D.PDF +TO-262-3 Horizontal RM 2.54mm IIPAK I2PAK +0 +4 +4 +TO_SOT_Packages_THT +TO-262-3_Vertical +TO-262-3, Vertical, RM 2.54mm, IIPAK, I2PAK, see http://www.onsemi.com/pub/Collateral/EN8586-D.PDF +TO-262-3 Vertical RM 2.54mm IIPAK I2PAK +0 +3 +3 +TO_SOT_Packages_THT +TO-262-5-1EP_Horizontal_TabDown +TO-262-5, Horizontal, RM 1.7mm, IIPAK, I2PAK, see http://pdf.datasheetcatalog.com/datasheet/irf/iris4011.pdf +TO-262-5 Horizontal RM 1.7mm IIPAK I2PAK +0 +6 +6 +TO_SOT_Packages_THT +TO-262-5_Vertical +TO-262-5, Vertical, RM 1.7mm, IIPAK, I2PAK, see http://pdf.datasheetcatalog.com/datasheet/irf/iris4011.pdf +TO-262-5 Vertical RM 1.7mm IIPAK I2PAK +0 +5 +5 +TO_SOT_Packages_THT +TO-264-2_Horizontal_TabDown +TO-264-2, Horizontal, RM 10.9mm, see https://www.fairchildsemi.com/package-drawings/TO/TO264A03.pdf +TO-264-2 Horizontal RM 10.9mm +0 +2 +2 +TO_SOT_Packages_THT +TO-264-2_Horizontal_TabUp +TO-264-2, Horizontal, RM 10.9mm, see https://www.fairchildsemi.com/package-drawings/TO/TO264A03.pdf +TO-264-2 Horizontal RM 10.9mm +0 +2 +2 +TO_SOT_Packages_THT +TO-264-2_Vertical +TO-264-2, Vertical, RM 10.9mm, see https://www.fairchildsemi.com/package-drawings/TO/TO264A03.pdf +TO-264-2 Vertical RM 10.9mm +0 +2 +2 +TO_SOT_Packages_THT +TO-264-3_Horizontal_TabDown +TO-264-3, Horizontal, RM 5.45mm, see https://www.fairchildsemi.com/package-drawings/TO/TO264A03.pdf +TO-264-3 Horizontal RM 5.45mm +0 +3 +3 +TO_SOT_Packages_THT +TO-264-3_Horizontal_TabUp +TO-264-3, Horizontal, RM 5.45mm, see https://www.fairchildsemi.com/package-drawings/TO/TO264A03.pdf +TO-264-3 Horizontal RM 5.45mm +0 +3 +3 +TO_SOT_Packages_THT +TO-264-3_Vertical +TO-264-3, Vertical, RM 5.45mm, see https://www.fairchildsemi.com/package-drawings/TO/TO264A03.pdf +TO-264-3 Vertical RM 5.45mm +0 +3 +3 +TO_SOT_Packages_THT +TO-264-5_Horizontal_TabDown +TO-264-5, Horizontal, RM 3.81mm, see https://www.onsemi.com/pub/Collateral/NJL3281D-D.PDF +TO-264-5 Horizontal RM 3.81mm +0 +5 +5 +TO_SOT_Packages_THT +TO-264-5_Horizontal_TabUp +TO-264-5, Horizontal, RM 3.81mm, see https://www.onsemi.com/pub/Collateral/NJL3281D-D.PDF +TO-264-5 Horizontal RM 3.81mm +0 +5 +5 +TO_SOT_Packages_THT +TO-264-5_Vertical +TO-264-5, Vertical, RM 3.81mm, see https://www.onsemi.com/pub/Collateral/NJL3281D-D.PDF +TO-264-5 Vertical RM 3.81mm +0 +5 +5 diff --git a/F1-nolib/chronometer/kicad/chrono/fp-lib-table b/F1-nolib/chronometer/kicad/chrono/fp-lib-table new file mode 100644 index 0000000..a5f87ad --- /dev/null +++ b/F1-nolib/chronometer/kicad/chrono/fp-lib-table @@ -0,0 +1,7 @@ +(fp_lib_table + (lib (name chrono)(type KiCad)(uri ${KIPRJMOD}/chrono.pretty)(options "")(descr "")) + (lib (name TerminalBlock_Phoenix)(type KiCad)(uri ${KISYSMOD}/TerminalBlock_Phoenix.pretty)(options "")(descr "")) + (lib (name Inductor_SMD)(type KiCad)(uri ${KISYSMOD}/Inductor_SMD.pretty)(options "")(descr "")) + (lib (name LED_THT)(type KiCad)(uri ${KISYSMOD}/LED_THT.pretty)(options "")(descr "")) + (lib (name Crystal)(type KiCad)(uri ${KISYSMOD}/Crystal.pretty)(options "")(descr "")) +) diff --git a/F1-nolib/chronometer/kicad/chrono/stm32-rescue.lib b/F1-nolib/chronometer/kicad/chrono/stm32-rescue.lib new file mode 100644 index 0000000..0232b24 --- /dev/null +++ b/F1-nolib/chronometer/kicad/chrono/stm32-rescue.lib @@ -0,0 +1,694 @@ +EESchema-LIBRARY Version 2.4 +#encoding utf-8 +# +# +3.3V +# +DEF +3.3V #PWR 0 0 Y Y 1 F P +F0 "#PWR" 0 -150 50 H I C CNN +F1 "+3.3V" 0 140 50 H V C CNN +F2 "" 0 0 50 H I C CNN +F3 "" 0 0 50 H I C CNN +DRAW +P 2 0 1 0 -30 50 0 100 N +P 2 0 1 0 0 0 0 100 N +P 2 0 1 0 0 100 30 50 N +X +3V3 1 0 0 0 U 50 50 1 1 W N +ENDDRAW +ENDDEF +# +# +5V +# +DEF +5V #PWR 0 0 Y Y 1 F P +F0 "#PWR" 0 -150 50 H I C CNN +F1 "+5V" 0 140 50 H V C CNN +F2 "" 0 0 50 H I C CNN +F3 "" 0 0 50 H I C CNN +DRAW +P 2 0 1 0 -30 50 0 100 N +P 2 0 1 0 0 0 0 100 N +P 2 0 1 0 0 100 30 50 N +X +5V 1 0 0 0 U 50 50 1 1 W N +ENDDRAW +ENDDEF +# +# 74HC4051 +# +DEF 74HC4051 U 0 10 Y Y 1 F N +F0 "U" 0 0 50 H V C CNN +F1 "74HC4051" 0 -150 50 H V C CNN +F2 "" 0 0 50 H V C CNN +F3 "" 0 0 50 H V C CNN +$FPLIST + SO16 + TSSOP16 + SSOP16 + DHVQFN16 +$ENDFPLIST +DRAW +S -400 450 400 -450 0 1 0 N +X Y4 1 700 -50 300 L 50 50 1 1 B +X S1 10 -700 250 300 R 50 50 1 1 I +X S0 11 -700 350 300 R 50 50 1 1 I +X Y3 12 700 50 300 L 50 50 1 1 B +X Y0 13 700 350 300 L 50 50 1 1 B +X Y1 14 700 250 300 L 50 50 1 1 B +X Y2 15 700 150 300 L 50 50 1 1 B +X VCC 16 -700 -100 300 R 50 50 1 1 W +X Y6 2 700 -250 300 L 50 50 1 1 B +X Z 3 0 -750 300 U 50 50 1 1 B +X Y7 4 700 -350 300 L 50 50 1 1 B +X Y5 5 700 -150 300 L 50 50 1 1 B +X ~E 6 -700 -350 300 R 50 50 1 1 I I +X VEE 7 -700 0 300 R 50 50 1 1 W +X GND 8 -700 -200 300 R 50 50 1 1 W +X S2 9 -700 150 300 R 50 50 1 1 I +ENDDRAW +ENDDEF +# +# C +# +DEF C C 0 10 N Y 1 F N +F0 "C" 25 100 50 H V L CNN +F1 "C" 25 -100 50 H V L CNN +F2 "" 38 -150 50 H I C CNN +F3 "" 0 0 50 H I C CNN +$FPLIST + C_* +$ENDFPLIST +DRAW +P 2 0 1 20 -80 -30 80 -30 N +P 2 0 1 20 -80 30 80 30 N +X ~ 1 0 150 110 D 50 50 1 1 P +X ~ 2 0 -150 110 U 50 50 1 1 P +ENDDRAW +ENDDEF +# +# CONN_01X01 +# +DEF CONN_01X01 J 0 40 Y N 1 F N +F0 "J" 0 100 50 H V C CNN +F1 "CONN_01X01" 100 0 50 V V C CNN +F2 "" 0 0 50 H I C CNN +F3 "" 0 0 50 H I C CNN +$FPLIST + Pin_Header_Straight_1X* + Pin_Header_Angled_1X* + Socket_Strip_Straight_1X* + Socket_Strip_Angled_1X* +$ENDFPLIST +DRAW +S -50 5 10 -5 0 1 0 N +S -50 50 50 -50 0 1 0 N +X P1 1 -200 0 150 R 50 50 1 1 P +ENDDRAW +ENDDEF +# +# CONN_01X03 +# +DEF CONN_01X03 J 0 40 Y N 1 F N +F0 "J" 0 200 50 H V C CNN +F1 "CONN_01X03" 100 0 50 V V C CNN +F2 "" 0 0 50 H I C CNN +F3 "" 0 0 50 H I C CNN +$FPLIST + Pin_Header_Straight_1X* + Pin_Header_Angled_1X* + Socket_Strip_Straight_1X* + Socket_Strip_Angled_1X* +$ENDFPLIST +DRAW +S -50 -95 10 -105 0 1 0 N +S -50 5 10 -5 0 1 0 N +S -50 105 10 95 0 1 0 N +S -50 150 50 -150 0 1 0 N +X P1 1 -200 100 150 R 50 50 1 1 P +X P2 2 -200 0 150 R 50 50 1 1 P +X P3 3 -200 -100 150 R 50 50 1 1 P +ENDDRAW +ENDDEF +# +# CONN_01X04 +# +DEF CONN_01X04 J 0 40 Y N 1 F N +F0 "J" 0 250 50 H V C CNN +F1 "CONN_01X04" 100 0 50 V V C CNN +F2 "" 0 0 50 H I C CNN +F3 "" 0 0 50 H I C CNN +$FPLIST + Pin_Header_Straight_1X* + Pin_Header_Angled_1X* + Socket_Strip_Straight_1X* + Socket_Strip_Angled_1X* +$ENDFPLIST +DRAW +S -50 -145 10 -155 0 1 0 N +S -50 -45 10 -55 0 1 0 N +S -50 55 10 45 0 1 0 N +S -50 155 10 145 0 1 0 N +S -50 200 50 -200 0 1 0 N +X P1 1 -200 150 150 R 50 50 1 1 P +X P2 2 -200 50 150 R 50 50 1 1 P +X P3 3 -200 -50 150 R 50 50 1 1 P +X P4 4 -200 -150 150 R 50 50 1 1 P +ENDDRAW +ENDDEF +# +# CONN_01X08 +# +DEF CONN_01X08 J 0 40 Y N 1 F N +F0 "J" 0 450 50 H V C CNN +F1 "CONN_01X08" 100 0 50 V V C CNN +F2 "" 0 0 50 H I C CNN +F3 "" 0 0 50 H I C CNN +$FPLIST + Pin_Header_Straight_1X* + Pin_Header_Angled_1X* + Socket_Strip_Straight_1X* + Socket_Strip_Angled_1X* +$ENDFPLIST +DRAW +S -50 -400 50 400 0 1 0 N +S -50 -345 10 -355 0 1 0 N +S -50 -245 10 -255 0 1 0 N +S -50 -145 10 -155 0 1 0 N +S -50 -45 10 -55 0 1 0 N +S -50 55 10 45 0 1 0 N +S -50 155 10 145 0 1 0 N +S -50 255 10 245 0 1 0 N +S -50 355 10 345 0 1 0 N +X P1 1 -200 350 150 R 50 50 1 1 P +X P2 2 -200 250 150 R 50 50 1 1 P +X P3 3 -200 150 150 R 50 50 1 1 P +X P4 4 -200 50 150 R 50 50 1 1 P +X P5 5 -200 -50 150 R 50 50 1 1 P +X P6 6 -200 -150 150 R 50 50 1 1 P +X P7 7 -200 -250 150 R 50 50 1 1 P +X P8 8 -200 -350 150 R 50 50 1 1 P +ENDDRAW +ENDDEF +# +# CP +# +DEF CP C 0 10 N Y 1 F N +F0 "C" 25 100 50 H V L CNN +F1 "CP" 25 -100 50 H V L CNN +F2 "" 38 -150 50 H I C CNN +F3 "" 0 0 50 H I C CNN +$FPLIST + CP_* +$ENDFPLIST +DRAW +S -90 20 -90 40 0 1 0 N +S -90 20 90 20 0 1 0 N +S 90 -20 -90 -40 0 1 0 F +S 90 40 -90 40 0 1 0 N +S 90 40 90 20 0 1 0 N +P 2 0 1 0 -70 90 -30 90 N +P 2 0 1 0 -50 110 -50 70 N +X ~ 1 0 150 110 D 50 50 1 1 P +X ~ 2 0 -150 110 U 50 50 1 1 P +ENDDRAW +ENDDEF +# +# D +# +DEF D D 0 40 N N 1 F N +F0 "D" 0 100 50 H V C CNN +F1 "D" 0 -100 50 H V C CNN +F2 "" 0 0 50 H I C CNN +F3 "" 0 0 50 H I C CNN +$FPLIST + TO-???* + *SingleDiode + *_Diode_* + *SingleDiode* + D_* +$ENDFPLIST +DRAW +P 2 0 1 8 -50 50 -50 -50 N +P 2 0 1 0 50 0 -50 0 N +P 4 0 1 8 50 50 50 -50 -50 0 50 50 N +X K 1 -150 0 100 R 50 50 1 1 P +X A 2 150 0 100 L 50 50 1 1 P +ENDDRAW +ENDDEF +# +# D_Schottky +# +DEF D_Schottky D 0 40 N N 1 F N +F0 "D" 0 100 50 H V C CNN +F1 "D_Schottky" 0 -100 50 H V C CNN +F2 "" 0 0 50 H I C CNN +F3 "" 0 0 50 H I C CNN +$FPLIST + TO-???* + *SingleDiode + *_Diode_* + *SingleDiode* + D_* +$ENDFPLIST +DRAW +P 2 0 1 0 50 0 -50 0 N +P 4 0 1 8 50 50 50 -50 -50 0 50 50 N +P 6 0 1 8 -75 25 -75 50 -50 50 -50 -50 -25 -50 -25 -25 N +X K 1 -150 0 100 R 50 50 1 1 P +X A 2 150 0 100 L 50 50 1 1 P +ENDDRAW +ENDDEF +# +# D_Zener +# +DEF D_Zener D 0 40 N N 1 F N +F0 "D" 0 100 50 H V C CNN +F1 "D_Zener" 0 -100 50 H V C CNN +F2 "" 0 0 50 H I C CNN +F3 "" 0 0 50 H I C CNN +$FPLIST + TO-???* + *SingleDiode + *_Diode_* + *SingleDiode* + D_* +$ENDFPLIST +DRAW +P 2 0 1 0 50 0 -50 0 N +P 3 0 1 8 -50 -50 -50 50 -30 50 N +P 4 0 1 8 50 -50 50 50 -50 0 50 -50 N +X K 1 -150 0 100 R 50 50 1 1 P +X A 2 150 0 100 L 50 50 1 1 P +ENDDRAW +ENDDEF +# +# GND +# +DEF GND #PWR 0 0 Y Y 1 F P +F0 "#PWR" 0 -250 50 H I C CNN +F1 "GND" 0 -150 50 H V C CNN +F2 "" 0 0 50 H I C CNN +F3 "" 0 0 50 H I C CNN +DRAW +P 6 0 1 0 0 0 0 -50 50 -50 0 -100 -50 -50 0 -50 N +X GND 1 0 0 0 D 50 50 1 1 W N +ENDDRAW +ENDDEF +# +# Jumper_NO_Small +# +DEF Jumper_NO_Small JP 0 30 N N 1 F N +F0 "JP" 0 80 50 H V C CNN +F1 "Jumper_NO_Small" 10 -60 50 H V C CNN +F2 "" 0 0 50 H I C CNN +F3 "" 0 0 50 H I C CNN +DRAW +C -40 0 20 0 1 0 N +C 40 0 20 0 1 0 N +X 1 1 -100 0 40 R 50 50 0 1 P +X 2 2 100 0 40 L 50 50 0 1 P +ENDDRAW +ENDDEF +# +# L +# +DEF L L 0 40 N N 1 F N +F0 "L" -50 0 50 V V C CNN +F1 "L" 75 0 50 V V C CNN +F2 "" 0 0 50 H I C CNN +F3 "" 0 0 50 H I C CNN +$FPLIST + Choke_* + *Coil* + Inductor_* + L_* +$ENDFPLIST +DRAW +A 0 -75 25 -899 899 0 1 0 N 0 -100 0 -50 +A 0 -25 25 -899 899 0 1 0 N 0 -50 0 0 +A 0 25 25 -899 899 0 1 0 N 0 0 0 50 +A 0 75 25 -899 899 0 1 0 N 0 50 0 100 +X 1 1 0 150 50 D 50 50 1 1 P +X 2 2 0 -150 50 U 50 50 1 1 P +ENDDRAW +ENDDEF +# +# LED-RESCUE-stm32 +# +DEF LED-RESCUE-stm32 D 0 40 Y N 1 F N +F0 "D" 0 100 50 H V C CNN +F1 "LED-RESCUE-stm32" 0 -100 50 H V C CNN +F2 "" 0 0 50 H V C CNN +F3 "" 0 0 50 H V C CNN +$FPLIST + LED* +$ENDFPLIST +DRAW +P 2 0 1 8 -50 -50 -50 50 N +P 2 0 1 0 -50 0 50 0 N +P 4 0 1 8 50 -50 50 50 -50 0 50 -50 N +P 5 0 1 0 -120 -30 -180 -90 -150 -90 -180 -90 -180 -60 N +P 5 0 1 0 -70 -30 -130 -90 -100 -90 -130 -90 -130 -60 N +X K 1 -150 0 100 R 50 50 1 1 P +X A 2 150 0 100 L 50 50 1 1 P +ENDDRAW +ENDDEF +# +# LM1117-3.3-RESCUE-stm32 +# +DEF LM1117-3.3-RESCUE-stm32 U 0 30 Y Y 1 F N +F0 "U" 100 -250 50 H V C CNN +F1 "LM1117-3.3-RESCUE-stm32" 0 250 50 H V C CNN +F2 "" 0 0 50 H I C CNN +F3 "" 0 0 50 H I C CNN +$FPLIST + SOT-223* + TO-263* + TO-252* +$ENDFPLIST +DRAW +S -200 -200 200 200 0 1 10 f +X GND/ADJ 1 0 -300 100 U 50 50 1 1 W +X VO 2 300 50 100 L 50 50 1 1 P +X VI 3 -300 0 100 R 50 50 1 1 W +X VO 4 300 -50 100 L 50 50 1 1 w +ENDDRAW +ENDDEF +# +# LM2576HV +# +DEF LM2576HV U 0 40 Y Y 1 F N +F0 "U" -350 250 60 H V C CNN +F1 "LM2576HV" 250 250 60 H V C CNN +F2 "" 0 0 60 H I C CNN +F3 "" 0 0 60 H I C CNN +F4 "Texas Instruments" 0 350 60 H I C CNN "Manufacturer" +$FPLIST + *DIP8 + SOIC8 +$ENDFPLIST +DRAW +S -400 200 400 -250 0 1 0 N +X VIN 1 -700 100 300 R 50 50 1 1 W +X VOUT 2 700 -100 300 L 50 50 1 1 w +X GND 3 100 -550 300 U 50 50 1 1 W +X FB 4 700 100 300 L 50 50 1 1 I +X ON/OFF 5 -100 -550 300 U 50 50 1 1 I I +ENDDRAW +ENDDEF +# +# MAX471-RESCUE-stm32 +# +DEF MAX471-RESCUE-stm32 U 0 40 Y Y 1 F N +F0 "U" -300 350 50 H V L CNN +F1 "MAX471-RESCUE-stm32" -300 -350 50 H V L CNN +F2 "" 0 0 50 H I C CNN +F3 "" 0 0 50 H I C CNN +DRAW +S -300 300 300 -300 0 1 10 f +X SHDN 1 -400 -100 100 R 50 50 1 1 I +X RS+ 2 -400 200 100 R 50 50 1 1 W +X RS+ 3 -400 100 100 R 50 50 1 1 P +X GND 4 -400 -200 100 R 50 50 1 1 W +X SIGN 5 400 -100 100 L 50 50 1 1 C +X RS- 6 400 200 100 L 50 50 1 1 w +X RS- 7 400 100 100 L 50 50 1 1 P +X OUT 8 400 -200 100 L 50 50 1 1 O +ENDDRAW +ENDDEF +# +# MCP2551-I_SN +# +DEF MCP2551-I_SN U 0 40 Y Y 1 F N +F0 "U" -400 350 50 H V L CNN +F1 "MCP2551-I_SN" 100 350 50 H V L CNN +F2 "Housings_SOIC:SOIC-8_3.9x4.9mm_Pitch1.27mm" 0 -500 50 H I C CIN +F3 "" 0 0 50 H I C CNN +$FPLIST + SOIC*Pitch1.27mm* +$ENDFPLIST +DRAW +S -400 300 400 -300 0 1 10 f +X TXD 1 -500 200 100 R 50 50 1 1 I +X VSS 2 0 -400 100 U 50 50 1 1 W +X VDD 3 0 400 100 D 50 50 1 1 W +X RXD 4 -500 100 100 R 50 50 1 1 O +X Vref 5 -500 -100 100 R 50 50 1 1 w +X CANL 6 500 -100 100 L 50 50 1 1 B +X CANH 7 500 100 100 L 50 50 1 1 B +X Rs 8 -500 -200 100 R 50 50 1 1 I +ENDDRAW +ENDDEF +# +# PESD1CAN +# +DEF PESD1CAN D 0 30 Y N 1 F N +F0 "D" 0 -350 50 H V C CNN +F1 "PESD1CAN" 50 150 50 H V C CNN +F2 "" 0 0 50 H V C CNN +F3 "" 0 0 50 H V C CNN +$FPLIST + SOT23 +$ENDFPLIST +DRAW +S -200 100 300 -300 0 1 0 N +P 2 0 1 0 -140 -200 150 -200 N +P 2 0 1 0 -140 0 150 0 N +P 3 0 1 8 -150 -150 -150 -250 -150 -250 N +P 3 0 1 8 -150 50 -150 -50 -150 -50 N +P 3 0 1 8 150 -150 150 -250 150 -250 N +P 3 0 1 8 150 50 150 -50 150 -50 N +P 4 0 1 8 -150 -150 -170 -150 -170 -160 -170 -160 N +P 4 0 1 8 -150 50 -170 50 -170 40 -170 40 N +P 4 0 1 8 150 -250 170 -250 170 -240 170 -240 N +P 4 0 1 8 150 -150 130 -150 130 -160 130 -160 N +P 4 0 1 8 150 -50 170 -50 170 -40 170 -40 N +P 4 0 1 0 150 0 250 0 250 -200 150 -200 N +P 4 0 1 8 150 50 130 50 130 40 130 40 N +P 5 0 1 8 -130 -240 -130 -250 -150 -250 -150 -250 -150 -250 N +P 5 0 1 8 -130 -40 -130 -50 -150 -50 -150 -50 -150 -50 N +P 6 0 1 8 -50 -250 -150 -200 -50 -150 -50 -250 -50 -250 -50 -250 N +P 6 0 1 8 -50 -50 -150 0 -50 50 -50 -50 -50 -50 -50 -50 N +P 6 0 1 8 50 -150 150 -200 50 -250 50 -150 50 -150 50 -150 N +P 6 0 1 8 50 50 150 0 50 -50 50 50 50 50 50 50 N +X K 1 -300 0 150 R 50 50 0 1 P +X K 2 -300 -200 150 R 50 50 0 1 P +X O 3 400 -100 150 L 50 50 0 1 P +ENDDRAW +ENDDEF +# +# PWR_FLAG +# +DEF PWR_FLAG #FLG 0 0 N N 1 F P +F0 "#FLG" 0 75 50 H I C CNN +F1 "PWR_FLAG" 0 150 50 H V C CNN +F2 "" 0 0 50 H I C CNN +F3 "" 0 0 50 H I C CNN +DRAW +P 6 0 1 0 0 0 0 50 -40 75 0 100 40 75 0 50 N +X pwr 1 0 0 0 U 50 50 0 0 w +ENDDRAW +ENDDEF +# +# Q_PMOS_GSD +# +DEF Q_PMOS_GSD Q 0 0 Y N 1 F N +F0 "Q" 200 50 50 H V L CNN +F1 "Q_PMOS_GSD" 200 -50 50 H V L CNN +F2 "" 200 100 50 H I C CNN +F3 "" 0 0 50 H I C CNN +DRAW +C 65 0 111 0 1 10 N +C 100 -70 11 0 1 0 F +C 100 70 11 0 1 0 F +P 2 0 1 0 2 0 10 0 N +P 2 0 1 0 30 -70 100 -70 N +P 2 0 1 10 30 -50 30 -90 N +P 2 0 1 0 30 0 100 0 N +P 2 0 1 10 30 20 30 -20 N +P 2 0 1 0 30 70 100 70 N +P 2 0 1 10 30 90 30 50 N +P 2 0 1 0 100 -70 100 -100 N +P 2 0 1 0 100 -70 100 0 N +P 2 0 1 0 100 100 100 70 N +P 3 0 1 10 10 75 10 -75 10 -75 N +P 4 0 1 0 90 0 50 -15 50 15 90 0 F +P 4 0 1 0 100 -70 130 -70 130 70 100 70 N +P 4 0 1 0 110 -20 115 -15 145 -15 150 -10 N +P 4 0 1 0 130 -15 115 10 145 10 130 -15 N +X G 1 -200 0 200 R 50 50 1 1 I +X S 2 100 -200 100 U 50 50 1 1 P +X D 3 100 200 100 D 50 50 1 1 P +ENDDRAW +ENDDEF +# +# R +# +DEF R R 0 0 N Y 1 F N +F0 "R" 80 0 50 V V C CNN +F1 "R" 0 0 50 V V C CNN +F2 "" -70 0 50 V I C CNN +F3 "" 0 0 50 H I C CNN +$FPLIST + R_* + R_* +$ENDFPLIST +DRAW +S -40 -100 40 100 0 1 10 N +X ~ 1 0 150 50 D 50 50 1 1 P +X ~ 2 0 -150 50 U 50 50 1 1 P +ENDDRAW +ENDDEF +# +# STM32F042C6Tx +# +DEF STM32F042C6Tx U 0 40 Y Y 1 L N +F0 "U" -3000 1725 50 H V L BNN +F1 "STM32F042C6Tx" 3000 1725 50 H V R BNN +F2 "LQFP48" 3000 1675 50 H V R TNN +F3 "" 0 0 50 H V C CNN +DRAW +S -3000 -1700 3000 1700 0 1 10 f +X VBAT 1 -3100 1100 100 R 50 50 1 1 W +X ADC_IN0/RTC_TAMP2/SYS_WKUP1/TIM2_CH1/TIM2_ETR/TSC_G1_IO1/USART2_CTS/PA0 10 3100 100 100 L 50 50 1 1 B +X ADC_IN1/TIM2_CH2/TSC_G1_IO2/USART2_DE/USART2_RTS/PA1 11 3100 0 100 L 50 50 1 1 B +X ADC_IN2/SYS_WKUP4/TIM2_CH3/TSC_G1_IO3/USART2_TX/PA2 12 3100 -100 100 L 50 50 1 1 B +X ADC_IN3/TIM2_CH4/TSC_G1_IO4/USART2_RX/PA3 13 3100 -200 100 L 50 50 1 1 B +X ADC_IN4/I2S1_WS/SPI1_NSS/TIM14_CH1/TSC_G2_IO1/USART2_CK/USB_OE/PA4 14 3100 -300 100 L 50 50 1 1 B +X ADC_IN5/CEC/I2S1_CK/SPI1_SCK/TIM2_CH1/TIM2_ETR/TSC_G2_IO2/PA5 15 3100 -400 100 L 50 50 1 1 B +X ADC_IN6/I2S1_MCK/SPI1_MISO/TIM16_CH1/TIM1_BKIN/TIM3_CH1/TSC_G2_IO3/PA6 16 3100 -500 100 L 50 50 1 1 B +X ADC_IN7/I2S1_SD/SPI1_MOSI/TIM14_CH1/TIM17_CH1/TIM1_CH1N/TIM3_CH2/TSC_G2_IO4/PA7 17 3100 -600 100 L 50 50 1 1 B +X PB0/ADC_IN8/TIM1_CH2N/TIM3_CH3/TSC_G3_IO2 18 -3100 100 100 R 50 50 1 1 B +X PB1/ADC_IN9/TIM14_CH1/TIM1_CH3N/TIM3_CH4/TSC_G3_IO3 19 -3100 0 100 R 50 50 1 1 B +X PC13/RTC_OUT_ALARM/RTC_OUT_CALIB/RTC_TAMP1/RTC_TS/SYS_WKUP2 2 -3100 500 100 R 50 50 1 1 B +X PB2/TSC_G3_IO4 20 -3100 -100 100 R 50 50 1 1 B +X PB10/CEC/I2C1_SCL/SPI2_SCK/TIM2_CH3/TSC_SYNC 21 -3100 -900 100 R 50 50 1 1 B +X PB11/I2C1_SDA/TIM2_CH4 22 -3100 -1000 100 R 50 50 1 1 B +X VSS 23 -200 -1800 100 U 50 50 1 1 W +X VDD 24 -200 1800 100 D 50 50 1 1 W +X PB12/SPI2_NSS/TIM1_BKIN 25 -3100 -1100 100 R 50 50 1 1 B +X PB13/I2C1_SCL/SPI2_SCK/TIM1_CH1N 26 -3100 -1200 100 R 50 50 1 1 B +X PB14/I2C1_SDA/SPI2_MISO/TIM1_CH2N 27 -3100 -1300 100 R 50 50 1 1 B +X PB15/RTC_REFIN/SPI2_MOSI/SYS_WKUP7/TIM1_CH3N 28 -3100 -1400 100 R 50 50 1 1 B +X CRS_SYNC/RCC_MCO/TIM1_CH1/USART1_CK/PA8 29 3100 -700 100 L 50 50 1 1 B +X PC14/RCC_OSC32_IN 3 -3100 400 100 R 50 50 1 1 B +X I2C1_SCL/TIM1_CH2/TSC_G4_IO1/USART1_TX/PA9 30 3100 -800 100 L 50 50 1 1 B +X I2C1_SDA/TIM17_BKIN/TIM1_CH3/TSC_G4_IO2/USART1_RX/PA10 31 3100 -900 100 L 50 50 1 1 B +X CAN_RX/I2C1_SCL/TIM1_CH4/TSC_G4_IO3/USART1_CTS/USB_DM/PA11 32 3100 -1000 100 L 50 50 1 1 B +X CAN_TX/I2C1_SDA/TIM1_ETR/TSC_G4_IO4/USART1_DE/USART1_RTS/USB_DP/PA12 33 3100 -1100 100 L 50 50 1 1 B +X IR_OUT/SYS_SWDIO/USB_OE/PA13 34 3100 -1200 100 L 50 50 1 1 B +X VSS 35 -100 -1800 100 U 50 50 1 1 W +X VDDIO2 36 100 1800 100 D 50 50 1 1 W +X SYS_SWCLK/USART2_TX/PA14 37 3100 -1300 100 L 50 50 1 1 B +X I2S1_WS/SPI1_NSS/TIM2_CH1/TIM2_ETR/USART2_RX/USB_OE/PA15 38 3100 -1400 100 L 50 50 1 1 B +X PB3/I2S1_CK/SPI1_SCK/TIM2_CH2/TSC_G5_IO1 39 -3100 -200 100 R 50 50 1 1 B +X PC15/RCC_OSC32_OUT 4 -3100 300 100 R 50 50 1 1 B +X PB4/I2S1_MCK/SPI1_MISO/TIM17_BKIN/TIM3_CH1/TSC_G5_IO2 40 -3100 -300 100 R 50 50 1 1 B +X PB5/I2C1_SMBA/I2S1_SD/SPI1_MOSI/SYS_WKUP6/TIM16_BKIN/TIM3_CH2 41 -3100 -400 100 R 50 50 1 1 B +X PB6/I2C1_SCL/TIM16_CH1N/TSC_G5_IO3/USART1_TX 42 -3100 -500 100 R 50 50 1 1 B +X PB7/I2C1_SDA/TIM17_CH1N/TSC_G5_IO4/USART1_RX 43 -3100 -600 100 R 50 50 1 1 B +X PF11 44 -3100 700 100 R 50 50 1 1 B +X PB8/CAN_RX/CEC/I2C1_SCL/TIM16_CH1/TSC_SYNC 45 -3100 -700 100 R 50 50 1 1 B +X PB9/CAN_TX/I2C1_SDA/IR_OUT/SPI2_NSS/TIM17_CH1 46 -3100 -800 100 R 50 50 1 1 B +X VSS 47 0 -1800 100 U 50 50 1 1 W +X VDD 48 -100 1800 100 D 50 50 1 1 W +X PF0/CRS_SYNC/I2C1_SDA/RCC_OSC_IN 5 -3100 900 100 R 50 50 1 1 I +X PF1/I2C1_SCL/RCC_OSC_OUT 6 -3100 800 100 R 50 50 1 1 I +X NRST 7 -3100 1300 100 R 50 50 1 1 I +X VSSA 8 100 -1800 100 U 50 50 1 1 W +X VDDA 9 0 1800 100 D 50 50 1 1 W +ENDDRAW +ENDDEF +# +# TPS2051 +# +DEF TPS2051 U 0 40 Y Y 1 F N +F0 "U" 0 -300 60 H V C CNN +F1 "TPS2051" 0 300 60 H V C CNN +F2 "" 0 0 60 H I C CNN +F3 "" 0 0 60 H I C CNN +DRAW +S -250 250 250 -250 0 1 0 N +X GND 1 -450 150 200 R 50 50 1 1 W +X IN 2 -450 50 200 R 50 50 1 1 W +X IN 3 -450 -50 200 R 50 50 1 1 P +X EN 4 -450 -150 200 R 50 50 1 1 I +X ~OC 5 450 -150 200 L 50 50 1 1 O +X OUT 6 450 -50 200 L 50 50 1 1 P +X OUT 7 450 50 200 L 50 50 1 1 P +X OUT 8 450 150 200 L 50 50 1 1 w +ENDDRAW +ENDDEF +# +# USB6B1 +# +DEF USB6B1 D 0 30 Y N 1 F N +F0 "D" 0 -450 50 H V C CNN +F1 "USB6B1" 0 400 50 H V C CNN +F2 "" 200 -100 50 V V C CNN +F3 "" 200 -100 50 V V C CNN +$FPLIST + SO8 +$ENDFPLIST +DRAW +C -150 -300 7 0 1 0 N +C -150 100 7 0 1 0 N +C -150 300 7 0 1 0 N +C 0 -300 7 0 1 0 N +C 0 -100 7 0 1 0 N +C 0 300 7 0 1 0 N +C 200 -300 7 0 1 0 N +C 200 300 7 0 1 0 N +S -300 -100 300 -100 0 1 0 N +S -300 300 300 300 0 1 0 N +S -200 -150 -100 -150 0 1 0 N +S -200 250 -100 250 0 1 0 N +S -150 300 -150 -300 0 1 0 N +S -50 -150 50 -150 0 1 0 N +S -50 250 50 250 0 1 0 N +S 0 300 0 -300 0 1 0 N +S 200 300 200 -300 0 1 0 N +S 300 -300 -300 -300 0 1 0 N +S 300 100 -300 100 0 1 0 N +P 3 0 1 8 150 50 250 50 250 50 N +P 4 0 1 8 150 50 150 30 160 30 160 30 N +P 4 0 1 8 250 50 250 70 240 70 240 70 N +P 5 0 1 0 -250 350 300 350 300 -350 -250 -350 -250 350 N +P 6 0 1 8 -200 -250 -150 -150 -100 -250 -200 -250 -200 -250 -200 -250 N +P 6 0 1 8 -200 150 -150 250 -100 150 -200 150 -200 150 -200 150 N +P 6 0 1 8 -50 -250 0 -150 50 -250 -50 -250 -50 -250 -50 -250 N +P 6 0 1 8 -50 150 0 250 50 150 -50 150 -50 150 -50 150 N +P 6 0 1 8 150 -50 200 50 250 -50 150 -50 150 -50 150 -50 N +X VCC 1 -500 300 200 R 50 50 1 1 P +X I/O1 2 -500 100 200 R 50 50 1 1 P +X I/O2 3 -500 -100 200 R 50 50 1 1 P +X GND 4 -500 -300 200 R 50 50 1 1 P +X GND 5 500 -300 200 L 50 50 1 1 P +X I/O2 6 500 -100 200 L 50 50 1 1 P +X I/O1 7 500 100 200 L 50 50 1 1 P +X VCC 8 500 300 200 L 50 50 1 1 P +ENDDRAW +ENDDEF +# +# USB_A-RESCUE-stm32 +# +DEF USB_A-RESCUE-stm32 P 0 40 Y Y 1 F N +F0 "P" 200 -200 50 H V C CNN +F1 "USB_A-RESCUE-stm32" -50 200 50 H V C CNN +F2 "" -50 -100 50 V V C CNN +F3 "" -50 -100 50 V V C CNN +$FPLIST + USB* +$ENDFPLIST +DRAW +S -250 -150 150 150 0 1 0 N +S -205 -150 -195 -120 0 1 0 N +S -105 -150 -95 -120 0 1 0 N +S -5 -150 5 -120 0 1 0 N +S 95 -150 105 -120 0 1 0 N +X VBUS 1 -200 -300 150 U 50 50 1 1 W +X D- 2 -100 -300 150 U 50 50 1 1 P +X D+ 3 0 -300 150 U 50 50 1 1 P +X GND 4 100 -300 150 U 50 50 1 1 W +X shield 5 300 100 150 L 50 50 1 1 P +ENDDRAW +ENDDEF +# +#End Library diff --git a/F1-nolib/chronometer/kicad/chrono/sym-lib-table b/F1-nolib/chronometer/kicad/chrono/sym-lib-table new file mode 100644 index 0000000..cf01dbc --- /dev/null +++ b/F1-nolib/chronometer/kicad/chrono/sym-lib-table @@ -0,0 +1,4 @@ +(sym_lib_table + (lib (name Chrono)(type Legacy)(uri ${KIPRJMOD}/Chrono.lib)(options "")(descr "")) + (lib (name stm32-rescue)(type Legacy)(uri ${KIPRJMOD}/stm32-rescue.lib)(options "")(descr "")) +) diff --git a/F1-nolib/chronometer/lidar.c b/F1-nolib/chronometer/lidar.c new file mode 100644 index 0000000..b21810c --- /dev/null +++ b/F1-nolib/chronometer/lidar.c @@ -0,0 +1,61 @@ +/* + * This file is part of the chronometer project. + * Copyright 2019 Edward V. Emelianov . + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + */ + +#include "lidar.h" +#include "usart.h" + +uint16_t lidar_max_dist = 100; +uint16_t lidar_min_dist = 50; +uint16_t last_lidar_dist = 0; +uint16_t last_lidar_stren = 0; +uint16_t lidar_triggered_dist = 0; + +void parse_lidar_data(char *txt){ + static int triggered = 0; + last_lidar_dist = txt[2] | (txt[3] << 8); + last_lidar_stren = txt[4] | (txt[5] << 8); + if(last_lidar_stren < LIDAR_LOWER_STREN) return; // weak signal + if(!lidar_triggered_dist){ // first run + lidar_triggered_dist = last_lidar_dist; + return; + } + if(triggered){ // check if body gone + if(last_lidar_dist < lidar_min_dist || last_lidar_dist > lidar_max_dist || last_lidar_dist > lidar_triggered_dist + LIDAR_DIST_THRES){ + triggered = 0; +#ifdef EBUG + SEND("Untriggered! distance="); + printu(1, last_lidar_dist); + SEND(" signal="); + printu(1, last_lidar_stren); + newline(); +#endif + } + }else{ + if(last_lidar_dist > lidar_min_dist && last_lidar_dist < lidar_max_dist){ + triggered = 1; + lidar_triggered_dist = last_lidar_dist; +#ifdef EBUG + SEND("Triggered! distance="); + printu(1, last_lidar_dist); + SEND(" signal="); + printu(1, last_lidar_stren); + newline(); +#endif + } + } +} diff --git a/F1-nolib/chronometer/lidar.h b/F1-nolib/chronometer/lidar.h new file mode 100644 index 0000000..80c15d3 --- /dev/null +++ b/F1-nolib/chronometer/lidar.h @@ -0,0 +1,36 @@ +/* + * This file is part of the chronometer project. + * Copyright 2019 Edward V. Emelianov . + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + */ +#pragma once +#ifndef LIDAR_H__ +#define LIDAR_H__ +#include + +#define LIDAR_FRAME_LEN (9) +// frame header +#define LIDAR_FRAME_HEADER (0x59) +// lower strength limit +#define LIDAR_LOWER_STREN (10) +// triggered distance threshold - 1 meter +#define LIDAR_DIST_THRES (100) +extern uint16_t last_lidar_dist; +extern uint16_t lidar_triggered_dist; +extern uint16_t last_lidar_stren; + +void parse_lidar_data(char *txt); + +#endif // LIDAR_H__ diff --git a/F1-nolib/chronometer/main.c b/F1-nolib/chronometer/main.c new file mode 100644 index 0000000..6e0e2e2 --- /dev/null +++ b/F1-nolib/chronometer/main.c @@ -0,0 +1,254 @@ +/* + * main.c + * + * Copyright 2017 Edward V. Emelianoff + * + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program; if not, write to the Free Software + * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, + * MA 02110-1301, USA. + */ + +//#include "adc.h" +#include "GPS.h" +#include "hardware.h" +#include "lidar.h" +#include "str.h" +#include "time.h" +#include "usart.h" +#include "usb.h" +#include "usb_lib.h" + +#ifndef VERSION +#define VERSION "0.0.0" +#endif + +volatile uint32_t Tms = 0; + +/* Called when systick fires */ +void sys_tick_handler(void){ + ++Tms; +} + +void iwdg_setup(){ + uint32_t tmout = 16000000; + /* Enable the peripheral clock RTC */ + /* (1) Enable the LSI (40kHz) */ + /* (2) Wait while it is not ready */ + RCC->CSR |= RCC_CSR_LSION; /* (1) */ + while((RCC->CSR & RCC_CSR_LSIRDY) != RCC_CSR_LSIRDY){if(--tmout == 0) break;} /* (2) */ + /* Configure IWDG */ + /* (1) Activate IWDG (not needed if done in option bytes) */ + /* (2) Enable write access to IWDG registers */ + /* (3) Set prescaler by 64 (1.6ms for each tick) */ + /* (4) Set reload value to have a rollover each 2s */ + /* (5) Check if flags are reset */ + /* (6) Refresh counter */ + IWDG->KR = IWDG_START; /* (1) */ + IWDG->KR = IWDG_WRITE_ACCESS; /* (2) */ + IWDG->PR = IWDG_PR_PR_1; /* (3) */ + IWDG->RLR = 1250; /* (4) */ + tmout = 16000000; + while(IWDG->SR){if(--tmout == 0) break;} /* (5) */ + IWDG->KR = IWDG_REFRESH; /* (6) */ +} + +#ifdef EBUG +char *parse_cmd(char *buf){ + static char btns[] = "BTN0=0, BTN1=0, PPS=0\n"; + if(buf[1] != '\n') return buf; + switch(*buf){ + case '0': + LED_off(); + break; + case '1': + LED_on(); + break; + case 'b': + btns[5] = GET_BTN0() + '0'; + btns[13] = GET_BTN1() + '0'; + btns[20] = GET_PPS() + '0'; + return btns; + break; + case 'p': + pin_toggle(USBPU_port, USBPU_pin); + SEND("USB pullup is "); + if(pin_read(USBPU_port, USBPU_pin)) SEND("off"); + else SEND("on"); + newline(); + break; + case 'G': + SEND("LIDAR_DIST="); + printu(1, last_lidar_dist); + SEND(", LIDAR_STREN="); + printu(1, last_lidar_stren); + newline(); + break; + case 'L': + USB_send("Very long test string for USB (it's length is more than 64 bytes).\n" + "This is another part of the string! Can you see all of this?\n"); + return "Long test sent\n"; + break; + case 'R': + USB_send("Soft reset\n"); + SEND("Soft reset\n"); + NVIC_SystemReset(); + break; + case 'S': + USB_send("Test string for USB\n"); + return "Short test sent\n"; + break; + case 'T': + SEND(get_time(¤t_time, get_millis())); + break; + case 'W': + USB_send("Wait for reboot\n"); + SEND("Wait for reboot\n"); + while(1){nop();}; + break; + default: // help + return + "0/1 - turn on/off LED1\n" + "'b' - get buttons's state\n" + "'p' - toggle USB pullup\n" + "'G' - get last LIDAR distance\n" + "'L' - send long string over USB\n" + "'R' - software reset\n" + "'S' - send short string over USB\n" + "'T' - show current GPS time\n" + "'W' - test watchdog\n" + ; + break; + } + return NULL; +} +#endif + +// usb getline +static char *get_USB(){ + static char tmpbuf[512], *curptr = tmpbuf; + static int rest = 511; + int x = USB_receive(curptr, rest); + curptr[x] = 0; + if(!x) return NULL; + if(curptr[x-1] == '\n'){ + curptr = tmpbuf; + rest = 511; + return tmpbuf; + } + curptr += x; rest -= x; + if(rest <= 0){ // buffer overflow + SEND("USB buffer overflow!\n"); + curptr = tmpbuf; + rest = 511; + } + return NULL; +} + +#define CMP(a,b) cmpstr(a, b, sizeof(b)-1) +static void parse_USBCMD(char *cmd){ + if(!cmd || !*cmd) return; + if(*cmd == '?'){ // help + USB_send("Commands:\n" + CMD_DISTMIN " - min distance threshold (cm)\n" + CMD_DISTMAX " - max distance threshold (cm)\n" + CMD_PRINTTIME " - print time\n" + ); + }else if(CMP(cmd, CMD_PRINTTIME) == 0){ + USB_send(get_time(¤t_time, get_millis())); + }else if(CMP(cmd, CMD_DISTMIN) == 0){ // set low limit + DBG("CMD_DISTMIN"); + }else if(CMP(cmd, CMD_DISTMAX) == 0){ // set low limit + DBG("CMD_DISTMAX"); + } +} + +int main(void){ + uint32_t lastT = 0; + sysreset(); + StartHSE(); + hw_setup(); + USBPU_OFF(); + usarts_setup(); + SysTick_Config(72000); + SEND("Chronometer version " VERSION ".\n"); + if(RCC->CSR & RCC_CSR_IWDGRSTF){ // watchdog reset occured + SEND("WDGRESET=1\n"); + } + if(RCC->CSR & RCC_CSR_SFTRSTF){ // software reset occured + SEND("SOFTRESET=1\n"); + } + RCC->CSR |= RCC_CSR_RMVF; // remove reset flags + + USB_setup(); + //iwdg_setup(); + USBPU_ON(); + + while (1){ + IWDG->KR = IWDG_REFRESH; // refresh watchdog + if(lastT > Tms || Tms - lastT > 499){ + if(need2startseq) GPS_send_start_seq(); + LED_blink(); + lastT = Tms; + if(usartrx(LIDAR_USART)){ + char *txt; + if(usart_getline(LIDAR_USART, &txt)){ + DBG("LIDAR:"); + DBG(txt); + } + } +#ifdef EBUG + transmit_tbuf(1); // non-blocking transmission of data from UART buffer every 0.5s +#endif + transmit_tbuf(GPS_USART); + transmit_tbuf(LIDAR_USART); + } + usb_proc(); + int r = 0; + char *txt, *ans; + if((txt = get_USB())){ + parse_USBCMD(txt); + DBG("Received data over USB:"); + DBG(txt); + USB_send(txt); // echo all back + } +#ifdef EBUG + if(usartrx(1)){ // usart1 received data, store in in buffer + r = usart_getline(1, &txt); + if(r){ + txt[r] = 0; + ans = parse_cmd(txt); + if(ans){ + usart_send(1, ans); + transmit_tbuf(1); + } + } + } +#endif + if(usartrx(GPS_USART)){ + r = usart_getline(GPS_USART, &txt); + if(r){ + txt[r] = 0; + GPS_parse_answer(txt); + } + } + if(usartrx(LIDAR_USART)){ + r = usart_getline(LIDAR_USART, &txt); + if(r){ + parse_lidar_data(txt); + } + } + } + return 0; +} + diff --git a/F1-nolib/chronometer/str.c b/F1-nolib/chronometer/str.c new file mode 100644 index 0000000..1929765 --- /dev/null +++ b/F1-nolib/chronometer/str.c @@ -0,0 +1,46 @@ +/* + * This file is part of the chronometer project. + * Copyright 2019 Edward V. Emelianov . + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + */ + +#include "str.h" +#include "usart.h" +/** + * @brief cmpstr - the same as strncmp + * @param s1,s2 - strings to compare + * @param n - max symbols amount + * @return 0 if strings equal or 1/-1 + */ +int cmpstr(const char *s1, const char *s2, int n){ + int ret = 0; + do{ + ret = *s1 - *s2; + }while(*s1++ && *s2++ && --n); + return ret; +} + +/** + * @brief getchr - analog of strchr + * @param str - string to search + * @param symbol - searching symbol + * @return pointer to symbol found or NULL + */ +char *getchr(const char *str, char symbol){ + do{ + if(*str == symbol) return (char*)str; + }while(*(++str)); + return NULL; +} diff --git a/F1-nolib/chronometer/str.h b/F1-nolib/chronometer/str.h new file mode 100644 index 0000000..4b2e50d --- /dev/null +++ b/F1-nolib/chronometer/str.h @@ -0,0 +1,25 @@ +/* + * This file is part of the chronometer project. + * Copyright 2019 Edward V. Emelianov . + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + */ +#pragma once +#ifndef STR_H__ +#define STR_H__ + +int cmpstr(const char *s1, const char *s2, int n); +char *getchr(const char *str, char symbol); + +#endif // STR_H__ diff --git a/F1-nolib/chronometer/time.c b/F1-nolib/chronometer/time.c new file mode 100644 index 0000000..c430e6f --- /dev/null +++ b/F1-nolib/chronometer/time.c @@ -0,0 +1,92 @@ +/* + * This file is part of the chronometer project. + * Copyright 2019 Edward V. Emelianov . + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + */ + +#include "GPS.h" +#include "time.h" +#include "usb.h" +#include + +curtime current_time = TMNOTINI; +volatile int need_sync = 1; + +static inline uint8_t atou(const char *b){ + return (b[0]-'0')*10 + b[1]-'0'; +} + +void set_time(const char *buf){ + uint8_t H = atou(buf) + TIMEZONE_GMT_PLUS; + if(H > 23) H -= 24; + current_time.H = H; + current_time.M = atou(&buf[2]); + current_time.S = atou(&buf[4]); +} + +/** + * print time: Tm - time structure, T - milliseconds + */ +char *get_time(curtime *Tm, uint32_t T){ + static char buf[64]; + char *bstart = &buf[5], *bptr = bstart; + /* + void putint(int i){ // put integer from 0 to 99 into buffer with leading zeros + if(i > 9){ + *bptr++ = i/10 + '0'; + i = i%10; + }else *bptr++ = '0'; + *bptr++ = i + '0'; + }*/ + int S = 0; + if(Tm->S < 60 && Tm->M < 60 && Tm->H < 24) + S = Tm->S + Tm->H*3600 + Tm->M*60; // seconds from day beginning + if(!S) *(--bstart) = '0'; + while(S){ + *(--bstart) = S%10 + '0'; + S /= 10; + } + // now bstart is buffer starting index; bptr points to decimal point + *bptr++ = '.'; + if(T > 99){ + *bptr++ = T/100 + '0'; + T %= 100; + }else *bptr++ = '0'; + if(T > 9){ + *bptr++ = T/10 + '0'; + T %= 10; + }else *bptr++ = '0'; + *bptr++ = T + '0'; + if(GPS_status == GPS_NOT_VALID){ + strcpy(bptr, " (not valid)"); + bptr += 12; + } + if(need_sync){ + strcpy(bptr, " need synchronisation"); + bptr += 21; + } + *bptr++ = '\n'; + *bptr = 0; + return bstart; +} + +/** + * @brief get_millis - calculate milliseconds due to global fix parameter + * @return milliseconds value + */ +uint32_t get_millis(){ + // TODO: calculate right millis + return Tms % 1000; // temporary gag +} diff --git a/F1-nolib/chronometer/time.h b/F1-nolib/chronometer/time.h new file mode 100644 index 0000000..e8e61cc --- /dev/null +++ b/F1-nolib/chronometer/time.h @@ -0,0 +1,52 @@ +/* + * This file is part of the chronometer project. + * Copyright 2019 Edward V. Emelianov . + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + */ +#pragma once +#ifndef TIME_H__ +#define TIME_H__ + +#include + +#define STK_RVR_DEFAULT_VAL (8999) +#define TIMEZONE_GMT_PLUS (3) + +#define DIDNT_TRIGGERED (2000) + +// debounce delay: .4s +#define TRIGGER_DELAY (400) + +#define TMNOTINI {25,61,61} + +typedef struct{ + uint8_t H; + uint8_t M; + uint8_t S; +} curtime; + +extern volatile uint32_t Tms; +extern curtime current_time; + +extern curtime trigger_time[]; +extern uint32_t trigger_ms[]; + +extern volatile int need_sync; + +char *get_time(curtime *T, uint32_t m); +void set_time(const char *buf); +uint32_t get_millis(); // current milliseconds + +#endif // TIME_H__ diff --git a/F1-nolib/chronometer/usart.c b/F1-nolib/chronometer/usart.c new file mode 100644 index 0000000..91879f5 --- /dev/null +++ b/F1-nolib/chronometer/usart.c @@ -0,0 +1,334 @@ +/* + * This file is part of the chronometer project. + * Copyright 2019 Edward V. Emelianov . + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + */ + + +#include "stm32f1.h" +#include "usart.h" +#include "lidar.h" + +extern volatile uint32_t Tms; +static volatile int idatalen[4][2] = {0}; // received data line length (including '\n') +static volatile int odatalen[4][2] = {0}; + +volatile int linerdy[4] = {0}, // received data ready + dlen[4] = {0}, // length of data (including '\n') in current buffer + bufovr[4] = {0}, // input buffer overfull + txrdy[4] = {0,1,1,1} // transmission done +; + + +int rbufno[4] = {0}, tbufno[4] = {0}; // current rbuf/tbuf numbers +static char rbuf[4][2][UARTBUFSZ], tbuf[4][2][UARTBUFSZ]; // receive & transmit buffers +static char *recvdata[4] = {0}; + +/** + * return length of received data (without trailing zero) + */ +int usart_getline(int n, char **line){ + if(bufovr[n]){ + bufovr[n] = 0; + linerdy[n] = 0; + return 0; + } + *line = recvdata[n]; + linerdy[n] = 0; + return dlen[n]; +} + +// transmit current tbuf and swap buffers +void transmit_tbuf(int n){ + if(n < 1 || n > 3) return; + uint32_t tmout = 72000; + while(!txrdy[n]){if(--tmout == 0) return;}; // wait for previos buffer transmission + register int l = odatalen[n][tbufno[n]]; + if(!l) return; + txrdy[n] = 0; + odatalen[n][tbufno[n]] = 0; + DMA_Channel_TypeDef *DMA; + IWDG->KR = IWDG_REFRESH; + switch(n){ + case 1: + DMA = DMA1_Channel4; + break; + case 2: + DMA = DMA1_Channel7; + break; + case 3: + DMA = DMA1_Channel2; + break; + } + DMA->CCR &= ~DMA_CCR_EN; + DMA->CMAR = (uint32_t) tbuf[n][tbufno[n]]; // mem + DMA->CNDTR = l; + DMA->CCR |= DMA_CCR_EN; + tbufno[n] = !tbufno[n]; +} + +void usart_putchar(int n, char ch){ + for(int i = 0; odatalen[n][tbufno[n]] == UARTBUFSZ && i < 1024; ++i) transmit_tbuf(n); + tbuf[n][tbufno[n]][odatalen[n][tbufno[n]]++] = ch; +} + +void usart_send(int n, const char *str){ + uint32_t x = 512; + while(*str && --x){ + if(odatalen[n][tbufno[n]] == UARTBUFSZ){ + transmit_tbuf(n); + continue; + } + tbuf[n][tbufno[n]][odatalen[n][tbufno[n]]++] = *str++; + } +} +#ifdef EBUG +// only for USART1 +void newline(){ + usart_putchar(1, '\n'); + transmit_tbuf(1); +} +#endif + +/* + * USART speed: baudrate = Fck/(USARTDIV) + * USARTDIV stored in USART->BRR + * + * for 72MHz USARTDIV=72000/f(kboud); so for 115200 USARTDIV=72000/115.2=625 -> BRR=0x271 + * 9600: BRR = 7500 (0x1D4C) + */ +static void usart_setup(int n, uint32_t BRR){ + DMA_Channel_TypeDef *DMA; + IRQn_Type DMAirqN, USARTirqN; + USART_TypeDef *USART; + switch(n){ + case 1: + // USART1 Tx DMA - Channel4 (Rx - channel 5) + DMA = DMA1_Channel4; + DMAirqN = DMA1_Channel4_IRQn; + USARTirqN = USART1_IRQn; + // PA9 - Tx, PA10 - Rx + RCC->APB2ENR |= RCC_APB2ENR_IOPAEN | RCC_APB2ENR_USART1EN; + GPIOA->CRH |= CRH(9, CNF_AFPP|MODE_NORMAL) | CRH(10, CNF_FLINPUT|MODE_INPUT); + USART = USART1; + break; + case 2: + // USART2 Tx DMA - Channel7 + DMA = DMA1_Channel7; + DMAirqN = DMA1_Channel7_IRQn; + USARTirqN = USART2_IRQn; + // PA2 - Tx, PA3 - Rx + RCC->APB2ENR |= RCC_APB2ENR_IOPAEN; + RCC->APB1ENR |= RCC_APB1ENR_USART2EN; + GPIOA->CRL |= CRL(2, CNF_AFPP|MODE_NORMAL) | CRL(3, CNF_FLINPUT|MODE_INPUT); + USART = USART2; + break; + case 3: + // USART3 Tx DMA - Channel2 + DMA = DMA1_Channel2; + DMAirqN = DMA1_Channel2_IRQn; + USARTirqN = USART3_IRQn; + // PB10 - Tx, PB11 - Rx + RCC->APB2ENR |= RCC_APB2ENR_IOPBEN; + RCC->APB1ENR |= RCC_APB1ENR_USART3EN; + GPIOB->CRH |= CRH(10, CNF_AFPP|MODE_NORMAL) | CRH(11, CNF_FLINPUT|MODE_INPUT); + USART = USART3; + break; + default: + return; + } + DMA->CPAR = (uint32_t) &USART->DR; // periph + DMA->CCR |= DMA_CCR_MINC | DMA_CCR_DIR | DMA_CCR_TCIE; // 8bit, mem++, mem->per, transcompl irq + // setup usart(n) + USART->BRR = BRR; + USART->CR1 = USART_CR1_TE | USART_CR1_RE | USART_CR1_UE; // 1start,8data,nstop; enable Rx,Tx,USART + uint32_t tmout = 16000000; + while(!(USART->SR & USART_SR_TC)){if(--tmout == 0) break;} // polling idle frame Transmission + USART->SR = 0; // clear flags + USART->CR1 |= USART_CR1_RXNEIE; // allow Rx IRQ + USART->CR3 = USART_CR3_DMAT; // enable DMA Tx + // Tx CNDTR set @ each transmission due to data size + NVIC_SetPriority(DMAirqN, n); + NVIC_EnableIRQ(DMAirqN); + NVIC_SetPriority(USARTirqN, n); + NVIC_EnableIRQ(USARTirqN); +} + +void usarts_setup(){ + RCC->AHBENR |= RCC_AHBENR_DMA1EN; +#ifdef EBUG + usart_setup(1, 72000000 / 115200); // debug console +#endif + usart_setup(2, 36000000 / 9600); // GPS + usart_setup(3, 36000000 / 115200); // LIDAR +} + + +void usart_isr(int n, USART_TypeDef *USART){ + #ifdef CHECK_TMOUT + static uint32_t tmout[n] = 0; + #endif + IWDG->KR = IWDG_REFRESH; + if(USART->SR & USART_SR_RXNE){ // RX not emty - receive next char + #ifdef CHECK_TMOUT + if(tmout[n] && Tms >= tmout[n]){ // set overflow flag + bufovr[n] = 1; + idatalen[n][rbufno[n]] = 0; + } + tmout[n] = Tms + TIMEOUT_MS; + if(!tmout[n]) tmout[n] = 1; // prevent 0 + #endif + uint8_t rb = USART->DR; + if(idatalen[n][rbufno[n]] < UARTBUFSZ){ // put next char into buf + rbuf[n][rbufno[n]][idatalen[n][rbufno[n]]++] = rb; + if(rb == '\n'){ // got newline - line ready + linerdy[n] = 1; + dlen[n] = idatalen[n][rbufno[n]]; + recvdata[n] = rbuf[n][rbufno[n]]; + // prepare other buffer + rbufno[n] = !rbufno[n]; + idatalen[n][rbufno[n]] = 0; + #ifdef CHECK_TMOUT + // clear timeout at line end + tmout[n] = 0; + #endif + } + }else{ // buffer overrun + bufovr[n] = 1; + idatalen[n][rbufno[n]] = 0; + #ifdef CHECK_TMOUT + tmout[n] = 0; + #endif + } + } +} + +#ifdef EBUG +void usart1_isr(){ + usart_isr(1, USART1); +} +#endif + +// GPS_USART +void usart2_isr(){ + usart_isr(2, USART2); +} + +// LIDAR_USART +void usart3_isr(){ + IWDG->KR = IWDG_REFRESH; + if(USART3->SR & USART_SR_RXNE){ // RX not emty - receive next char + uint8_t rb = USART3->DR, L = idatalen[3][rbufno[3]]; + if(rb != LIDAR_FRAME_HEADER && (L == 0 || L == 1)){ // bad starting sequence + idatalen[3][rbufno[3]] = 0; + return; + } + if(L < LIDAR_FRAME_LEN){ // put next char into buf + rbuf[3][rbufno[3]][idatalen[3][rbufno[3]]++] = rb; + if(L == LIDAR_FRAME_LEN-1){ // got LIDAR_FRAME_LEN bytes - line ready + linerdy[3] = 1; + dlen[3] = idatalen[3][rbufno[3]]; + recvdata[3] = rbuf[3][rbufno[3]]; + // prepare other buffer + rbufno[3] = !rbufno[3]; + idatalen[3][rbufno[3]] = 0; + } + }else{ // buffer overrun + idatalen[3][rbufno[3]] = 0; + } + } +} + +// return string buffer with val +char *u2str(uint32_t val){ + static char bufa[11]; + char bufb[10]; + int l = 0, bpos = 0; + IWDG->KR = IWDG_REFRESH; + if(!val){ + bufa[0] = '0'; + l = 1; + }else{ + while(val){ + bufb[l++] = val % 10 + '0'; + val /= 10; + } + int i; + bpos += l; + for(i = 0; i < l; ++i){ + bufa[--bpos] = bufb[i]; + } + } + bufa[l + bpos] = 0; + return bufa; +} +// print 32bit unsigned int +void printu(int n, uint32_t val){ + usart_send(n, u2str(val)); +} + +// print 32bit unsigned int as hex +void printuhex(int n, uint32_t val){ + usart_send(n, "0x"); + uint8_t *ptr = (uint8_t*)&val + 3; + int i, j; + IWDG->KR = IWDG_REFRESH; + for(i = 0; i < 4; ++i, --ptr){ + for(j = 1; j > -1; --j){ + register uint8_t half = (*ptr >> (4*j)) & 0x0f; + if(half < 10) usart_putchar(n, half + '0'); + else usart_putchar(n, half - 10 + 'a'); + } + } +} + +#ifdef EBUG +// dump memory buffer +void hexdump(uint8_t *arr, uint16_t len){ + for(uint16_t l = 0; l < len; ++l, ++arr){ + IWDG->KR = IWDG_REFRESH; + for(int16_t j = 1; j > -1; --j){ + register uint8_t half = (*arr >> (4*j)) & 0x0f; + if(half < 10) usart_putchar(1, half + '0'); + else usart_putchar(1, half - 10 + 'a'); + } + if(l % 16 == 15) usart_putchar(1, '\n'); + else if((l & 3) == 3) usart_putchar(1, ' '); + } +} +#endif + +#ifdef EBUG +void dma1_channel4_isr(){ // USART1 + if(DMA1->ISR & DMA_ISR_TCIF4){ // Tx + DMA1->IFCR = DMA_IFCR_CTCIF4; // clear TC flag + txrdy[1] = 1; + } +} +#endif + +void dma1_channel7_isr(){ // USART2 + if(DMA1->ISR & DMA_ISR_TCIF7){ // Tx + DMA1->IFCR = DMA_IFCR_CTCIF7; // clear TC flag + txrdy[2] = 1; + } +} + +void dma1_channel2_isr(){ // USART3 + if(DMA1->ISR & DMA_ISR_TCIF2){ // Tx + DMA1->IFCR = DMA_IFCR_CTCIF2; // clear TC flag + txrdy[3] = 1; + } +} diff --git a/F1-nolib/chronometer/usart.h b/F1-nolib/chronometer/usart.h new file mode 100644 index 0000000..d92b605 --- /dev/null +++ b/F1-nolib/chronometer/usart.h @@ -0,0 +1,67 @@ +/* + * This file is part of the chronometer project. + * Copyright 2019 Edward V. Emelianov . + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + */ + +#pragma once +#ifndef __USART_H__ +#define __USART_H__ + +#include + +// input and output buffers size +#define UARTBUFSZ (128) +// timeout between data bytes +#ifndef TIMEOUT_MS +#define TIMEOUT_MS (1500) +#endif + +#define STR_HELPER(s) #s +#define STR(s) STR_HELPER(s) + +#ifdef EBUG +#define SEND(str) usart_send(1, str) +#define MSG(str) do{SEND(__FILE__ " (L" STR(__LINE__) "): " str);}while(0) +#define DBG(str) do{SEND(str); newline(); }while(0) +#else +#define SEND(str) +#define MSG(str) +#define DBG(str) +#endif + +#define usartrx(n) (linerdy[n]) +#define usartovr(n) (bufovr[n]) + +extern volatile int linerdy[4], bufovr[4], txrdy[4]; + +void transmit_tbuf(int n); +void usarts_setup(); +int usart_getline(int n, char **line); +void usart_send(int n, const char *str); +void usart_putchar(int n, char ch); +char *u2str(uint32_t val); +void printu(int n, uint32_t val); +void printuhex(int n, uint32_t val); + +#ifdef EBUG +void newline(); +void hexdump(uint8_t *arr, uint16_t len); +#endif +/* +void hexdump16(uint16_t *arr, uint16_t len); +void hexdump32(uint32_t *arr, uint16_t len); +*/ +#endif // __USART_H__ diff --git a/F1-nolib/chronometer/usb.c b/F1-nolib/chronometer/usb.c new file mode 100644 index 0000000..4fc2fa8 --- /dev/null +++ b/F1-nolib/chronometer/usb.c @@ -0,0 +1,153 @@ +/* + * geany_encoding=koi8-r + * usb.c - base functions for different USB types + * + * Copyright 2018 Edward V. Emelianov + * + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program; if not, write to the Free Software + * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, + * MA 02110-1301, USA. + * + */ +#include "usb.h" +#include "usb_lib.h" +#include "usart.h" + +// incoming buffer size +#define IDATASZ (256) +static uint8_t incoming_data[IDATASZ]; +static uint8_t ovfl = 0; +static uint16_t idatalen = 0; +static volatile uint8_t tx_succesfull = 0; +static int8_t usbON = 0; // ==1 when USB fully configured + +// interrupt IN handler (never used?) +static uint16_t EP1_Handler(ep_t ep){ + if (ep.rx_flag){ + ep.status = SET_VALID_TX(ep.status); + ep.status = KEEP_STAT_RX(ep.status); + }else if (ep.tx_flag){ + ep.status = SET_VALID_RX(ep.status); + ep.status = SET_STALL_TX(ep.status); + } + return ep.status; +} + +// data IN/OUT handler +static uint16_t EP23_Handler(ep_t ep){ + if(ep.rx_flag){ + int rd = ep.rx_cnt, rest = IDATASZ - idatalen; + if(rd){ + if(rd <= rest){ + idatalen += EP_Read(2, (uint16_t*)&incoming_data[idatalen]); + ovfl = 0; + }else{ + ep.status = SET_NAK_RX(ep.status); + ovfl = 1; + return ep.status; + } + } + // end of transaction: clear DTOGs + ep.status = CLEAR_DTOG_RX(ep.status); + ep.status = CLEAR_DTOG_TX(ep.status); + ep.status = SET_STALL_TX(ep.status); + }else if (ep.tx_flag){ + ep.status = KEEP_STAT_TX(ep.status); + tx_succesfull = 1; + } + ep.status = SET_VALID_RX(ep.status); + return ep.status; +} + +void USB_setup(){ + NVIC_DisableIRQ(USB_LP_CAN1_RX0_IRQn); + NVIC_DisableIRQ(USB_HP_CAN1_TX_IRQn); + RCC->APB1ENR |= RCC_APB1ENR_USBEN; + USB->CNTR = USB_CNTR_FRES; // Force USB Reset + for(uint32_t ctr = 0; ctr < 72000; ++ctr) nop(); // wait >1ms + //uint32_t ctr = 0; + USB->CNTR = 0; + USB->BTABLE = 0; + USB->DADDR = 0; + USB->ISTR = 0; + USB->CNTR = USB_CNTR_RESETM | USB_CNTR_WKUPM; // allow only wakeup & reset interrupts + NVIC_EnableIRQ(USB_LP_CAN1_RX0_IRQn); + NVIC_EnableIRQ(USB_HP_CAN1_TX_IRQn ); +} + +void usb_proc(){ + if(USB_GetState() == USB_CONFIGURE_STATE){ // USB configured - activate other endpoints + if(!usbON){ // endpoints not activated + // make new BULK endpoint + // Buffer have 1024 bytes, but last 256 we use for CAN bus (30.2 of RM: USB main features) + EP_Init(1, EP_TYPE_INTERRUPT, 10, 0, EP1_Handler); // IN1 - transmit + EP_Init(2, EP_TYPE_BULK, 0, USB_RXBUFSZ, EP23_Handler); // OUT2 - receive data + EP_Init(3, EP_TYPE_BULK, USB_TXBUFSZ, 0, EP23_Handler); // IN3 - transmit data + usbON = 1; + } + }else{ + usbON = 0; + } +} + +void USB_send(char *buf){ + uint16_t l = 0, ctr = 0; + char *p = buf; + while(*p++) ++l; + while(l){ + uint16_t s = (l > USB_TXBUFSZ) ? USB_TXBUFSZ : l; + tx_succesfull = 0; + EP_Write(3, (uint8_t*)&buf[ctr], s); + uint32_t ctra = 1000000; + while(--ctra && tx_succesfull == 0); + l -= s; + ctr += s; + } +} + +/** + * @brief USB_receive + * @param buf (i) - buffer for received data + * @param bufsize - its size + * @return amount of received bytes + */ +int USB_receive(char *buf, int bufsize){ + if(!bufsize || !idatalen) return 0; + USB->CNTR = 0; + int sz = (idatalen > bufsize) ? bufsize : idatalen, rest = idatalen - sz; + for(int i = 0; i < sz; ++i) buf[i] = incoming_data[i]; + if(rest > 0){ + uint8_t *ptr = &incoming_data[sz]; + for(int i = 0; i < rest; ++i) incoming_data[i] = *ptr++; + //memmove(incoming_data, &incoming_data[sz], rest); - hardfault on memcpy&memmove + idatalen = rest; + }else idatalen = 0; + if(ovfl){ + EP23_Handler(endpoints[2]); + uint16_t epstatus = USB->EPnR[2]; + epstatus = CLEAR_DTOG_RX(epstatus); + epstatus = SET_VALID_RX(epstatus); + USB->EPnR[2] = epstatus; + } + USB->CNTR = USB_CNTR_RESETM | USB_CNTR_CTRM; + return sz; +} + +/** + * @brief USB_configured + * @return 1 if USB is in configured state + */ +int USB_configured(){ + return usbON; +} diff --git a/F1-nolib/chronometer/usb.h b/F1-nolib/chronometer/usb.h new file mode 100644 index 0000000..0d5831a --- /dev/null +++ b/F1-nolib/chronometer/usb.h @@ -0,0 +1,37 @@ +/* + * geany_encoding=koi8-r + * usb.h + * + * Copyright 2018 Edward V. Emelianov + * + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program; if not, write to the Free Software + * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, + * MA 02110-1301, USA. + * + */ +#pragma once +#ifndef __USB_H__ +#define __USB_H__ + +#include "hardware.h" + +#define BUFFSIZE (64) + +void USB_setup(); +void usb_proc(); +void USB_send(char *buf); +int USB_receive(char *buf, int bufsize); +int USB_configured(); + +#endif // __USB_H__ diff --git a/F1-nolib/chronometer/usb_defs.h b/F1-nolib/chronometer/usb_defs.h new file mode 100644 index 0000000..d6bc03f --- /dev/null +++ b/F1-nolib/chronometer/usb_defs.h @@ -0,0 +1,117 @@ +/* + * geany_encoding=koi8-r + * usb_defs.h + * + * Copyright 2018 Edward V. Emelianov + * + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program; if not, write to the Free Software + * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, + * MA 02110-1301, USA. + * + */ + +#pragma once +#ifndef __USB_DEFS_H__ +#define __USB_DEFS_H__ + +#include + +// max endpoints number +#define STM32ENDPOINTS 8 +/** + * Buffers size definition + **/ +#define USB_BTABLE_SIZE 512 +// first 64 bytes of USB_BTABLE are registers! +//#define USB_EP0_BASEADDR 64 +// for USB FS EP0 buffers are from 8 to 64 bytes long (64 for PL2303) +#define USB_EP0_BUFSZ 64 +// USB transmit buffer size (64 for PL2303) +#define USB_TXBUFSZ 64 +// USB receive buffer size (64 for PL2303) +#define USB_RXBUFSZ 64 + +#define USB_BTABLE_BASE 0x40006000 +#define USB_BASE ((uint32_t)0x40005C00) +#define USB ((USB_TypeDef *) USB_BASE) + +#ifdef USB_BTABLE +#undef USB_BTABLE +#endif +#define USB_BTABLE ((USB_BtableDef *)(USB_BTABLE_BASE)) +#define USB_ISTR_EPID 0x0000000F +#define USB_FNR_LSOF_0 0x00000800 +#define USB_FNR_lSOF_1 0x00001000 +#define USB_LPMCSR_BESL_0 0x00000010 +#define USB_LPMCSR_BESL_1 0x00000020 +#define USB_LPMCSR_BESL_2 0x00000040 +#define USB_LPMCSR_BESL_3 0x00000080 +#define USB_EPnR_CTR_RX 0x00008000 +#define USB_EPnR_DTOG_RX 0x00004000 +#define USB_EPnR_STAT_RX 0x00003000 +#define USB_EPnR_STAT_RX_0 0x00001000 +#define USB_EPnR_STAT_RX_1 0x00002000 +#define USB_EPnR_SETUP 0x00000800 +#define USB_EPnR_EP_TYPE 0x00000600 +#define USB_EPnR_EP_TYPE_0 0x00000200 +#define USB_EPnR_EP_TYPE_1 0x00000400 +#define USB_EPnR_EP_KIND 0x00000100 +#define USB_EPnR_CTR_TX 0x00000080 +#define USB_EPnR_DTOG_TX 0x00000040 +#define USB_EPnR_STAT_TX 0x00000030 +#define USB_EPnR_STAT_TX_0 0x00000010 +#define USB_EPnR_STAT_TX_1 0x00000020 +#define USB_EPnR_EA 0x0000000F +#define USB_COUNTn_RX_BLSIZE 0x00008000 +#define USB_COUNTn_NUM_BLOCK 0x00007C00 +#define USB_COUNTn_RX 0x0000003F + +#ifdef USB_TypeDef +#define USB_TypeDef USB_TypeDef_custom +#endif + +typedef struct { + __IO uint32_t EPnR[STM32ENDPOINTS]; + __IO uint32_t RESERVED[STM32ENDPOINTS]; + __IO uint32_t CNTR; + __IO uint32_t ISTR; + __IO uint32_t FNR; + __IO uint32_t DADDR; + __IO uint32_t BTABLE; +} USB_TypeDef; + +/* +typedef struct{ + __IO uint16_t USB_ADDR_TX; + __IO uint16_t res1; + __IO uint16_t USB_COUNT_TX; + __IO uint16_t res2; + __IO uint16_t USB_ADDR_RX; + __IO uint16_t res3; + __IO uint16_t USB_COUNT_RX; + __IO uint16_t res4; +} USB_EPDATA_TypeDef;*/ + +typedef struct{ + __IO uint32_t USB_ADDR_TX; + __IO uint32_t USB_COUNT_TX; + __IO uint32_t USB_ADDR_RX; + __IO uint32_t USB_COUNT_RX; +} USB_EPDATA_TypeDef; + +typedef struct{ + __IO USB_EPDATA_TypeDef EP[STM32ENDPOINTS]; +} USB_BtableDef; + +#endif // __USB_DEFS_H__ diff --git a/F1-nolib/chronometer/usb_lib.c b/F1-nolib/chronometer/usb_lib.c new file mode 100644 index 0000000..d543269 --- /dev/null +++ b/F1-nolib/chronometer/usb_lib.c @@ -0,0 +1,524 @@ +/* + * geany_encoding=koi8-r + * usb_lib.c + * + * Copyright 2018 Edward V. Emelianov + * + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program; if not, write to the Free Software + * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, + * MA 02110-1301, USA. + * + */ + +#include +#include "usb_lib.h" +#include "usart.h" + +ep_t endpoints[STM32ENDPOINTS]; + +static usb_dev_t USB_Dev; +static usb_LineCoding lineCoding = {115200, 0, 0, 8}; +config_pack_t setup_packet; +static uint8_t ep0databuf[EP0DATABUF_SIZE]; +static uint8_t ep0dbuflen = 0; + +usb_LineCoding getLineCoding(){return lineCoding;} + +// definition of parts common for USB_DeviceDescriptor & USB_DeviceQualifierDescriptor +#define bcdUSB_L 0x10 +#define bcdUSB_H 0x01 +#define bDeviceClass 0 +#define bDeviceSubClass 0 +#define bDeviceProtocol 0 +#define bNumConfigurations 1 + +static const uint8_t USB_DeviceDescriptor[] = { + 18, // bLength + 0x01, // bDescriptorType - Device descriptor + bcdUSB_L, // bcdUSB_L - 1.10 + bcdUSB_H, // bcdUSB_H + bDeviceClass, // bDeviceClass - USB_COMM + bDeviceSubClass, // bDeviceSubClass + bDeviceProtocol, // bDeviceProtocol + USB_EP0_BUFSZ, // bMaxPacketSize + 0x7b, // idVendor_L PL2303: VID=0x067b, PID=0x2303 + 0x06, // idVendor_H + 0x03, // idProduct_L + 0x23, // idProduct_H + 0x00, // bcdDevice_Ver_L + 0x03, // bcdDevice_Ver_H + 0x01, // iManufacturer + 0x02, // iProduct + 0x00, // iSerialNumber + bNumConfigurations // bNumConfigurations +}; + +static const uint8_t USB_DeviceQualifierDescriptor[] = { + 10, //bLength + 0x06, // bDescriptorType - Device qualifier + bcdUSB_L, // bcdUSB_L + bcdUSB_H, // bcdUSB_H + bDeviceClass, // bDeviceClass + bDeviceSubClass, // bDeviceSubClass + bDeviceProtocol, // bDeviceProtocol + USB_EP0_BUFSZ, // bMaxPacketSize0 + bNumConfigurations, // bNumConfigurations + 0x00 // Reserved +}; + +static const uint8_t USB_ConfigDescriptor[] = { + /*Configuration Descriptor*/ + 0x09, /* bLength: Configuration Descriptor size */ + 0x02, /* bDescriptorType: Configuration */ + 39, /* wTotalLength:no of returned bytes */ + 0x00, + 0x01, /* bNumInterfaces: 1 interface */ + 0x01, /* bConfigurationValue: Configuration value */ + 0x00, /* iConfiguration: Index of string descriptor describing the configuration */ + 0xa0, /* bmAttributes - Bus powered, Remote wakeup */ + 0x32, /* MaxPower 100 mA */ + + /*---------------------------------------------------------------------------*/ + + /*Interface Descriptor */ + 0x09, /* bLength: Interface Descriptor size */ + 0x04, /* bDescriptorType: Interface */ + 0x00, /* bInterfaceNumber: Number of Interface */ + 0x00, /* bAlternateSetting: Alternate setting */ + 0x03, /* bNumEndpoints: 3 endpoints used */ + 0xff, /* bInterfaceClass */ + 0x00, /* bInterfaceSubClass */ + 0x00, /* bInterfaceProtocol */ + 0x00, /* iInterface: */ +/////////////////////////////////////////////////// + /*Endpoint 1 Descriptor*/ + 0x07, /* bLength: Endpoint Descriptor size */ + 0x05, /* bDescriptorType: Endpoint */ + 0x81, /* bEndpointAddress IN1 */ + 0x03, /* bmAttributes: Interrupt */ + 0x0a, /* wMaxPacketSize LO: */ + 0x00, /* wMaxPacketSize HI: */ + 0x01, /* bInterval: */ + + /*Endpoint OUT2 Descriptor*/ + 0x07, /* bLength: Endpoint Descriptor size */ + 0x05, /* bDescriptorType: Endpoint */ + 0x02, /* bEndpointAddress: OUT2 */ + 0x02, /* bmAttributes: Bulk */ + (USB_RXBUFSZ & 0xff), /* wMaxPacketSize: 64 */ + (USB_RXBUFSZ >> 8), + 0x00, /* bInterval: ignore for Bulk transfer */ + + /*Endpoint IN3 Descriptor*/ + 0x07, /* bLength: Endpoint Descriptor size */ + 0x05, /* bDescriptorType: Endpoint */ + 0x83, /* bEndpointAddress IN3 */ + 0x02, /* bmAttributes: Bulk */ + (USB_TXBUFSZ & 0xff), /* wMaxPacketSize: 64 */ + (USB_TXBUFSZ >> 8), + 0x00, /* bInterval: ignore for Bulk transfer */ +}; + +_USB_LANG_ID_(USB_StringLangDescriptor, LANG_US); +// these descriptors are not used in PL2303 emulator! +_USB_STRING_(USB_StringSerialDescriptor, u"0"); +_USB_STRING_(USB_StringManufacturingDescriptor, u"Prolific Technology Inc."); +_USB_STRING_(USB_StringProdDescriptor, u"USB-Serial Controller"); + +/* + * default handlers + */ +// SET_LINE_CODING +void WEAK linecoding_handler(usb_LineCoding __attribute__((unused)) *lc){ +} + +// SET_CONTROL_LINE_STATE +void WEAK clstate_handler(uint16_t __attribute__((unused)) val){ +} + +// SEND_BREAK +void WEAK break_handler(){ +} + +// handler of vendor requests +void WEAK vendor_handler(config_pack_t *packet){ + if(packet->bmRequestType & 0x80){ // read + uint8_t c; + switch(packet->wValue){ + case 0x8484: + c = 2; + break; + case 0x0080: + c = 1; + break; + case 0x8686: + c = 0xaa; + break; + default: + c = 0; + } + EP_WriteIRQ(0, &c, 1); + }else{ // write ZLP + EP_WriteIRQ(0, (uint8_t *)0, 0); + } +} + +static void wr0(const uint8_t *buf, uint16_t size){ + if(setup_packet.wLength < size) size = setup_packet.wLength; + EP_WriteIRQ(0, buf, size); +} + +static inline void get_descriptor(){ + switch(setup_packet.wValue){ + case DEVICE_DESCRIPTOR: + wr0(USB_DeviceDescriptor, sizeof(USB_DeviceDescriptor)); + break; + case CONFIGURATION_DESCRIPTOR: + wr0(USB_ConfigDescriptor, sizeof(USB_ConfigDescriptor)); + break; + case STRING_LANG_DESCRIPTOR: + wr0((const uint8_t *)&USB_StringLangDescriptor, STRING_LANG_DESCRIPTOR_SIZE_BYTE); + break; + case STRING_MAN_DESCRIPTOR: + wr0((const uint8_t *)&USB_StringManufacturingDescriptor, USB_StringManufacturingDescriptor.bLength); + break; + case STRING_PROD_DESCRIPTOR: + wr0((const uint8_t *)&USB_StringProdDescriptor, USB_StringProdDescriptor.bLength); + break; + case STRING_SN_DESCRIPTOR: + wr0((const uint8_t *)&USB_StringSerialDescriptor, USB_StringSerialDescriptor.bLength); + break; + case DEVICE_QUALIFIER_DESCRIPTOR: + wr0(USB_DeviceQualifierDescriptor, USB_DeviceQualifierDescriptor[0]); + break; + default: + break; + } +} + +static uint8_t configuration = 0; // reply for GET_CONFIGURATION (==1 if configured) +static inline void std_d2h_req(){ + uint16_t status = 0; // bus powered + switch(setup_packet.bRequest){ + case GET_DESCRIPTOR: + get_descriptor(); + break; + case GET_STATUS: + EP_WriteIRQ(0, (uint8_t *)&status, 2); // send status: Bus Powered + break; + case GET_CONFIGURATION: + EP_WriteIRQ(0, &configuration, 1); + break; + default: + break; + } +} + +static inline void std_h2d_req(){ + switch(setup_packet.bRequest){ + case SET_ADDRESS: + // new address will be assigned later - after acknowlegement or request to host + USB_Dev.USB_Addr = setup_packet.wValue; + break; + case SET_CONFIGURATION: + // Now device configured + USB_Dev.USB_Status = USB_CONFIGURE_STATE; + configuration = setup_packet.wValue; + break; + default: + break; + } +} + +/* +bmRequestType: 76543210 +7 direction: 0 - host->device, 1 - device->host +65 type: 0 - standard, 1 - class, 2 - vendor +4..0 getter: 0 - device, 1 - interface, 2 - endpoint, 3 - other +*/ +/** + * Endpoint0 (control) handler + * @param ep - endpoint state + * @return data written to EP0R + */ +static uint16_t EP0_Handler(ep_t ep){ + uint16_t epstatus = ep.status; // EP0R on input -> return this value after modifications + uint8_t reqtype = setup_packet.bmRequestType & 0x7f; + uint8_t dev2host = (setup_packet.bmRequestType & 0x80) ? 1 : 0; + if ((ep.rx_flag) && (ep.setup_flag)){ + switch(reqtype){ + case STANDARD_DEVICE_REQUEST_TYPE: // standard device request + if(dev2host){ + std_d2h_req(); + }else{ + std_h2d_req(); + EP_WriteIRQ(0, (uint8_t *)0, 0); + } + epstatus = SET_NAK_RX(epstatus); + epstatus = SET_VALID_TX(epstatus); + break; + case STANDARD_ENDPOINT_REQUEST_TYPE: // standard endpoint request + if(setup_packet.bRequest == CLEAR_FEATURE){ + EP_WriteIRQ(0, (uint8_t *)0, 0); + epstatus = SET_NAK_RX(epstatus); + epstatus = SET_VALID_TX(epstatus); + } + break; + case VENDOR_REQUEST_TYPE: + vendor_handler(&setup_packet); + epstatus = SET_NAK_RX(epstatus); + epstatus = SET_VALID_TX(epstatus); + break; + case CONTROL_REQUEST_TYPE: + switch(setup_packet.bRequest){ + case GET_LINE_CODING: + EP_WriteIRQ(0, (uint8_t*)&lineCoding, sizeof(lineCoding)); + break; + case SET_LINE_CODING: // omit this for next stage, when data will come + break; + case SET_CONTROL_LINE_STATE: + clstate_handler(setup_packet.wValue); + break; + case SEND_BREAK: + break_handler(); + break; + default: + break; + } + if(!dev2host) EP_WriteIRQ(0, (uint8_t *)0, 0); // write acknowledgement + epstatus = SET_VALID_RX(epstatus); + epstatus = SET_VALID_TX(epstatus); + break; + default: + EP_WriteIRQ(0, (uint8_t *)0, 0); + epstatus = SET_NAK_RX(epstatus); + epstatus = SET_VALID_TX(epstatus); + } + }else if (ep.rx_flag){ // got data over EP0 or host acknowlegement + if(ep.rx_cnt){ + EP_WriteIRQ(0, (uint8_t *)0, 0); + if(setup_packet.bRequest == SET_LINE_CODING){ + linecoding_handler((usb_LineCoding*)ep0databuf); + } + } + // Close transaction + epstatus = CLEAR_DTOG_RX(epstatus); + epstatus = CLEAR_DTOG_TX(epstatus); + // wait for new data from host + epstatus = SET_VALID_RX(epstatus); + epstatus = SET_STALL_TX(epstatus); + } else if (ep.tx_flag){ // package transmitted + // now we can change address after enumeration + if ((USB->DADDR & USB_DADDR_ADD) != USB_Dev.USB_Addr){ + USB->DADDR = USB_DADDR_EF | USB_Dev.USB_Addr; + // change state to ADRESSED + USB_Dev.USB_Status = USB_ADRESSED_STATE; + } + // end of transaction + epstatus = CLEAR_DTOG_RX(epstatus); + epstatus = CLEAR_DTOG_TX(epstatus); + epstatus = SET_VALID_RX(epstatus); + epstatus = SET_VALID_TX(epstatus); + } + return epstatus; +} + +static uint16_t lastaddr = LASTADDR_DEFAULT; +/** + * Endpoint initialisation + * @param number - EP num (0...7) + * @param type - EP type (EP_TYPE_BULK, EP_TYPE_CONTROL, EP_TYPE_ISO, EP_TYPE_INTERRUPT) + * @param txsz - transmission buffer size @ USB/CAN buffer + * @param rxsz - reception buffer size @ USB/CAN buffer + * @param uint16_t (*func)(ep_t *ep) - EP handler function + * @return 0 if all OK + */ +int EP_Init(uint8_t number, uint8_t type, uint16_t txsz, uint16_t rxsz, uint16_t (*func)(ep_t ep)){ + if(number >= STM32ENDPOINTS) return 4; // out of configured amount + if(txsz > USB_BTABLE_SIZE || rxsz > USB_BTABLE_SIZE) return 1; // buffer too large + if(lastaddr + txsz + rxsz >= USB_BTABLE_SIZE) return 2; // out of btable + USB->EPnR[number] = (type << 9) | (number & USB_EPnR_EA); + USB->EPnR[number] ^= USB_EPnR_STAT_RX | USB_EPnR_STAT_TX_1; + if(rxsz & 1 || rxsz > 512) return 3; // wrong rx buffer size + uint16_t countrx = 0; + if(rxsz < 64) countrx = rxsz / 2; + else{ + if(rxsz & 0x1f) return 3; // should be multiple of 32 + countrx = 31 + rxsz / 32; + } + USB_BTABLE->EP[number].USB_ADDR_TX = lastaddr; + endpoints[number].tx_buf = (uint16_t *)(USB_BTABLE_BASE + lastaddr*2); + lastaddr += txsz; + USB_BTABLE->EP[number].USB_COUNT_TX = 0; + USB_BTABLE->EP[number].USB_ADDR_RX = lastaddr; + endpoints[number].rx_buf = (uint16_t *)(USB_BTABLE_BASE + lastaddr*2); + lastaddr += rxsz; + USB_BTABLE->EP[number].USB_COUNT_RX = countrx << 10; + endpoints[number].func = func; + return 0; +} + +//extern int8_t dump; +// standard IRQ handler +void usb_isr(){ + if (USB->ISTR & USB_ISTR_RESET){ + // Reinit registers + USB->CNTR = USB_CNTR_RESETM | USB_CNTR_CTRM; + USB->ISTR = 0; + // Endpoint 0 - CONTROL + // ON USB LS size of EP0 may be 8 bytes, but on FS it should be 64 bytes! + lastaddr = LASTADDR_DEFAULT; + if(EP_Init(0, EP_TYPE_CONTROL, USB_EP0_BUFSZ, USB_EP0_BUFSZ, EP0_Handler)){ + DBG("Err init EP0"); + } + // clear address, leave only enable bit + USB->DADDR = USB_DADDR_EF; + // state is default - wait for enumeration + USB_Dev.USB_Status = USB_DEFAULT_STATE; + } + if(USB->ISTR & USB_ISTR_CTR){ + // EP number + uint8_t n = USB->ISTR & USB_ISTR_EPID; + // copy status register + uint16_t epstatus = USB->EPnR[n]; + // dump = 1; + // Calculate flags + endpoints[n].rx_flag = (epstatus & USB_EPnR_CTR_RX) ? 1 : 0; + endpoints[n].setup_flag = (epstatus & USB_EPnR_SETUP) ? 1 : 0; + endpoints[n].tx_flag = (epstatus & USB_EPnR_CTR_TX) ? 1 : 0; + // copy received bytes amount + endpoints[n].rx_cnt = USB_BTABLE->EP[n].USB_COUNT_RX & 0x3FF; // low 10 bits is counter + // check direction + if(USB->ISTR & USB_ISTR_DIR){ // OUT interrupt - receive data, CTR_RX==1 (if CTR_TX == 1 - two pending transactions: receive following by transmit) + if(n == 0){ // control endpoint + if(epstatus & USB_EPnR_SETUP){ // setup packet -> copy data to conf_pack + EP_Read(0, (uint16_t*)&setup_packet); + ep0dbuflen = 0; + // interrupt handler will be called later + }else if(epstatus & USB_EPnR_CTR_RX){ // data packet -> push received data to ep0databuf + ep0dbuflen = endpoints[0].rx_cnt; + EP_Read(0, (uint16_t*)&ep0databuf); + } + } + }else{ // IN interrupt - transmit data, only CTR_TX == 1 + // enumeration end could be here (if EP0) + } + // prepare status field for EP handler + endpoints[n].status = epstatus; + // call EP handler (even if it will change EPnR, it should return new status) + epstatus = endpoints[n].func(endpoints[n]); + // keep DTOG state + epstatus = KEEP_DTOG_TX(epstatus); + epstatus = KEEP_DTOG_RX(epstatus); + // clear all RX/TX flags + epstatus = CLEAR_CTR_RX(epstatus); + epstatus = CLEAR_CTR_TX(epstatus); + // refresh EPnR + USB->EPnR[n] = epstatus; + } +} + +/* + if (USB->ISTR & USB_ISTR_PMAOVR) { + MSG("PMAOVR\n"); + // Handle PMAOVR status + } + if (USB->ISTR & USB_ISTR_SUSP) { + MSG("SUSP\n"); + if (USB->DADDR & 0x7f) { + USB->DADDR = 0; + USB->CNTR &= ~ 0x800; + } + } + if (USB->ISTR & USB_ISTR_ERR) { + MSG("ERR\n"); + // Handle Error + } + if (USB->ISTR & USB_ISTR_WKUP) { + MSG("WKUP\n"); + // Handle Wakeup + } + if (USB->ISTR & USB_ISTR_SOF) { + MSG("SOF\n"); + // Handle SOF + } + if (USB->ISTR & USB_ISTR_ESOF) { + MSG("ESOF\n"); + // Handle ESOF + } + USB->ISTR = 0; +*/ + +void usb_lp_can_rx0_isr(){ + usb_isr(); +} + +void usb_hp_can_tx_isr(){ + usb_isr(); +} + +/** + * Write data to EP buffer (called from IRQ handler) + * @param number - EP number + * @param *buf - array with data + * @param size - its size + */ +void EP_WriteIRQ(uint8_t number, const uint8_t *buf, uint16_t size){ + uint8_t i; + if(size > USB_TXBUFSZ) size = USB_TXBUFSZ; + uint16_t N2 = (size + 1) >> 1; + // the buffer is 16-bit, so we should copy data as it would be uint16_t + uint16_t *buf16 = (uint16_t *)buf; + uint32_t *out = (uint32_t *)endpoints[number].tx_buf; + for(i = 0; i < N2; ++i, ++out){ + *out = buf16[i]; + } + USB_BTABLE->EP[number].USB_COUNT_TX = size; +} + +/** + * Write data to EP buffer (called outside IRQ handler) + * @param number - EP number + * @param *buf - array with data + * @param size - its size + */ +void EP_Write(uint8_t number, const uint8_t *buf, uint16_t size){ + uint16_t status = USB->EPnR[number]; + EP_WriteIRQ(number, buf, size); + status = SET_NAK_RX(status); + status = SET_VALID_TX(status); + status = KEEP_DTOG_TX(status); + status = KEEP_DTOG_RX(status); + USB->EPnR[number] = status; +} + +/* + * Copy data from EP buffer into user buffer area + * @param *buf - user array for data + * @return amount of data read + */ +int EP_Read(uint8_t number, uint16_t *buf){ + int n = (endpoints[number].rx_cnt + 1) >> 1; + uint32_t *in = (uint32_t *)endpoints[number].rx_buf; + if(n){ + for(int i = 0; i < n; ++i, ++in) + buf[i] = *(uint16_t*)in; + } + return endpoints[number].rx_cnt; +} + +// USB status +uint8_t USB_GetState(){ + return USB_Dev.USB_Status; +} diff --git a/F1-nolib/chronometer/usb_lib.h b/F1-nolib/chronometer/usb_lib.h new file mode 100644 index 0000000..25398c5 --- /dev/null +++ b/F1-nolib/chronometer/usb_lib.h @@ -0,0 +1,202 @@ +/* + * geany_encoding=koi8-r + * usb_lib.h + * + * Copyright 2018 Edward V. Emelianov + * + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program; if not, write to the Free Software + * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, + * MA 02110-1301, USA. + * + */ + +#pragma once +#ifndef __USB_LIB_H__ +#define __USB_LIB_H__ + +#include +#include "usb_defs.h" + +#define EP0DATABUF_SIZE (64) +#define LASTADDR_DEFAULT (STM32ENDPOINTS * 8) + +// Max EP amount (EP0 + other used) +//#define ENDPOINTS_NUM 4 +// bmRequestType & 0x7f +#define STANDARD_DEVICE_REQUEST_TYPE 0 +#define STANDARD_ENDPOINT_REQUEST_TYPE 2 +#define VENDOR_REQUEST_TYPE 0x40 +#define CONTROL_REQUEST_TYPE 0x21 +// bRequest, standard; for bmRequestType == 0x80 +#define GET_STATUS 0x00 +#define GET_DESCRIPTOR 0x06 +#define GET_CONFIGURATION 0x08 +// for bmRequestType == 0 +#define CLEAR_FEATURE 0x01 +#define SET_FEATURE 0x03 // unused +#define SET_ADDRESS 0x05 +#define SET_DESCRIPTOR 0x07 // unused +#define SET_CONFIGURATION 0x09 +// for bmRequestType == 0x81, 1 or 0xB2 +#define GET_INTERFACE 0x0A // unused +#define SET_INTERFACE 0x0B // unused +#define SYNC_FRAME 0x0C // unused +#define VENDOR_REQUEST 0x01 // unused + +// Class-Specific Control Requests +#define SEND_ENCAPSULATED_COMMAND 0x00 // unused +#define GET_ENCAPSULATED_RESPONSE 0x01 // unused +#define SET_COMM_FEATURE 0x02 // unused +#define GET_COMM_FEATURE 0x03 // unused +#define CLEAR_COMM_FEATURE 0x04 // unused +#define SET_LINE_CODING 0x20 +#define GET_LINE_CODING 0x21 +#define SET_CONTROL_LINE_STATE 0x22 +#define SEND_BREAK 0x23 + +// control line states +#define CONTROL_DTR 0x01 +#define CONTROL_RTS 0x02 + +// wValue +#define DEVICE_DESCRIPTOR 0x100 +#define CONFIGURATION_DESCRIPTOR 0x200 +#define STRING_LANG_DESCRIPTOR 0x300 +#define STRING_MAN_DESCRIPTOR 0x301 +#define STRING_PROD_DESCRIPTOR 0x302 +#define STRING_SN_DESCRIPTOR 0x303 +#define DEVICE_QUALIFIER_DESCRIPTOR 0x600 + +// EPnR bits manipulation +#define CLEAR_DTOG_RX(R) (R & USB_EPnR_DTOG_RX) ? R : (R & (~USB_EPnR_DTOG_RX)) +#define SET_DTOG_RX(R) (R & USB_EPnR_DTOG_RX) ? (R & (~USB_EPnR_DTOG_RX)) : R +#define TOGGLE_DTOG_RX(R) (R | USB_EPnR_DTOG_RX) +#define KEEP_DTOG_RX(R) (R & (~USB_EPnR_DTOG_RX)) +#define CLEAR_DTOG_TX(R) (R & USB_EPnR_DTOG_TX) ? R : (R & (~USB_EPnR_DTOG_TX)) +#define SET_DTOG_TX(R) (R & USB_EPnR_DTOG_TX) ? (R & (~USB_EPnR_DTOG_TX)) : R +#define TOGGLE_DTOG_TX(R) (R | USB_EPnR_DTOG_TX) +#define KEEP_DTOG_TX(R) (R & (~USB_EPnR_DTOG_TX)) +#define SET_VALID_RX(R) ((R & USB_EPnR_STAT_RX) ^ USB_EPnR_STAT_RX) | (R & (~USB_EPnR_STAT_RX)) +#define SET_NAK_RX(R) ((R & USB_EPnR_STAT_RX) ^ USB_EPnR_STAT_RX_1) | (R & (~USB_EPnR_STAT_RX)) +#define SET_STALL_RX(R) ((R & USB_EPnR_STAT_RX) ^ USB_EPnR_STAT_RX_0) | (R & (~USB_EPnR_STAT_RX)) +#define KEEP_STAT_RX(R) (R & (~USB_EPnR_STAT_RX)) +#define SET_VALID_TX(R) ((R & USB_EPnR_STAT_TX) ^ USB_EPnR_STAT_TX) | (R & (~USB_EPnR_STAT_TX)) +#define SET_NAK_TX(R) ((R & USB_EPnR_STAT_TX) ^ USB_EPnR_STAT_TX_1) | (R & (~USB_EPnR_STAT_TX)) +#define SET_STALL_TX(R) ((R & USB_EPnR_STAT_TX) ^ USB_EPnR_STAT_TX_0) | (R & (~USB_EPnR_STAT_TX)) +#define KEEP_STAT_TX(R) (R & (~USB_EPnR_STAT_TX)) +#define CLEAR_CTR_RX(R) (R & (~USB_EPnR_CTR_RX)) +#define CLEAR_CTR_TX(R) (R & (~USB_EPnR_CTR_TX)) +#define CLEAR_CTR_RX_TX(R) (R & (~(USB_EPnR_CTR_TX | USB_EPnR_CTR_RX))) + +// USB state: uninitialized, addressed, ready for use +#define USB_DEFAULT_STATE 0 +#define USB_ADRESSED_STATE 1 +#define USB_CONFIGURE_STATE 2 + +// EP types +#define EP_TYPE_BULK 0x00 +#define EP_TYPE_CONTROL 0x01 +#define EP_TYPE_ISO 0x02 +#define EP_TYPE_INTERRUPT 0x03 + +#define LANG_US (uint16_t)0x0409 + +#define _USB_STRING_(name, str) \ +static const struct name \ +{ \ + uint8_t bLength; \ + uint8_t bDescriptorType; \ + uint16_t bString[(sizeof(str) - 2) / 2]; \ + \ +} \ +name = {sizeof(name), 0x03, str} + +#define _USB_LANG_ID_(name, lng_id) \ + \ +static const struct name \ +{ \ + uint8_t bLength; \ + uint8_t bDescriptorType; \ + uint16_t bString; \ + \ +} \ +name = {0x04, 0x03, lng_id} +#define STRING_LANG_DESCRIPTOR_SIZE_BYTE (4) + +// EP0 configuration packet +typedef struct { + uint8_t bmRequestType; + uint8_t bRequest; + uint16_t wValue; + uint16_t wIndex; + uint16_t wLength; +} config_pack_t; + +// endpoints state +typedef struct __ep_t{ + uint16_t *tx_buf; // transmission buffer address + uint16_t *rx_buf; // reception buffer address + uint16_t (*func)(); // endpoint action function + uint16_t status; // status flags + unsigned rx_cnt : 10; // received data counter + unsigned tx_flag : 1; // transmission flag + unsigned rx_flag : 1; // reception flag + unsigned setup_flag : 1; // this is setup packet (only for EP0) +} ep_t; + +// USB status & its address +typedef struct { + uint8_t USB_Status; + uint16_t USB_Addr; +}usb_dev_t; + +typedef struct { + uint32_t dwDTERate; + uint8_t bCharFormat; + #define USB_CDC_1_STOP_BITS 0 + #define USB_CDC_1_5_STOP_BITS 1 + #define USB_CDC_2_STOP_BITS 2 + uint8_t bParityType; + #define USB_CDC_NO_PARITY 0 + #define USB_CDC_ODD_PARITY 1 + #define USB_CDC_EVEN_PARITY 2 + #define USB_CDC_MARK_PARITY 3 + #define USB_CDC_SPACE_PARITY 4 + uint8_t bDataBits; +} __attribute__ ((packed)) usb_LineCoding; + +typedef struct { + uint8_t bmRequestType; + uint8_t bNotificationType; + uint16_t wValue; + uint16_t wIndex; + uint16_t wLength; +} __attribute__ ((packed)) usb_cdc_notification; + +extern ep_t endpoints[]; + +void USB_Init(); +uint8_t USB_GetState(); +int EP_Init(uint8_t number, uint8_t type, uint16_t txsz, uint16_t rxsz, uint16_t (*func)(ep_t ep)); +void EP_WriteIRQ(uint8_t number, const uint8_t *buf, uint16_t size); +void EP_Write(uint8_t number, const uint8_t *buf, uint16_t size); +int EP_Read(uint8_t number, uint16_t *buf); +usb_LineCoding getLineCoding(); + +void WEAK linecoding_handler(usb_LineCoding *lc); +void WEAK clstate_handler(uint16_t val); +void WEAK break_handler(); +void WEAK vendor_handler(config_pack_t *packet); + +#endif // __USB_LIB_H__ diff --git a/F1-nolib/led_blink/blink.bin b/F1-nolib/led_blink/blink.bin index 879543f..1ca7c17 100755 Binary files a/F1-nolib/led_blink/blink.bin and b/F1-nolib/led_blink/blink.bin differ