diff --git a/F0-nolib/Readme.md b/F0-nolib/Readme.md index eaccc7d..e09067a 100644 --- a/F0-nolib/Readme.md +++ b/F0-nolib/Readme.md @@ -3,13 +3,15 @@ Samples for STM32F042-nucleo and chinese STM32F030-based devboard This directory contains examples for F0 without any library +- Chiller - chiller controller +- Servo - simple servo (like SG-90) controller - blink - simple LED blink - canbus - CAN bus on STM32F042C6T6 - htu21d_nucleo - operaing with HTU-21D in STM32F042-nucleo - morze - for STM32F030, echo data from USART1 on TIM3CH1 (PA6) as Morze code +- pl2303 - CDC template (emulation of PL2303) - tsys01_nucleo - read two TSYS01 sensors using STM32F042 - uart - USART over DMA with hardware end-of-string detection - uart_blink - code for STM32F030F4, echo data on USART1 and blink LEDS on PA4 and PA5 - uart_nucleo - USART over DMA for STM32F042-nucleo - usbcdc - CDC for STM32F042 (emulation of PL2303) with working CAN bus -- pl2303 - CDC template (emulation of PL2303) diff --git a/F0-nolib/Servo/Makefile b/F0-nolib/Servo/Makefile new file mode 100644 index 0000000..7653b72 --- /dev/null +++ b/F0-nolib/Servo/Makefile @@ -0,0 +1,134 @@ +BINARY = servo +BOOTPORT ?= /dev/ttyUSB0 +BOOTSPEED ?= 115200 +# MCU FAMILY +FAMILY = F0 +# MCU code +MCU = F030x4 +DEFS = -DEBUG +# change this linking script depending on particular MCU model, +# for example, if you have STM32F103VBT6, you should write: +LDSCRIPT = stm32f030f.ld + +INDEPENDENT_HEADERS= + +FP_FLAGS ?= -msoft-float +ASM_FLAGS = -mthumb -mcpu=cortex-m0 -march=armv6-m -mtune=cortex-m0 +ARCH_FLAGS = $(ASM_FLAGS) $(FP_FLAGS) + +############################################################################### +# Executables +PREFIX ?= /opt/bin/arm-none-eabi + +RM := rm -f +RMDIR := rmdir +CC := $(PREFIX)-gcc +LD := $(PREFIX)-gcc +AR := $(PREFIX)-ar +AS := $(PREFIX)-as +OBJCOPY := $(PREFIX)-objcopy +OBJDUMP := $(PREFIX)-objdump +GDB := $(PREFIX)-gdb +STFLASH := $(shell which st-flash) +STBOOT := $(shell which stm32flash) + +############################################################################### +# Source files +OBJDIR = mk +LDSCRIPT ?= $(BINARY).ld +SRC := $(wildcard *.c) +OBJS := $(addprefix $(OBJDIR)/, $(SRC:%.c=%.o)) +STARTUP = $(OBJDIR)/startup.o +OBJS += $(STARTUP) +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 -MD -D__thumb2__=1 +CFLAGS += -Wall -Werror -Wextra -Wshadow -Wimplicit-function-declaration +CFLAGS += -Wredundant-decls $(INCLUDE) +# -Wmissing-prototypes -Wstrict-prototypes +CFLAGS += -fno-common -ffunction-sections -fdata-sections + +############################################################################### +# Linker flags +LDFLAGS += --static -nostartfiles +#--specs=nano.specs +LDFLAGS += -L$(LIB_DIR) +LDFLAGS += -T$(LDSCRIPT) +LDFLAGS += -Wl,-Map=$(OBJDIR)/$(BINARY).map +LDFLAGS += -Wl,--gc-sections + +############################################################################### +# Used libraries +LDLIBS += -Wl,--start-group -lc -lgcc -Wl,--end-group +LDLIBS += $(shell $(CC) $(CFLAGS) -print-libgcc-file-name) + +DEFS += -DSTM32$(FAMILY) -DSTM32$(MCU) + +#.SUFFIXES: .elf .bin .hex .srec .list .map .images +#.SECONDEXPANSION: +#.SECONDARY: + +ELF := $(OBJDIR)/$(BINARY).elf +LIST := $(OBJDIR)/$(BINARY).list +BIN := $(BINARY).bin +HEX := $(BINARY).hex + +all: bin list + +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) $(ARCH_FLAGS) -o $@ -c $< + +$(OBJDIR)/%.o: %.c + @echo " CC $<" + $(CC) $(CFLAGS) $(DEFS) $(INCLUDE) $(ARCH_FLAGS) -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) $(ARCH_FLAGS) $(OBJS) $(LDLIBS) -o $(ELF) + +clean: + @echo " CLEAN" + $(RM) $(OBJS) $(DEPS) $(ELF) $(HEX) $(LIST) $(OBJDIR)/*.map + @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) + +.PHONY: clean flash boot diff --git a/F0-nolib/Servo/Readme.md b/F0-nolib/Servo/Readme.md new file mode 100644 index 0000000..571e922 --- /dev/null +++ b/F0-nolib/Servo/Readme.md @@ -0,0 +1,47 @@ +Servo motors SG-90 management +============================= + +## GPIO + +- PA0 - (ADC_IN0) - Servo1 control, +- PA1 - (ADC_IN1) - Servo2 control, +- PA2 - (ADC_IN2) - Servo3 control, +- PA3 - (ADC_IN3) - external analogue signal, +- PA4 - (PullUp in) - ext. input 0, +- PA5 - (PullUp in) - ext. input 1, +- PA6 - (TIM3_CH1) - Servo1, +- PA7 - (TIM3_CH2) - Servo2, +- PA9 - (USART_Tx) - TX, +- PA10 - (USART_Rx) - RX, +- PA13 - (PullUp in) - Jumper 0, +- PA14 - (PullUp in) - Jumper 1, +- PB1 - (TIM3_CH4) - Servo3, +- PF0 - (OpenDrain) - Buzzer, +- PF1 - (OpenDrain) - External LED (or weak laser module). + +## UART +115200N1, not more than 100ms between data bytes in command. +To turn ON human terminal (without timeout) send "####". + +## Protocol +All commands are in brackets: `[ command line ]`. + +'[' clears earlier input; '\n', '\r', ' ', '\t' are ignored. +All messages are asynchronous! + +## Commands +* **d** - debugging commands: + * **A** - get raw ADC values, + * **w** - watchdog test; +* **R** - reset; +* **t** - get MCU temperature; +* **V** - get VDD value. + +## Messages + + + +## Servos +The board controls up to three servos like SG-90. +Three timer's outputs used for this purpose. Timer frequency 50Hz, pulse width from 500 to 2400us. + diff --git a/F0-nolib/Servo/Servo.config b/F0-nolib/Servo/Servo.config new file mode 100644 index 0000000..b7b1aa0 --- /dev/null +++ b/F0-nolib/Servo/Servo.config @@ -0,0 +1,5 @@ +// Add predefined macros for your project here. For example: +// #define THE_ANSWER 42 +#define EBUG 1 +#define STM32F0 +#define STM32F030x4 diff --git a/F0-nolib/Servo/Servo.creator b/F0-nolib/Servo/Servo.creator new file mode 100644 index 0000000..e94cbbd --- /dev/null +++ b/F0-nolib/Servo/Servo.creator @@ -0,0 +1 @@ +[General] diff --git a/F0-nolib/Servo/Servo.creator.user b/F0-nolib/Servo/Servo.creator.user new file mode 100644 index 0000000..f804542 --- /dev/null +++ b/F0-nolib/Servo/Servo.creator.user @@ -0,0 +1,204 @@ + + + + + + EnvironmentId + {7bd84e39-ca37-46d3-be9d-99ebea85bc0d} + + + ProjectExplorer.Project.ActiveTarget + 0 + + + ProjectExplorer.Project.EditorSettings + + true + false + true + + Cpp + + CppGlobal + + + + QmlJS + + QmlJSGlobal + + + 2 + KOI8-R + false + 4 + false + 80 + true + true + 1 + true + false + 0 + true + true + 0 + 8 + true + 1 + true + false + true + false + + + + ProjectExplorer.Project.PluginSettings + + + true + + + + ProjectExplorer.Project.Target.0 + + Desktop + Desktop + {65a14f9e-e008-4c1b-89df-4eaa4774b6e3} + 0 + 0 + 0 + + /Big/Data/00__Electronics/STM32/F0-nolib/Servo + + + + all + + false + + + false + true + Сборка + + GenericProjectManager.GenericMakeStep + + 1 + Сборка + + ProjectExplorer.BuildSteps.Build + + + + + clean + + false + + + false + true + Сборка + + GenericProjectManager.GenericMakeStep + + 1 + Очистка + + ProjectExplorer.BuildSteps.Clean + + 2 + false + + По умолчанию + По умолчанию + GenericProjectManager.GenericBuildConfiguration + + 1 + + + 0 + Установка + + ProjectExplorer.BuildSteps.Deploy + + 1 + Конфигурация установки + + ProjectExplorer.DefaultDeployConfiguration + + 1 + + + false + false + 1000 + + true + + false + false + false + false + true + 0.01 + 10 + true + 1 + 25 + + 1 + true + false + true + valgrind + + 0 + 1 + 2 + 3 + 4 + 5 + 6 + 7 + 8 + 9 + 10 + 11 + 12 + 13 + 14 + + 2 + + + Особая программа + + ProjectExplorer.CustomExecutableRunConfiguration + + 3768 + false + true + false + false + true + + + + 1 + + + + ProjectExplorer.Project.TargetCount + 1 + + + ProjectExplorer.Project.Updater.FileVersion + 20 + + + Version + 20 + + diff --git a/F0-nolib/Servo/Servo.files b/F0-nolib/Servo/Servo.files new file mode 100644 index 0000000..a21f58e --- /dev/null +++ b/F0-nolib/Servo/Servo.files @@ -0,0 +1,12 @@ +Makefile +adc.c +adc.h +hardware.c +hardware.h +main.c +mainloop.c +mainloop.h +protocol.c +protocol.h +usart.c +usart.h diff --git a/F0-nolib/Servo/Servo.includes b/F0-nolib/Servo/Servo.includes new file mode 100644 index 0000000..641fd56 --- /dev/null +++ b/F0-nolib/Servo/Servo.includes @@ -0,0 +1,4 @@ +. +../inc +../inc/Fx +../inc/cm diff --git a/F0-nolib/Servo/adc.c b/F0-nolib/Servo/adc.c new file mode 100644 index 0000000..ede9f9e --- /dev/null +++ b/F0-nolib/Servo/adc.c @@ -0,0 +1,74 @@ +/* + * This file is part of the Chiller 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..3 - external NTC + * 4 - internal Tsens + * 5 - Vref + */ +#define TSENS_CHAN (4) +#define VREF_CHAN (5) +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(){ + getVdd(); + // make correction on Vdd value +// int32_t temperature = (int32_t)ADC_array[4] * VddValue / 330; + int32_t ADval = getADCval(TSENS_CHAN); + int32_t temperature = (int32_t) *TEMP30_CAL_ADDR - ADval; + temperature *= (int32_t)(1100 - 300); + temperature /= (int32_t)(*TEMP30_CAL_ADDR - *TEMP110_CAL_ADDR); + temperature += 300; + return(temperature); +} + +// return Vdd * 100 (V) +uint32_t getVdd(){ + uint32_t vdd = ((uint32_t) *VREFINT_CAL_ADDR) * (uint32_t)330; // 3.3V + vdd /= getADCval(VREF_CHAN); + return vdd; +} diff --git a/F0-nolib/Servo/adc.h b/F0-nolib/Servo/adc.h new file mode 100644 index 0000000..15d7f0b --- /dev/null +++ b/F0-nolib/Servo/adc.h @@ -0,0 +1,29 @@ +/* + * This file is part of the Chiller 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 "stm32f0.h" + +#define NUMBER_OF_ADC_CHANNELS (6) + +extern uint16_t ADC_array[]; +int32_t getMCUtemp(); +uint32_t getVdd(); +uint16_t getADCval(int nch); + +#endif // ADC_H diff --git a/F0-nolib/Servo/hardware.c b/F0-nolib/Servo/hardware.c new file mode 100644 index 0000000..938c63b --- /dev/null +++ b/F0-nolib/Servo/hardware.c @@ -0,0 +1,201 @@ +/* + * This file is part of the Chiller 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 "hardware.h" +#include "usart.h" +#include "adc.h" + +static inline void iwdg_setup(){ + /* 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); /* (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 1s */ + /* (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 = 625; /* (4) */ + while(IWDG->SR); /* (5) */ + IWDG->KR = IWDG_REFRESH; /* (6) */ +} + +static inline void adc_setup(){ + uint16_t ctr = 0; // 0xfff0 - more than 1.3ms + // Enable clocking + /* (1) Enable the peripheral clock of the ADC */ + /* (2) Start HSI14 RC oscillator */ + /* (3) Wait HSI14 is ready */ + RCC->APB2ENR |= RCC_APB2ENR_ADC1EN; /* (1) */ + RCC->CR2 |= RCC_CR2_HSI14ON; /* (2) */ + while ((RCC->CR2 & RCC_CR2_HSI14RDY) == 0 && ++ctr < 0xfff0){}; /* (3) */ + // calibration + /* (1) Ensure that ADEN = 0 */ + /* (2) Clear ADEN */ + /* (3) Launch the calibration by setting ADCAL */ + /* (4) Wait until ADCAL=0 */ + if ((ADC1->CR & ADC_CR_ADEN) != 0){ /* (1) */ + ADC1->CR &= (uint32_t)(~ADC_CR_ADEN); /* (2) */ + } + ADC1->CR |= ADC_CR_ADCAL; /* (3) */ + ctr = 0; // ADC calibration time is 5.9us + while ((ADC1->CR & ADC_CR_ADCAL) != 0 && ++ctr < 0xfff0){}; /* (4) */ + // enable ADC + ctr = 0; + do{ + ADC1->CR |= ADC_CR_ADEN; + }while ((ADC1->ISR & ADC_ISR_ADRDY) == 0 && ++ctr < 0xfff0); + // configure ADC + /* (1) Select HSI14 by writing 00 in CKMODE (reset value) */ + /* (2) Select the continuous mode */ + /* (3) Select CHSEL0..3 - ADC inputs, 16,17 - t. sensor and vref */ + /* (4) Select a sampling mode of 111 i.e. 239.5 ADC clk to be greater than 17.1us */ + /* (5) Wake-up the VREFINT and Temperature sensor (only for VBAT, Temp sensor and VRefInt) */ + // ADC1->CFGR2 &= ~ADC_CFGR2_CKMODE; /* (1) */ + ADC1->CFGR1 |= ADC_CFGR1_CONT; /* (2)*/ + ADC1->CHSELR = ADC_CHSELR_CHSEL0 | ADC_CHSELR_CHSEL1 | ADC_CHSELR_CHSEL2 | + ADC_CHSELR_CHSEL3 | ADC_CHSELR_CHSEL16 | ADC_CHSELR_CHSEL17; /* (3)*/ + ADC1->SMPR |= ADC_SMPR_SMP_0 | ADC_SMPR_SMP_1 | ADC_SMPR_SMP_2; /* (4) */ + ADC->CCR |= ADC_CCR_TSEN | ADC_CCR_VREFEN; /* (5) */ + // configure DMA for ADC + // DMA for AIN + /* (1) Enable the peripheral clock on DMA */ + /* (2) Enable DMA transfer on ADC and circular mode */ + /* (3) Configure the peripheral data register address */ + /* (4) Configure the memory address */ + /* (5) Configure the number of DMA tranfer to be performs on DMA channel 1 */ + /* (6) Configure increment, size, interrupts and circular mode */ + /* (7) Enable DMA Channel 1 */ + RCC->AHBENR |= RCC_AHBENR_DMA1EN; /* (1) */ + ADC1->CFGR1 |= ADC_CFGR1_DMAEN | ADC_CFGR1_DMACFG; /* (2) */ + DMA1_Channel1->CPAR = (uint32_t) (&(ADC1->DR)); /* (3) */ + DMA1_Channel1->CMAR = (uint32_t)(ADC_array); /* (4) */ + DMA1_Channel1->CNDTR = NUMBER_OF_ADC_CHANNELS * 9; /* (5) */ + DMA1_Channel1->CCR |= DMA_CCR_MINC | DMA_CCR_MSIZE_0 | DMA_CCR_PSIZE_0 | DMA_CCR_CIRC; /* (6) */ + DMA1_Channel1->CCR |= DMA_CCR_EN; /* (7) */ + ADC1->CR |= ADC_CR_ADSTART; /* start the ADC conversions */ +} + +/** + * @brief gpio_setup - setup GPIOs for external IO + * GPIO pinout: + * PA5 - floating input - Ef of TLE5205 + * PA13 - open drain - IN1 of TLE5205 + * PA14 - open drain - IN2 of TLE5205 + * PF0 - floating input - water level alert + * PF1 - push-pull - external alarm + * PA0..PA3 - ADC_IN0..3 + * PA4, PA6, PA7 - PWM outputs + * Registers + * MODER - input/output/alternate/analog (2 bit) + * OTYPER - 0 pushpull, 1 opendrain + * OSPEEDR - x0 low, 01 medium, 11 high + * PUPDR - no/pullup/pulldown/resr (2 bit) + * IDR - input + * ODR - output + * BSRR - 0..15 - set, 16..31 - reset + * BRR - 0..15 - reset + * AFRL/AFRH - alternate functions (4 bit, AF: 0..7); L - AFR0..7, H - ARF8..15 + */ +static inline void gpio_setup(){ + // Enable clocks to the GPIO subsystems + RCC->AHBENR |= RCC_AHBENR_GPIOAEN | RCC_AHBENR_GPIOBEN | RCC_AHBENR_GPIOFEN; + GPIOA->MODER = + GPIO_MODER_MODER13_O | GPIO_MODER_MODER14_O | + GPIO_MODER_MODER4_AF | GPIO_MODER_MODER6_AF | + GPIO_MODER_MODER7_AF | + GPIO_MODER_MODER0_AI | GPIO_MODER_MODER1_AI | + GPIO_MODER_MODER2_AI | GPIO_MODER_MODER3_AI; + RCC->APB2ENR |= RCC_APB2ENR_SYSCFGEN; // enable syscfg clock for EXTI + GPIOA->OTYPER = 3 << 13; // 13/14 opendrain + GPIOF->MODER = GPIO_MODER_MODER1_O; + // PB1 - interrupt input + /* (2) Select Port B for pin 1 external interrupt by writing 0001 in EXTI1*/ + /* (3) Configure the corresponding mask bit in the EXTI_IMR register */ + /* (4) Configure the Trigger Selection bits of the Interrupt line on rising edge*/ + /* (5) Configure the Trigger Selection bits of the Interrupt line on falling edge*/ + SYSCFG->EXTICR[0] = SYSCFG_EXTICR1_EXTI1_PB; /* (2) */ + EXTI->IMR = EXTI_IMR_MR1; /* (3) */ + //EXTI->RTSR = 0x0000; /* (4) */ + EXTI->FTSR = EXTI_FTSR_TR1; /* (5) */ + /* (6) Enable Interrupt on EXTI0_1 */ + /* (7) Set priority for EXTI0_1 */ + NVIC_EnableIRQ(EXTI0_1_IRQn); /* (6) */ + NVIC_SetPriority(EXTI0_1_IRQn, 3); /* (7) */ + // alternate functions: + // PA4 - TIM14_CH1 (AF4) + // PA6 - TIM16_CH1 (AF5), PA7 - TIM17_CH1 (AF5) + GPIOA->AFR[0] = (GPIOA->AFR[0] &~ (GPIO_AFRL_AFRL4 | GPIO_AFRL_AFRL6 | GPIO_AFRL_AFRL7)) \ + | (4 << (4 * 4)) | (5 << (6 * 4)) | (5 << (7 * 4)); +} + +static inline void timers_setup(){ + // timer 14 ch1 - cooler PWM + // timer 16 ch1 - heater PWM + // timer 17 ch1 - pump PWM + RCC->APB1ENR |= RCC_APB1ENR_TIM3EN | RCC_APB1ENR_TIM14EN; // enable clocking for timers 3 and 14 + RCC->APB2ENR |= RCC_APB2ENR_TIM16EN | RCC_APB2ENR_TIM17EN; // & timers 16/17 + // PWM mode 1 (active -> inactive) + TIM14->CCMR1 = TIM_CCMR1_OC1M_2 | TIM_CCMR1_OC1M_1; + TIM16->CCMR1 = TIM_CCMR1_OC1M_2 | TIM_CCMR1_OC1M_1; + TIM17->CCMR1 = TIM_CCMR1_OC1M_2 | TIM_CCMR1_OC1M_1; + // frequency + TIM14->PSC = 59; // 0.8MHz for 3kHz PWM + TIM16->PSC = 18749; // 2.56kHz for 10Hz PWM + TIM17->PSC = 5; // 8MHz for 31kHz PWM + // ARR for 8-bit PWM + TIM14->ARR = 254; + TIM16->ARR = 254; + TIM17->ARR = 254; + // start in OFF state + // TIM14->CCR1 = 0; and so on + // enable main output + TIM14->BDTR |= TIM_BDTR_MOE; + TIM16->BDTR |= TIM_BDTR_MOE; + TIM17->BDTR |= TIM_BDTR_MOE; + // enable PWM output + TIM14->CCER = TIM_CCER_CC1E; + TIM16->CCER = TIM_CCER_CC1E; + TIM17->CCER = TIM_CCER_CC1E; + // enable timers + TIM14->CR1 |= TIM_CR1_CEN; + TIM16->CR1 |= TIM_CR1_CEN; + TIM17->CR1 |= TIM_CR1_CEN; +} + +void hw_setup(){ + sysreset(); + gpio_setup(); + adc_setup(); + timers_setup(); + USART1_config(); + iwdg_setup(); +} + + +void exti0_1_isr(){ + if (EXTI->PR & EXTI_PR_PR1){ + EXTI->PR |= EXTI_PR_PR1; /* Clear the pending bit */ + ; + } +} diff --git a/F0-nolib/Servo/hardware.h b/F0-nolib/Servo/hardware.h new file mode 100644 index 0000000..6e1a37a --- /dev/null +++ b/F0-nolib/Servo/hardware.h @@ -0,0 +1,78 @@ +/* + * This file is part of the Chiller 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 . + */ +#pragma once +#ifndef HARDWARE_H +#define HARDWARE_H +#include "stm32f0.h" + +// measure flow sensor data each 1 second +#define FLOW_RATE_MS (999) +// previous as string constant +#define FLOWRATESTR "1" + +// each TMEASURE_MS ms calculate temperatures & check them +#define TMEASURE_MS (1000) +// each TCHECK_MS ms check cooler state and regulate temperature +#define TCHECK_MS (10000) + +/* + temperature limits and tolerances + */ +// tolerance: +-1.5degrC +#define TEMP_TOLERANCE (15) +// dT tolerance: +-0.5degrC +#define DT_TOLERANCE (5) +// maximal heater temperature - 80degrC; normal - <60 +#define MAX_HEATER_T (800) +#define NORMAL_HEATER_T (600) +// maximal output temperature - 45degrC; minimal - 10 +#define MAX_OUTPUT_T (450) +#define MIN_OUTPUT_T (100) +// temperature working values: from 15 to 30degrC +#define OUTPUT_T_H (300) +#define OUTPUT_T_L (150) + +/* + other limits & tolerances +*/ +// minimal flow rate - 0.2l per minute +#define MIN_FLOW_RATE (20) +// normal flow rate +#define NORMAL_FLOW_RATE (30) +// minimal PWM values when motors should work +#define MIN_PUMP_PWM (90) +#define MIN_COOLER_PWM (90) + +// PWM setters and getters +#define SET_COOLER_PWM(N) do{TIM14->CCR1 = (uint32_t)N;}while(0) +#define GET_COOLER_PWM() (uint16_t)(TIM14->CCR1) +#define SET_HEATER_PWM(N) do{TIM16->CCR1 = (uint32_t)N;}while(0) +#define GET_HEATER_PWM() (uint16_t)(TIM16->CCR1) +#define SET_PUMP_PWM(N) do{TIM17->CCR1 = (uint32_t)N;}while(0) +#define GET_PUMP_PWM() (uint16_t)(TIM17->CCR1) + +// ext. alarm states +#define ALARM_ON() pin_set(GPIOF, 2) +#define ALARM_OFF() pin_clear(GPIOF, 2) +#define ALARM_STATE() pin_read(GPIOF, 2) + +extern volatile uint32_t Tms; + +void hw_setup(void); + +#endif // HARDWARE_H diff --git a/F0-nolib/Servo/kicad/Servo_control-rescue.lib b/F0-nolib/Servo/kicad/Servo_control-rescue.lib new file mode 100644 index 0000000..9d836dc --- /dev/null +++ b/F0-nolib/Servo/kicad/Servo_control-rescue.lib @@ -0,0 +1,445 @@ +EESchema-LIBRARY Version 2.4 +#encoding utf-8 +# +# +12V-Chiller_control-rescue +# +DEF +12V-Chiller_control-rescue #PWR 0 0 Y Y 1 F P +F0 "#PWR" 0 -150 50 H I C CNN +F1 "+12V-Chiller_control-rescue" 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 +12V 1 0 0 0 U 50 50 1 1 W N +ENDDRAW +ENDDEF +# +# +3.3V-Chiller_control-rescue +# +DEF +3.3V-Chiller_control-rescue #PWR 0 0 Y Y 1 F P +F0 "#PWR" 0 -150 50 H I C CNN +F1 "+3.3V-Chiller_control-rescue" 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 +# +# +3.3VADC-Chiller_control-rescue +# +DEF +3.3VADC-Chiller_control-rescue #PWR 0 0 Y Y 1 F P +F0 "#PWR" 150 -50 50 H I C CNN +F1 "+3.3VADC-Chiller_control-rescue" 0 100 50 H V C CNN +F2 "" 0 0 50 H I C CNN +F3 "" 0 0 50 H I C CNN +DRAW +P 3 0 1 0 0 0 0 40 0 40 N +P 6 0 1 0 0 40 20 20 0 70 -20 20 0 40 0 40 N +X +3.3VADC 1 0 0 0 U 50 50 0 0 W N +ENDDRAW +ENDDEF +# +# +5V-power +# +DEF +5V-power #PWR 0 0 Y Y 1 F P +F0 "#PWR" 0 -150 50 H I C CNN +F1 "+5V-power" 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 +# +# C-Chiller_control-rescue +# +DEF C-Chiller_control-rescue C 0 10 N Y 1 F N +F0 "C" 25 100 50 H V L CNN +F1 "C-Chiller_control-rescue" 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 +# +# CP-Chiller_control-rescue +# +DEF CP-Chiller_control-rescue C 0 10 N Y 1 F N +F0 "C" 25 100 50 H V L CNN +F1 "CP-Chiller_control-rescue" 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 +# +# Conn_01x02-Chiller_control-rescue +# +DEF Conn_01x02-Chiller_control-rescue J 0 40 Y N 1 F N +F0 "J" 0 100 50 H V C CNN +F1 "Conn_01x02-Chiller_control-rescue" 0 -200 50 H V C CNN +F2 "" 0 0 50 H I C CNN +F3 "" 0 0 50 H I C CNN +$FPLIST + Connector*:*_??x*mm* + Connector*:*1x??x*mm* + Pin?Header?Straight?1X* + Pin?Header?Angled?1X* + Socket?Strip?Straight?1X* + Socket?Strip?Angled?1X* +$ENDFPLIST +DRAW +S -50 -95 0 -105 1 1 6 N +S -50 5 0 -5 1 1 6 N +S -50 50 50 -150 1 1 10 f +X Pin_1 1 -200 0 150 R 50 50 1 1 P +X Pin_2 2 -200 -100 150 R 50 50 1 1 P +ENDDRAW +ENDDEF +# +# D-Chiller_control-rescue +# +DEF D-Chiller_control-rescue D 0 40 N N 1 F N +F0 "D" 0 100 50 H V C CNN +F1 "D-Chiller_control-rescue" 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 +# +# DB9_Female-Chiller_control-rescue +# +DEF DB9_Female-Chiller_control-rescue J 0 40 Y N 1 F N +F0 "J" 0 550 50 H V C CNN +F1 "DB9_Female-Chiller_control-rescue" 0 -575 50 H V C CNN +F2 "" 0 0 50 H I C CNN +F3 "" 0 0 50 H I C CNN +$FPLIST + DB*F* +$ENDFPLIST +DRAW +C -70 -400 30 0 1 0 N +C -70 -200 30 0 1 0 N +C -70 0 30 0 1 0 N +C -70 200 30 0 1 0 N +C -70 400 30 0 1 0 N +C 50 -300 30 0 1 0 N +C 50 -100 30 0 1 0 N +C 50 100 30 0 1 0 N +C 50 300 30 0 1 0 N +P 2 0 1 0 -150 -400 -100 -400 N +P 2 0 1 0 -150 -300 20 -300 N +P 2 0 1 0 -150 -200 -100 -200 N +P 2 0 1 0 -150 -100 20 -100 N +P 2 0 1 0 -150 0 -100 0 N +P 2 0 1 0 -150 100 20 100 N +P 2 0 1 0 -150 200 -100 200 N +P 2 0 1 0 -150 300 20 300 N +P 2 0 1 0 -150 400 -100 400 N +P 5 0 1 10 -150 525 -150 -525 150 -375 150 375 -150 525 f +X 1 1 -300 400 150 R 50 50 1 1 P +X 2 2 -300 200 150 R 50 50 1 1 P +X 3 3 -300 0 150 R 50 50 1 1 P +X 4 4 -300 -200 150 R 50 50 1 1 P +X 5 5 -300 -400 150 R 50 50 1 1 P +X 6 6 -300 300 150 R 50 50 1 1 P +X 7 7 -300 100 150 R 50 50 1 1 P +X 8 8 -300 -100 150 R 50 50 1 1 P +X 9 9 -300 -300 150 R 50 50 1 1 P +ENDDRAW +ENDDEF +# +# GND-Chiller_control-rescue +# +DEF GND-Chiller_control-rescue #PWR 0 0 Y Y 1 F P +F0 "#PWR" 0 -250 50 H I C CNN +F1 "GND-Chiller_control-rescue" 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 +# +# L-Chiller_control-rescue +# +DEF L-Chiller_control-rescue L 0 40 N N 1 F N +F0 "L" -50 0 50 V V C CNN +F1 "L-Chiller_control-rescue" 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 +# +# LM1117-3.3-Chiller_control-rescue +# +DEF LM1117-3.3-Chiller_control-rescue U 0 10 Y Y 1 F N +F0 "U" -150 125 50 H V C CNN +F1 "LM1117-3.3-Chiller_control-rescue" 0 125 50 H V L CNN +F2 "" 0 0 50 H I C CNN +F3 "" 0 0 50 H I C CNN +$FPLIST + SOT?223* + TO?263* + TO?252* + TO?220* +$ENDFPLIST +DRAW +S -200 -200 200 75 0 1 10 f +X GND 1 0 -300 100 U 50 50 1 1 W +X VO 2 300 0 100 L 50 50 1 1 w +X VI 3 -300 0 100 R 50 50 1 1 W +ENDDRAW +ENDDEF +# +# MAX3232-Chiller_control-rescue +# +DEF MAX3232-Chiller_control-rescue U 0 40 Y Y 1 F N +F0 "U" -100 1125 50 H V R CNN +F1 "MAX3232-Chiller_control-rescue" -100 1050 50 H V R CNN +F2 "" 50 -1050 50 H I L CNN +F3 "" 0 100 50 H I C CNN +$FPLIST + SOIC*Pitch1.27mm* + DIP*W7.62mm* + TSSOP*4.4x5mm*Pitch0.65mm* +$ENDFPLIST +DRAW +C -100 -700 25 0 1 10 N +C -100 -500 25 0 1 10 N +C 25 -300 25 0 1 10 N +C 25 -100 25 0 1 10 N +T 0 -450 -900 50 0 0 0 LOGIC Normal 0 C C +T 0 450 -900 50 0 0 0 RS232 Normal 0 C C +S -600 -1000 600 1000 0 1 10 f +P 2 0 1 10 -150 -300 -325 -300 N +P 2 0 1 10 -150 -100 -325 -100 N +P 2 0 1 10 -125 -700 -325 -700 N +P 2 0 1 10 -125 -500 -325 -500 N +P 2 0 1 10 50 -300 250 -300 N +P 2 0 1 10 50 -100 250 -100 N +P 2 0 1 10 75 -700 250 -700 N +P 2 0 1 10 75 -500 250 -500 N +P 4 0 1 10 -150 -225 -150 -375 0 -300 -150 -225 N +P 4 0 1 10 -150 -25 -150 -175 0 -100 -150 -25 N +P 4 0 1 10 75 -625 75 -775 -75 -700 75 -625 N +P 4 0 1 10 75 -425 75 -575 -75 -500 75 -425 N +X C1+ 1 -800 900 200 R 50 50 1 1 P +X T2IN 10 -800 -300 200 R 50 50 1 1 I +X T1IN 11 -800 -100 200 R 50 50 1 1 I +X R1OUT 12 -800 -500 200 R 50 50 1 1 O +X R1IN 13 800 -500 200 L 50 50 1 1 I +X T1OUT 14 800 -100 200 L 50 50 1 1 O +X GND 15 0 -1200 200 U 50 50 1 1 W +X VCC 16 0 1200 200 D 50 50 1 1 W +X VS+ 2 800 400 200 L 50 50 1 1 w +X C1- 3 -800 600 200 R 50 50 1 1 P +X C2+ 4 800 900 200 L 50 50 1 1 P +X C2- 5 800 600 200 L 50 50 1 1 P +X VS- 6 800 100 200 L 50 50 1 1 w +X T2OUT 7 800 -300 200 L 50 50 1 1 O +X R2IN 8 800 -700 200 L 50 50 1 1 I +X R2OUT 9 -800 -700 200 R 50 50 1 1 O +ENDDRAW +ENDDEF +# +# PWR_FLAG-Chiller_control-rescue +# +DEF PWR_FLAG-Chiller_control-rescue #FLG 0 0 N N 1 F P +F0 "#FLG" 0 75 50 H I C CNN +F1 "PWR_FLAG-Chiller_control-rescue" 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_NMOS_GDS-Chiller_control-rescue +# +DEF Q_NMOS_GDS-Chiller_control-rescue Q 0 0 Y N 1 F N +F0 "Q" 200 50 50 H V L CNN +F1 "Q_NMOS_GDS-Chiller_control-rescue" 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 40 0 80 15 80 -15 40 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 D 2 100 200 100 D 50 50 1 1 P +X S 3 100 -200 100 U 50 50 1 1 P +ENDDRAW +ENDDEF +# +# Q_NMOS_GSD-Chiller_control-rescue +# +DEF Q_NMOS_GSD-Chiller_control-rescue Q 0 0 Y N 1 F N +F0 "Q" 200 50 50 H V L CNN +F1 "Q_NMOS_GSD-Chiller_control-rescue" 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 40 0 80 15 80 -15 40 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-Chiller_control-rescue +# +DEF R-Chiller_control-rescue R 0 0 N Y 1 F N +F0 "R" 80 0 50 V V C CNN +F1 "R-Chiller_control-rescue" 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 +# +# STM32F030F4Px-Chiller_control-rescue +# +DEF STM32F030F4Px-Chiller_control-rescue U 0 40 Y Y 1 L N +F0 "U" -1600 925 50 H V L BNN +F1 "STM32F030F4Px-Chiller_control-rescue" 1600 925 50 H V R BNN +F2 "Housings_SSOP:TSSOP-20_4.4x6.5mm_Pitch0.65mm" 1600 875 50 H I R TNN +F3 "" 0 0 50 H I C CNN +DRAW +S -1600 -800 1600 900 0 1 10 f +X BOOT0 1 -1700 400 100 R 50 50 1 1 I +X ADC_IN4/SPI1_NSS/TIM14_CH1/USART1_CK/PA4 10 1700 200 100 L 50 50 1 1 B +X ADC_IN5/SPI1_SCK/PA5 11 1700 100 100 L 50 50 1 1 B +X ADC_IN6/SPI1_MISO/TIM16_CH1/TIM1_BKIN/TIM3_CH1/PA6 12 1700 0 100 L 50 50 1 1 B +X ADC_IN7/SPI1_MOSI/TIM14_CH1/TIM17_CH1/TIM1_CH1N/TIM3_CH2/PA7 13 1700 -100 100 L 50 50 1 1 B +X PB1/ADC_IN9/TIM14_CH1/TIM1_CH3N/TIM3_CH4 14 -1700 -500 100 R 50 50 1 1 B +X VSS 15 0 -900 100 U 50 50 1 1 W +X VDD 16 -100 1000 100 D 50 50 1 1 W +X I2C1_SCL/TIM1_CH2/USART1_TX/PA9 17 1700 -200 100 L 50 50 1 1 B +X I2C1_SDA/TIM17_BKIN/TIM1_CH3/USART1_RX/PA10 18 1700 -300 100 L 50 50 1 1 B +X IR_OUT/SYS_SWDIO/PA13 19 1700 -400 100 L 50 50 1 1 B +X PF0/RCC_OSC_IN 2 -1700 -200 100 R 50 50 1 1 I +X SYS_SWCLK/USART1_TX/PA14 20 1700 -500 100 L 50 50 1 1 B +X PF1/RCC_OSC_OUT 3 -1700 -300 100 R 50 50 1 1 I +X NRST 4 -1700 600 100 R 50 50 1 1 I +X VDDA 5 0 1000 100 D 50 50 1 1 W +X ADC_IN0/RTC_TAMP2/SYS_WKUP1/USART1_CTS/PA0 6 1700 600 100 L 50 50 1 1 B +X ADC_IN1/USART1_DE/USART1_RTS/PA1 7 1700 500 100 L 50 50 1 1 B +X ADC_IN2/USART1_TX/PA2 8 1700 400 100 L 50 50 1 1 B +X ADC_IN3/USART1_RX/PA3 9 1700 300 100 L 50 50 1 1 B +ENDDRAW +ENDDEF +# +# SW_Push-Chiller_control-rescue +# +DEF SW_Push-Chiller_control-rescue SW 0 40 N N 1 F N +F0 "SW" 50 100 50 H V L CNN +F1 "SW_Push-Chiller_control-rescue" 0 -60 50 H V C CNN +F2 "" 0 200 50 H I C CNN +F3 "" 0 200 50 H I C CNN +DRAW +C -80 0 20 0 1 0 N +C 80 0 20 0 1 0 N +P 2 0 1 0 0 50 0 120 N +P 2 0 1 0 100 50 -100 50 N +X 1 1 -200 0 100 R 50 50 0 1 P +X 2 2 200 0 100 L 50 50 0 1 P +ENDDRAW +ENDDEF +# +#End Library diff --git a/F0-nolib/Servo/kicad/Servo_control.kicad_pcb b/F0-nolib/Servo/kicad/Servo_control.kicad_pcb new file mode 100644 index 0000000..e6f8063 --- /dev/null +++ b/F0-nolib/Servo/kicad/Servo_control.kicad_pcb @@ -0,0 +1,2597 @@ +(kicad_pcb (version 20171130) (host pcbnew 5.0.1) + + (general + (thickness 1.6) + (drawings 0) + (tracks 6) + (zones 0) + (modules 58) + (nets 47) + ) + + (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 0.25) + (user_trace_width 0.25) + (user_trace_width 0.5) + (user_trace_width 2) + (trace_clearance 0.2) + (zone_clearance 0.508) + (zone_45_only no) + (trace_min 0.2) + (segment_width 0.2) + (edge_width 0.15) + (via_size 1.5) + (via_drill 0.6) + (via_min_size 0.4) + (via_min_drill 0.3) + (user_via 1.5 0.6) + (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) + (pcb_text_width 0.3) + (pcb_text_size 1.5 1.5) + (mod_edge_width 0.15) + (mod_text_size 0.000001 0.000001) + (mod_text_width 0.15) + (pad_size 1.4 1.4) + (pad_drill 0.6) + (pad_to_mask_clearance 0.2) + (solder_mask_min_width 0.25) + (aux_axis_origin 0 0) + (visible_elements FFFFFF7F) + (pcbplotparams + (layerselection 0x010fc_ffffffff) + (usegerberextensions false) + (usegerberattributes false) + (usegerberadvancedattributes false) + (creategerberjobfile false) + (excludeedgelayer true) + (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 true) + (plotinvisibletext false) + (padsonsilk false) + (subtractmaskfromsilk false) + (outputformat 1) + (mirror false) + (drillshape 1) + (scaleselection 1) + (outputdirectory "")) + ) + + (net 0 "") + (net 1 +3V3) + (net 2 "Net-(BZ1-Pad2)") + (net 3 GND) + (net 4 "Net-(C7-Pad1)") + (net 5 /ADC0) + (net 6 /ADC1) + (net 7 /ADC2) + (net 8 /ADC3) + (net 9 /DigIn0) + (net 10 /DigIn1) + (net 11 +5V) + (net 12 "Net-(J2-Pad2)") + (net 13 "Net-(J2-Pad3)") + (net 14 "Net-(J2-Pad4)") + (net 15 "Net-(J2-Pad5)") + (net 16 /Jumper0) + (net 17 /Jumper1) + (net 18 "Net-(J5-Pad2)") + (net 19 "Net-(J5-Pad3)") + (net 20 "Net-(J6-Pad2)") + (net 21 "Net-(J7-Pad3)") + (net 22 "Net-(J8-Pad3)") + (net 23 "Net-(J9-Pad3)") + (net 24 /BOOT0) + (net 25 "Net-(Q1-Pad1)") + (net 26 /DigOut0) + (net 27 "Net-(Q2-Pad1)") + (net 28 /DigOut1) + (net 29 /TIM3_CH1) + (net 30 "Net-(Q3-Pad1)") + (net 31 "Net-(Q4-Pad1)") + (net 32 /TIM3_CH2) + (net 33 /TIM3_CH4) + (net 34 "Net-(Q5-Pad1)") + (net 35 /USART_Rx) + (net 36 /USART_Tx) + (net 37 "Net-(C6-Pad1)") + (net 38 /NRST) + (net 39 +3.3VADC) + (net 40 "Net-(C9-Pad1)") + (net 41 "Net-(D1-Pad1)") + (net 42 "Net-(D1-Pad2)") + (net 43 "Net-(D1-Pad3)") + (net 44 "Net-(D1-Pad4)") + (net 45 "Net-(D1-Pad6)") + (net 46 "Net-(D1-Pad7)") + + (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 +3.3VADC) + (add_net +3V3) + (add_net +5V) + (add_net /ADC0) + (add_net /ADC1) + (add_net /ADC2) + (add_net /ADC3) + (add_net /BOOT0) + (add_net /DigIn0) + (add_net /DigIn1) + (add_net /DigOut0) + (add_net /DigOut1) + (add_net /Jumper0) + (add_net /Jumper1) + (add_net /NRST) + (add_net /TIM3_CH1) + (add_net /TIM3_CH2) + (add_net /TIM3_CH4) + (add_net /USART_Rx) + (add_net /USART_Tx) + (add_net GND) + (add_net "Net-(BZ1-Pad2)") + (add_net "Net-(C6-Pad1)") + (add_net "Net-(C7-Pad1)") + (add_net "Net-(C9-Pad1)") + (add_net "Net-(D1-Pad1)") + (add_net "Net-(D1-Pad2)") + (add_net "Net-(D1-Pad3)") + (add_net "Net-(D1-Pad4)") + (add_net "Net-(D1-Pad6)") + (add_net "Net-(D1-Pad7)") + (add_net "Net-(J2-Pad2)") + (add_net "Net-(J2-Pad3)") + (add_net "Net-(J2-Pad4)") + (add_net "Net-(J2-Pad5)") + (add_net "Net-(J5-Pad2)") + (add_net "Net-(J5-Pad3)") + (add_net "Net-(J6-Pad2)") + (add_net "Net-(J7-Pad3)") + (add_net "Net-(J8-Pad3)") + (add_net "Net-(J9-Pad3)") + (add_net "Net-(Q1-Pad1)") + (add_net "Net-(Q2-Pad1)") + (add_net "Net-(Q3-Pad1)") + (add_net "Net-(Q4-Pad1)") + (add_net "Net-(Q5-Pad1)") + ) + + (net_class 0.5 "" + (clearance 0.5) + (trace_width 0.5) + (via_dia 1.5) + (via_drill 0.6) + (uvia_dia 0.3) + (uvia_drill 0.1) + ) + + (net_class 2 "" + (clearance 0.5) + (trace_width 2) + (via_dia 2.5) + (via_drill 0.8) + (uvia_dia 0.3) + (uvia_drill 0.1) + ) + + (module Buzzer_Beeper:Buzzer_12x9.5RM7.6 (layer F.Cu) (tedit 5A030281) (tstamp 5CAAAC8C) + (at 188.4172 107.1372) + (descr "Generic Buzzer, D12mm height 9.5mm with RM7.6mm") + (tags buzzer) + (path /5C83133C) + (fp_text reference BZ1 (at 3.8 -7.2) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text value Buzzer (at 3.8 7.4) (layer F.Fab) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text user + (at -0.01 -2.54) (layer F.Fab) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text user + (at -0.01 -2.54) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text user %R (at 3.8 -4) (layer F.Fab) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_circle (center 3.8 0) (end 10.05 0) (layer F.CrtYd) (width 0.05)) + (fp_circle (center 3.8 0) (end 9.8 0) (layer F.Fab) (width 0.1)) + (fp_circle (center 3.8 0) (end 4.8 0) (layer F.Fab) (width 0.1)) + (fp_circle (center 3.8 0) (end 9.9 0) (layer F.SilkS) (width 0.12)) + (pad 1 thru_hole rect (at 0 0) (size 2 2) (drill 1) (layers *.Cu *.Mask) + (net 1 +3V3)) + (pad 2 thru_hole circle (at 7.6 0) (size 2 2) (drill 1) (layers *.Cu *.Mask) + (net 2 "Net-(BZ1-Pad2)")) + (model ${KISYS3DMOD}/Buzzer_Beeper.3dshapes/Buzzer_12x9.5RM7.6.wrl + (at (xyz 0 0 0)) + (scale (xyz 1 1 1)) + (rotate (xyz 0 0 0)) + ) + ) + + (module Capacitor_SMD:C_0603_1608Metric_Pad0.84x1.00mm_HandSolder (layer F.Cu) (tedit 59FE48B8) (tstamp 5C9EAD2E) + (at 121.295 104.0765) + (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 /5C8CDF63) + (attr smd) + (fp_text reference C7 (at 0 -1.65) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text value 22p (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.64 0.75) (end -1.64 0.75) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.64 -0.75) (end 1.64 0.75) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.64 -0.75) (end 1.64 -0.75) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.64 0.75) (end -1.64 -0.75) (layer F.CrtYd) (width 0.05)) + (fp_line (start -0.22 0.51) (end 0.22 0.51) (layer F.SilkS) (width 0.12)) + (fp_line (start -0.22 -0.51) (end 0.22 -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 rect (at 0.9625 0) (size 0.845 1) (layers F.Cu F.Paste F.Mask) + (net 3 GND)) + (pad 1 smd rect (at -0.9625 0) (size 0.845 1) (layers F.Cu F.Paste F.Mask) + (net 4 "Net-(C7-Pad1)")) + (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_Pad0.84x1.00mm_HandSolder (layer F.Cu) (tedit 59FE48B8) (tstamp 5C9EAD3F) + (at 126.2915 103.886) + (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 /5C86267B) + (attr smd) + (fp_text reference C8 (at 0 -1.65) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text value 0.1 (at 0 1.65) (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.22 -0.51) (end 0.22 -0.51) (layer F.SilkS) (width 0.12)) + (fp_line (start -0.22 0.51) (end 0.22 0.51) (layer F.SilkS) (width 0.12)) + (fp_line (start -1.64 0.75) (end -1.64 -0.75) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.64 -0.75) (end 1.64 -0.75) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.64 -0.75) (end 1.64 0.75) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.64 0.75) (end -1.64 0.75) (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 rect (at -0.9625 0) (size 0.845 1) (layers F.Cu F.Paste F.Mask) + (net 8 /ADC3)) + (pad 2 smd rect (at 0.9625 0) (size 0.845 1) (layers F.Cu F.Paste F.Mask) + (net 3 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_SMA_Handsoldering (layer F.Cu) (tedit 58643398) (tstamp 5C9EAD84) + (at 213.066 -39.1795) + (descr "Diode SMA (DO-214AC) Handsoldering") + (tags "Diode SMA (DO-214AC) Handsoldering") + (path /5C95243A) + (attr smd) + (fp_text reference D3 (at 0 -2.5) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text value SMAJ5.0 (at 0 2.6) (layer F.Fab) + (effects (font (size 1 1) (thickness 0.15))) + ) + (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)) + (fp_line (start -0.64944 0.00102) (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.50118 0.75032) (end 0.50118 -0.79908) (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.00102) (end 1.4994 0.00102) (layer F.Fab) (width 0.1)) + (fp_line (start -0.64944 0.00102) (end -1.55114 0.00102) (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 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.4 -1.65) (end -4.4 1.65) (layer F.SilkS) (width 0.12)) + (fp_text user %R (at 0 -2.5) (layer F.Fab) + (effects (font (size 1 1) (thickness 0.15))) + ) + (pad 2 smd rect (at 2.5 0) (size 3.5 1.8) (layers F.Cu F.Paste F.Mask) + (net 3 GND)) + (pad 1 smd rect (at -2.5 0) (size 3.5 1.8) (layers F.Cu F.Paste F.Mask) + (net 9 /DigIn0)) + (model ${KISYS3DMOD}/Diode_SMD.3dshapes/D_SMA.wrl + (at (xyz 0 0 0)) + (scale (xyz 1 1 1)) + (rotate (xyz 0 0 0)) + ) + ) + + (module Connector_USB:USB_Micro-B_Wuerth-629105150521 (layer F.Cu) (tedit 5A142044) (tstamp 5C9EADB3) + (at 67.1068 98.5012 270) + (descr "USB Micro-B receptacle, http://www.mouser.com/ds/2/445/629105150521-469306.pdf") + (tags "usb micro receptacle") + (path /5C8BC41C) + (attr smd) + (fp_text reference J1 (at 0 -3.5 270) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text value USB_B_Micro (at 0 5.6 270) (layer F.Fab) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_line (start -4 -2.25) (end -4 3.15) (layer F.Fab) (width 0.15)) + (fp_line (start -4 3.15) (end -3.7 3.15) (layer F.Fab) (width 0.15)) + (fp_line (start -3.7 3.15) (end -3.7 4.35) (layer F.Fab) (width 0.15)) + (fp_line (start -3.7 4.35) (end 3.7 4.35) (layer F.Fab) (width 0.15)) + (fp_line (start 3.7 4.35) (end 3.7 3.15) (layer F.Fab) (width 0.15)) + (fp_line (start 3.7 3.15) (end 4 3.15) (layer F.Fab) (width 0.15)) + (fp_line (start 4 3.15) (end 4 -2.25) (layer F.Fab) (width 0.15)) + (fp_line (start 4 -2.25) (end -4 -2.25) (layer F.Fab) (width 0.15)) + (fp_line (start -2.7 3.75) (end 2.7 3.75) (layer F.Fab) (width 0.15)) + (fp_line (start -1.075 -2.725) (end -1.3 -2.55) (layer F.Fab) (width 0.15)) + (fp_line (start -1.3 -2.55) (end -1.525 -2.725) (layer F.Fab) (width 0.15)) + (fp_line (start -1.525 -2.725) (end -1.525 -2.95) (layer F.Fab) (width 0.15)) + (fp_line (start -1.525 -2.95) (end -1.075 -2.95) (layer F.Fab) (width 0.15)) + (fp_line (start -1.075 -2.95) (end -1.075 -2.725) (layer F.Fab) (width 0.15)) + (fp_line (start -4.15 -0.65) (end -4.15 0.75) (layer F.SilkS) (width 0.15)) + (fp_line (start -4.15 3.15) (end -4.15 3.3) (layer F.SilkS) (width 0.15)) + (fp_line (start -4.15 3.3) (end -3.85 3.3) (layer F.SilkS) (width 0.15)) + (fp_line (start -3.85 3.3) (end -3.85 3.75) (layer F.SilkS) (width 0.15)) + (fp_line (start 3.85 3.75) (end 3.85 3.3) (layer F.SilkS) (width 0.15)) + (fp_line (start 3.85 3.3) (end 4.15 3.3) (layer F.SilkS) (width 0.15)) + (fp_line (start 4.15 3.3) (end 4.15 3.15) (layer F.SilkS) (width 0.15)) + (fp_line (start 4.15 0.75) (end 4.15 -0.65) (layer F.SilkS) (width 0.15)) + (fp_line (start -1.075 -2.825) (end -1.8 -2.825) (layer F.SilkS) (width 0.15)) + (fp_line (start -1.8 -2.825) (end -1.8 -2.4) (layer F.SilkS) (width 0.15)) + (fp_line (start -1.8 -2.4) (end -2.8 -2.4) (layer F.SilkS) (width 0.15)) + (fp_line (start 1.8 -2.4) (end 2.8 -2.4) (layer F.SilkS) (width 0.15)) + (fp_line (start -4.94 -3.34) (end -4.94 4.85) (layer F.CrtYd) (width 0.05)) + (fp_line (start -4.94 4.85) (end 4.95 4.85) (layer F.CrtYd) (width 0.05)) + (fp_line (start 4.95 4.85) (end 4.95 -3.34) (layer F.CrtYd) (width 0.05)) + (fp_line (start 4.95 -3.34) (end -4.94 -3.34) (layer F.CrtYd) (width 0.05)) + (fp_text user %R (at 0 1.05 270) (layer F.Fab) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text user "PCB Edge" (at 0 3.75 270) (layer Dwgs.User) + (effects (font (size 0.5 0.5) (thickness 0.08))) + ) + (pad 1 smd rect (at -1.3 -1.9 270) (size 0.45 1.3) (layers F.Cu F.Paste F.Mask) + (net 41 "Net-(D1-Pad1)")) + (pad 2 smd rect (at -0.65 -1.9 270) (size 0.45 1.3) (layers F.Cu F.Paste F.Mask) + (net 42 "Net-(D1-Pad2)")) + (pad 3 smd rect (at 0 -1.9 270) (size 0.45 1.3) (layers F.Cu F.Paste F.Mask) + (net 43 "Net-(D1-Pad3)")) + (pad 4 smd rect (at 0.65 -1.9 270) (size 0.45 1.3) (layers F.Cu F.Paste F.Mask)) + (pad 5 smd rect (at 1.3 -1.9 270) (size 0.45 1.3) (layers F.Cu F.Paste F.Mask) + (net 44 "Net-(D1-Pad4)")) + (pad 6 thru_hole oval (at -3.725 -1.85 270) (size 1.45 2) (drill oval 0.85 1.4) (layers *.Cu *.Mask) + (net 44 "Net-(D1-Pad4)")) + (pad 6 thru_hole oval (at 3.725 -1.85 270) (size 1.45 2) (drill oval 0.85 1.4) (layers *.Cu *.Mask) + (net 44 "Net-(D1-Pad4)")) + (pad 6 thru_hole oval (at -3.875 1.95 270) (size 1.15 1.8) (drill oval 0.55 1.2) (layers *.Cu *.Mask) + (net 44 "Net-(D1-Pad4)")) + (pad 6 thru_hole oval (at 3.875 1.95 270) (size 1.15 1.8) (drill oval 0.55 1.2) (layers *.Cu *.Mask) + (net 44 "Net-(D1-Pad4)")) + (pad "" np_thru_hole oval (at -2.5 -0.8 270) (size 0.8 0.8) (drill 0.8) (layers *.Cu *.Mask)) + (pad "" np_thru_hole oval (at 2.5 -0.8 270) (size 0.8 0.8) (drill 0.8) (layers *.Cu *.Mask)) + (model ${KISYS3DMOD}/Connector_USB.3dshapes/USB_Micro-B_Wuerth-629105150521.wrl + (at (xyz 0 0 0)) + (scale (xyz 1 1 1)) + (rotate (xyz 0 0 0)) + ) + ) + + (module Connector_PinHeader_2.54mm:PinHeader_1x06_P2.54mm_Vertical (layer F.Cu) (tedit 59FED5CC) (tstamp 5CAA7986) + (at 303.657 49.0855) + (descr "Through hole straight pin header, 1x06, 2.54mm pitch, single row") + (tags "Through hole pin header THT 1x06 2.54mm single row") + (path /5C85A71E) + (fp_text reference J2 (at 0 -2.33) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text value ADC_in (at 0 15.03) (layer F.Fab) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_line (start -0.635 -1.27) (end 1.27 -1.27) (layer F.Fab) (width 0.1)) + (fp_line (start 1.27 -1.27) (end 1.27 13.97) (layer F.Fab) (width 0.1)) + (fp_line (start 1.27 13.97) (end -1.27 13.97) (layer F.Fab) (width 0.1)) + (fp_line (start -1.27 13.97) (end -1.27 -0.635) (layer F.Fab) (width 0.1)) + (fp_line (start -1.27 -0.635) (end -0.635 -1.27) (layer F.Fab) (width 0.1)) + (fp_line (start -1.33 14.03) (end 1.33 14.03) (layer F.SilkS) (width 0.12)) + (fp_line (start -1.33 1.27) (end -1.33 14.03) (layer F.SilkS) (width 0.12)) + (fp_line (start 1.33 1.27) (end 1.33 14.03) (layer F.SilkS) (width 0.12)) + (fp_line (start -1.33 1.27) (end 1.33 1.27) (layer F.SilkS) (width 0.12)) + (fp_line (start -1.33 0) (end -1.33 -1.33) (layer F.SilkS) (width 0.12)) + (fp_line (start -1.33 -1.33) (end 0 -1.33) (layer F.SilkS) (width 0.12)) + (fp_line (start -1.8 -1.8) (end -1.8 14.5) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.8 14.5) (end 1.8 14.5) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.8 14.5) (end 1.8 -1.8) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.8 -1.8) (end -1.8 -1.8) (layer F.CrtYd) (width 0.05)) + (fp_text user %R (at 0 6.35 90) (layer F.Fab) + (effects (font (size 1 1) (thickness 0.15))) + ) + (pad 1 thru_hole rect (at 0 0) (size 1.7 1.7) (drill 1) (layers *.Cu *.Mask) + (net 3 GND)) + (pad 2 thru_hole oval (at 0 2.54) (size 1.7 1.7) (drill 1) (layers *.Cu *.Mask) + (net 12 "Net-(J2-Pad2)")) + (pad 3 thru_hole oval (at 0 5.08) (size 1.7 1.7) (drill 1) (layers *.Cu *.Mask) + (net 13 "Net-(J2-Pad3)")) + (pad 4 thru_hole oval (at 0 7.62) (size 1.7 1.7) (drill 1) (layers *.Cu *.Mask) + (net 14 "Net-(J2-Pad4)")) + (pad 5 thru_hole oval (at 0 10.16) (size 1.7 1.7) (drill 1) (layers *.Cu *.Mask) + (net 15 "Net-(J2-Pad5)")) + (pad 6 thru_hole oval (at 0 12.7) (size 1.7 1.7) (drill 1) (layers *.Cu *.Mask) + (net 1 +3V3)) + (model ${KISYS3DMOD}/Connector_PinHeader_2.54mm.3dshapes/PinHeader_1x06_P2.54mm_Vertical.wrl + (at (xyz 0 0 0)) + (scale (xyz 1 1 1)) + (rotate (xyz 0 0 0)) + ) + ) + + (module Connector_PinHeader_2.54mm:PinHeader_1x02_P2.54mm_Vertical (layer F.Cu) (tedit 59FED5CC) (tstamp 5C9EADE3) + (at 264.541 -41.5925) + (descr "Through hole straight pin header, 1x02, 2.54mm pitch, single row") + (tags "Through hole pin header THT 1x02 2.54mm single row") + (path /5C98F117) + (fp_text reference J3 (at 0 -2.33) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text value Jumper0 (at 0 4.87) (layer F.Fab) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text user %R (at 0 1.27 90) (layer F.Fab) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_line (start 1.8 -1.8) (end -1.8 -1.8) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.8 4.35) (end 1.8 -1.8) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.8 4.35) (end 1.8 4.35) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.8 -1.8) (end -1.8 4.35) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.33 -1.33) (end 0 -1.33) (layer F.SilkS) (width 0.12)) + (fp_line (start -1.33 0) (end -1.33 -1.33) (layer F.SilkS) (width 0.12)) + (fp_line (start -1.33 1.27) (end 1.33 1.27) (layer F.SilkS) (width 0.12)) + (fp_line (start 1.33 1.27) (end 1.33 3.87) (layer F.SilkS) (width 0.12)) + (fp_line (start -1.33 1.27) (end -1.33 3.87) (layer F.SilkS) (width 0.12)) + (fp_line (start -1.33 3.87) (end 1.33 3.87) (layer F.SilkS) (width 0.12)) + (fp_line (start -1.27 -0.635) (end -0.635 -1.27) (layer F.Fab) (width 0.1)) + (fp_line (start -1.27 3.81) (end -1.27 -0.635) (layer F.Fab) (width 0.1)) + (fp_line (start 1.27 3.81) (end -1.27 3.81) (layer F.Fab) (width 0.1)) + (fp_line (start 1.27 -1.27) (end 1.27 3.81) (layer F.Fab) (width 0.1)) + (fp_line (start -0.635 -1.27) (end 1.27 -1.27) (layer F.Fab) (width 0.1)) + (pad 2 thru_hole oval (at 0 2.54) (size 1.7 1.7) (drill 1) (layers *.Cu *.Mask) + (net 16 /Jumper0)) + (pad 1 thru_hole rect (at 0 0) (size 1.7 1.7) (drill 1) (layers *.Cu *.Mask) + (net 3 GND)) + (model ${KISYS3DMOD}/Connector_PinHeader_2.54mm.3dshapes/PinHeader_1x02_P2.54mm_Vertical.wrl + (at (xyz 0 0 0)) + (scale (xyz 1 1 1)) + (rotate (xyz 0 0 0)) + ) + ) + + (module Connector_PinHeader_2.54mm:PinHeader_1x02_P2.54mm_Vertical (layer F.Cu) (tedit 59FED5CC) (tstamp 5C9EEA26) + (at 259.334 -41.275) + (descr "Through hole straight pin header, 1x02, 2.54mm pitch, single row") + (tags "Through hole pin header THT 1x02 2.54mm single row") + (path /5C98F3D6) + (fp_text reference J4 (at 0 -2.33) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text value Jumper1 (at 0 4.87) (layer F.Fab) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_line (start -0.635 -1.27) (end 1.27 -1.27) (layer F.Fab) (width 0.1)) + (fp_line (start 1.27 -1.27) (end 1.27 3.81) (layer F.Fab) (width 0.1)) + (fp_line (start 1.27 3.81) (end -1.27 3.81) (layer F.Fab) (width 0.1)) + (fp_line (start -1.27 3.81) (end -1.27 -0.635) (layer F.Fab) (width 0.1)) + (fp_line (start -1.27 -0.635) (end -0.635 -1.27) (layer F.Fab) (width 0.1)) + (fp_line (start -1.33 3.87) (end 1.33 3.87) (layer F.SilkS) (width 0.12)) + (fp_line (start -1.33 1.27) (end -1.33 3.87) (layer F.SilkS) (width 0.12)) + (fp_line (start 1.33 1.27) (end 1.33 3.87) (layer F.SilkS) (width 0.12)) + (fp_line (start -1.33 1.27) (end 1.33 1.27) (layer F.SilkS) (width 0.12)) + (fp_line (start -1.33 0) (end -1.33 -1.33) (layer F.SilkS) (width 0.12)) + (fp_line (start -1.33 -1.33) (end 0 -1.33) (layer F.SilkS) (width 0.12)) + (fp_line (start -1.8 -1.8) (end -1.8 4.35) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.8 4.35) (end 1.8 4.35) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.8 4.35) (end 1.8 -1.8) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.8 -1.8) (end -1.8 -1.8) (layer F.CrtYd) (width 0.05)) + (fp_text user %R (at 0 1.27 90) (layer F.Fab) + (effects (font (size 1 1) (thickness 0.15))) + ) + (pad 1 thru_hole rect (at 0 0) (size 1.7 1.7) (drill 1) (layers *.Cu *.Mask) + (net 3 GND)) + (pad 2 thru_hole oval (at 0 2.54) (size 1.7 1.7) (drill 1) (layers *.Cu *.Mask) + (net 17 /Jumper1)) + (model ${KISYS3DMOD}/Connector_PinHeader_2.54mm.3dshapes/PinHeader_1x02_P2.54mm_Vertical.wrl + (at (xyz 0 0 0)) + (scale (xyz 1 1 1)) + (rotate (xyz 0 0 0)) + ) + ) + + (module Connector_PinHeader_2.54mm:PinHeader_1x03_P2.54mm_Vertical (layer F.Cu) (tedit 59FED5CC) (tstamp 5C9EAE10) + (at 195.6435 -38.6715) + (descr "Through hole straight pin header, 1x03, 2.54mm pitch, single row") + (tags "Through hole pin header THT 1x03 2.54mm single row") + (path /5C9581BA) + (fp_text reference J5 (at 0 -2.33) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text value Conn_01x03 (at 0 7.41) (layer F.Fab) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_line (start -0.635 -1.27) (end 1.27 -1.27) (layer F.Fab) (width 0.1)) + (fp_line (start 1.27 -1.27) (end 1.27 6.35) (layer F.Fab) (width 0.1)) + (fp_line (start 1.27 6.35) (end -1.27 6.35) (layer F.Fab) (width 0.1)) + (fp_line (start -1.27 6.35) (end -1.27 -0.635) (layer F.Fab) (width 0.1)) + (fp_line (start -1.27 -0.635) (end -0.635 -1.27) (layer F.Fab) (width 0.1)) + (fp_line (start -1.33 6.41) (end 1.33 6.41) (layer F.SilkS) (width 0.12)) + (fp_line (start -1.33 1.27) (end -1.33 6.41) (layer F.SilkS) (width 0.12)) + (fp_line (start 1.33 1.27) (end 1.33 6.41) (layer F.SilkS) (width 0.12)) + (fp_line (start -1.33 1.27) (end 1.33 1.27) (layer F.SilkS) (width 0.12)) + (fp_line (start -1.33 0) (end -1.33 -1.33) (layer F.SilkS) (width 0.12)) + (fp_line (start -1.33 -1.33) (end 0 -1.33) (layer F.SilkS) (width 0.12)) + (fp_line (start -1.8 -1.8) (end -1.8 6.85) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.8 6.85) (end 1.8 6.85) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.8 6.85) (end 1.8 -1.8) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.8 -1.8) (end -1.8 -1.8) (layer F.CrtYd) (width 0.05)) + (fp_text user %R (at 0 2.54 90) (layer F.Fab) + (effects (font (size 1 1) (thickness 0.15))) + ) + (pad 1 thru_hole rect (at 0 0) (size 1.7 1.7) (drill 1) (layers *.Cu *.Mask) + (net 3 GND)) + (pad 2 thru_hole oval (at 0 2.54) (size 1.7 1.7) (drill 1) (layers *.Cu *.Mask) + (net 18 "Net-(J5-Pad2)")) + (pad 3 thru_hole oval (at 0 5.08) (size 1.7 1.7) (drill 1) (layers *.Cu *.Mask) + (net 19 "Net-(J5-Pad3)")) + (model ${KISYS3DMOD}/Connector_PinHeader_2.54mm.3dshapes/PinHeader_1x03_P2.54mm_Vertical.wrl + (at (xyz 0 0 0)) + (scale (xyz 1 1 1)) + (rotate (xyz 0 0 0)) + ) + ) + + (module Connector_PinHeader_2.54mm:PinHeader_1x02_P2.54mm_Vertical (layer F.Cu) (tedit 59FED5CC) (tstamp 5CAA7892) + (at 164.4015 -29.5275) + (descr "Through hole straight pin header, 1x02, 2.54mm pitch, single row") + (tags "Through hole pin header THT 1x02 2.54mm single row") + (path /5C93CB05) + (fp_text reference J6 (at 0 -2.33) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text value Ext_LED (at 0 4.87) (layer F.Fab) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_line (start -0.635 -1.27) (end 1.27 -1.27) (layer F.Fab) (width 0.1)) + (fp_line (start 1.27 -1.27) (end 1.27 3.81) (layer F.Fab) (width 0.1)) + (fp_line (start 1.27 3.81) (end -1.27 3.81) (layer F.Fab) (width 0.1)) + (fp_line (start -1.27 3.81) (end -1.27 -0.635) (layer F.Fab) (width 0.1)) + (fp_line (start -1.27 -0.635) (end -0.635 -1.27) (layer F.Fab) (width 0.1)) + (fp_line (start -1.33 3.87) (end 1.33 3.87) (layer F.SilkS) (width 0.12)) + (fp_line (start -1.33 1.27) (end -1.33 3.87) (layer F.SilkS) (width 0.12)) + (fp_line (start 1.33 1.27) (end 1.33 3.87) (layer F.SilkS) (width 0.12)) + (fp_line (start -1.33 1.27) (end 1.33 1.27) (layer F.SilkS) (width 0.12)) + (fp_line (start -1.33 0) (end -1.33 -1.33) (layer F.SilkS) (width 0.12)) + (fp_line (start -1.33 -1.33) (end 0 -1.33) (layer F.SilkS) (width 0.12)) + (fp_line (start -1.8 -1.8) (end -1.8 4.35) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.8 4.35) (end 1.8 4.35) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.8 4.35) (end 1.8 -1.8) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.8 -1.8) (end -1.8 -1.8) (layer F.CrtYd) (width 0.05)) + (fp_text user %R (at 0 1.27 90) (layer F.Fab) + (effects (font (size 1 1) (thickness 0.15))) + ) + (pad 1 thru_hole rect (at 0 0) (size 1.7 1.7) (drill 1) (layers *.Cu *.Mask) + (net 11 +5V)) + (pad 2 thru_hole oval (at 0 2.54) (size 1.7 1.7) (drill 1) (layers *.Cu *.Mask) + (net 20 "Net-(J6-Pad2)")) + (model ${KISYS3DMOD}/Connector_PinHeader_2.54mm.3dshapes/PinHeader_1x02_P2.54mm_Vertical.wrl + (at (xyz 0 0 0)) + (scale (xyz 1 1 1)) + (rotate (xyz 0 0 0)) + ) + ) + + (module Connector_PinHeader_2.54mm:PinHeader_1x03_P2.54mm_Vertical (layer F.Cu) (tedit 59FED5CC) (tstamp 5C9EAE3D) + (at 257.8735 94.9325) + (descr "Through hole straight pin header, 1x03, 2.54mm pitch, single row") + (tags "Through hole pin header THT 1x03 2.54mm single row") + (path /5C88A162) + (fp_text reference J7 (at 0 -2.33) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text value Servo1 (at 0 7.41) (layer F.Fab) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text user %R (at 0 2.54 90) (layer F.Fab) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_line (start 1.8 -1.8) (end -1.8 -1.8) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.8 6.85) (end 1.8 -1.8) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.8 6.85) (end 1.8 6.85) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.8 -1.8) (end -1.8 6.85) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.33 -1.33) (end 0 -1.33) (layer F.SilkS) (width 0.12)) + (fp_line (start -1.33 0) (end -1.33 -1.33) (layer F.SilkS) (width 0.12)) + (fp_line (start -1.33 1.27) (end 1.33 1.27) (layer F.SilkS) (width 0.12)) + (fp_line (start 1.33 1.27) (end 1.33 6.41) (layer F.SilkS) (width 0.12)) + (fp_line (start -1.33 1.27) (end -1.33 6.41) (layer F.SilkS) (width 0.12)) + (fp_line (start -1.33 6.41) (end 1.33 6.41) (layer F.SilkS) (width 0.12)) + (fp_line (start -1.27 -0.635) (end -0.635 -1.27) (layer F.Fab) (width 0.1)) + (fp_line (start -1.27 6.35) (end -1.27 -0.635) (layer F.Fab) (width 0.1)) + (fp_line (start 1.27 6.35) (end -1.27 6.35) (layer F.Fab) (width 0.1)) + (fp_line (start 1.27 -1.27) (end 1.27 6.35) (layer F.Fab) (width 0.1)) + (fp_line (start -0.635 -1.27) (end 1.27 -1.27) (layer F.Fab) (width 0.1)) + (pad 3 thru_hole oval (at 0 5.08) (size 1.7 1.7) (drill 1) (layers *.Cu *.Mask) + (net 21 "Net-(J7-Pad3)")) + (pad 2 thru_hole oval (at 0 2.54) (size 1.7 1.7) (drill 1) (layers *.Cu *.Mask) + (net 11 +5V)) + (pad 1 thru_hole rect (at 0 0) (size 1.7 1.7) (drill 1) (layers *.Cu *.Mask) + (net 3 GND)) + (model ${KISYS3DMOD}/Connector_PinHeader_2.54mm.3dshapes/PinHeader_1x03_P2.54mm_Vertical.wrl + (at (xyz 0 0 0)) + (scale (xyz 1 1 1)) + (rotate (xyz 0 0 0)) + ) + ) + + (module Connector_PinHeader_2.54mm:PinHeader_1x03_P2.54mm_Vertical (layer F.Cu) (tedit 59FED5CC) (tstamp 5CAA80B8) + (at 271.653 50.8635) + (descr "Through hole straight pin header, 1x03, 2.54mm pitch, single row") + (tags "Through hole pin header THT 1x03 2.54mm single row") + (path /5C83F212) + (fp_text reference J8 (at 0 -2.33) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text value Servo2 (at 0 7.41) (layer F.Fab) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_line (start -0.635 -1.27) (end 1.27 -1.27) (layer F.Fab) (width 0.1)) + (fp_line (start 1.27 -1.27) (end 1.27 6.35) (layer F.Fab) (width 0.1)) + (fp_line (start 1.27 6.35) (end -1.27 6.35) (layer F.Fab) (width 0.1)) + (fp_line (start -1.27 6.35) (end -1.27 -0.635) (layer F.Fab) (width 0.1)) + (fp_line (start -1.27 -0.635) (end -0.635 -1.27) (layer F.Fab) (width 0.1)) + (fp_line (start -1.33 6.41) (end 1.33 6.41) (layer F.SilkS) (width 0.12)) + (fp_line (start -1.33 1.27) (end -1.33 6.41) (layer F.SilkS) (width 0.12)) + (fp_line (start 1.33 1.27) (end 1.33 6.41) (layer F.SilkS) (width 0.12)) + (fp_line (start -1.33 1.27) (end 1.33 1.27) (layer F.SilkS) (width 0.12)) + (fp_line (start -1.33 0) (end -1.33 -1.33) (layer F.SilkS) (width 0.12)) + (fp_line (start -1.33 -1.33) (end 0 -1.33) (layer F.SilkS) (width 0.12)) + (fp_line (start -1.8 -1.8) (end -1.8 6.85) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.8 6.85) (end 1.8 6.85) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.8 6.85) (end 1.8 -1.8) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.8 -1.8) (end -1.8 -1.8) (layer F.CrtYd) (width 0.05)) + (fp_text user %R (at 0 2.54 90) (layer F.Fab) + (effects (font (size 1 1) (thickness 0.15))) + ) + (pad 1 thru_hole rect (at 0 0) (size 1.7 1.7) (drill 1) (layers *.Cu *.Mask) + (net 3 GND)) + (pad 2 thru_hole oval (at 0 2.54) (size 1.7 1.7) (drill 1) (layers *.Cu *.Mask) + (net 11 +5V)) + (pad 3 thru_hole oval (at 0 5.08) (size 1.7 1.7) (drill 1) (layers *.Cu *.Mask) + (net 22 "Net-(J8-Pad3)")) + (model ${KISYS3DMOD}/Connector_PinHeader_2.54mm.3dshapes/PinHeader_1x03_P2.54mm_Vertical.wrl + (at (xyz 0 0 0)) + (scale (xyz 1 1 1)) + (rotate (xyz 0 0 0)) + ) + ) + + (module Connector_PinHeader_2.54mm:PinHeader_1x03_P2.54mm_Vertical (layer F.Cu) (tedit 59FED5CC) (tstamp 5C9EAE6B) + (at 270.3195 18.542) + (descr "Through hole straight pin header, 1x03, 2.54mm pitch, single row") + (tags "Through hole pin header THT 1x03 2.54mm single row") + (path /5C83F4E9) + (fp_text reference J9 (at 0 -2.33) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text value Servo3 (at 0 7.41) (layer F.Fab) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text user %R (at 0 2.54 90) (layer F.Fab) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_line (start 1.8 -1.8) (end -1.8 -1.8) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.8 6.85) (end 1.8 -1.8) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.8 6.85) (end 1.8 6.85) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.8 -1.8) (end -1.8 6.85) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.33 -1.33) (end 0 -1.33) (layer F.SilkS) (width 0.12)) + (fp_line (start -1.33 0) (end -1.33 -1.33) (layer F.SilkS) (width 0.12)) + (fp_line (start -1.33 1.27) (end 1.33 1.27) (layer F.SilkS) (width 0.12)) + (fp_line (start 1.33 1.27) (end 1.33 6.41) (layer F.SilkS) (width 0.12)) + (fp_line (start -1.33 1.27) (end -1.33 6.41) (layer F.SilkS) (width 0.12)) + (fp_line (start -1.33 6.41) (end 1.33 6.41) (layer F.SilkS) (width 0.12)) + (fp_line (start -1.27 -0.635) (end -0.635 -1.27) (layer F.Fab) (width 0.1)) + (fp_line (start -1.27 6.35) (end -1.27 -0.635) (layer F.Fab) (width 0.1)) + (fp_line (start 1.27 6.35) (end -1.27 6.35) (layer F.Fab) (width 0.1)) + (fp_line (start 1.27 -1.27) (end 1.27 6.35) (layer F.Fab) (width 0.1)) + (fp_line (start -0.635 -1.27) (end 1.27 -1.27) (layer F.Fab) (width 0.1)) + (pad 3 thru_hole oval (at 0 5.08) (size 1.7 1.7) (drill 1) (layers *.Cu *.Mask) + (net 23 "Net-(J9-Pad3)")) + (pad 2 thru_hole oval (at 0 2.54) (size 1.7 1.7) (drill 1) (layers *.Cu *.Mask) + (net 11 +5V)) + (pad 1 thru_hole rect (at 0 0) (size 1.7 1.7) (drill 1) (layers *.Cu *.Mask) + (net 3 GND)) + (model ${KISYS3DMOD}/Connector_PinHeader_2.54mm.3dshapes/PinHeader_1x03_P2.54mm_Vertical.wrl + (at (xyz 0 0 0)) + (scale (xyz 1 1 1)) + (rotate (xyz 0 0 0)) + ) + ) + + (module Resistor_SMD:R_0805_2012Metric_Pad1.15x1.50mm_HandSolder (layer F.Cu) (tedit 59FE48B8) (tstamp 5C9EAE7C) + (at 93.8265 9.398) + (descr "Resistor SMD 0805 (2012 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 /5C943CF3) + (attr smd) + (fp_text reference R1 (at 0 -1.85) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text value 10k (at 0 1.85) (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.15 -0.71) (end 0.15 -0.71) (layer F.SilkS) (width 0.12)) + (fp_line (start -0.15 0.71) (end 0.15 0.71) (layer F.SilkS) (width 0.12)) + (fp_line (start -1.86 1) (end -1.86 -1) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.86 -1) (end 1.86 -1) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.86 -1) (end 1.86 1) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.86 1) (end -1.86 1) (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 rect (at -1.0425 0) (size 1.145 1.5) (layers F.Cu F.Paste F.Mask) + (net 3 GND)) + (pad 2 smd rect (at 1.0425 0) (size 1.145 1.5) (layers F.Cu F.Paste F.Mask) + (net 24 /BOOT0)) + (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.50mm_HandSolder (layer F.Cu) (tedit 59FE48B8) (tstamp 5C9EAE8D) + (at 315.976 61.849) + (descr "Resistor SMD 0805 (2012 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 /5C85C2A8) + (attr smd) + (fp_text reference R2 (at 0 -1.85) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text value 220 (at 0 1.85) (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.86 1) (end -1.86 1) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.86 -1) (end 1.86 1) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.86 -1) (end 1.86 -1) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.86 1) (end -1.86 -1) (layer F.CrtYd) (width 0.05)) + (fp_line (start -0.15 0.71) (end 0.15 0.71) (layer F.SilkS) (width 0.12)) + (fp_line (start -0.15 -0.71) (end 0.15 -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 rect (at 1.0425 0) (size 1.145 1.5) (layers F.Cu F.Paste F.Mask) + (net 15 "Net-(J2-Pad5)")) + (pad 1 smd rect (at -1.0425 0) (size 1.145 1.5) (layers F.Cu F.Paste F.Mask) + (net 5 /ADC0)) + (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.50mm_HandSolder (layer F.Cu) (tedit 59FE48B8) (tstamp 5C9EAE9E) + (at 310.261 62.5475) + (descr "Resistor SMD 0805 (2012 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 /5C85BD06) + (attr smd) + (fp_text reference R3 (at 0 -1.85) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text value 220 (at 0 1.85) (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.15 -0.71) (end 0.15 -0.71) (layer F.SilkS) (width 0.12)) + (fp_line (start -0.15 0.71) (end 0.15 0.71) (layer F.SilkS) (width 0.12)) + (fp_line (start -1.86 1) (end -1.86 -1) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.86 -1) (end 1.86 -1) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.86 -1) (end 1.86 1) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.86 1) (end -1.86 1) (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 rect (at -1.0425 0) (size 1.145 1.5) (layers F.Cu F.Paste F.Mask) + (net 6 /ADC1)) + (pad 2 smd rect (at 1.0425 0) (size 1.145 1.5) (layers F.Cu F.Paste F.Mask) + (net 14 "Net-(J2-Pad4)")) + (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.50mm_HandSolder (layer F.Cu) (tedit 59FE48B8) (tstamp 5CAA7A52) + (at 321.5375 61.976) + (descr "Resistor SMD 0805 (2012 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 /5C85C1A1) + (attr smd) + (fp_text reference R4 (at 0 -1.85) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text value 220 (at 0 1.85) (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.86 1) (end -1.86 1) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.86 -1) (end 1.86 1) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.86 -1) (end 1.86 -1) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.86 1) (end -1.86 -1) (layer F.CrtYd) (width 0.05)) + (fp_line (start -0.15 0.71) (end 0.15 0.71) (layer F.SilkS) (width 0.12)) + (fp_line (start -0.15 -0.71) (end 0.15 -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 rect (at 1.0425 0) (size 1.145 1.5) (layers F.Cu F.Paste F.Mask) + (net 13 "Net-(J2-Pad3)")) + (pad 1 smd rect (at -1.0425 0) (size 1.145 1.5) (layers F.Cu F.Paste F.Mask) + (net 7 /ADC2)) + (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.50mm_HandSolder (layer F.Cu) (tedit 59FE48B8) (tstamp 5C9EAEC0) + (at 317.2195 58.42) + (descr "Resistor SMD 0805 (2012 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 /5C85C24A) + (attr smd) + (fp_text reference R5 (at 0 -1.85) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text value 220 (at 0 1.85) (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.15 -0.71) (end 0.15 -0.71) (layer F.SilkS) (width 0.12)) + (fp_line (start -0.15 0.71) (end 0.15 0.71) (layer F.SilkS) (width 0.12)) + (fp_line (start -1.86 1) (end -1.86 -1) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.86 -1) (end 1.86 -1) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.86 -1) (end 1.86 1) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.86 1) (end -1.86 1) (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 rect (at -1.0425 0) (size 1.145 1.5) (layers F.Cu F.Paste F.Mask) + (net 8 /ADC3)) + (pad 2 smd rect (at 1.0425 0) (size 1.145 1.5) (layers F.Cu F.Paste F.Mask) + (net 12 "Net-(J2-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.50mm_HandSolder (layer F.Cu) (tedit 59FE48B8) (tstamp 5C9EAED1) + (at 195.3503 93.1672) + (descr "Resistor SMD 0805 (2012 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 /5C929CAD) + (attr smd) + (fp_text reference R6 (at 0 -1.85) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text value 510 (at 0 1.85) (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.15 -0.71) (end 0.15 -0.71) (layer F.SilkS) (width 0.12)) + (fp_line (start -0.15 0.71) (end 0.15 0.71) (layer F.SilkS) (width 0.12)) + (fp_line (start -1.86 1) (end -1.86 -1) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.86 -1) (end 1.86 -1) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.86 -1) (end 1.86 1) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.86 1) (end -1.86 1) (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 rect (at -1.0425 0) (size 1.145 1.5) (layers F.Cu F.Paste F.Mask) + (net 25 "Net-(Q1-Pad1)")) + (pad 2 smd rect (at 1.0425 0) (size 1.145 1.5) (layers F.Cu F.Paste F.Mask) + (net 26 /DigOut0)) + (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.50mm_HandSolder (layer F.Cu) (tedit 59FE48B8) (tstamp 5C9EAEE2) + (at 196.8743 119.2276) + (descr "Resistor SMD 0805 (2012 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 /5C929D7F) + (attr smd) + (fp_text reference R7 (at 0 -1.85) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text value 10k (at 0 1.85) (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.86 1) (end -1.86 1) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.86 -1) (end 1.86 1) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.86 -1) (end 1.86 -1) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.86 1) (end -1.86 -1) (layer F.CrtYd) (width 0.05)) + (fp_line (start -0.15 0.71) (end 0.15 0.71) (layer F.SilkS) (width 0.12)) + (fp_line (start -0.15 -0.71) (end 0.15 -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 rect (at 1.0425 0) (size 1.145 1.5) (layers F.Cu F.Paste F.Mask) + (net 26 /DigOut0)) + (pad 1 smd rect (at -1.0425 0) (size 1.145 1.5) (layers F.Cu F.Paste F.Mask) + (net 3 GND)) + (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.50mm_HandSolder (layer F.Cu) (tedit 59FE48B8) (tstamp 5C9EAEF3) + (at 154.977 -23.241) + (descr "Resistor SMD 0805 (2012 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 /5C924EC0) + (attr smd) + (fp_text reference R8 (at 0 -1.85) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text value 510 (at 0 1.85) (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.15 -0.71) (end 0.15 -0.71) (layer F.SilkS) (width 0.12)) + (fp_line (start -0.15 0.71) (end 0.15 0.71) (layer F.SilkS) (width 0.12)) + (fp_line (start -1.86 1) (end -1.86 -1) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.86 -1) (end 1.86 -1) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.86 -1) (end 1.86 1) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.86 1) (end -1.86 1) (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 rect (at -1.0425 0) (size 1.145 1.5) (layers F.Cu F.Paste F.Mask) + (net 27 "Net-(Q2-Pad1)")) + (pad 2 smd rect (at 1.0425 0) (size 1.145 1.5) (layers F.Cu F.Paste F.Mask) + (net 28 /DigOut1)) + (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.50mm_HandSolder (layer F.Cu) (tedit 59FE48B8) (tstamp 5C9EAF04) + (at 154.9135 -17.4625) + (descr "Resistor SMD 0805 (2012 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 /5C924F9E) + (attr smd) + (fp_text reference R9 (at 0 -1.85) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text value 10k (at 0 1.85) (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.86 1) (end -1.86 1) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.86 -1) (end 1.86 1) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.86 -1) (end 1.86 -1) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.86 1) (end -1.86 -1) (layer F.CrtYd) (width 0.05)) + (fp_line (start -0.15 0.71) (end 0.15 0.71) (layer F.SilkS) (width 0.12)) + (fp_line (start -0.15 -0.71) (end 0.15 -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 rect (at 1.0425 0) (size 1.145 1.5) (layers F.Cu F.Paste F.Mask) + (net 28 /DigOut1)) + (pad 1 smd rect (at -1.0425 0) (size 1.145 1.5) (layers F.Cu F.Paste F.Mask) + (net 3 GND)) + (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.50mm_HandSolder (layer F.Cu) (tedit 59FE48B8) (tstamp 5C9EAF15) + (at 203.9355 -33.147) + (descr "Resistor SMD 0805 (2012 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 /5C957A49) + (attr smd) + (fp_text reference R10 (at 0 -1.85) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text value 1k (at 0 1.85) (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.86 1) (end -1.86 1) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.86 -1) (end 1.86 1) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.86 -1) (end 1.86 -1) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.86 1) (end -1.86 -1) (layer F.CrtYd) (width 0.05)) + (fp_line (start -0.15 0.71) (end 0.15 0.71) (layer F.SilkS) (width 0.12)) + (fp_line (start -0.15 -0.71) (end 0.15 -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 rect (at 1.0425 0) (size 1.145 1.5) (layers F.Cu F.Paste F.Mask) + (net 19 "Net-(J5-Pad3)")) + (pad 1 smd rect (at -1.0425 0) (size 1.145 1.5) (layers F.Cu F.Paste F.Mask) + (net 10 /DigIn1)) + (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.50mm_HandSolder (layer F.Cu) (tedit 59FE48B8) (tstamp 5C9EAF26) + (at 204.089 -38.227) + (descr "Resistor SMD 0805 (2012 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 /5C957B70) + (attr smd) + (fp_text reference R11 (at 0 -1.85) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text value 1k (at 0 1.85) (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.15 -0.71) (end 0.15 -0.71) (layer F.SilkS) (width 0.12)) + (fp_line (start -0.15 0.71) (end 0.15 0.71) (layer F.SilkS) (width 0.12)) + (fp_line (start -1.86 1) (end -1.86 -1) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.86 -1) (end 1.86 -1) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.86 -1) (end 1.86 1) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.86 1) (end -1.86 1) (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 rect (at -1.0425 0) (size 1.145 1.5) (layers F.Cu F.Paste F.Mask) + (net 9 /DigIn0)) + (pad 2 smd rect (at 1.0425 0) (size 1.145 1.5) (layers F.Cu F.Paste F.Mask) + (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.50mm_HandSolder (layer F.Cu) (tedit 59FE48B8) (tstamp 5C9EAF37) + (at 248.629 91.059) + (descr "Resistor SMD 0805 (2012 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 /5BEEBD1E) + (attr smd) + (fp_text reference R12 (at 0 -1.85) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text value 510 (at 0 1.85) (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.86 1) (end -1.86 1) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.86 -1) (end 1.86 1) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.86 -1) (end 1.86 -1) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.86 1) (end -1.86 -1) (layer F.CrtYd) (width 0.05)) + (fp_line (start -0.15 0.71) (end 0.15 0.71) (layer F.SilkS) (width 0.12)) + (fp_line (start -0.15 -0.71) (end 0.15 -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 rect (at 1.0425 0) (size 1.145 1.5) (layers F.Cu F.Paste F.Mask) + (net 29 /TIM3_CH1)) + (pad 1 smd rect (at -1.0425 0) (size 1.145 1.5) (layers F.Cu F.Paste F.Mask) + (net 30 "Net-(Q3-Pad1)")) + (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.50mm_HandSolder (layer F.Cu) (tedit 59FE48B8) (tstamp 5C9EAF48) + (at 258.4185 50.419) + (descr "Resistor SMD 0805 (2012 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 /5C84B03F) + (attr smd) + (fp_text reference R13 (at 0 -1.85) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text value 510 (at 0 1.85) (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.15 -0.71) (end 0.15 -0.71) (layer F.SilkS) (width 0.12)) + (fp_line (start -0.15 0.71) (end 0.15 0.71) (layer F.SilkS) (width 0.12)) + (fp_line (start -1.86 1) (end -1.86 -1) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.86 -1) (end 1.86 -1) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.86 -1) (end 1.86 1) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.86 1) (end -1.86 1) (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 rect (at -1.0425 0) (size 1.145 1.5) (layers F.Cu F.Paste F.Mask) + (net 31 "Net-(Q4-Pad1)")) + (pad 2 smd rect (at 1.0425 0) (size 1.145 1.5) (layers F.Cu F.Paste F.Mask) + (net 32 /TIM3_CH2)) + (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.50mm_HandSolder (layer F.Cu) (tedit 59FE48B8) (tstamp 5C9EAF59) + (at 261.3903 21.5392) + (descr "Resistor SMD 0805 (2012 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 /5C84B0D1) + (attr smd) + (fp_text reference R14 (at 0 -1.85) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text value 510 (at 0 1.85) (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.86 1) (end -1.86 1) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.86 -1) (end 1.86 1) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.86 -1) (end 1.86 -1) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.86 1) (end -1.86 -1) (layer F.CrtYd) (width 0.05)) + (fp_line (start -0.15 0.71) (end 0.15 0.71) (layer F.SilkS) (width 0.12)) + (fp_line (start -0.15 -0.71) (end 0.15 -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 rect (at 1.0425 0) (size 1.145 1.5) (layers F.Cu F.Paste F.Mask) + (net 33 /TIM3_CH4)) + (pad 1 smd rect (at -1.0425 0) (size 1.145 1.5) (layers F.Cu F.Paste F.Mask) + (net 34 "Net-(Q5-Pad1)")) + (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.50mm_HandSolder (layer F.Cu) (tedit 59FE48B8) (tstamp 5C9EAF6A) + (at 248.285 96.393) + (descr "Resistor SMD 0805 (2012 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 /5BEEBD18) + (attr smd) + (fp_text reference R15 (at 0 -1.85) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text value 10k (at 0 1.85) (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.15 -0.71) (end 0.15 -0.71) (layer F.SilkS) (width 0.12)) + (fp_line (start -0.15 0.71) (end 0.15 0.71) (layer F.SilkS) (width 0.12)) + (fp_line (start -1.86 1) (end -1.86 -1) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.86 -1) (end 1.86 -1) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.86 -1) (end 1.86 1) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.86 1) (end -1.86 1) (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 rect (at -1.0425 0) (size 1.145 1.5) (layers F.Cu F.Paste F.Mask) + (net 3 GND)) + (pad 2 smd rect (at 1.0425 0) (size 1.145 1.5) (layers F.Cu F.Paste F.Mask) + (net 29 /TIM3_CH1)) + (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.50mm_HandSolder (layer F.Cu) (tedit 59FE48B8) (tstamp 5C9EAF7B) + (at 258.863 56.3245) + (descr "Resistor SMD 0805 (2012 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 /5C84B278) + (attr smd) + (fp_text reference R16 (at 0 -1.85) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text value 10k (at 0 1.85) (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.15 -0.71) (end 0.15 -0.71) (layer F.SilkS) (width 0.12)) + (fp_line (start -0.15 0.71) (end 0.15 0.71) (layer F.SilkS) (width 0.12)) + (fp_line (start -1.86 1) (end -1.86 -1) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.86 -1) (end 1.86 -1) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.86 -1) (end 1.86 1) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.86 1) (end -1.86 1) (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 rect (at -1.0425 0) (size 1.145 1.5) (layers F.Cu F.Paste F.Mask) + (net 3 GND)) + (pad 2 smd rect (at 1.0425 0) (size 1.145 1.5) (layers F.Cu F.Paste F.Mask) + (net 32 /TIM3_CH2)) + (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.50mm_HandSolder (layer F.Cu) (tedit 59FE48B8) (tstamp 5C9EAF8C) + (at 260.9839 26.9748) + (descr "Resistor SMD 0805 (2012 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 /5C84B3BD) + (attr smd) + (fp_text reference R17 (at 0 -1.85) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text value 10k (at 0 1.85) (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.86 1) (end -1.86 1) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.86 -1) (end 1.86 1) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.86 -1) (end 1.86 -1) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.86 1) (end -1.86 -1) (layer F.CrtYd) (width 0.05)) + (fp_line (start -0.15 0.71) (end 0.15 0.71) (layer F.SilkS) (width 0.12)) + (fp_line (start -0.15 -0.71) (end 0.15 -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 rect (at 1.0425 0) (size 1.145 1.5) (layers F.Cu F.Paste F.Mask) + (net 33 /TIM3_CH4)) + (pad 1 smd rect (at -1.0425 0) (size 1.145 1.5) (layers F.Cu F.Paste F.Mask) + (net 3 GND)) + (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 Crystal:Crystal_HC49-U_Vertical (layer F.Cu) (tedit 5A1AD3B8) (tstamp 5C9EF034) + (at 121.9835 97.536) + (descr "Crystal THT HC-49/U http://5hertz.com/pdfs/04404_D.pdf") + (tags "THT crystalHC-49/U") + (path /5C8CDA20) + (fp_text reference Y1 (at 2.44 -3.525) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text value 12MHz (at 2.44 3.525) (layer F.Fab) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text user %R (at 2.44 0) (layer F.Fab) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_line (start -0.685 -2.325) (end 5.565 -2.325) (layer F.Fab) (width 0.1)) + (fp_line (start -0.685 2.325) (end 5.565 2.325) (layer F.Fab) (width 0.1)) + (fp_line (start -0.56 -2) (end 5.44 -2) (layer F.Fab) (width 0.1)) + (fp_line (start -0.56 2) (end 5.44 2) (layer F.Fab) (width 0.1)) + (fp_line (start -0.685 -2.525) (end 5.565 -2.525) (layer F.SilkS) (width 0.12)) + (fp_line (start -0.685 2.525) (end 5.565 2.525) (layer F.SilkS) (width 0.12)) + (fp_line (start -3.5 -2.8) (end -3.5 2.8) (layer F.CrtYd) (width 0.05)) + (fp_line (start -3.5 2.8) (end 8.4 2.8) (layer F.CrtYd) (width 0.05)) + (fp_line (start 8.4 2.8) (end 8.4 -2.8) (layer F.CrtYd) (width 0.05)) + (fp_line (start 8.4 -2.8) (end -3.5 -2.8) (layer F.CrtYd) (width 0.05)) + (fp_arc (start -0.685 0) (end -0.685 -2.325) (angle -180) (layer F.Fab) (width 0.1)) + (fp_arc (start 5.565 0) (end 5.565 -2.325) (angle 180) (layer F.Fab) (width 0.1)) + (fp_arc (start -0.56 0) (end -0.56 -2) (angle -180) (layer F.Fab) (width 0.1)) + (fp_arc (start 5.44 0) (end 5.44 -2) (angle 180) (layer F.Fab) (width 0.1)) + (fp_arc (start -0.685 0) (end -0.685 -2.525) (angle -180) (layer F.SilkS) (width 0.12)) + (fp_arc (start 5.565 0) (end 5.565 -2.525) (angle 180) (layer F.SilkS) (width 0.12)) + (pad 1 thru_hole circle (at 0 0) (size 1.5 1.5) (drill 0.8) (layers *.Cu *.Mask) + (net 4 "Net-(C7-Pad1)")) + (pad 2 thru_hole circle (at 4.88 0) (size 1.5 1.5) (drill 0.8) (layers *.Cu *.Mask) + (net 40 "Net-(C9-Pad1)")) + (model ${KISYS3DMOD}/Crystal.3dshapes/Crystal_HC49-U_Vertical.wrl + (at (xyz 0 0 0)) + (scale (xyz 1 1 1)) + (rotate (xyz 0 0 0)) + ) + ) + + (module Button_Switch_SMD:SW_SPST_FSMSM (layer F.Cu) (tedit 5A02FC95) (tstamp 5C9F332D) + (at 115.824 -12.6365) + (descr http://www.te.com/commerce/DocumentDelivery/DDEController?Action=srchrtrv&DocNm=1437566-3&DocType=Customer+Drawing&DocLang=English) + (tags "SPST button tactile switch") + (path /590A0134) + (attr smd) + (fp_text reference SW1 (at 0 -2.6) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text value Reset (at 0 3) (layer F.Fab) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text user %R (at 0 -2.6) (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) (size 2.18 1.6) (layers F.Cu F.Paste F.Mask) + (net 38 /NRST)) + (pad 2 smd rect (at 4.59 0) (size 2.18 1.6) (layers F.Cu F.Paste F.Mask) + (net 3 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 Button_Switch_SMD:SW_SPST_FSMSM (layer F.Cu) (tedit 5A02FC95) (tstamp 5C9F3348) + (at 88.9455 2.54) + (descr http://www.te.com/commerce/DocumentDelivery/DDEController?Action=srchrtrv&DocNm=1437566-3&DocType=Customer+Drawing&DocLang=English) + (tags "SPST button tactile switch") + (path /5909F6B6) + (attr smd) + (fp_text reference SW2 (at 0 -2.6) (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 1 +3V3)) + (pad 1 smd rect (at -4.59 0) (size 2.18 1.6) (layers F.Cu F.Paste F.Mask) + (net 24 /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 Capacitor_SMD:C_0603_1608Metric_Pad0.84x1.00mm_HandSolder (layer F.Cu) (tedit 59FE48B8) (tstamp 5CAA4D88) + (at 60.8865 -11.303) + (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 /5A178C32) + (attr smd) + (fp_text reference C1 (at 0 -1.65) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text value 0.1 (at 0 1.65) (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.22 -0.51) (end 0.22 -0.51) (layer F.SilkS) (width 0.12)) + (fp_line (start -0.22 0.51) (end 0.22 0.51) (layer F.SilkS) (width 0.12)) + (fp_line (start -1.64 0.75) (end -1.64 -0.75) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.64 -0.75) (end 1.64 -0.75) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.64 -0.75) (end 1.64 0.75) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.64 0.75) (end -1.64 0.75) (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 rect (at -0.9625 0) (size 0.845 1) (layers F.Cu F.Paste F.Mask) + (net 11 +5V)) + (pad 2 smd rect (at 0.9625 0) (size 0.845 1) (layers F.Cu F.Paste F.Mask) + (net 3 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_Pad0.84x1.00mm_HandSolder (layer F.Cu) (tedit 59FE48B8) (tstamp 5CAA5079) + (at 115.6235 -6.604) + (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 /590D4832) + (attr smd) + (fp_text reference C2 (at 0 -1.65) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text value 0.1 (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.64 0.75) (end -1.64 0.75) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.64 -0.75) (end 1.64 0.75) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.64 -0.75) (end 1.64 -0.75) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.64 0.75) (end -1.64 -0.75) (layer F.CrtYd) (width 0.05)) + (fp_line (start -0.22 0.51) (end 0.22 0.51) (layer F.SilkS) (width 0.12)) + (fp_line (start -0.22 -0.51) (end 0.22 -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 rect (at 0.9625 0) (size 0.845 1) (layers F.Cu F.Paste F.Mask) + (net 3 GND)) + (pad 1 smd rect (at -0.9625 0) (size 0.845 1) (layers F.Cu F.Paste F.Mask) + (net 38 /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_Pad0.84x1.00mm_HandSolder (layer F.Cu) (tedit 59FE48B8) (tstamp 5CAA4DAA) + (at 84.953 9.398) + (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 C3 (at 0 -1.65) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text value 0.1 (at 0 1.65) (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.22 -0.51) (end 0.22 -0.51) (layer F.SilkS) (width 0.12)) + (fp_line (start -0.22 0.51) (end 0.22 0.51) (layer F.SilkS) (width 0.12)) + (fp_line (start -1.64 0.75) (end -1.64 -0.75) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.64 -0.75) (end 1.64 -0.75) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.64 -0.75) (end 1.64 0.75) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.64 0.75) (end -1.64 0.75) (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 rect (at -0.9625 0) (size 0.845 1) (layers F.Cu F.Paste F.Mask) + (net 24 /BOOT0)) + (pad 2 smd rect (at 0.9625 0) (size 0.845 1) (layers F.Cu F.Paste F.Mask) + (net 3 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_Pad0.84x1.00mm_HandSolder (layer F.Cu) (tedit 59FE48B8) (tstamp 5CAA4DBB) + (at 54.6735 -11.557) + (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 /5BEE1D09) + (attr smd) + (fp_text reference C5 (at 0 -1.65) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text value 0.1 (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.64 0.75) (end -1.64 0.75) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.64 -0.75) (end 1.64 0.75) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.64 -0.75) (end 1.64 -0.75) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.64 0.75) (end -1.64 -0.75) (layer F.CrtYd) (width 0.05)) + (fp_line (start -0.22 0.51) (end 0.22 0.51) (layer F.SilkS) (width 0.12)) + (fp_line (start -0.22 -0.51) (end 0.22 -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 rect (at 0.9625 0) (size 0.845 1) (layers F.Cu F.Paste F.Mask) + (net 3 GND)) + (pad 1 smd rect (at -0.9625 0) (size 0.845 1) (layers F.Cu F.Paste F.Mask) + (net 1 +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_Pad0.84x1.00mm_HandSolder (layer F.Cu) (tedit 59FE48B8) (tstamp 5CAA4DCC) + (at 108.3945 91.186) + (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 /5C8AFE6B) + (attr smd) + (fp_text reference C6 (at 0 -1.65) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text value 0.1 (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.64 0.75) (end -1.64 0.75) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.64 -0.75) (end 1.64 0.75) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.64 -0.75) (end 1.64 -0.75) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.64 0.75) (end -1.64 -0.75) (layer F.CrtYd) (width 0.05)) + (fp_line (start -0.22 0.51) (end 0.22 0.51) (layer F.SilkS) (width 0.12)) + (fp_line (start -0.22 -0.51) (end 0.22 -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 rect (at 0.9625 0) (size 0.845 1) (layers F.Cu F.Paste F.Mask) + (net 3 GND)) + (pad 1 smd rect (at -0.9625 0) (size 0.845 1) (layers F.Cu F.Paste F.Mask) + (net 37 "Net-(C6-Pad1)")) + (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_Pad0.84x1.00mm_HandSolder (layer F.Cu) (tedit 59FE48B8) (tstamp 5CAA4DDD) + (at 308.6635 44.7675) + (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 /5C8CE285) + (attr smd) + (fp_text reference C9 (at 0 -1.65) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text value 22p (at 0 1.65) (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.22 -0.51) (end 0.22 -0.51) (layer F.SilkS) (width 0.12)) + (fp_line (start -0.22 0.51) (end 0.22 0.51) (layer F.SilkS) (width 0.12)) + (fp_line (start -1.64 0.75) (end -1.64 -0.75) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.64 -0.75) (end 1.64 -0.75) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.64 -0.75) (end 1.64 0.75) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.64 0.75) (end -1.64 0.75) (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 rect (at -0.9625 0) (size 0.845 1) (layers F.Cu F.Paste F.Mask) + (net 40 "Net-(C9-Pad1)")) + (pad 2 smd rect (at 0.9625 0) (size 0.845 1) (layers F.Cu F.Paste F.Mask) + (net 3 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_Pad0.84x1.00mm_HandSolder (layer F.Cu) (tedit 59FE48B8) (tstamp 5CAA4DEE) + (at 313.2555 44.6405) + (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 /5C862E72) + (attr smd) + (fp_text reference C10 (at 0 -1.65) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text value 0.1 (at 0 1.65) (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.22 -0.51) (end 0.22 -0.51) (layer F.SilkS) (width 0.12)) + (fp_line (start -0.22 0.51) (end 0.22 0.51) (layer F.SilkS) (width 0.12)) + (fp_line (start -1.64 0.75) (end -1.64 -0.75) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.64 -0.75) (end 1.64 -0.75) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.64 -0.75) (end 1.64 0.75) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.64 0.75) (end -1.64 0.75) (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 rect (at -0.9625 0) (size 0.845 1) (layers F.Cu F.Paste F.Mask) + (net 7 /ADC2)) + (pad 2 smd rect (at 0.9625 0) (size 0.845 1) (layers F.Cu F.Paste F.Mask) + (net 3 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_Pad0.84x1.00mm_HandSolder (layer F.Cu) (tedit 59FE48B8) (tstamp 5CAA5007) + (at 317.4465 44.958) + (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 /5C862EDE) + (attr smd) + (fp_text reference C11 (at 0 -1.65) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text value 0.1 (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.64 0.75) (end -1.64 0.75) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.64 -0.75) (end 1.64 0.75) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.64 -0.75) (end 1.64 -0.75) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.64 0.75) (end -1.64 -0.75) (layer F.CrtYd) (width 0.05)) + (fp_line (start -0.22 0.51) (end 0.22 0.51) (layer F.SilkS) (width 0.12)) + (fp_line (start -0.22 -0.51) (end 0.22 -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 rect (at 0.9625 0) (size 0.845 1) (layers F.Cu F.Paste F.Mask) + (net 3 GND)) + (pad 1 smd rect (at -0.9625 0) (size 0.845 1) (layers F.Cu F.Paste F.Mask) + (net 6 /ADC1)) + (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_Pad0.84x1.00mm_HandSolder (layer F.Cu) (tedit 59FE48B8) (tstamp 5CAA4E10) + (at 321.828 44.2595) + (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 /5C864D09) + (attr smd) + (fp_text reference C12 (at 0 -1.65) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text value 0.1 (at 0 1.65) (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.22 -0.51) (end 0.22 -0.51) (layer F.SilkS) (width 0.12)) + (fp_line (start -0.22 0.51) (end 0.22 0.51) (layer F.SilkS) (width 0.12)) + (fp_line (start -1.64 0.75) (end -1.64 -0.75) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.64 -0.75) (end 1.64 -0.75) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.64 -0.75) (end 1.64 0.75) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.64 0.75) (end -1.64 0.75) (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 rect (at -0.9625 0) (size 0.845 1) (layers F.Cu F.Paste F.Mask) + (net 5 /ADC0)) + (pad 2 smd rect (at 0.9625 0) (size 0.845 1) (layers F.Cu F.Paste F.Mask) + (net 3 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 Package_TO_SOT_SMD:SOT-223 (layer F.Cu) (tedit 5A02FF57) (tstamp 5CAA64E1) + (at 57.658 -20.5105) + (descr "module CMS SOT223 4 pins") + (tags "CMS SOT") + (path /5A2588E7) + (attr smd) + (fp_text reference U1 (at 0 -4.5) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text value LM1117-3.3 (at 0 4.5) (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 -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) (size 2 3.8) (layers F.Cu F.Paste F.Mask)) + (pad 2 smd rect (at -3.15 0) (size 2 1.5) (layers F.Cu F.Paste F.Mask) + (net 1 +3V3)) + (pad 3 smd rect (at -3.15 2.3) (size 2 1.5) (layers F.Cu F.Paste F.Mask) + (net 11 +5V)) + (pad 1 smd rect (at -3.15 -2.3) (size 2 1.5) (layers F.Cu F.Paste F.Mask) + (net 3 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 Capacitor_Tantalum_SMD:CP_EIA-3216-18_Kemet-A_Pad1.53x1.40mm_HandSolder (layer F.Cu) (tedit 5A1ED0F1) (tstamp 5CAA68C4) + (at 48.4505 -18.034) + (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 /58C454F6) + (attr smd) + (fp_text reference C4 (at 0 -1.75) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text value 47u (at 0 1.75) (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 -1.06) (end -2.495 -1.06) (layer F.SilkS) (width 0.12)) + (fp_line (start -2.495 -1.06) (end -2.495 1.06) (layer F.SilkS) (width 0.12)) + (fp_line (start -2.495 1.06) (end 1.6 1.06) (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) (layer F.Fab) + (effects (font (size 0.8 0.8) (thickness 0.12))) + ) + (pad 1 smd rect (at -1.4675 0) (size 1.535 1.4) (layers F.Cu F.Paste F.Mask) + (net 1 +3V3)) + (pad 2 smd rect (at 1.4675 0) (size 1.535 1.4) (layers F.Cu F.Paste F.Mask) + (net 3 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 Package_TO_SOT_SMD:SOT-23 (layer F.Cu) (tedit 5A02FF57) (tstamp 5CAA7602) + (at 203.438 100.0404) + (descr "SOT-23, Standard") + (tags SOT-23) + (path /5C9233AA) + (attr smd) + (fp_text reference Q1 (at 0 -2.5) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text value 2N7002 (at 0 2.5) (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.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.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 -1.7 -1.75) (end 1.7 -1.75) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.7 -1.75) (end 1.7 1.75) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.7 1.75) (end -1.7 1.75) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.7 1.75) (end -1.7 -1.75) (layer F.CrtYd) (width 0.05)) + (fp_line (start 0.76 -1.58) (end -1.4 -1.58) (layer F.SilkS) (width 0.12)) + (fp_line (start 0.76 1.58) (end -0.7 1.58) (layer F.SilkS) (width 0.12)) + (pad 1 smd rect (at -1 -0.95) (size 0.9 0.8) (layers F.Cu F.Paste F.Mask) + (net 25 "Net-(Q1-Pad1)")) + (pad 2 smd rect (at -1 0.95) (size 0.9 0.8) (layers F.Cu F.Paste F.Mask) + (net 3 GND)) + (pad 3 smd rect (at 1 0) (size 0.9 0.8) (layers F.Cu F.Paste F.Mask) + (net 2 "Net-(BZ1-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 Package_TO_SOT_SMD:SOT-23 (layer F.Cu) (tedit 5A02FF57) (tstamp 5CAA7617) + (at 154.686 -29.718) + (descr "SOT-23, Standard") + (tags SOT-23) + (path /5BEEB585) + (attr smd) + (fp_text reference Q2 (at 0 -2.5) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text value SI2300 (at 0 2.5) (layer F.Fab) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_line (start 0.76 1.58) (end -0.7 1.58) (layer F.SilkS) (width 0.12)) + (fp_line (start 0.76 -1.58) (end -1.4 -1.58) (layer F.SilkS) (width 0.12)) + (fp_line (start -1.7 1.75) (end -1.7 -1.75) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.7 1.75) (end -1.7 1.75) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.7 -1.75) (end 1.7 1.75) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.7 -1.75) (end 1.7 -1.75) (layer F.CrtYd) (width 0.05)) + (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 -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.7 -0.95) (end -0.15 -1.52) (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.7 1.5) (layer F.Fab) (width 0.1)) + (fp_text user %R (at 0 0 90) (layer F.Fab) + (effects (font (size 0.5 0.5) (thickness 0.075))) + ) + (pad 3 smd rect (at 1 0) (size 0.9 0.8) (layers F.Cu F.Paste F.Mask) + (net 20 "Net-(J6-Pad2)")) + (pad 2 smd rect (at -1 0.95) (size 0.9 0.8) (layers F.Cu F.Paste F.Mask) + (net 3 GND)) + (pad 1 smd rect (at -1 -0.95) (size 0.9 0.8) (layers F.Cu F.Paste F.Mask) + (net 27 "Net-(Q2-Pad1)")) + (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 Package_TO_SOT_SMD:SOT-23 (layer F.Cu) (tedit 5A02FF57) (tstamp 5CAA762C) + (at 249.809 103.3145) + (descr "SOT-23, Standard") + (tags SOT-23) + (path /5BEEBD24) + (attr smd) + (fp_text reference Q3 (at 0 -2.5) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text value 2N7002 (at 0 2.5) (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.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.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 -1.7 -1.75) (end 1.7 -1.75) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.7 -1.75) (end 1.7 1.75) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.7 1.75) (end -1.7 1.75) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.7 1.75) (end -1.7 -1.75) (layer F.CrtYd) (width 0.05)) + (fp_line (start 0.76 -1.58) (end -1.4 -1.58) (layer F.SilkS) (width 0.12)) + (fp_line (start 0.76 1.58) (end -0.7 1.58) (layer F.SilkS) (width 0.12)) + (pad 1 smd rect (at -1 -0.95) (size 0.9 0.8) (layers F.Cu F.Paste F.Mask) + (net 30 "Net-(Q3-Pad1)")) + (pad 2 smd rect (at -1 0.95) (size 0.9 0.8) (layers F.Cu F.Paste F.Mask) + (net 3 GND)) + (pad 3 smd rect (at 1 0) (size 0.9 0.8) (layers F.Cu F.Paste F.Mask) + (net 21 "Net-(J7-Pad3)")) + (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 Package_TO_SOT_SMD:SOT-23 (layer F.Cu) (tedit 5A02FF57) (tstamp 5CAA7641) + (at 265.3665 54.2925) + (descr "SOT-23, Standard") + (tags SOT-23) + (path /5C8882AE) + (attr smd) + (fp_text reference Q4 (at 0 -2.5) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text value 2N7002 (at 0 2.5) (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.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.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 -1.7 -1.75) (end 1.7 -1.75) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.7 -1.75) (end 1.7 1.75) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.7 1.75) (end -1.7 1.75) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.7 1.75) (end -1.7 -1.75) (layer F.CrtYd) (width 0.05)) + (fp_line (start 0.76 -1.58) (end -1.4 -1.58) (layer F.SilkS) (width 0.12)) + (fp_line (start 0.76 1.58) (end -0.7 1.58) (layer F.SilkS) (width 0.12)) + (pad 1 smd rect (at -1 -0.95) (size 0.9 0.8) (layers F.Cu F.Paste F.Mask) + (net 31 "Net-(Q4-Pad1)")) + (pad 2 smd rect (at -1 0.95) (size 0.9 0.8) (layers F.Cu F.Paste F.Mask) + (net 3 GND)) + (pad 3 smd rect (at 1 0) (size 0.9 0.8) (layers F.Cu F.Paste F.Mask) + (net 22 "Net-(J8-Pad3)")) + (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 Package_TO_SOT_SMD:SOT-23 (layer F.Cu) (tedit 5A02FF57) (tstamp 5CAA8165) + (at 260.5532 15.1384) + (descr "SOT-23, Standard") + (tags SOT-23) + (path /5C888320) + (attr smd) + (fp_text reference Q5 (at 0 -2.5) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text value 2N7002 (at 0 2.5) (layer F.Fab) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_line (start 0.76 1.58) (end -0.7 1.58) (layer F.SilkS) (width 0.12)) + (fp_line (start 0.76 -1.58) (end -1.4 -1.58) (layer F.SilkS) (width 0.12)) + (fp_line (start -1.7 1.75) (end -1.7 -1.75) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.7 1.75) (end -1.7 1.75) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.7 -1.75) (end 1.7 1.75) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.7 -1.75) (end 1.7 -1.75) (layer F.CrtYd) (width 0.05)) + (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 -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.7 -0.95) (end -0.15 -1.52) (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.7 1.5) (layer F.Fab) (width 0.1)) + (fp_text user %R (at 0 0 90) (layer F.Fab) + (effects (font (size 0.5 0.5) (thickness 0.075))) + ) + (pad 3 smd rect (at 1 0) (size 0.9 0.8) (layers F.Cu F.Paste F.Mask) + (net 23 "Net-(J9-Pad3)")) + (pad 2 smd rect (at -1 0.95) (size 0.9 0.8) (layers F.Cu F.Paste F.Mask) + (net 3 GND)) + (pad 1 smd rect (at -1 -0.95) (size 0.9 0.8) (layers F.Cu F.Paste F.Mask) + (net 34 "Net-(Q5-Pad1)")) + (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 Capacitor_SMD:C_0805_2012Metric_Pad1.15x1.50mm_HandSolder (layer F.Cu) (tedit 59FE48B8) (tstamp 5CAA9951) + (at 177.1904 55.1423 270) + (descr "Capacitor SMD 0805 (2012 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 /5A1AB970) + (attr smd) + (fp_text reference C13 (at 0 -1.85 270) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text value 1u (at 0 1.85 270) (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.15 -0.71) (end 0.15 -0.71) (layer F.SilkS) (width 0.12)) + (fp_line (start -0.15 0.71) (end 0.15 0.71) (layer F.SilkS) (width 0.12)) + (fp_line (start -1.86 1) (end -1.86 -1) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.86 -1) (end 1.86 -1) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.86 -1) (end 1.86 1) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.86 1) (end -1.86 1) (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 rect (at -1.0425 0 270) (size 1.145 1.5) (layers F.Cu F.Paste F.Mask) + (net 1 +3V3)) + (pad 2 smd rect (at 1.0425 0 270) (size 1.145 1.5) (layers F.Cu F.Paste F.Mask) + (net 3 GND)) + (model ${KISYS3DMOD}/Capacitor_SMD.3dshapes/C_0805_2012Metric.wrl + (at (xyz 0 0 0)) + (scale (xyz 1 1 1)) + (rotate (xyz 0 0 0)) + ) + ) + + (module Capacitor_SMD:C_1206_3216Metric_Pad1.24x1.80mm_HandSolder (layer F.Cu) (tedit 59FE48B8) (tstamp 5CAA9962) + (at 149.7915 55.5244) + (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 /5BEE8065) + (attr smd) + (fp_text reference C14 (at 0 -2.05) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text value 10u (at 0 2.05) (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.65 -0.91) (end 0.65 -0.91) (layer F.SilkS) (width 0.12)) + (fp_line (start -0.65 0.91) (end 0.65 0.91) (layer F.SilkS) (width 0.12)) + (fp_line (start -2.46 1.15) (end -2.46 -1.15) (layer F.CrtYd) (width 0.05)) + (fp_line (start -2.46 -1.15) (end 2.46 -1.15) (layer F.CrtYd) (width 0.05)) + (fp_line (start 2.46 -1.15) (end 2.46 1.15) (layer F.CrtYd) (width 0.05)) + (fp_line (start 2.46 1.15) (end -2.46 1.15) (layer F.CrtYd) (width 0.05)) + (fp_text user %R (at 0 0) (layer F.Fab) + (effects (font (size 0.8 0.8) (thickness 0.12))) + ) + (pad 1 smd rect (at -1.5925 0) (size 1.245 1.8) (layers F.Cu F.Paste F.Mask) + (net 3 GND)) + (pad 2 smd rect (at 1.5925 0) (size 1.245 1.8) (layers F.Cu F.Paste F.Mask) + (net 39 +3.3VADC)) + (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 Inductor_SMD:L_0805_2012Metric_Pad1.15x1.50mm_HandSolder (layer F.Cu) (tedit 59FE48B8) (tstamp 5CAA9973) + (at 157.0979 56.6928) + (descr "Capacitor SMD 0805 (2012 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 "inductor handsolder") + (path /5BEE7949) + (attr smd) + (fp_text reference L1 (at 0 -1.85) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text value "BMBA 0.1mH" (at 0 1.85) (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.15 -0.71) (end 0.15 -0.71) (layer F.SilkS) (width 0.12)) + (fp_line (start -0.15 0.71) (end 0.15 0.71) (layer F.SilkS) (width 0.12)) + (fp_line (start -1.86 1) (end -1.86 -1) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.86 -1) (end 1.86 -1) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.86 -1) (end 1.86 1) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.86 1) (end -1.86 1) (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 rect (at -1.0425 0) (size 1.145 1.5) (layers F.Cu F.Paste F.Mask) + (net 1 +3V3)) + (pad 2 smd rect (at 1.0425 0) (size 1.145 1.5) (layers F.Cu F.Paste F.Mask) + (net 39 +3.3VADC)) + (model ${KISYS3DMOD}/Inductor_SMD.3dshapes/L_0805_2012Metric.wrl + (at (xyz 0 0 0)) + (scale (xyz 1 1 1)) + (rotate (xyz 0 0 0)) + ) + ) + + (module Package_SSOP:TSSOP-20_4.4x6.5mm_P0.65mm (layer F.Cu) (tedit 5A02F25C) (tstamp 5CAAAAED) + (at 168.8084 55.1688) + (descr "20-Lead Plastic Thin Shrink Small Outline (ST)-4.4 mm Body [TSSOP] (see Microchip Packaging Specification 00000049BS.pdf)") + (tags "SSOP 0.65") + (path /5A189F52) + (attr smd) + (fp_text reference U4 (at 0 -4.3) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text value STM32F030F4Px (at 0 4.3) (layer F.Fab) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_line (start -1.2 -3.25) (end 2.2 -3.25) (layer F.Fab) (width 0.15)) + (fp_line (start 2.2 -3.25) (end 2.2 3.25) (layer F.Fab) (width 0.15)) + (fp_line (start 2.2 3.25) (end -2.2 3.25) (layer F.Fab) (width 0.15)) + (fp_line (start -2.2 3.25) (end -2.2 -2.25) (layer F.Fab) (width 0.15)) + (fp_line (start -2.2 -2.25) (end -1.2 -3.25) (layer F.Fab) (width 0.15)) + (fp_line (start -3.95 -3.55) (end -3.95 3.55) (layer F.CrtYd) (width 0.05)) + (fp_line (start 3.95 -3.55) (end 3.95 3.55) (layer F.CrtYd) (width 0.05)) + (fp_line (start -3.95 -3.55) (end 3.95 -3.55) (layer F.CrtYd) (width 0.05)) + (fp_line (start -3.95 3.55) (end 3.95 3.55) (layer F.CrtYd) (width 0.05)) + (fp_line (start -2.225 3.45) (end 2.225 3.45) (layer F.SilkS) (width 0.15)) + (fp_line (start -3.75 -3.45) (end 2.225 -3.45) (layer F.SilkS) (width 0.15)) + (fp_text user %R (at 0 0) (layer F.Fab) + (effects (font (size 0.8 0.8) (thickness 0.15))) + ) + (pad 1 smd rect (at -2.95 -2.925) (size 1.45 0.45) (layers F.Cu F.Paste F.Mask) + (net 24 /BOOT0)) + (pad 2 smd rect (at -2.95 -2.275) (size 1.45 0.45) (layers F.Cu F.Paste F.Mask) + (net 26 /DigOut0)) + (pad 3 smd rect (at -2.95 -1.625) (size 1.45 0.45) (layers F.Cu F.Paste F.Mask) + (net 28 /DigOut1)) + (pad 4 smd rect (at -2.95 -0.975) (size 1.45 0.45) (layers F.Cu F.Paste F.Mask) + (net 38 /NRST)) + (pad 5 smd rect (at -2.95 -0.325) (size 1.45 0.45) (layers F.Cu F.Paste F.Mask) + (net 39 +3.3VADC)) + (pad 6 smd rect (at -2.95 0.325) (size 1.45 0.45) (layers F.Cu F.Paste F.Mask) + (net 5 /ADC0)) + (pad 7 smd rect (at -2.95 0.975) (size 1.45 0.45) (layers F.Cu F.Paste F.Mask) + (net 6 /ADC1)) + (pad 8 smd rect (at -2.95 1.625) (size 1.45 0.45) (layers F.Cu F.Paste F.Mask) + (net 7 /ADC2)) + (pad 9 smd rect (at -2.95 2.275) (size 1.45 0.45) (layers F.Cu F.Paste F.Mask) + (net 8 /ADC3)) + (pad 10 smd rect (at -2.95 2.925) (size 1.45 0.45) (layers F.Cu F.Paste F.Mask) + (net 9 /DigIn0)) + (pad 11 smd rect (at 2.95 2.925) (size 1.45 0.45) (layers F.Cu F.Paste F.Mask) + (net 10 /DigIn1)) + (pad 12 smd rect (at 2.95 2.275) (size 1.45 0.45) (layers F.Cu F.Paste F.Mask) + (net 29 /TIM3_CH1)) + (pad 13 smd rect (at 2.95 1.625) (size 1.45 0.45) (layers F.Cu F.Paste F.Mask) + (net 32 /TIM3_CH2)) + (pad 14 smd rect (at 2.95 0.975) (size 1.45 0.45) (layers F.Cu F.Paste F.Mask) + (net 33 /TIM3_CH4)) + (pad 15 smd rect (at 2.95 0.325) (size 1.45 0.45) (layers F.Cu F.Paste F.Mask) + (net 3 GND)) + (pad 16 smd rect (at 2.95 -0.325) (size 1.45 0.45) (layers F.Cu F.Paste F.Mask) + (net 1 +3V3)) + (pad 17 smd rect (at 2.95 -0.975) (size 1.45 0.45) (layers F.Cu F.Paste F.Mask) + (net 36 /USART_Tx)) + (pad 18 smd rect (at 2.95 -1.625) (size 1.45 0.45) (layers F.Cu F.Paste F.Mask) + (net 35 /USART_Rx)) + (pad 19 smd rect (at 2.95 -2.275) (size 1.45 0.45) (layers F.Cu F.Paste F.Mask) + (net 16 /Jumper0)) + (pad 20 smd rect (at 2.95 -2.925) (size 1.45 0.45) (layers F.Cu F.Paste F.Mask) + (net 17 /Jumper1)) + (model ${KISYS3DMOD}/Package_SSOP.3dshapes/TSSOP-20_4.4x6.5mm_P0.65mm.wrl + (at (xyz 0 0 0)) + (scale (xyz 1 1 1)) + (rotate (xyz 0 0 0)) + ) + ) + + (module Package_SOIC:SOIC-8_3.9x4.9mm_P1.27mm (layer F.Cu) (tedit 5A02F2D3) (tstamp 5CAAB132) + (at 77.1144 98.1456) + (descr "8-Lead Plastic Small Outline (SN) - Narrow, 3.90 mm Body [SOIC] (see Microchip Packaging Specification 00000049BS.pdf)") + (tags "SOIC 1.27") + (path /5C9BF24E) + (attr smd) + (fp_text reference D1 (at 0 -3.5) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text value USB6B1 (at 0 3.5) (layer F.Fab) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text user %R (at 0 0) (layer F.Fab) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_line (start -0.95 -2.45) (end 1.95 -2.45) (layer F.Fab) (width 0.1)) + (fp_line (start 1.95 -2.45) (end 1.95 2.45) (layer F.Fab) (width 0.1)) + (fp_line (start 1.95 2.45) (end -1.95 2.45) (layer F.Fab) (width 0.1)) + (fp_line (start -1.95 2.45) (end -1.95 -1.45) (layer F.Fab) (width 0.1)) + (fp_line (start -1.95 -1.45) (end -0.95 -2.45) (layer F.Fab) (width 0.1)) + (fp_line (start -3.73 -2.7) (end -3.73 2.7) (layer F.CrtYd) (width 0.05)) + (fp_line (start 3.73 -2.7) (end 3.73 2.7) (layer F.CrtYd) (width 0.05)) + (fp_line (start -3.73 -2.7) (end 3.73 -2.7) (layer F.CrtYd) (width 0.05)) + (fp_line (start -3.73 2.7) (end 3.73 2.7) (layer F.CrtYd) (width 0.05)) + (fp_line (start -2.075 -2.575) (end -2.075 -2.525) (layer F.SilkS) (width 0.15)) + (fp_line (start 2.075 -2.575) (end 2.075 -2.43) (layer F.SilkS) (width 0.15)) + (fp_line (start 2.075 2.575) (end 2.075 2.43) (layer F.SilkS) (width 0.15)) + (fp_line (start -2.075 2.575) (end -2.075 2.43) (layer F.SilkS) (width 0.15)) + (fp_line (start -2.075 -2.575) (end 2.075 -2.575) (layer F.SilkS) (width 0.15)) + (fp_line (start -2.075 2.575) (end 2.075 2.575) (layer F.SilkS) (width 0.15)) + (fp_line (start -2.075 -2.525) (end -3.475 -2.525) (layer F.SilkS) (width 0.15)) + (pad 1 smd rect (at -2.7 -1.905) (size 1.55 0.6) (layers F.Cu F.Paste F.Mask) + (net 41 "Net-(D1-Pad1)")) + (pad 2 smd rect (at -2.7 -0.635) (size 1.55 0.6) (layers F.Cu F.Paste F.Mask) + (net 42 "Net-(D1-Pad2)")) + (pad 3 smd rect (at -2.7 0.635) (size 1.55 0.6) (layers F.Cu F.Paste F.Mask) + (net 43 "Net-(D1-Pad3)")) + (pad 4 smd rect (at -2.7 1.905) (size 1.55 0.6) (layers F.Cu F.Paste F.Mask) + (net 44 "Net-(D1-Pad4)")) + (pad 5 smd rect (at 2.7 1.905) (size 1.55 0.6) (layers F.Cu F.Paste F.Mask) + (net 3 GND)) + (pad 6 smd rect (at 2.7 0.635) (size 1.55 0.6) (layers F.Cu F.Paste F.Mask) + (net 45 "Net-(D1-Pad6)")) + (pad 7 smd rect (at 2.7 -0.635) (size 1.55 0.6) (layers F.Cu F.Paste F.Mask) + (net 46 "Net-(D1-Pad7)")) + (pad 8 smd rect (at 2.7 -1.905) (size 1.55 0.6) (layers F.Cu F.Paste F.Mask) + (net 11 +5V)) + (model ${KISYS3DMOD}/Package_SOIC.3dshapes/SOIC-8_3.9x4.9mm_P1.27mm.wrl + (at (xyz 0 0 0)) + (scale (xyz 1 1 1)) + (rotate (xyz 0 0 0)) + ) + ) + + (module Package_TO_SOT_SMD:SOT-23-5 (layer F.Cu) (tedit 5A02FF57) (tstamp 5CAAB1E0) + (at 312.7424 50.1548) + (descr "5-pin SOT23 package") + (tags SOT-23-5) + (path /5C8580E1) + (attr smd) + (fp_text reference D2 (at 0 -2.9) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text value SP0504BAHT (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 -1.55 -1.61) (layer F.SilkS) (width 0.12)) + (fp_line (start -1.9 -1.8) (end 1.9 -1.8) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.9 -1.8) (end 1.9 1.8) (layer F.CrtYd) (width 0.05)) + (fp_line (start 1.9 1.8) (end -1.9 1.8) (layer F.CrtYd) (width 0.05)) + (fp_line (start -1.9 1.8) (end -1.9 -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.1 -0.95) (size 1.06 0.65) (layers F.Cu F.Paste F.Mask) + (net 5 /ADC0)) + (pad 2 smd rect (at -1.1 0) (size 1.06 0.65) (layers F.Cu F.Paste F.Mask) + (net 3 GND)) + (pad 3 smd rect (at -1.1 0.95) (size 1.06 0.65) (layers F.Cu F.Paste F.Mask) + (net 6 /ADC1)) + (pad 4 smd rect (at 1.1 0.95) (size 1.06 0.65) (layers F.Cu F.Paste F.Mask) + (net 7 /ADC2)) + (pad 5 smd rect (at 1.1 -0.95) (size 1.06 0.65) (layers F.Cu F.Paste F.Mask) + (net 8 /ADC3)) + (model ${KISYS3DMOD}/Package_TO_SOT_SMD.3dshapes/SOT-23-5.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 5CAAAFD9) + (at 213.614 -46.482) + (descr "Diode SMA (DO-214AC) Handsoldering") + (tags "Diode SMA (DO-214AC) Handsoldering") + (path /5C952A1B) + (attr smd) + (fp_text reference D4 (at 0 -2.5) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text value SMAJ5.0 (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 10 /DigIn1)) + (pad 2 smd rect (at 2.5 0) (size 3.5 1.8) (layers F.Cu F.Paste F.Mask) + (net 3 GND)) + (model ${KISYS3DMOD}/Diode_SMD.3dshapes/D_SMA.wrl + (at (xyz 0 0 0)) + (scale (xyz 1 1 1)) + (rotate (xyz 0 0 0)) + ) + ) + + (module Package_SOIC:SOIC-16_3.9x9.9mm_P1.27mm (layer F.Cu) (tedit 5A02F2D3) (tstamp 5CAAAFDA) + (at 97.1296 99.6188 180) + (descr "16-Lead Plastic Small Outline (SL) - Narrow, 3.90 mm Body [SOIC] (see Microchip Packaging Specification 00000049BS.pdf)") + (tags "SOIC 1.27") + (path /5C891E7A) + (attr smd) + (fp_text reference U2 (at 0 -6 180) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text value CH340G (at 0 6 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.9 0.9) (thickness 0.135))) + ) + (fp_line (start -0.95 -4.95) (end 1.95 -4.95) (layer F.Fab) (width 0.15)) + (fp_line (start 1.95 -4.95) (end 1.95 4.95) (layer F.Fab) (width 0.15)) + (fp_line (start 1.95 4.95) (end -1.95 4.95) (layer F.Fab) (width 0.15)) + (fp_line (start -1.95 4.95) (end -1.95 -3.95) (layer F.Fab) (width 0.15)) + (fp_line (start -1.95 -3.95) (end -0.95 -4.95) (layer F.Fab) (width 0.15)) + (fp_line (start -3.7 -5.25) (end -3.7 5.25) (layer F.CrtYd) (width 0.05)) + (fp_line (start 3.7 -5.25) (end 3.7 5.25) (layer F.CrtYd) (width 0.05)) + (fp_line (start -3.7 -5.25) (end 3.7 -5.25) (layer F.CrtYd) (width 0.05)) + (fp_line (start -3.7 5.25) (end 3.7 5.25) (layer F.CrtYd) (width 0.05)) + (fp_line (start -2.075 -5.075) (end -2.075 -5.05) (layer F.SilkS) (width 0.15)) + (fp_line (start 2.075 -5.075) (end 2.075 -4.97) (layer F.SilkS) (width 0.15)) + (fp_line (start 2.075 5.075) (end 2.075 4.97) (layer F.SilkS) (width 0.15)) + (fp_line (start -2.075 5.075) (end -2.075 4.97) (layer F.SilkS) (width 0.15)) + (fp_line (start -2.075 -5.075) (end 2.075 -5.075) (layer F.SilkS) (width 0.15)) + (fp_line (start -2.075 5.075) (end 2.075 5.075) (layer F.SilkS) (width 0.15)) + (fp_line (start -2.075 -5.05) (end -3.45 -5.05) (layer F.SilkS) (width 0.15)) + (pad 1 smd rect (at -2.7 -4.445 180) (size 1.5 0.6) (layers F.Cu F.Paste F.Mask) + (net 3 GND)) + (pad 2 smd rect (at -2.7 -3.175 180) (size 1.5 0.6) (layers F.Cu F.Paste F.Mask) + (net 35 /USART_Rx)) + (pad 3 smd rect (at -2.7 -1.905 180) (size 1.5 0.6) (layers F.Cu F.Paste F.Mask) + (net 36 /USART_Tx)) + (pad 4 smd rect (at -2.7 -0.635 180) (size 1.5 0.6) (layers F.Cu F.Paste F.Mask) + (net 37 "Net-(C6-Pad1)")) + (pad 5 smd rect (at -2.7 0.635 180) (size 1.5 0.6) (layers F.Cu F.Paste F.Mask) + (net 46 "Net-(D1-Pad7)")) + (pad 6 smd rect (at -2.7 1.905 180) (size 1.5 0.6) (layers F.Cu F.Paste F.Mask) + (net 45 "Net-(D1-Pad6)")) + (pad 7 smd rect (at -2.7 3.175 180) (size 1.5 0.6) (layers F.Cu F.Paste F.Mask) + (net 4 "Net-(C7-Pad1)")) + (pad 8 smd rect (at -2.7 4.445 180) (size 1.5 0.6) (layers F.Cu F.Paste F.Mask) + (net 40 "Net-(C9-Pad1)")) + (pad 9 smd rect (at 2.7 4.445 180) (size 1.5 0.6) (layers F.Cu F.Paste F.Mask)) + (pad 10 smd rect (at 2.7 3.175 180) (size 1.5 0.6) (layers F.Cu F.Paste F.Mask)) + (pad 11 smd rect (at 2.7 1.905 180) (size 1.5 0.6) (layers F.Cu F.Paste F.Mask)) + (pad 12 smd rect (at 2.7 0.635 180) (size 1.5 0.6) (layers F.Cu F.Paste F.Mask)) + (pad 13 smd rect (at 2.7 -0.635 180) (size 1.5 0.6) (layers F.Cu F.Paste F.Mask)) + (pad 14 smd rect (at 2.7 -1.905 180) (size 1.5 0.6) (layers F.Cu F.Paste F.Mask)) + (pad 15 smd rect (at 2.7 -3.175 180) (size 1.5 0.6) (layers F.Cu F.Paste F.Mask)) + (pad 16 smd rect (at 2.7 -4.445 180) (size 1.5 0.6) (layers F.Cu F.Paste F.Mask) + (net 1 +3V3)) + (model ${KISYS3DMOD}/Package_SOIC.3dshapes/SOIC-16_3.9x9.9mm_P1.27mm.wrl + (at (xyz 0 0 0)) + (scale (xyz 1 1 1)) + (rotate (xyz 0 0 0)) + ) + ) + + (module Package_SSOP:TSSOP-20_4.4x6.5mm_P0.65mm (layer F.Cu) (tedit 5A02F25C) (tstamp 5CAAAFFE) + (at 108.585 99.6315) + (descr "20-Lead Plastic Thin Shrink Small Outline (ST)-4.4 mm Body [TSSOP] (see Microchip Packaging Specification 00000049BS.pdf)") + (tags "SSOP 0.65") + (path /5A189F52) + (attr smd) + (fp_text reference U3 (at 0 -4.3) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text value STM32F030F4Px (at 0 4.3) (layer F.Fab) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_line (start -1.2 -3.25) (end 2.2 -3.25) (layer F.Fab) (width 0.15)) + (fp_line (start 2.2 -3.25) (end 2.2 3.25) (layer F.Fab) (width 0.15)) + (fp_line (start 2.2 3.25) (end -2.2 3.25) (layer F.Fab) (width 0.15)) + (fp_line (start -2.2 3.25) (end -2.2 -2.25) (layer F.Fab) (width 0.15)) + (fp_line (start -2.2 -2.25) (end -1.2 -3.25) (layer F.Fab) (width 0.15)) + (fp_line (start -3.95 -3.55) (end -3.95 3.55) (layer F.CrtYd) (width 0.05)) + (fp_line (start 3.95 -3.55) (end 3.95 3.55) (layer F.CrtYd) (width 0.05)) + (fp_line (start -3.95 -3.55) (end 3.95 -3.55) (layer F.CrtYd) (width 0.05)) + (fp_line (start -3.95 3.55) (end 3.95 3.55) (layer F.CrtYd) (width 0.05)) + (fp_line (start -2.225 3.45) (end 2.225 3.45) (layer F.SilkS) (width 0.15)) + (fp_line (start -3.75 -3.45) (end 2.225 -3.45) (layer F.SilkS) (width 0.15)) + (fp_text user %R (at 0 0) (layer F.Fab) + (effects (font (size 0.8 0.8) (thickness 0.15))) + ) + (pad 1 smd rect (at -2.95 -2.925) (size 1.45 0.45) (layers F.Cu F.Paste F.Mask) + (net 24 /BOOT0)) + (pad 2 smd rect (at -2.95 -2.275) (size 1.45 0.45) (layers F.Cu F.Paste F.Mask) + (net 26 /DigOut0)) + (pad 3 smd rect (at -2.95 -1.625) (size 1.45 0.45) (layers F.Cu F.Paste F.Mask) + (net 28 /DigOut1)) + (pad 4 smd rect (at -2.95 -0.975) (size 1.45 0.45) (layers F.Cu F.Paste F.Mask) + (net 38 /NRST)) + (pad 5 smd rect (at -2.95 -0.325) (size 1.45 0.45) (layers F.Cu F.Paste F.Mask) + (net 39 +3.3VADC)) + (pad 6 smd rect (at -2.95 0.325) (size 1.45 0.45) (layers F.Cu F.Paste F.Mask) + (net 5 /ADC0)) + (pad 7 smd rect (at -2.95 0.975) (size 1.45 0.45) (layers F.Cu F.Paste F.Mask) + (net 6 /ADC1)) + (pad 8 smd rect (at -2.95 1.625) (size 1.45 0.45) (layers F.Cu F.Paste F.Mask) + (net 7 /ADC2)) + (pad 9 smd rect (at -2.95 2.275) (size 1.45 0.45) (layers F.Cu F.Paste F.Mask) + (net 8 /ADC3)) + (pad 10 smd rect (at -2.95 2.925) (size 1.45 0.45) (layers F.Cu F.Paste F.Mask) + (net 9 /DigIn0)) + (pad 11 smd rect (at 2.95 2.925) (size 1.45 0.45) (layers F.Cu F.Paste F.Mask) + (net 10 /DigIn1)) + (pad 12 smd rect (at 2.95 2.275) (size 1.45 0.45) (layers F.Cu F.Paste F.Mask) + (net 29 /TIM3_CH1)) + (pad 13 smd rect (at 2.95 1.625) (size 1.45 0.45) (layers F.Cu F.Paste F.Mask) + (net 32 /TIM3_CH2)) + (pad 14 smd rect (at 2.95 0.975) (size 1.45 0.45) (layers F.Cu F.Paste F.Mask) + (net 33 /TIM3_CH4)) + (pad 15 smd rect (at 2.95 0.325) (size 1.45 0.45) (layers F.Cu F.Paste F.Mask) + (net 3 GND)) + (pad 16 smd rect (at 2.95 -0.325) (size 1.45 0.45) (layers F.Cu F.Paste F.Mask) + (net 1 +3V3)) + (pad 17 smd rect (at 2.95 -0.975) (size 1.45 0.45) (layers F.Cu F.Paste F.Mask) + (net 36 /USART_Tx)) + (pad 18 smd rect (at 2.95 -1.625) (size 1.45 0.45) (layers F.Cu F.Paste F.Mask) + (net 35 /USART_Rx)) + (pad 19 smd rect (at 2.95 -2.275) (size 1.45 0.45) (layers F.Cu F.Paste F.Mask) + (net 16 /Jumper0)) + (pad 20 smd rect (at 2.95 -2.925) (size 1.45 0.45) (layers F.Cu F.Paste F.Mask) + (net 17 /Jumper1)) + (model ${KISYS3DMOD}/Package_SSOP.3dshapes/TSSOP-20_4.4x6.5mm_P0.65mm.wrl + (at (xyz 0 0 0)) + (scale (xyz 1 1 1)) + (rotate (xyz 0 0 0)) + ) + ) + + (segment (start 171.7584 54.8438) (end 174.061 54.8438) (width 0.25) (layer F.Cu) (net 1)) + (segment (start 174.805 54.0998) (end 177.1904 54.0998) (width 0.25) (layer F.Cu) (net 1)) + (segment (start 174.061 54.8438) (end 174.805 54.0998) (width 0.25) (layer F.Cu) (net 1)) + (segment (start 171.7584 55.4938) (end 174.061 55.4938) (width 0.25) (layer F.Cu) (net 3)) + (segment (start 174.752 56.1848) (end 177.1904 56.1848) (width 0.25) (layer F.Cu) (net 3)) + (segment (start 174.061 55.4938) (end 174.752 56.1848) (width 0.25) (layer F.Cu) (net 3)) + +) diff --git a/F0-nolib/Servo/kicad/Servo_control.net b/F0-nolib/Servo/kicad/Servo_control.net new file mode 100644 index 0000000..9af0d9f --- /dev/null +++ b/F0-nolib/Servo/kicad/Servo_control.net @@ -0,0 +1,869 @@ +(export (version D) + (design + (source /Big/Data/00__Electronics/STM32/F0-nolib/Servo/kicad/Servo_control.sch) + (date "Пн 11 мар 2019 00:06:44") + (tool "Eeschema 5.0.1") + (sheet (number 1) (name /) (tstamps /) + (title_block + (title) + (company) + (rev) + (date) + (source Servo_control.sch) + (comment (number 1) (value "")) + (comment (number 2) (value "")) + (comment (number 3) (value "")) + (comment (number 4) (value ""))))) + (components + (comp (ref C4) + (value 47u) + (footprint Capacitor_Tantalum_SMD:CP_EIA-3216-18_Kemet-A_Pad1.53x1.40mm_HandSolder) + (libsource (lib Servo_control-rescue) (part CP-Chiller_control-rescue) (description "")) + (sheetpath (names /) (tstamps /)) + (tstamp 58C454F6)) + (comp (ref C3) + (value 0.1) + (footprint Capacitor_SMD:C_0603_1608Metric_Pad0.84x1.00mm_HandSolder) + (libsource (lib Servo_control-rescue) (part C-Chiller_control-rescue) (description "")) + (sheetpath (names /) (tstamps /)) + (tstamp 590D4150)) + (comp (ref C2) + (value 0.1) + (footprint Capacitor_SMD:C_0603_1608Metric_Pad0.84x1.00mm_HandSolder) + (libsource (lib Servo_control-rescue) (part C-Chiller_control-rescue) (description "")) + (sheetpath (names /) (tstamps /)) + (tstamp 590D4832)) + (comp (ref SW2) + (value Boot) + (footprint Button_Switch_SMD:SW_SPST_FSMSM) + (libsource (lib Servo_control-rescue) (part SW_Push-Chiller_control-rescue) (description "")) + (sheetpath (names /) (tstamps /)) + (tstamp 5909F6B6)) + (comp (ref SW1) + (value Reset) + (footprint Button_Switch_SMD:SW_SPST_FSMSM) + (libsource (lib Servo_control-rescue) (part SW_Push-Chiller_control-rescue) (description "")) + (sheetpath (names /) (tstamps /)) + (tstamp 590A0134)) + (comp (ref C1) + (value 0.1) + (footprint Capacitor_SMD:C_0603_1608Metric_Pad0.84x1.00mm_HandSolder) + (libsource (lib Servo_control-rescue) (part C-Chiller_control-rescue) (description "")) + (sheetpath (names /) (tstamps /)) + (tstamp 5A178C32)) + (comp (ref U3) + (value STM32F030F4Px) + (footprint Package_SSOP:TSSOP-20_4.4x6.5mm_P0.65mm) + (libsource (lib Servo_control-rescue) (part STM32F030F4Px-Chiller_control-rescue) (description "")) + (sheetpath (names /) (tstamps /)) + (tstamp 5A189F52)) + (comp (ref C13) + (value 1u) + (footprint Capacitor_SMD:C_0805_2012Metric_Pad1.15x1.50mm_HandSolder) + (libsource (lib Servo_control-rescue) (part C-Chiller_control-rescue) (description "")) + (sheetpath (names /) (tstamps /)) + (tstamp 5A1AB970)) + (comp (ref U1) + (value LM1117-3.3) + (footprint Package_TO_SOT_SMD:SOT-223) + (libsource (lib Servo_control-rescue) (part LM1117-3.3-Chiller_control-rescue) (description "")) + (sheetpath (names /) (tstamps /)) + (tstamp 5A2588E7)) + (comp (ref C5) + (value 0.1) + (footprint Capacitor_SMD:C_0603_1608Metric_Pad0.84x1.00mm_HandSolder) + (libsource (lib Servo_control-rescue) (part C-Chiller_control-rescue) (description "")) + (sheetpath (names /) (tstamps /)) + (tstamp 5BEE1D09)) + (comp (ref L1) + (value "BMBA 0.1mH") + (footprint Inductor_SMD:L_0805_2012Metric_Pad1.15x1.50mm_HandSolder) + (libsource (lib Servo_control-rescue) (part L-Chiller_control-rescue) (description "")) + (sheetpath (names /) (tstamps /)) + (tstamp 5BEE7949)) + (comp (ref C14) + (value 10u) + (footprint Capacitor_SMD:C_1206_3216Metric_Pad1.24x1.80mm_HandSolder) + (libsource (lib Servo_control-rescue) (part C-Chiller_control-rescue) (description "")) + (sheetpath (names /) (tstamps /)) + (tstamp 5BEE8065)) + (comp (ref R15) + (value 10k) + (footprint Resistor_SMD:R_0805_2012Metric_Pad1.15x1.50mm_HandSolder) + (libsource (lib Servo_control-rescue) (part R-Chiller_control-rescue) (description "")) + (sheetpath (names /) (tstamps /)) + (tstamp 5BEEBD18)) + (comp (ref R12) + (value 510) + (footprint Resistor_SMD:R_0805_2012Metric_Pad1.15x1.50mm_HandSolder) + (libsource (lib Servo_control-rescue) (part R-Chiller_control-rescue) (description "")) + (sheetpath (names /) (tstamps /)) + (tstamp 5BEEBD1E)) + (comp (ref Q3) + (value 2N7002) + (footprint Package_TO_SOT_SMD:SOT-23) + (libsource (lib Servo_control-rescue) (part Q_NMOS_GSD-Chiller_control-rescue) (description "")) + (sheetpath (names /) (tstamps /)) + (tstamp 5BEEBD24)) + (comp (ref Q2) + (value SI2300) + (footprint Package_TO_SOT_SMD:SOT-23) + (libsource (lib Servo_control-rescue) (part Q_NMOS_GSD-Chiller_control-rescue) (description "")) + (sheetpath (names /) (tstamps /)) + (tstamp 5BEEB585)) + (comp (ref BZ1) + (value Buzzer) + (footprint Buzzer_Beeper:Buzzer_12x9.5RM7.6) + (datasheet ~) + (libsource (lib Device) (part Buzzer) (description "Buzzer, polar")) + (sheetpath (names /) (tstamps /)) + (tstamp 5C83133C)) + (comp (ref Q4) + (value 2N7002) + (footprint Package_TO_SOT_SMD:SOT-23) + (libsource (lib Servo_control-rescue) (part Q_NMOS_GSD-Chiller_control-rescue) (description "")) + (sheetpath (names /) (tstamps /)) + (tstamp 5C8882AE)) + (comp (ref Q5) + (value 2N7002) + (footprint Package_TO_SOT_SMD:SOT-23) + (libsource (lib Servo_control-rescue) (part Q_NMOS_GSD-Chiller_control-rescue) (description "")) + (sheetpath (names /) (tstamps /)) + (tstamp 5C888320)) + (comp (ref J7) + (value Servo1) + (footprint Connector_PinHeader_2.54mm:PinHeader_1x03_P2.54mm_Vertical) + (datasheet ~) + (libsource (lib Connector_Generic) (part Conn_01x03) (description "Generic connector, single row, 01x03, script generated (kicad-library-utils/schlib/autogen/connector/)")) + (sheetpath (names /) (tstamps /)) + (tstamp 5C88A162)) + (comp (ref J8) + (value Servo2) + (footprint Connector_PinHeader_2.54mm:PinHeader_1x03_P2.54mm_Vertical) + (datasheet ~) + (libsource (lib Connector_Generic) (part Conn_01x03) (description "Generic connector, single row, 01x03, script generated (kicad-library-utils/schlib/autogen/connector/)")) + (sheetpath (names /) (tstamps /)) + (tstamp 5C83F212)) + (comp (ref J9) + (value Servo3) + (footprint Connector_PinHeader_2.54mm:PinHeader_1x03_P2.54mm_Vertical) + (datasheet ~) + (libsource (lib Connector_Generic) (part Conn_01x03) (description "Generic connector, single row, 01x03, script generated (kicad-library-utils/schlib/autogen/connector/)")) + (sheetpath (names /) (tstamps /)) + (tstamp 5C83F4E9)) + (comp (ref R13) + (value 510) + (footprint Resistor_SMD:R_0805_2012Metric_Pad1.15x1.50mm_HandSolder) + (libsource (lib Servo_control-rescue) (part R-Chiller_control-rescue) (description "")) + (sheetpath (names /) (tstamps /)) + (tstamp 5C84B03F)) + (comp (ref R14) + (value 510) + (footprint Resistor_SMD:R_0805_2012Metric_Pad1.15x1.50mm_HandSolder) + (libsource (lib Servo_control-rescue) (part R-Chiller_control-rescue) (description "")) + (sheetpath (names /) (tstamps /)) + (tstamp 5C84B0D1)) + (comp (ref R16) + (value 10k) + (footprint Resistor_SMD:R_0805_2012Metric_Pad1.15x1.50mm_HandSolder) + (libsource (lib Servo_control-rescue) (part R-Chiller_control-rescue) (description "")) + (sheetpath (names /) (tstamps /)) + (tstamp 5C84B278)) + (comp (ref R17) + (value 10k) + (footprint Resistor_SMD:R_0805_2012Metric_Pad1.15x1.50mm_HandSolder) + (libsource (lib Servo_control-rescue) (part R-Chiller_control-rescue) (description "")) + (sheetpath (names /) (tstamps /)) + (tstamp 5C84B3BD)) + (comp (ref D2) + (value SP0504BAHT) + (footprint Package_TO_SOT_SMD:SOT-23-5) + (datasheet http://www.littelfuse.com/~/media/files/littelfuse/technical%20resources/documents/data%20sheets/sp05xxba.pdf) + (libsource (lib Power_Protection) (part SP0504BAHT) (description "TVS Diode Array, 5.5V Standoff, 4 Channels, SOT-23-5 package")) + (sheetpath (names /) (tstamps /)) + (tstamp 5C8580E1)) + (comp (ref J2) + (value ADC_in) + (footprint Connector_PinHeader_2.54mm:PinHeader_1x06_P2.54mm_Vertical) + (datasheet ~) + (libsource (lib Connector_Generic) (part Conn_01x06) (description "Generic connector, single row, 01x06, script generated (kicad-library-utils/schlib/autogen/connector/)")) + (sheetpath (names /) (tstamps /)) + (tstamp 5C85A71E)) + (comp (ref R3) + (value 220) + (footprint Resistor_SMD:R_0805_2012Metric_Pad1.15x1.50mm_HandSolder) + (libsource (lib Device) (part R) (description Resistor)) + (sheetpath (names /) (tstamps /)) + (tstamp 5C85BD06)) + (comp (ref R4) + (value 220) + (footprint Resistor_SMD:R_0805_2012Metric_Pad1.15x1.50mm_HandSolder) + (libsource (lib Device) (part R) (description Resistor)) + (sheetpath (names /) (tstamps /)) + (tstamp 5C85C1A1)) + (comp (ref R5) + (value 220) + (footprint Resistor_SMD:R_0805_2012Metric_Pad1.15x1.50mm_HandSolder) + (libsource (lib Device) (part R) (description Resistor)) + (sheetpath (names /) (tstamps /)) + (tstamp 5C85C24A)) + (comp (ref R2) + (value 220) + (footprint Resistor_SMD:R_0805_2012Metric_Pad1.15x1.50mm_HandSolder) + (libsource (lib Device) (part R) (description Resistor)) + (sheetpath (names /) (tstamps /)) + (tstamp 5C85C2A8)) + (comp (ref C8) + (value 0.1) + (footprint Capacitor_SMD:C_0603_1608Metric_Pad0.84x1.00mm_HandSolder) + (libsource (lib Servo_control-rescue) (part C-Chiller_control-rescue) (description "")) + (sheetpath (names /) (tstamps /)) + (tstamp 5C86267B)) + (comp (ref C10) + (value 0.1) + (footprint Capacitor_SMD:C_0603_1608Metric_Pad0.84x1.00mm_HandSolder) + (libsource (lib Servo_control-rescue) (part C-Chiller_control-rescue) (description "")) + (sheetpath (names /) (tstamps /)) + (tstamp 5C862E72)) + (comp (ref C11) + (value 0.1) + (footprint Capacitor_SMD:C_0603_1608Metric_Pad0.84x1.00mm_HandSolder) + (libsource (lib Servo_control-rescue) (part C-Chiller_control-rescue) (description "")) + (sheetpath (names /) (tstamps /)) + (tstamp 5C862EDE)) + (comp (ref C12) + (value 0.1) + (footprint Capacitor_SMD:C_0603_1608Metric_Pad0.84x1.00mm_HandSolder) + (libsource (lib Servo_control-rescue) (part C-Chiller_control-rescue) (description "")) + (sheetpath (names /) (tstamps /)) + (tstamp 5C864D09)) + (comp (ref U2) + (value CH340G) + (footprint Package_SOIC:SOIC-16_3.9x9.9mm_P1.27mm) + (libsource (lib ch34x) (part CH340G) (description "")) + (sheetpath (names /) (tstamps /)) + (tstamp 5C891E7A)) + (comp (ref C6) + (value 0.1) + (footprint Capacitor_SMD:C_0603_1608Metric_Pad0.84x1.00mm_HandSolder) + (libsource (lib Servo_control-rescue) (part C-Chiller_control-rescue) (description "")) + (sheetpath (names /) (tstamps /)) + (tstamp 5C8AFE6B)) + (comp (ref Y1) + (value 12MHz) + (footprint Crystal:Crystal_HC49-U_Vertical) + (libsource (lib Device) (part Crystal) (description "Two pin crystal")) + (sheetpath (names /) (tstamps /)) + (tstamp 5C8CDA20)) + (comp (ref C7) + (value 22p) + (footprint Capacitor_SMD:C_0603_1608Metric_Pad0.84x1.00mm_HandSolder) + (libsource (lib Device) (part C) (description "Unpolarized capacitor")) + (sheetpath (names /) (tstamps /)) + (tstamp 5C8CDF63)) + (comp (ref C9) + (value 22p) + (footprint Capacitor_SMD:C_0603_1608Metric_Pad0.84x1.00mm_HandSolder) + (libsource (lib Device) (part C) (description "Unpolarized capacitor")) + (sheetpath (names /) (tstamps /)) + (tstamp 5C8CE285)) + (comp (ref Q1) + (value 2N7002) + (footprint Package_TO_SOT_SMD:SOT-23) + (libsource (lib Servo_control-rescue) (part Q_NMOS_GSD-Chiller_control-rescue) (description "")) + (sheetpath (names /) (tstamps /)) + (tstamp 5C9233AA)) + (comp (ref R8) + (value 510) + (footprint Resistor_SMD:R_0805_2012Metric_Pad1.15x1.50mm_HandSolder) + (libsource (lib Servo_control-rescue) (part R-Chiller_control-rescue) (description "")) + (sheetpath (names /) (tstamps /)) + (tstamp 5C924EC0)) + (comp (ref R9) + (value 10k) + (footprint Resistor_SMD:R_0805_2012Metric_Pad1.15x1.50mm_HandSolder) + (libsource (lib Servo_control-rescue) (part R-Chiller_control-rescue) (description "")) + (sheetpath (names /) (tstamps /)) + (tstamp 5C924F9E)) + (comp (ref R6) + (value 510) + (footprint Resistor_SMD:R_0805_2012Metric_Pad1.15x1.50mm_HandSolder) + (libsource (lib Servo_control-rescue) (part R-Chiller_control-rescue) (description "")) + (sheetpath (names /) (tstamps /)) + (tstamp 5C929CAD)) + (comp (ref R7) + (value 10k) + (footprint Resistor_SMD:R_0805_2012Metric_Pad1.15x1.50mm_HandSolder) + (libsource (lib Servo_control-rescue) (part R-Chiller_control-rescue) (description "")) + (sheetpath (names /) (tstamps /)) + (tstamp 5C929D7F)) + (comp (ref J6) + (value Ext_LED) + (footprint Connector_PinHeader_2.54mm:PinHeader_1x02_P2.54mm_Vertical) + (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 5C93CB05)) + (comp (ref R1) + (value 10k) + (footprint Resistor_SMD:R_0805_2012Metric_Pad1.15x1.50mm_HandSolder) + (libsource (lib Servo_control-rescue) (part R-Chiller_control-rescue) (description "")) + (sheetpath (names /) (tstamps /)) + (tstamp 5C943CF3)) + (comp (ref D3) + (value SMAJ5.0) + (footprint Diode_SMD:D_SMA_Handsoldering) + (libsource (lib Device) (part D) (description Diode)) + (sheetpath (names /) (tstamps /)) + (tstamp 5C95243A)) + (comp (ref D4) + (value SMAJ5.0) + (footprint Diode_SMD:D_SMA_Handsoldering) + (libsource (lib Device) (part D) (description Diode)) + (sheetpath (names /) (tstamps /)) + (tstamp 5C952A1B)) + (comp (ref R10) + (value 1k) + (footprint Resistor_SMD:R_0805_2012Metric_Pad1.15x1.50mm_HandSolder) + (libsource (lib Servo_control-rescue) (part R-Chiller_control-rescue) (description "")) + (sheetpath (names /) (tstamps /)) + (tstamp 5C957A49)) + (comp (ref R11) + (value 1k) + (footprint Resistor_SMD:R_0805_2012Metric_Pad1.15x1.50mm_HandSolder) + (libsource (lib Servo_control-rescue) (part R-Chiller_control-rescue) (description "")) + (sheetpath (names /) (tstamps /)) + (tstamp 5C957B70)) + (comp (ref J5) + (value Conn_01x03) + (footprint Connector_PinHeader_2.54mm:PinHeader_1x03_P2.54mm_Vertical) + (datasheet ~) + (libsource (lib Connector_Generic) (part Conn_01x03) (description "Generic connector, single row, 01x03, script generated (kicad-library-utils/schlib/autogen/connector/)")) + (sheetpath (names /) (tstamps /)) + (tstamp 5C9581BA)) + (comp (ref J3) + (value Jumper0) + (footprint Connector_PinHeader_2.54mm:PinHeader_1x02_P2.54mm_Vertical) + (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 5C98F117)) + (comp (ref J4) + (value Jumper1) + (footprint Connector_PinHeader_2.54mm:PinHeader_1x02_P2.54mm_Vertical) + (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 5C98F3D6)) + (comp (ref J1) + (value USB_B_Micro) + (footprint Connector_USB:USB_Micro-B_Wuerth-629105150521) + (datasheet ~) + (libsource (lib Connector_Specialized) (part USB_B_Micro) (description "USB Micro Type B connector")) + (sheetpath (names /) (tstamps /)) + (tstamp 5C8BC41C)) + (comp (ref D1) + (value USB6B1) + (footprint Package_SOIC:SOIC-8_3.9x4.9mm_P1.27mm) + (libsource (lib elements) (part USB6B1) (description "")) + (sheetpath (names /) (tstamps /)) + (tstamp 5C9BF24E))) + (libparts + (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 Connector_Generic) (part Conn_01x03) + (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)) + (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_Generic) (part Conn_01x06) + (description "Generic connector, single row, 01x06, script generated (kicad-library-utils/schlib/autogen/connector/)") + (docs ~) + (footprints + (fp Connector*:*_1x??_*)) + (fields + (field (name Reference) J) + (field (name Value) Conn_01x06)) + (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)) + (pin (num 5) (name Pin_5) (type passive)) + (pin (num 6) (name Pin_6) (type passive)))) + (libpart (lib Connector_Specialized) (part USB_B_Micro) + (aliases + (alias USB_B_Mini)) + (description "USB Micro Type B connector") + (docs ~) + (footprints + (fp USB*)) + (fields + (field (name Reference) J) + (field (name Value) USB_B_Micro)) + (pins + (pin (num 1) (name VBUS) (type power_out)) + (pin (num 2) (name D-) (type passive)) + (pin (num 3) (name D+) (type passive)) + (pin (num 4) (name ID) (type passive)) + (pin (num 5) (name GND) (type power_out)) + (pin (num 6) (name Shield) (type passive)))) + (libpart (lib Device) (part Buzzer) + (description "Buzzer, polar") + (footprints + (fp *Buzzer*)) + (fields + (field (name Reference) BZ) + (field (name Value) Buzzer)) + (pins + (pin (num 1) (name -) (type passive)) + (pin (num 2) (name +) (type passive)))) + (libpart (lib Device) (part C) + (description "Unpolarized capacitor") + (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") + (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) + (description Diode) + (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 Device) (part R) + (description Resistor) + (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 Power_Protection) (part SP0504BAHT) + (description "TVS Diode Array, 5.5V Standoff, 4 Channels, SOT-23-5 package") + (docs http://www.littelfuse.com/~/media/files/littelfuse/technical%20resources/documents/data%20sheets/sp05xxba.pdf) + (footprints + (fp SOT?23*)) + (fields + (field (name Reference) D) + (field (name Value) SP0504BAHT) + (field (name Footprint) Package_TO_SOT_SMD:SOT-23-5)) + (pins + (pin (num 1) (name K) (type input)) + (pin (num 2) (name A) (type input)) + (pin (num 3) (name K) (type input)) + (pin (num 4) (name K) (type input)) + (pin (num 5) (name K) (type input)))) + (libpart (lib Servo_control-rescue) (part C-Chiller_control-rescue) + (footprints + (fp C_*)) + (fields + (field (name Reference) C) + (field (name Value) C-Chiller_control-rescue)) + (pins + (pin (num 1) (name ~) (type passive)) + (pin (num 2) (name ~) (type passive)))) + (libpart (lib Servo_control-rescue) (part CP-Chiller_control-rescue) + (footprints + (fp CP_*)) + (fields + (field (name Reference) C) + (field (name Value) CP-Chiller_control-rescue)) + (pins + (pin (num 1) (name ~) (type passive)) + (pin (num 2) (name ~) (type passive)))) + (libpart (lib Servo_control-rescue) (part L-Chiller_control-rescue) + (footprints + (fp Choke_*) + (fp *Coil*) + (fp Inductor_*) + (fp L_*)) + (fields + (field (name Reference) L) + (field (name Value) L-Chiller_control-rescue)) + (pins + (pin (num 1) (name 1) (type passive)) + (pin (num 2) (name 2) (type passive)))) + (libpart (lib Servo_control-rescue) (part LM1117-3.3-Chiller_control-rescue) + (footprints + (fp SOT?223*) + (fp TO?263*) + (fp TO?252*) + (fp TO?220*)) + (fields + (field (name Reference) U) + (field (name Value) LM1117-3.3-Chiller_control-rescue)) + (pins + (pin (num 1) (name GND) (type power_in)) + (pin (num 2) (name VO) (type power_out)) + (pin (num 3) (name VI) (type power_in)))) + (libpart (lib Servo_control-rescue) (part Q_NMOS_GSD-Chiller_control-rescue) + (fields + (field (name Reference) Q) + (field (name Value) Q_NMOS_GSD-Chiller_control-rescue)) + (pins + (pin (num 1) (name G) (type input)) + (pin (num 2) (name S) (type passive)) + (pin (num 3) (name D) (type passive)))) + (libpart (lib Servo_control-rescue) (part R-Chiller_control-rescue) + (footprints + (fp R_*) + (fp R_*)) + (fields + (field (name Reference) R) + (field (name Value) R-Chiller_control-rescue)) + (pins + (pin (num 1) (name ~) (type passive)) + (pin (num 2) (name ~) (type passive)))) + (libpart (lib Servo_control-rescue) (part STM32F030F4Px-Chiller_control-rescue) + (fields + (field (name Reference) U) + (field (name Value) STM32F030F4Px-Chiller_control-rescue) + (field (name Footprint) Housings_SSOP:TSSOP-20_4.4x6.5mm_Pitch0.65mm)) + (pins + (pin (num 1) (name BOOT0) (type input)) + (pin (num 2) (name PF0/RCC_OSC_IN) (type input)) + (pin (num 3) (name PF1/RCC_OSC_OUT) (type input)) + (pin (num 4) (name NRST) (type input)) + (pin (num 5) (name VDDA) (type power_in)) + (pin (num 6) (name ADC_IN0/RTC_TAMP2/SYS_WKUP1/USART1_CTS/PA0) (type BiDi)) + (pin (num 7) (name ADC_IN1/USART1_DE/USART1_RTS/PA1) (type BiDi)) + (pin (num 8) (name ADC_IN2/USART1_TX/PA2) (type BiDi)) + (pin (num 9) (name ADC_IN3/USART1_RX/PA3) (type BiDi)) + (pin (num 10) (name ADC_IN4/SPI1_NSS/TIM14_CH1/USART1_CK/PA4) (type BiDi)) + (pin (num 11) (name ADC_IN5/SPI1_SCK/PA5) (type BiDi)) + (pin (num 12) (name ADC_IN6/SPI1_MISO/TIM16_CH1/TIM1_BKIN/TIM3_CH1/PA6) (type BiDi)) + (pin (num 13) (name ADC_IN7/SPI1_MOSI/TIM14_CH1/TIM17_CH1/TIM1_CH1N/TIM3_CH2/PA7) (type BiDi)) + (pin (num 14) (name PB1/ADC_IN9/TIM14_CH1/TIM1_CH3N/TIM3_CH4) (type BiDi)) + (pin (num 15) (name VSS) (type power_in)) + (pin (num 16) (name VDD) (type power_in)) + (pin (num 17) (name I2C1_SCL/TIM1_CH2/USART1_TX/PA9) (type BiDi)) + (pin (num 18) (name I2C1_SDA/TIM17_BKIN/TIM1_CH3/USART1_RX/PA10) (type BiDi)) + (pin (num 19) (name IR_OUT/SYS_SWDIO/PA13) (type BiDi)) + (pin (num 20) (name SYS_SWCLK/USART1_TX/PA14) (type BiDi)))) + (libpart (lib Servo_control-rescue) (part SW_Push-Chiller_control-rescue) + (fields + (field (name Reference) SW) + (field (name Value) SW_Push-Chiller_control-rescue)) + (pins + (pin (num 1) (name 1) (type passive)) + (pin (num 2) (name 2) (type passive)))) + (libpart (lib ch34x) (part CH340G) + (fields + (field (name Reference) U) + (field (name Value) CH340G)) + (pins + (pin (num 1) (name GND) (type power_in)) + (pin (num 2) (name TX) (type output)) + (pin (num 3) (name RX) (type input)) + (pin (num 4) (name V3) (type passive)) + (pin (num 5) (name D+) (type BiDi)) + (pin (num 6) (name D-) (type BiDi)) + (pin (num 7) (name XI) (type input)) + (pin (num 8) (name XO) (type input)) + (pin (num 9) (name CTS) (type output)) + (pin (num 10) (name DSR) (type output)) + (pin (num 11) (name RI) (type output)) + (pin (num 12) (name DCD) (type output)) + (pin (num 13) (name DTR) (type output)) + (pin (num 14) (name RTS) (type output)) + (pin (num 15) (name RS232) (type input)) + (pin (num 16) (name VCC) (type power_in)))) + (libpart (lib elements) (part USB6B1) + (footprints + (fp SO8)) + (fields + (field (name Reference) D) + (field (name Value) USB6B1)) + (pins + (pin (num 1) (name VCC) (type passive)) + (pin (num 2) (name I/O1) (type passive)) + (pin (num 3) (name I/O2) (type passive)) + (pin (num 4) (name GND) (type passive)) + (pin (num 5) (name GND) (type passive)) + (pin (num 6) (name I/O2) (type passive)) + (pin (num 7) (name I/O1) (type passive)) + (pin (num 8) (name VCC) (type passive))))) + (libraries + (library (logical Connector_Generic) + (uri /usr/share/kicad/library/Connector_Generic.lib)) + (library (logical Connector_Specialized) + (uri /usr/share/kicad/library/Connector_Specialized.lib)) + (library (logical Device) + (uri /usr/share/kicad/library/Device.lib)) + (library (logical Power_Protection) + (uri /usr/share/kicad/library/Power_Protection.lib)) + (library (logical Servo_control-rescue) + (uri /Big/Data/00__Electronics/STM32/F0-nolib/Servo/kicad/Servo_control-rescue.lib)) + (library (logical ch34x) + (uri /Big/Data/00__Electronics/STM32/F0-nolib/Servo/kicad/ch34x.lib)) + (library (logical elements) + (uri /Big/Data/00__Electronics/STM32/F0-nolib/Servo/kicad/elements.lib))) + (nets + (net (code 1) (name "Net-(U2-Pad13)") + (node (ref U2) (pin 13))) + (net (code 2) (name "Net-(U2-Pad12)") + (node (ref U2) (pin 12))) + (net (code 3) (name "Net-(U2-Pad11)") + (node (ref U2) (pin 11))) + (net (code 4) (name "Net-(U2-Pad10)") + (node (ref U2) (pin 10))) + (net (code 5) (name "Net-(U2-Pad9)") + (node (ref U2) (pin 9))) + (net (code 6) (name +3V3) + (node (ref C13) (pin 1)) + (node (ref C4) (pin 1)) + (node (ref C5) (pin 1)) + (node (ref U1) (pin 2)) + (node (ref J2) (pin 6)) + (node (ref SW2) (pin 2)) + (node (ref U3) (pin 16)) + (node (ref L1) (pin 1)) + (node (ref BZ1) (pin 1)) + (node (ref U2) (pin 16))) + (net (code 7) (name "Net-(U2-Pad15)") + (node (ref U2) (pin 15))) + (net (code 8) (name "Net-(U2-Pad14)") + (node (ref U2) (pin 14))) + (net (code 9) (name "Net-(C9-Pad1)") + (node (ref U2) (pin 8)) + (node (ref C9) (pin 1)) + (node (ref Y1) (pin 2))) + (net (code 10) (name "Net-(D1-Pad7)") + (node (ref D1) (pin 7)) + (node (ref U2) (pin 5))) + (net (code 11) (name "Net-(C6-Pad1)") + (node (ref C6) (pin 1)) + (node (ref U2) (pin 4))) + (net (code 12) (name /USART_Tx) + (node (ref U2) (pin 3)) + (node (ref U3) (pin 17))) + (net (code 13) (name /USART_Rx) + (node (ref U2) (pin 2)) + (node (ref U3) (pin 18))) + (net (code 14) (name GND) + (node (ref C14) (pin 1)) + (node (ref R15) (pin 1)) + (node (ref C5) (pin 2)) + (node (ref D4) (pin 2)) + (node (ref R7) (pin 1)) + (node (ref R9) (pin 1)) + (node (ref Q1) (pin 2)) + (node (ref R1) (pin 1)) + (node (ref J5) (pin 1)) + (node (ref Q3) (pin 2)) + (node (ref D3) (pin 2)) + (node (ref J2) (pin 1)) + (node (ref J9) (pin 1)) + (node (ref J8) (pin 1)) + (node (ref J7) (pin 1)) + (node (ref D2) (pin 2)) + (node (ref R17) (pin 1)) + (node (ref R16) (pin 1)) + (node (ref C3) (pin 2)) + (node (ref U3) (pin 15)) + (node (ref C1) (pin 2)) + (node (ref SW1) (pin 2)) + (node (ref Q2) (pin 2)) + (node (ref C2) (pin 2)) + (node (ref C4) (pin 2)) + (node (ref C13) (pin 2)) + (node (ref Q4) (pin 2)) + (node (ref U1) (pin 1)) + (node (ref Q5) (pin 2)) + (node (ref D1) (pin 5)) + (node (ref C12) (pin 2)) + (node (ref C11) (pin 2)) + (node (ref C10) (pin 2)) + (node (ref C8) (pin 2)) + (node (ref J3) (pin 1)) + (node (ref J4) (pin 1)) + (node (ref C9) (pin 2)) + (node (ref U2) (pin 1)) + (node (ref C7) (pin 2)) + (node (ref C6) (pin 2))) + (net (code 15) (name "Net-(C7-Pad1)") + (node (ref C7) (pin 1)) + (node (ref Y1) (pin 1)) + (node (ref U2) (pin 7))) + (net (code 16) (name "Net-(J2-Pad3)") + (node (ref R4) (pin 2)) + (node (ref J2) (pin 3))) + (net (code 17) (name "Net-(J2-Pad5)") + (node (ref J2) (pin 5)) + (node (ref R2) (pin 2))) + (net (code 18) (name "Net-(J2-Pad4)") + (node (ref R3) (pin 2)) + (node (ref J2) (pin 4))) + (net (code 19) (name "Net-(J2-Pad2)") + (node (ref J2) (pin 2)) + (node (ref R5) (pin 2))) + (net (code 20) (name /Jumper1) + (node (ref J4) (pin 2)) + (node (ref U3) (pin 20))) + (net (code 21) (name /DigIn1) + (node (ref R10) (pin 1)) + (node (ref D4) (pin 1)) + (node (ref U3) (pin 11))) + (net (code 22) (name /DigIn0) + (node (ref U3) (pin 10)) + (node (ref R11) (pin 1)) + (node (ref D3) (pin 1))) + (net (code 23) (name "Net-(J5-Pad3)") + (node (ref J5) (pin 3)) + (node (ref R10) (pin 2))) + (net (code 24) (name "Net-(D1-Pad6)") + (node (ref D1) (pin 6)) + (node (ref U2) (pin 6))) + (net (code 25) (name "Net-(D1-Pad3)") + (node (ref D1) (pin 3)) + (node (ref J1) (pin 3))) + (net (code 26) (name "Net-(D1-Pad2)") + (node (ref J1) (pin 2)) + (node (ref D1) (pin 2))) + (net (code 27) (name +5V) + (node (ref C1) (pin 1)) + (node (ref U1) (pin 3)) + (node (ref D1) (pin 8)) + (node (ref J9) (pin 2)) + (node (ref J7) (pin 2)) + (node (ref J8) (pin 2)) + (node (ref J6) (pin 1))) + (net (code 28) (name "Net-(J5-Pad2)") + (node (ref J5) (pin 2)) + (node (ref R11) (pin 2))) + (net (code 29) (name "Net-(D1-Pad4)") + (node (ref D1) (pin 4)) + (node (ref J1) (pin 5)) + (node (ref J1) (pin 6))) + (net (code 30) (name "Net-(J1-Pad4)") + (node (ref J1) (pin 4))) + (net (code 31) (name "Net-(D1-Pad1)") + (node (ref J1) (pin 1)) + (node (ref D1) (pin 1))) + (net (code 32) (name "Net-(Q1-Pad1)") + (node (ref R6) (pin 1)) + (node (ref Q1) (pin 1))) + (net (code 33) (name "Net-(Q2-Pad1)") + (node (ref Q2) (pin 1)) + (node (ref R8) (pin 1))) + (net (code 34) (name "Net-(BZ1-Pad2)") + (node (ref BZ1) (pin 2)) + (node (ref Q1) (pin 3))) + (net (code 35) (name "Net-(J6-Pad2)") + (node (ref J6) (pin 2)) + (node (ref Q2) (pin 3))) + (net (code 36) (name "Net-(J7-Pad3)") + (node (ref Q3) (pin 3)) + (node (ref J7) (pin 3))) + (net (code 37) (name "Net-(Q3-Pad1)") + (node (ref R12) (pin 1)) + (node (ref Q3) (pin 1))) + (net (code 38) (name +3.3VADC) + (node (ref U3) (pin 5)) + (node (ref L1) (pin 2)) + (node (ref C14) (pin 2))) + (net (code 39) (name /TIM3_CH1) + (node (ref R12) (pin 2)) + (node (ref U3) (pin 12)) + (node (ref R15) (pin 2))) + (net (code 40) (name /BOOT0) + (node (ref SW2) (pin 1)) + (node (ref C3) (pin 1)) + (node (ref R1) (pin 2)) + (node (ref U3) (pin 1))) + (net (code 41) (name /ADC3) + (node (ref D2) (pin 5)) + (node (ref U3) (pin 9)) + (node (ref R5) (pin 1)) + (node (ref C8) (pin 1))) + (net (code 42) (name /ADC2) + (node (ref D2) (pin 4)) + (node (ref C10) (pin 1)) + (node (ref R4) (pin 1)) + (node (ref U3) (pin 8))) + (net (code 43) (name /ADC1) + (node (ref U3) (pin 7)) + (node (ref C11) (pin 1)) + (node (ref R3) (pin 1)) + (node (ref D2) (pin 3))) + (net (code 44) (name /ADC0) + (node (ref U3) (pin 6)) + (node (ref C12) (pin 1)) + (node (ref D2) (pin 1)) + (node (ref R2) (pin 1))) + (net (code 45) (name /NRST) + (node (ref U3) (pin 4)) + (node (ref SW1) (pin 1)) + (node (ref C2) (pin 1))) + (net (code 46) (name /DigOut1) + (node (ref R8) (pin 2)) + (node (ref R9) (pin 2)) + (node (ref U3) (pin 3))) + (net (code 47) (name /DigOut0) + (node (ref U3) (pin 2)) + (node (ref R7) (pin 2)) + (node (ref R6) (pin 2))) + (net (code 48) (name /Jumper0) + (node (ref U3) (pin 19)) + (node (ref J3) (pin 2))) + (net (code 49) (name "Net-(J8-Pad3)") + (node (ref Q4) (pin 3)) + (node (ref J8) (pin 3))) + (net (code 50) (name "Net-(J9-Pad3)") + (node (ref Q5) (pin 3)) + (node (ref J9) (pin 3))) + (net (code 51) (name /TIM3_CH2) + (node (ref R16) (pin 2)) + (node (ref R13) (pin 2)) + (node (ref U3) (pin 13))) + (net (code 52) (name /TIM3_CH4) + (node (ref U3) (pin 14)) + (node (ref R14) (pin 2)) + (node (ref R17) (pin 2))) + (net (code 53) (name "Net-(Q5-Pad1)") + (node (ref R14) (pin 1)) + (node (ref Q5) (pin 1))) + (net (code 54) (name "Net-(Q4-Pad1)") + (node (ref R13) (pin 1)) + (node (ref Q4) (pin 1))))) \ No newline at end of file diff --git a/F0-nolib/Servo/kicad/Servo_control.pro b/F0-nolib/Servo/kicad/Servo_control.pro new file mode 100644 index 0000000..9552699 --- /dev/null +++ b/F0-nolib/Servo/kicad/Servo_control.pro @@ -0,0 +1,100 @@ +update=Вс 27 янв 2019 15:05:22 +version=1 +last_client=kicad +[cvpcb] +version=1 +NetIExt=net +[general] +version=1 +[schematic_editor] +version=1 +PageLayoutDescrFile= +PlotDirectoryName= +SubpartIdSeparator=0 +SubpartFirstId=65 +NetFmtName=Pcbnew +SpiceForceRefPrefix=0 +SpiceUseNetNumbers=0 +LabSize=60 +[eeschema] +version=1 +LibDir= +[pcbnew] +version=1 +PageLayoutDescrFile= +LastNetListRead=Chiller_control.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.5 +TrackWidth2=0.25 +TrackWidth3=0.5 +TrackWidth4=1 +TrackWidth5=2 +ViaDiameter1=1.2 +ViaDrill1=0.6 +ViaDiameter2=1.2 +ViaDrill2=0.6 +ViaDiameter3=1.5 +ViaDrill3=0.8 +ViaDiameter4=2.5 +ViaDrill4=1 +dPairWidth1=0.2 +dPairGap1=0.25 +dPairViaGap1=0.25 +SilkLineWidth=0.15 +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.15 +CourtyardLineWidth=0.05 +OthersLineWidth=0.15 +OthersTextSizeV=1 +OthersTextSizeH=1 +OthersTextSizeThickness=0.15 +OthersTextItalic=0 +OthersTextUpright=1 +SolderMaskClearance=0.2 +SolderMaskMinWidth=0.25 +SolderPasteClearance=0 +SolderPasteRatio=-0 +[pcbnew/Netclasses] +[pcbnew/Netclasses/1] +Name=power +Clearance=0.3 +TrackWidth=1 +ViaDiameter=2.5 +ViaDrill=0.8 +uViaDiameter=0.3 +uViaDrill=0.1 +dPairWidth=0.2 +dPairGap=0.25 +dPairViaGap=0.25 +[pcbnew/Netclasses/2] +Name=wide +Clearance=0.5 +TrackWidth=2 +ViaDiameter=2.5 +ViaDrill=0.8 +uViaDiameter=0.3 +uViaDrill=0.1 +dPairWidth=0.2 +dPairGap=0.25 +dPairViaGap=0.25 diff --git a/F0-nolib/Servo/kicad/Servo_control.sch b/F0-nolib/Servo/kicad/Servo_control.sch new file mode 100644 index 0000000..d424a61 --- /dev/null +++ b/F0-nolib/Servo/kicad/Servo_control.sch @@ -0,0 +1,1539 @@ +EESchema Schematic File Version 4 +LIBS:Servo_control-cache +EELAYER 26 0 +EELAYER END +$Descr A4 11693 8268 +encoding utf-8 +Sheet 1 1 +Title "" +Date "" +Rev "" +Comp "" +Comment1 "" +Comment2 "" +Comment3 "" +Comment4 "" +$EndDescr +$Comp +L Servo_control-rescue:GND-Chiller_control-rescue #PWR03 +U 1 1 58C453C7 +P 1200 1475 +F 0 "#PWR03" H 1200 1225 50 0001 C CNN +F 1 "GND" H 1200 1325 50 0000 C CNN +F 2 "" H 1200 1475 50 0000 C CNN +F 3 "" H 1200 1475 50 0000 C CNN + 1 1200 1475 + 1 0 0 -1 +$EndComp +$Comp +L Servo_control-rescue:CP-Chiller_control-rescue C4 +U 1 1 58C454F6 +P 1600 1275 +F 0 "C4" H 1625 1375 50 0000 L CNN +F 1 "47u" H 1625 1175 50 0000 L CNN +F 2 "Capacitor_Tantalum_SMD:CP_EIA-3216-18_Kemet-A_Pad1.53x1.40mm_HandSolder" H 1638 1125 50 0001 C CNN +F 3 "" H 1600 1275 50 0000 C CNN + 1 1600 1275 + 1 0 0 -1 +$EndComp +$Comp +L Servo_control-rescue:+3.3V-Chiller_control-rescue #PWR07 +U 1 1 58C455CB +P 1800 975 +F 0 "#PWR07" H 1800 825 50 0001 C CNN +F 1 "+3.3V" H 1800 1115 50 0000 C CNN +F 2 "" H 1800 975 50 0000 C CNN +F 3 "" H 1800 975 50 0000 C CNN + 1 1800 975 + 1 0 0 -1 +$EndComp +Text Notes 600 700 0 100 ~ 0 +MCU power source +Text Notes 650 1950 0 100 ~ 0 +Bootloader init +Text Label 950 3050 2 60 ~ 0 +NRST +Text Label 950 2100 0 60 ~ 0 +BOOT0 +$Comp +L Servo_control-rescue:C-Chiller_control-rescue C3 +U 1 1 590D4150 +P 1550 2400 +F 0 "C3" H 1575 2500 50 0000 L CNN +F 1 "0.1" H 1575 2300 50 0000 L CNN +F 2 "Capacitor_SMD:C_0603_1608Metric_Pad0.84x1.00mm_HandSolder" H 1588 2250 50 0001 C CNN +F 3 "" H 1550 2400 50 0000 C CNN + 1 1550 2400 + 1 0 0 -1 +$EndComp +$Comp +L Servo_control-rescue:C-Chiller_control-rescue C2 +U 1 1 590D4832 +P 1500 3250 +F 0 "C2" H 1525 3350 50 0000 L CNN +F 1 "0.1" H 1525 3150 50 0000 L CNN +F 2 "Capacitor_SMD:C_0603_1608Metric_Pad0.84x1.00mm_HandSolder" H 1538 3100 50 0001 C CNN +F 3 "" H 1500 3250 50 0000 C CNN + 1 1500 3250 + 1 0 0 -1 +$EndComp +$Comp +L Servo_control-rescue:SW_Push-Chiller_control-rescue SW2 +U 1 1 5909F6B6 +P 1250 2400 +F 0 "SW2" H 1300 2500 50 0000 L CNN +F 1 "Boot" H 1250 2340 50 0000 C CNN +F 2 "Button_Switch_SMD:SW_SPST_FSMSM" H 1250 2600 50 0001 C CNN +F 3 "" H 1250 2600 50 0000 C CNN + 1 1250 2400 + 0 1 1 0 +$EndComp +$Comp +L Servo_control-rescue:SW_Push-Chiller_control-rescue SW1 +U 1 1 590A0134 +P 1200 3250 +F 0 "SW1" H 1250 3350 50 0000 L CNN +F 1 "Reset" H 1200 3190 50 0000 C CNN +F 2 "Button_Switch_SMD:SW_SPST_FSMSM" H 1200 3450 50 0001 C CNN +F 3 "" H 1200 3450 50 0000 C CNN + 1 1200 3250 + 0 1 1 0 +$EndComp +$Comp +L Servo_control-rescue:GND-Chiller_control-rescue #PWR02 +U 1 1 590A03AF +P 950 2600 +F 0 "#PWR02" H 950 2350 50 0001 C CNN +F 1 "GND" H 950 2450 50 0000 C CNN +F 2 "" H 950 2600 50 0000 C CNN +F 3 "" H 950 2600 50 0000 C CNN + 1 950 2600 + 1 0 0 -1 +$EndComp +$Comp +L Servo_control-rescue:GND-Chiller_control-rescue #PWR05 +U 1 1 590A509B +P 1350 3500 +F 0 "#PWR05" H 1350 3250 50 0001 C CNN +F 1 "GND" H 1350 3350 50 0000 C CNN +F 2 "" H 1350 3500 50 0000 C CNN +F 3 "" H 1350 3500 50 0000 C CNN + 1 1350 3500 + 1 0 0 -1 +$EndComp +$Comp +L Servo_control-rescue:C-Chiller_control-rescue C1 +U 1 1 5A178C32 +P 750 1125 +F 0 "C1" H 775 1225 50 0000 L CNN +F 1 "0.1" H 775 1025 50 0000 L CNN +F 2 "Capacitor_SMD:C_0603_1608Metric_Pad0.84x1.00mm_HandSolder" H 788 975 50 0001 C CNN +F 3 "" H 750 1125 50 0000 C CNN + 1 750 1125 + 1 0 0 -1 +$EndComp +$Comp +L Servo_control-rescue:STM32F030F4Px-Chiller_control-rescue U3 +U 1 1 5A189F52 +P 8775 2275 +F 0 "U3" H 7175 3200 50 0000 L BNN +F 1 "STM32F030F4Px" H 10375 3200 50 0000 R BNN +F 2 "Package_SSOP:TSSOP-20_4.4x6.5mm_P0.65mm" H 10375 3150 50 0001 R TNN +F 3 "" H 8775 2275 50 0001 C CNN + 1 8775 2275 + 1 0 0 -1 +$EndComp +$Comp +L Servo_control-rescue:C-Chiller_control-rescue C13 +U 1 1 5A1AB970 +P 8075 1025 +F 0 "C13" H 8100 1125 50 0000 L CNN +F 1 "1u" H 8100 925 50 0000 L CNN +F 2 "Capacitor_SMD:C_0805_2012Metric_Pad1.15x1.50mm_HandSolder" H 8113 875 50 0001 C CNN +F 3 "" H 8075 1025 50 0000 C CNN + 1 8075 1025 + 1 0 0 -1 +$EndComp +$Comp +L Servo_control-rescue:GND-Chiller_control-rescue #PWR025 +U 1 1 5A1B3C28 +P 8075 1175 +F 0 "#PWR025" H 8075 925 50 0001 C CNN +F 1 "GND" H 8075 1025 50 0000 C CNN +F 2 "" H 8075 1175 50 0000 C CNN +F 3 "" H 8075 1175 50 0000 C CNN + 1 8075 1175 + 1 0 0 -1 +$EndComp +$Comp +L Servo_control-rescue:GND-Chiller_control-rescue #PWR026 +U 1 1 5A1B4A11 +P 8775 3225 +F 0 "#PWR026" H 8775 2975 50 0001 C CNN +F 1 "GND" H 8775 3075 50 0000 C CNN +F 2 "" H 8775 3225 50 0000 C CNN +F 3 "" H 8775 3225 50 0000 C CNN + 1 8775 3225 + 1 0 0 -1 +$EndComp +$Comp +L Servo_control-rescue:+3.3V-Chiller_control-rescue #PWR024 +U 1 1 5A1B5A75 +P 8075 825 +F 0 "#PWR024" H 8075 675 50 0001 C CNN +F 1 "+3.3V" H 8075 965 50 0000 C CNN +F 2 "" H 8075 825 50 0000 C CNN +F 3 "" H 8075 825 50 0000 C CNN + 1 8075 825 + 1 0 0 -1 +$EndComp +$Comp +L Servo_control-rescue:+3.3V-Chiller_control-rescue #PWR04 +U 1 1 590A1E6C +P 1250 2650 +F 0 "#PWR04" H 1250 2500 50 0001 C CNN +F 1 "+3.3V" H 1250 2790 50 0000 C CNN +F 2 "" H 1250 2650 50 0000 C CNN +F 3 "" H 1250 2650 50 0000 C CNN + 1 1250 2650 + -1 0 0 1 +$EndComp +$Comp +L Servo_control-rescue:GND-Chiller_control-rescue #PWR06 +U 1 1 5A283BCF +P 1550 2600 +F 0 "#PWR06" H 1550 2350 50 0001 C CNN +F 1 "GND" H 1550 2450 50 0000 C CNN +F 2 "" H 1550 2600 50 0000 C CNN +F 3 "" H 1550 2600 50 0000 C CNN + 1 1550 2600 + 1 0 0 -1 +$EndComp +$Comp +L Servo_control-rescue:LM1117-3.3-Chiller_control-rescue U1 +U 1 1 5A2588E7 +P 1200 975 +F 0 "U1" H 1200 1175 50 0000 C CNN +F 1 "LM1117-3.3" H 950 1100 50 0000 L CNN +F 2 "Package_TO_SOT_SMD:SOT-223" H 1200 975 50 0001 C CNN +F 3 "" H 1200 975 50 0001 C CNN + 1 1200 975 + 1 0 0 -1 +$EndComp +$Comp +L Servo_control-rescue:C-Chiller_control-rescue C5 +U 1 1 5BEE1D09 +P 1850 1225 +F 0 "C5" H 1875 1325 50 0000 L CNN +F 1 "0.1" H 1875 1125 50 0000 L CNN +F 2 "Capacitor_SMD:C_0603_1608Metric_Pad0.84x1.00mm_HandSolder" H 1888 1075 50 0001 C CNN +F 3 "" H 1850 1225 50 0000 C CNN + 1 1850 1225 + 1 0 0 -1 +$EndComp +Text Label 7075 1875 2 60 ~ 0 +BOOT0 +Text Label 7075 1675 2 60 ~ 0 +NRST +Text Label 10475 2475 0 60 ~ 0 +USART_Tx +Text Label 10475 2575 0 60 ~ 0 +USART_Rx +$Comp +L Servo_control-rescue:L-Chiller_control-rescue L1 +U 1 1 5BEE7949 +P 8775 1025 +F 0 "L1" V 8725 1025 50 0000 C CNN +F 1 "BMBA 0.1mH" V 8850 1025 50 0000 C CNN +F 2 "Inductor_SMD:L_0805_2012Metric_Pad1.15x1.50mm_HandSolder" H 8775 1025 50 0001 C CNN +F 3 "" H 8775 1025 50 0001 C CNN + 1 8775 1025 + 1 0 0 -1 +$EndComp +$Comp +L Servo_control-rescue:C-Chiller_control-rescue C14 +U 1 1 5BEE8065 +P 9450 1125 +F 0 "C14" H 9475 1225 50 0000 L CNN +F 1 "10u" H 9475 1025 50 0000 L CNN +F 2 "Capacitor_SMD:C_1206_3216Metric_Pad1.24x1.80mm_HandSolder" H 9488 975 50 0001 C CNN +F 3 "" H 9450 1125 50 0001 C CNN + 1 9450 1125 + 1 0 0 -1 +$EndComp +$Comp +L Servo_control-rescue:GND-Chiller_control-rescue #PWR028 +U 1 1 5BEE83C2 +P 9675 975 +F 0 "#PWR028" H 9675 725 50 0001 C CNN +F 1 "GND" H 9675 825 50 0000 C CNN +F 2 "" H 9675 975 50 0000 C CNN +F 3 "" H 9675 975 50 0000 C CNN + 1 9675 975 + 1 0 0 -1 +$EndComp +Text Label 10475 1675 0 60 ~ 0 +ADC0 +Text Label 10475 1775 0 60 ~ 0 +ADC1 +Text Label 10475 1875 0 60 ~ 0 +ADC2 +Text Label 10475 1975 0 60 ~ 0 +ADC3 +Text Label 10475 2275 0 60 ~ 0 +TIM3_CH1 +Text Notes 6600 2775 2 60 ~ 0 +PWM +Text Notes 11150 2275 2 60 ~ 0 +PWM +Text Notes 11150 2375 2 60 ~ 0 +PWM +Text Label 7075 2475 2 60 ~ 0 +DigOut0 +Text Notes 6700 2450 2 60 ~ 0 +Alarm +Text Notes 9575 3725 2 60 ~ 0 +PWM +$Comp +L Servo_control-rescue:R-Chiller_control-rescue R15 +U 1 1 5BEEBD18 +P 10075 4475 +F 0 "R15" V 10155 4475 50 0000 C CNN +F 1 "10k" V 10075 4475 50 0000 C CNN +F 2 "Resistor_SMD:R_0805_2012Metric_Pad1.15x1.50mm_HandSolder" V 10005 4475 50 0001 C CNN +F 3 "" H 10075 4475 50 0001 C CNN + 1 10075 4475 + 0 1 1 0 +$EndComp +$Comp +L Servo_control-rescue:R-Chiller_control-rescue R12 +U 1 1 5BEEBD1E +P 9775 4275 +F 0 "R12" V 9855 4275 50 0000 C CNN +F 1 "510" V 9775 4275 50 0000 C CNN +F 2 "Resistor_SMD:R_0805_2012Metric_Pad1.15x1.50mm_HandSolder" V 9705 4275 50 0001 C CNN +F 3 "" H 9775 4275 50 0001 C CNN + 1 9775 4275 + 0 1 1 0 +$EndComp +$Comp +L Servo_control-rescue:Q_NMOS_GSD-Chiller_control-rescue Q3 +U 1 1 5BEEBD24 +P 10125 4275 +F 0 "Q3" H 10325 4325 50 0000 L CNN +F 1 "2N7002" H 10325 4225 50 0000 L CNN +F 2 "Package_TO_SOT_SMD:SOT-23" H 10325 4375 50 0001 C CNN +F 3 "" H 10125 4275 50 0001 C CNN + 1 10125 4275 + 1 0 0 -1 +$EndComp +$Comp +L Servo_control-rescue:GND-Chiller_control-rescue #PWR029 +U 1 1 5BEEBD2B +P 10225 4500 +F 0 "#PWR029" H 10225 4250 50 0001 C CNN +F 1 "GND" H 10225 4350 50 0000 C CNN +F 2 "" H 10225 4500 50 0000 C CNN +F 3 "" H 10225 4500 50 0000 C CNN + 1 10225 4500 + 1 0 0 -1 +$EndComp +$Comp +L Servo_control-rescue:GND-Chiller_control-rescue #PWR030 +U 1 1 5BEEC947 +P 10275 5375 +F 0 "#PWR030" H 10275 5125 50 0001 C CNN +F 1 "GND" H 10275 5225 50 0000 C CNN +F 2 "" H 10275 5375 50 0000 C CNN +F 3 "" H 10275 5375 50 0000 C CNN + 1 10275 5375 + 1 0 0 -1 +$EndComp +$Comp +L Servo_control-rescue:GND-Chiller_control-rescue #PWR031 +U 1 1 5BEED56A +P 10350 6125 +F 0 "#PWR031" H 10350 5875 50 0001 C CNN +F 1 "GND" H 10350 5975 50 0000 C CNN +F 2 "" H 10350 6125 50 0000 C CNN +F 3 "" H 10350 6125 50 0000 C CNN + 1 10350 6125 + 1 0 0 -1 +$EndComp +$Comp +L Servo_control-rescue:+3.3VADC-Chiller_control-rescue #PWR027 +U 1 1 5BEF64D3 +P 9100 1275 +F 0 "#PWR027" H 9250 1225 50 0001 C CNN +F 1 "+3.3VADC" H 9100 1375 50 0000 C CNN +F 2 "" H 9100 1275 50 0001 C CNN +F 3 "" H 9100 1275 50 0001 C CNN + 1 9100 1275 + 1 0 0 -1 +$EndComp +$Comp +L Servo_control-rescue:PWR_FLAG-Chiller_control-rescue #FLG01 +U 1 1 5BF0C65D +P 9325 1275 +F 0 "#FLG01" H 9325 1370 50 0001 C CNN +F 1 "PWR_FLAG" H 9325 1455 50 0001 C CNN +F 2 "" H 9325 1275 50 0000 C CNN +F 3 "" H 9325 1275 50 0000 C CNN + 1 9325 1275 + 1 0 0 -1 +$EndComp +Wire Wire Line + 950 2600 950 2550 +Wire Wire Line + 950 2100 950 2200 +Wire Wire Line + 1550 2200 1550 2250 +Wire Wire Line + 950 2200 1250 2200 +Connection ~ 1250 2200 +Connection ~ 950 2200 +Wire Wire Line + 1550 2600 1550 2550 +Wire Wire Line + 1500 3050 1500 3100 +Connection ~ 1200 3050 +Wire Wire Line + 1200 3450 1350 3450 +Wire Wire Line + 1500 3450 1500 3400 +Wire Wire Line + 1350 3500 1350 3450 +Connection ~ 1350 3450 +Wire Notes Line + 550 1800 550 3750 +Wire Notes Line + 550 3750 1900 3750 +Wire Notes Line + 1900 3750 1900 1800 +Wire Notes Line + 1900 1800 550 1800 +Wire Wire Line + 1500 975 1600 975 +Connection ~ 750 975 +Wire Wire Line + 8675 875 8675 1275 +Wire Wire Line + 8775 1175 8775 1275 +Wire Wire Line + 8775 3225 8775 3175 +Wire Wire Line + 8075 825 8075 875 +Wire Wire Line + 1600 975 1600 1125 +Connection ~ 1600 975 +Wire Wire Line + 8075 875 8675 875 +Wire Wire Line + 1200 1275 1200 1425 +Wire Wire Line + 750 1425 1200 1425 +Connection ~ 1200 1425 +Wire Wire Line + 750 1275 750 1425 +Connection ~ 8075 875 +Wire Wire Line + 1250 2650 1250 2600 +Wire Wire Line + 950 3050 1200 3050 +Wire Wire Line + 1850 1425 1850 1375 +Connection ~ 1600 1425 +Wire Wire Line + 1850 975 1850 1075 +Connection ~ 1800 975 +Connection ~ 8675 875 +Wire Wire Line + 9675 975 9450 975 +Wire Wire Line + 8775 1275 9100 1275 +Connection ~ 8775 1275 +Connection ~ 10225 4475 +Wire Wire Line + 10225 4500 10225 4475 +Wire Wire Line + 10275 5375 10275 5350 +Wire Wire Line + 10350 6125 10350 6100 +Connection ~ 9100 1275 +Connection ~ 9325 1275 +Wire Notes Line + 9075 3575 11050 3575 +Wire Notes Line + 11050 3575 11050 6350 +Wire Notes Line + 11050 6350 9075 6350 +Wire Notes Line + 9075 6350 9075 3575 +Wire Wire Line + 1250 2200 1550 2200 +Wire Wire Line + 950 2200 950 2250 +Wire Wire Line + 1200 3050 1500 3050 +Wire Wire Line + 1350 3450 1500 3450 +Wire Wire Line + 750 975 900 975 +Wire Wire Line + 1600 975 1800 975 +Wire Wire Line + 1200 1425 1200 1475 +Wire Wire Line + 1200 1425 1600 1425 +Wire Wire Line + 1600 1425 1850 1425 +Wire Wire Line + 1800 975 1850 975 +Wire Wire Line + 8675 875 8775 875 +Wire Wire Line + 9100 1275 9325 1275 +Wire Wire Line + 9325 1275 9450 1275 +Wire Notes Line + 2125 550 2125 1400 +Wire Wire Line + 3125 1175 3125 1150 +$Comp +L Servo_control-rescue:GND-Chiller_control-rescue #PWR016 +U 1 1 5BEE8828 +P 3125 1175 +F 0 "#PWR016" H 3125 925 50 0001 C CNN +F 1 "GND" H 3125 1025 50 0000 C CNN +F 2 "" H 3125 1175 50 0000 C CNN +F 3 "" H 3125 1175 50 0000 C CNN + 1 3125 1175 + 1 0 0 -1 +$EndComp +Text Notes 2950 675 2 60 ~ 0 +Alarm Buzzer +$Comp +L Servo_control-rescue:Q_NMOS_GSD-Chiller_control-rescue Q2 +U 1 1 5BEEB585 +P 4900 1075 +F 0 "Q2" H 5100 1125 50 0000 L CNN +F 1 "SI2300" H 5100 1025 50 0000 L CNN +F 2 "Package_TO_SOT_SMD:SOT-23" H 5100 1175 50 0001 C CNN +F 3 "" H 4900 1075 50 0001 C CNN + 1 4900 1075 + 1 0 0 -1 +$EndComp +Text Label 2525 950 2 60 ~ 0 +DigOut0 +$Comp +L Servo_control-rescue:+5V-power #PWR01 +U 1 1 5C56CC29 +P 750 975 +F 0 "#PWR01" H 750 825 50 0001 C CNN +F 1 "+5V" H 765 1148 50 0000 C CNN +F 2 "" H 750 975 50 0001 C CNN +F 3 "" H 750 975 50 0001 C CNN + 1 750 975 + 1 0 0 -1 +$EndComp +Wire Wire Line + 9625 4275 9625 4475 +Wire Wire Line + 9625 4475 9925 4475 +Wire Wire Line + 9675 5150 9675 5350 +Wire Wire Line + 9675 5350 9975 5350 +Wire Wire Line + 9750 5900 9750 6100 +Wire Wire Line + 9750 6100 10050 6100 +Wire Wire Line + 2525 1150 2825 1150 +Wire Wire Line + 2525 950 2525 1150 +$Comp +L Device:Buzzer BZ1 +U 1 1 5C83133C +P 3650 850 +F 0 "BZ1" H 3725 1050 50 0000 C CNN +F 1 "Buzzer" H 3654 616 50 0000 C CNN +F 2 "Buzzer_Beeper:Buzzer_12x9.5RM7.6" V 3625 950 50 0001 C CNN +F 3 "~" V 3625 950 50 0001 C CNN + 1 3650 850 + 1 0 0 1 +$EndComp +Wire Wire Line + 3125 750 3550 750 +$Comp +L Servo_control-rescue:+3.3V-Chiller_control-rescue #PWR017 +U 1 1 5C84A91E +P 3550 1075 +F 0 "#PWR017" H 3550 925 50 0001 C CNN +F 1 "+3.3V" H 3550 1215 50 0000 C CNN +F 2 "" H 3550 1075 50 0000 C CNN +F 3 "" H 3550 1075 50 0000 C CNN + 1 3550 1075 + -1 0 0 1 +$EndComp +Wire Wire Line + 3550 950 3550 1075 +Wire Notes Line + 3900 1400 3900 550 +Wire Notes Line + 2125 550 3900 550 +Wire Notes Line + 2125 1400 3900 1400 +$Comp +L Servo_control-rescue:Q_NMOS_GSD-Chiller_control-rescue Q4 +U 1 1 5C8882AE +P 10175 5150 +F 0 "Q4" H 10375 5200 50 0000 L CNN +F 1 "2N7002" H 10375 5100 50 0000 L CNN +F 2 "Package_TO_SOT_SMD:SOT-23" H 10375 5250 50 0001 C CNN +F 3 "" H 10175 5150 50 0001 C CNN + 1 10175 5150 + 1 0 0 -1 +$EndComp +$Comp +L Servo_control-rescue:Q_NMOS_GSD-Chiller_control-rescue Q5 +U 1 1 5C888320 +P 10250 5900 +F 0 "Q5" H 10450 5950 50 0000 L CNN +F 1 "2N7002" H 10450 5850 50 0000 L CNN +F 2 "Package_TO_SOT_SMD:SOT-23" H 10450 6000 50 0001 C CNN +F 3 "" H 10250 5900 50 0001 C CNN + 1 10250 5900 + 1 0 0 -1 +$EndComp +$Comp +L Connector_Generic:Conn_01x03 J7 +U 1 1 5C88A162 +P 10850 3975 +F 0 "J7" H 10825 4200 50 0000 L CNN +F 1 "Servo1" H 10750 3775 50 0000 L CNN +F 2 "Connector_PinHeader_2.54mm:PinHeader_1x03_P2.54mm_Vertical" H 10850 3975 50 0001 C CNN +F 3 "~" H 10850 3975 50 0001 C CNN + 1 10850 3975 + 1 0 0 -1 +$EndComp +$Comp +L Connector_Generic:Conn_01x03 J8 +U 1 1 5C83F212 +P 10850 4850 +F 0 "J8" H 10825 5075 50 0000 L CNN +F 1 "Servo2" H 10750 4650 50 0000 L CNN +F 2 "Connector_PinHeader_2.54mm:PinHeader_1x03_P2.54mm_Vertical" H 10850 4850 50 0001 C CNN +F 3 "~" H 10850 4850 50 0001 C CNN + 1 10850 4850 + 1 0 0 -1 +$EndComp +$Comp +L Connector_Generic:Conn_01x03 J9 +U 1 1 5C83F4E9 +P 10850 5600 +F 0 "J9" H 10825 5825 50 0000 L CNN +F 1 "Servo3" H 10750 5400 50 0000 L CNN +F 2 "Connector_PinHeader_2.54mm:PinHeader_1x03_P2.54mm_Vertical" H 10850 5600 50 0001 C CNN +F 3 "~" H 10850 5600 50 0001 C CNN + 1 10850 5600 + 1 0 0 -1 +$EndComp +Wire Wire Line + 10350 5700 10650 5700 +Wire Wire Line + 10275 4950 10650 4950 +Wire Wire Line + 10225 4075 10650 4075 +$Comp +L Servo_control-rescue:GND-Chiller_control-rescue #PWR035 +U 1 1 5C84362B +P 10650 3825 +F 0 "#PWR035" H 10650 3575 50 0001 C CNN +F 1 "GND" H 10650 3675 50 0000 C CNN +F 2 "" H 10650 3825 50 0000 C CNN +F 3 "" H 10650 3825 50 0000 C CNN + 1 10650 3825 + -1 0 0 1 +$EndComp +Wire Wire Line + 10650 3875 10650 3825 +$Comp +L Servo_control-rescue:GND-Chiller_control-rescue #PWR036 +U 1 1 5C8444DD +P 10650 4700 +F 0 "#PWR036" H 10650 4450 50 0001 C CNN +F 1 "GND" H 10650 4550 50 0000 C CNN +F 2 "" H 10650 4700 50 0000 C CNN +F 3 "" H 10650 4700 50 0000 C CNN + 1 10650 4700 + -1 0 0 1 +$EndComp +Wire Wire Line + 10650 4700 10650 4750 +$Comp +L Servo_control-rescue:GND-Chiller_control-rescue #PWR037 +U 1 1 5C8453AD +P 10650 5450 +F 0 "#PWR037" H 10650 5200 50 0001 C CNN +F 1 "GND" H 10650 5300 50 0000 C CNN +F 2 "" H 10650 5450 50 0000 C CNN +F 3 "" H 10650 5450 50 0000 C CNN + 1 10650 5450 + -1 0 0 1 +$EndComp +Wire Wire Line + 10650 5450 10650 5500 +$Comp +L Servo_control-rescue:+5V-power #PWR032 +U 1 1 5C846BFE +P 10425 3975 +F 0 "#PWR032" H 10425 3825 50 0001 C CNN +F 1 "+5V" H 10440 4148 50 0000 C CNN +F 2 "" H 10425 3975 50 0001 C CNN +F 3 "" H 10425 3975 50 0001 C CNN + 1 10425 3975 + 1 0 0 -1 +$EndComp +$Comp +L Servo_control-rescue:+5V-power #PWR033 +U 1 1 5C847311 +P 10425 4850 +F 0 "#PWR033" H 10425 4700 50 0001 C CNN +F 1 "+5V" H 10440 5023 50 0000 C CNN +F 2 "" H 10425 4850 50 0001 C CNN +F 3 "" H 10425 4850 50 0001 C CNN + 1 10425 4850 + 1 0 0 -1 +$EndComp +$Comp +L Servo_control-rescue:+5V-power #PWR034 +U 1 1 5C84751A +P 10450 5600 +F 0 "#PWR034" H 10450 5450 50 0001 C CNN +F 1 "+5V" H 10465 5773 50 0000 C CNN +F 2 "" H 10450 5600 50 0001 C CNN +F 3 "" H 10450 5600 50 0001 C CNN + 1 10450 5600 + 1 0 0 -1 +$EndComp +Wire Wire Line + 10450 5600 10650 5600 +Wire Wire Line + 10425 4850 10650 4850 +Wire Wire Line + 10425 3975 10650 3975 +$Comp +L Servo_control-rescue:R-Chiller_control-rescue R13 +U 1 1 5C84B03F +P 9825 5150 +F 0 "R13" V 9905 5150 50 0000 C CNN +F 1 "510" V 9825 5150 50 0000 C CNN +F 2 "Resistor_SMD:R_0805_2012Metric_Pad1.15x1.50mm_HandSolder" V 9755 5150 50 0001 C CNN +F 3 "" H 9825 5150 50 0001 C CNN + 1 9825 5150 + 0 1 1 0 +$EndComp +$Comp +L Servo_control-rescue:R-Chiller_control-rescue R14 +U 1 1 5C84B0D1 +P 9900 5900 +F 0 "R14" V 9980 5900 50 0000 C CNN +F 1 "510" V 9900 5900 50 0000 C CNN +F 2 "Resistor_SMD:R_0805_2012Metric_Pad1.15x1.50mm_HandSolder" V 9830 5900 50 0001 C CNN +F 3 "" H 9900 5900 50 0001 C CNN + 1 9900 5900 + 0 1 1 0 +$EndComp +$Comp +L Servo_control-rescue:R-Chiller_control-rescue R16 +U 1 1 5C84B278 +P 10125 5350 +F 0 "R16" V 10205 5350 50 0000 C CNN +F 1 "10k" V 10125 5350 50 0000 C CNN +F 2 "Resistor_SMD:R_0805_2012Metric_Pad1.15x1.50mm_HandSolder" V 10055 5350 50 0001 C CNN +F 3 "" H 10125 5350 50 0001 C CNN + 1 10125 5350 + 0 1 1 0 +$EndComp +Connection ~ 10275 5350 +$Comp +L Servo_control-rescue:R-Chiller_control-rescue R17 +U 1 1 5C84B3BD +P 10200 6100 +F 0 "R17" V 10280 6100 50 0000 C CNN +F 1 "10k" V 10200 6100 50 0000 C CNN +F 2 "Resistor_SMD:R_0805_2012Metric_Pad1.15x1.50mm_HandSolder" V 10130 6100 50 0001 C CNN +F 3 "" H 10200 6100 50 0001 C CNN + 1 10200 6100 + 0 1 1 0 +$EndComp +Connection ~ 10350 6100 +Text Label 10475 2375 0 60 ~ 0 +TIM3_CH2 +Text Label 9625 4275 2 60 ~ 0 +TIM3_CH1 +Text Label 9675 5150 2 60 ~ 0 +TIM3_CH2 +Text Label 7075 2775 2 60 ~ 0 +TIM3_CH4 +Text Label 9750 5900 2 60 ~ 0 +TIM3_CH4 +Text Label 3650 2325 0 60 ~ 0 +ADC0 +Text Label 3650 2475 0 60 ~ 0 +ADC1 +Text Label 3650 2625 0 60 ~ 0 +ADC2 +Text Label 3650 2775 0 60 ~ 0 +ADC3 +$Comp +L Power_Protection:SP0504BAHT D2 +U 1 1 5C8580E1 +P 3050 2075 +F 0 "D2" H 2845 2029 50 0000 R CNN +F 1 "SP0504BAHT" H 2845 2120 50 0000 R CNN +F 2 "Package_TO_SOT_SMD:SOT-23-5" H 3350 2025 50 0001 L CNN +F 3 "http://www.littelfuse.com/~/media/files/littelfuse/technical%20resources/documents/data%20sheets/sp05xxba.pdf" H 3175 2200 50 0001 C CNN + 1 3050 2075 + -1 0 0 1 +$EndComp +$Comp +L Connector_Generic:Conn_01x06 J2 +U 1 1 5C85A71E +P 2100 2600 +F 0 "J2" H 2020 2075 50 0000 C CNN +F 1 "ADC_in" H 2020 2166 50 0000 C CNN +F 2 "Connector_PinHeader_2.54mm:PinHeader_1x06_P2.54mm_Vertical" H 2100 2600 50 0001 C CNN +F 3 "~" H 2100 2600 50 0001 C CNN + 1 2100 2600 + -1 0 0 1 +$EndComp +$Comp +L Device:R R3 +U 1 1 5C85BD06 +P 2550 2475 +F 0 "R3" V 2475 2475 50 0000 C CNN +F 1 "220" V 2550 2475 50 0000 C CNN +F 2 "Resistor_SMD:R_0805_2012Metric_Pad1.15x1.50mm_HandSolder" V 2480 2475 50 0001 C CNN +F 3 "" H 2550 2475 50 0001 C CNN + 1 2550 2475 + 0 1 1 0 +$EndComp +$Comp +L Device:R R4 +U 1 1 5C85C1A1 +P 2550 2625 +F 0 "R4" V 2475 2625 50 0000 C CNN +F 1 "220" V 2550 2625 50 0000 C CNN +F 2 "Resistor_SMD:R_0805_2012Metric_Pad1.15x1.50mm_HandSolder" V 2480 2625 50 0001 C CNN +F 3 "" H 2550 2625 50 0001 C CNN + 1 2550 2625 + 0 1 1 0 +$EndComp +$Comp +L Device:R R5 +U 1 1 5C85C24A +P 2550 2775 +F 0 "R5" V 2475 2775 50 0000 C CNN +F 1 "220" V 2550 2775 50 0000 C CNN +F 2 "Resistor_SMD:R_0805_2012Metric_Pad1.15x1.50mm_HandSolder" V 2480 2775 50 0001 C CNN +F 3 "" H 2550 2775 50 0001 C CNN + 1 2550 2775 + 0 1 1 0 +$EndComp +$Comp +L Device:R R2 +U 1 1 5C85C2A8 +P 2550 2325 +F 0 "R2" V 2475 2325 50 0000 C CNN +F 1 "220" V 2550 2325 50 0000 C CNN +F 2 "Resistor_SMD:R_0805_2012Metric_Pad1.15x1.50mm_HandSolder" V 2480 2325 50 0001 C CNN +F 3 "" H 2550 2325 50 0001 C CNN + 1 2550 2325 + 0 1 1 0 +$EndComp +Wire Wire Line + 2300 2700 2300 2775 +Wire Wire Line + 2300 2775 2400 2775 +Wire Wire Line + 2300 2600 2400 2600 +Wire Wire Line + 2400 2600 2400 2625 +Wire Wire Line + 2300 2500 2400 2500 +Wire Wire Line + 2400 2500 2400 2475 +Wire Wire Line + 2300 2400 2400 2400 +Wire Wire Line + 2400 2400 2400 2325 +$Comp +L Servo_control-rescue:C-Chiller_control-rescue C8 +U 1 1 5C86267B +P 2775 2975 +F 0 "C8" H 2800 3075 50 0000 L CNN +F 1 "0.1" H 2800 2875 50 0000 L CNN +F 2 "Capacitor_SMD:C_0603_1608Metric_Pad0.84x1.00mm_HandSolder" H 2813 2825 50 0001 C CNN +F 3 "" H 2775 2975 50 0000 C CNN + 1 2775 2975 + 1 0 0 -1 +$EndComp +$Comp +L Servo_control-rescue:C-Chiller_control-rescue C10 +U 1 1 5C862E72 +P 2975 2975 +F 0 "C10" H 3000 3075 50 0000 L CNN +F 1 "0.1" H 3000 2875 50 0000 L CNN +F 2 "Capacitor_SMD:C_0603_1608Metric_Pad0.84x1.00mm_HandSolder" H 3013 2825 50 0001 C CNN +F 3 "" H 2975 2975 50 0000 C CNN + 1 2975 2975 + 1 0 0 -1 +$EndComp +$Comp +L Servo_control-rescue:C-Chiller_control-rescue C11 +U 1 1 5C862EDE +P 3175 2975 +F 0 "C11" H 3200 3075 50 0000 L CNN +F 1 "0.1" H 3200 2875 50 0000 L CNN +F 2 "Capacitor_SMD:C_0603_1608Metric_Pad0.84x1.00mm_HandSolder" H 3213 2825 50 0001 C CNN +F 3 "" H 3175 2975 50 0000 C CNN + 1 3175 2975 + 1 0 0 -1 +$EndComp +$Comp +L Servo_control-rescue:C-Chiller_control-rescue C12 +U 1 1 5C864D09 +P 3375 2975 +F 0 "C12" H 3400 3075 50 0000 L CNN +F 1 "0.1" H 3400 2875 50 0000 L CNN +F 2 "Capacitor_SMD:C_0603_1608Metric_Pad0.84x1.00mm_HandSolder" H 3413 2825 50 0001 C CNN +F 3 "" H 3375 2975 50 0000 C CNN + 1 3375 2975 + 1 0 0 -1 +$EndComp +Wire Wire Line + 3375 3125 3175 3125 +Wire Wire Line + 3175 3125 2975 3125 +Connection ~ 3175 3125 +Wire Wire Line + 2975 3125 2775 3125 +Connection ~ 2975 3125 +$Comp +L Servo_control-rescue:GND-Chiller_control-rescue #PWR014 +U 1 1 5C869325 +P 2725 3125 +F 0 "#PWR014" H 2725 2875 50 0001 C CNN +F 1 "GND" H 2725 2975 50 0000 C CNN +F 2 "" H 2725 3125 50 0000 C CNN +F 3 "" H 2725 3125 50 0000 C CNN + 1 2725 3125 + 1 0 0 -1 +$EndComp +Wire Wire Line + 2725 3125 2775 3125 +Connection ~ 2775 3125 +$Comp +L Servo_control-rescue:GND-Chiller_control-rescue #PWR013 +U 1 1 5C86AADA +P 2675 1875 +F 0 "#PWR013" H 2675 1625 50 0001 C CNN +F 1 "GND" H 2675 1725 50 0000 C CNN +F 2 "" H 2675 1875 50 0000 C CNN +F 3 "" H 2675 1875 50 0000 C CNN + 1 2675 1875 + 1 0 0 -1 +$EndComp +Wire Wire Line + 2675 1875 3050 1875 +Wire Wire Line + 2700 2325 3150 2325 +Wire Wire Line + 2700 2475 3050 2475 +Wire Wire Line + 2700 2625 2950 2625 +Wire Wire Line + 2700 2775 2775 2775 +Wire Wire Line + 2775 2825 2775 2775 +Connection ~ 2775 2775 +Wire Wire Line + 2775 2775 2850 2775 +Wire Wire Line + 2975 2825 2975 2625 +Connection ~ 2975 2625 +Wire Wire Line + 2975 2625 3650 2625 +Wire Wire Line + 3175 2825 3175 2475 +Connection ~ 3175 2475 +Wire Wire Line + 3175 2475 3650 2475 +Wire Wire Line + 3375 2825 3375 2325 +Connection ~ 3375 2325 +Wire Wire Line + 3375 2325 3650 2325 +Wire Wire Line + 3150 2275 3150 2325 +Connection ~ 3150 2325 +Wire Wire Line + 3150 2325 3375 2325 +Wire Wire Line + 3050 2275 3050 2475 +Connection ~ 3050 2475 +Wire Wire Line + 3050 2475 3175 2475 +Wire Wire Line + 2950 2275 2950 2625 +Connection ~ 2950 2625 +Wire Wire Line + 2950 2625 2975 2625 +Wire Wire Line + 2850 2275 2850 2775 +Connection ~ 2850 2775 +Wire Wire Line + 2850 2775 3650 2775 +Wire Notes Line + 2000 1800 3925 1800 +Wire Notes Line + 3925 1800 3925 3325 +Wire Notes Line + 3925 3325 2000 3325 +Wire Notes Line + 2000 3325 2000 1800 +$Comp +L ch34x:CH340G U2 +U 1 1 5C891E7A +P 3400 4550 +F 0 "U2" H 3400 5147 60 0000 C CNN +F 1 "CH340G" H 3400 5041 60 0000 C CNN +F 2 "Package_SOIC:SOIC-16_3.9x9.9mm_P1.27mm" H 3400 5041 60 0001 C CNN +F 3 "" H 3500 4350 60 0000 C CNN + 1 3400 4550 + 1 0 0 -1 +$EndComp +NoConn ~ 3850 4900 +NoConn ~ 3850 4800 +NoConn ~ 3850 4700 +NoConn ~ 3850 4600 +NoConn ~ 3850 4500 +NoConn ~ 3850 4400 +NoConn ~ 3850 4300 +$Comp +L Servo_control-rescue:+3.3V-Chiller_control-rescue #PWR018 +U 1 1 5C8ACD5C +P 3850 4150 +F 0 "#PWR018" H 3850 4000 50 0001 C CNN +F 1 "+3.3V" H 3850 4290 50 0000 C CNN +F 2 "" H 3850 4150 50 0000 C CNN +F 3 "" H 3850 4150 50 0000 C CNN + 1 3850 4150 + 1 0 0 -1 +$EndComp +Wire Wire Line + 3850 4150 3850 4200 +$Comp +L Servo_control-rescue:C-Chiller_control-rescue C6 +U 1 1 5C8AFE6B +P 2400 4350 +F 0 "C6" H 2425 4450 50 0000 L CNN +F 1 "0.1" H 2425 4250 50 0000 L CNN +F 2 "Capacitor_SMD:C_0603_1608Metric_Pad0.84x1.00mm_HandSolder" H 2438 4200 50 0001 C CNN +F 3 "" H 2400 4350 50 0000 C CNN + 1 2400 4350 + -1 0 0 1 +$EndComp +Text Label 2950 4400 2 60 ~ 0 +USART_Tx +Text Label 2950 4300 2 60 ~ 0 +USART_Rx +Wire Wire Line + 2400 4200 2875 4200 +Wire Wire Line + 2950 4500 2400 4500 +Wire Wire Line + 2950 4700 2400 4700 +Wire Wire Line + 2400 4700 2400 4800 +$Comp +L Servo_control-rescue:GND-Chiller_control-rescue #PWR09 +U 1 1 5C8CA4F4 +P 2250 5000 +F 0 "#PWR09" H 2250 4750 50 0001 C CNN +F 1 "GND" H 2250 4850 50 0000 C CNN +F 2 "" H 2250 5000 50 0000 C CNN +F 3 "" H 2250 5000 50 0000 C CNN + 1 2250 5000 + 1 0 0 -1 +$EndComp +$Comp +L Servo_control-rescue:GND-Chiller_control-rescue #PWR015 +U 1 1 5C8CA557 +P 2875 4150 +F 0 "#PWR015" H 2875 3900 50 0001 C CNN +F 1 "GND" H 2875 4000 50 0000 C CNN +F 2 "" H 2875 4150 50 0000 C CNN +F 3 "" H 2875 4150 50 0000 C CNN + 1 2875 4150 + -1 0 0 1 +$EndComp +Wire Wire Line + 2875 4150 2875 4200 +Connection ~ 2875 4200 +Wire Wire Line + 2875 4200 2950 4200 +$Comp +L Device:Crystal Y1 +U 1 1 5C8CDA20 +P 2750 5075 +F 0 "Y1" H 2950 5150 50 0000 C CNN +F 1 "12MHz" H 2750 5252 50 0000 C CNN +F 2 "Crystal:Crystal_HC49-U_Vertical" H 2750 5075 50 0001 C CNN +F 3 "" H 2750 5075 50 0001 C CNN + 1 2750 5075 + 1 0 0 -1 +$EndComp +$Comp +L Device:C C7 +U 1 1 5C8CDF63 +P 2600 5225 +F 0 "C7" H 2800 5275 50 0000 R CNN +F 1 "22p" H 2825 5175 50 0000 R CNN +F 2 "Capacitor_SMD:C_0603_1608Metric_Pad0.84x1.00mm_HandSolder" H 2638 5075 50 0001 C CNN +F 3 "" H 2600 5225 50 0001 C CNN + 1 2600 5225 + -1 0 0 -1 +$EndComp +$Comp +L Device:C C9 +U 1 1 5C8CE285 +P 2900 5225 +F 0 "C9" H 3015 5271 50 0000 L CNN +F 1 "22p" H 3015 5180 50 0000 L CNN +F 2 "Capacitor_SMD:C_0603_1608Metric_Pad0.84x1.00mm_HandSolder" H 2938 5075 50 0001 C CNN +F 3 "" H 2900 5225 50 0001 C CNN + 1 2900 5225 + 1 0 0 -1 +$EndComp +Wire Wire Line + 2600 5375 2900 5375 +$Comp +L Servo_control-rescue:GND-Chiller_control-rescue #PWR012 +U 1 1 5C8D4DFD +P 2575 5375 +F 0 "#PWR012" H 2575 5125 50 0001 C CNN +F 1 "GND" H 2575 5225 50 0000 C CNN +F 2 "" H 2575 5375 50 0000 C CNN +F 3 "" H 2575 5375 50 0000 C CNN + 1 2575 5375 + 1 0 0 -1 +$EndComp +Wire Wire Line + 2575 5375 2600 5375 +Connection ~ 2600 5375 +Wire Wire Line + 2900 5075 2900 4900 +Wire Wire Line + 2900 4900 2950 4900 +Connection ~ 2900 5075 +Wire Wire Line + 2950 4800 2600 4800 +Wire Wire Line + 2600 4800 2600 5075 +Connection ~ 2600 5075 +Wire Wire Line + 1150 4450 1150 4400 +$Comp +L Servo_control-rescue:+5V-power #PWR08 +U 1 1 5C8E7AF9 +P 2175 4275 +F 0 "#PWR08" H 2175 4125 50 0001 C CNN +F 1 "+5V" H 2190 4448 50 0000 C CNN +F 2 "" H 2175 4275 50 0001 C CNN +F 3 "" H 2175 4275 50 0001 C CNN + 1 2175 4275 + 1 0 0 -1 +$EndComp +Connection ~ 850 5050 +Wire Notes Line + 550 550 2050 550 +Wire Notes Line + 2050 550 2050 1700 +Wire Notes Line + 2050 1700 550 1700 +Wire Notes Line + 550 1700 550 550 +NoConn ~ 1150 4850 +Wire Wire Line + 750 5050 850 5050 +Text Notes 2150 1975 0 100 ~ 0 +ADC +Text Notes 700 4075 0 100 ~ 0 +USB +Text Label 7075 2575 2 60 ~ 0 +DigOut1 +Text Notes 6350 2575 0 50 ~ 0 +Ext. load +$Comp +L Servo_control-rescue:Q_NMOS_GSD-Chiller_control-rescue Q1 +U 1 1 5C9233AA +P 3025 950 +F 0 "Q1" H 3225 1000 50 0000 L CNN +F 1 "2N7002" H 3225 900 50 0000 L CNN +F 2 "Package_TO_SOT_SMD:SOT-23" H 3225 1050 50 0001 C CNN +F 3 "" H 3025 950 50 0001 C CNN + 1 3025 950 + 1 0 0 -1 +$EndComp +Text Label 4400 1075 2 60 ~ 0 +DigOut1 +$Comp +L Servo_control-rescue:R-Chiller_control-rescue R8 +U 1 1 5C924EC0 +P 4550 1075 +F 0 "R8" V 4630 1075 50 0000 C CNN +F 1 "510" V 4550 1075 50 0000 C CNN +F 2 "Resistor_SMD:R_0805_2012Metric_Pad1.15x1.50mm_HandSolder" V 4480 1075 50 0001 C CNN +F 3 "" H 4550 1075 50 0001 C CNN + 1 4550 1075 + 0 1 1 0 +$EndComp +$Comp +L Servo_control-rescue:R-Chiller_control-rescue R9 +U 1 1 5C924F9E +P 4550 1275 +F 0 "R9" V 4630 1275 50 0000 C CNN +F 1 "10k" V 4550 1275 50 0000 C CNN +F 2 "Resistor_SMD:R_0805_2012Metric_Pad1.15x1.50mm_HandSolder" V 4480 1275 50 0001 C CNN +F 3 "" H 4550 1275 50 0001 C CNN + 1 4550 1275 + 0 1 1 0 +$EndComp +$Comp +L Servo_control-rescue:R-Chiller_control-rescue R6 +U 1 1 5C929CAD +P 2675 950 +F 0 "R6" V 2755 950 50 0000 C CNN +F 1 "510" V 2675 950 50 0000 C CNN +F 2 "Resistor_SMD:R_0805_2012Metric_Pad1.15x1.50mm_HandSolder" V 2605 950 50 0001 C CNN +F 3 "" H 2675 950 50 0001 C CNN + 1 2675 950 + 0 1 1 0 +$EndComp +$Comp +L Servo_control-rescue:R-Chiller_control-rescue R7 +U 1 1 5C929D7F +P 2975 1150 +F 0 "R7" V 3055 1150 50 0000 C CNN +F 1 "10k" V 2975 1150 50 0000 C CNN +F 2 "Resistor_SMD:R_0805_2012Metric_Pad1.15x1.50mm_HandSolder" V 2905 1150 50 0001 C CNN +F 3 "" H 2975 1150 50 0001 C CNN + 1 2975 1150 + 0 1 1 0 +$EndComp +Connection ~ 3125 1150 +Wire Wire Line + 4400 1275 4400 1075 +Wire Wire Line + 4700 1275 5000 1275 +$Comp +L Servo_control-rescue:GND-Chiller_control-rescue #PWR023 +U 1 1 5C936297 +P 5000 1275 +F 0 "#PWR023" H 5000 1025 50 0001 C CNN +F 1 "GND" H 5000 1125 50 0000 C CNN +F 2 "" H 5000 1275 50 0000 C CNN +F 3 "" H 5000 1275 50 0000 C CNN + 1 5000 1275 + 1 0 0 -1 +$EndComp +Connection ~ 5000 1275 +$Comp +L Connector_Generic:Conn_01x02 J6 +U 1 1 5C93CB05 +P 5200 775 +F 0 "J6" H 5279 767 50 0000 L CNN +F 1 "Ext_LED" H 5279 676 50 0000 L CNN +F 2 "Connector_PinHeader_2.54mm:PinHeader_1x02_P2.54mm_Vertical" H 5200 775 50 0001 C CNN +F 3 "~" H 5200 775 50 0001 C CNN + 1 5200 775 + 1 0 0 -1 +$EndComp +$Comp +L Servo_control-rescue:+5V-power #PWR022 +U 1 1 5C93D5BD +P 5000 775 +F 0 "#PWR022" H 5000 625 50 0001 C CNN +F 1 "+5V" H 5015 948 50 0000 C CNN +F 2 "" H 5000 775 50 0001 C CNN +F 3 "" H 5000 775 50 0001 C CNN + 1 5000 775 + 1 0 0 -1 +$EndComp +$Comp +L Servo_control-rescue:GND-Chiller_control-rescue #PWR010 +U 1 1 5C93ECB6 +P 2300 2800 +F 0 "#PWR010" H 2300 2550 50 0001 C CNN +F 1 "GND" H 2300 2650 50 0000 C CNN +F 2 "" H 2300 2800 50 0000 C CNN +F 3 "" H 2300 2800 50 0000 C CNN + 1 2300 2800 + 1 0 0 -1 +$EndComp +$Comp +L Servo_control-rescue:+3.3V-Chiller_control-rescue #PWR011 +U 1 1 5C93F2A7 +P 2350 2225 +F 0 "#PWR011" H 2350 2075 50 0001 C CNN +F 1 "+3.3V" H 2350 2365 50 0000 C CNN +F 2 "" H 2350 2225 50 0000 C CNN +F 3 "" H 2350 2225 50 0000 C CNN + 1 2350 2225 + 1 0 0 -1 +$EndComp +Wire Wire Line + 2300 2300 2350 2300 +Wire Wire Line + 2350 2300 2350 2225 +$Comp +L Servo_control-rescue:R-Chiller_control-rescue R1 +U 1 1 5C943CF3 +P 950 2400 +F 0 "R1" V 1030 2400 50 0000 C CNN +F 1 "10k" V 950 2400 50 0000 C CNN +F 2 "Resistor_SMD:R_0805_2012Metric_Pad1.15x1.50mm_HandSolder" V 880 2400 50 0001 C CNN +F 3 "" H 950 2400 50 0001 C CNN + 1 950 2400 + -1 0 0 1 +$EndComp +Wire Notes Line + 4000 550 5625 550 +Wire Notes Line + 5625 550 5625 1500 +Wire Notes Line + 5625 1500 4000 1500 +Wire Notes Line + 4000 550 4000 1500 +$Comp +L Device:D D3 +U 1 1 5C95243A +P 4900 2375 +F 0 "D3" H 4900 2475 50 0000 C CNN +F 1 "SMAJ5.0" H 4900 2275 50 0000 C CNN +F 2 "Diode_SMD:D_SMA_Handsoldering" H 4900 2375 50 0001 C CNN +F 3 "" H 4900 2375 50 0001 C CNN + 1 4900 2375 + 0 1 1 0 +$EndComp +$Comp +L Device:D D4 +U 1 1 5C952A1B +P 5175 2375 +F 0 "D4" H 5175 2475 50 0000 C CNN +F 1 "SMAJ5.0" H 5175 2275 50 0000 C CNN +F 2 "Diode_SMD:D_SMA_Handsoldering" H 5175 2375 50 0001 C CNN +F 3 "" H 5175 2375 50 0001 C CNN + 1 5175 2375 + 0 1 1 0 +$EndComp +$Comp +L Servo_control-rescue:R-Chiller_control-rescue R10 +U 1 1 5C957A49 +P 4650 2000 +F 0 "R10" V 4730 2000 50 0000 C CNN +F 1 "1k" V 4650 2000 50 0000 C CNN +F 2 "Resistor_SMD:R_0805_2012Metric_Pad1.15x1.50mm_HandSolder" V 4580 2000 50 0001 C CNN +F 3 "" H 4650 2000 50 0001 C CNN + 1 4650 2000 + 0 1 1 0 +$EndComp +$Comp +L Servo_control-rescue:R-Chiller_control-rescue R11 +U 1 1 5C957B70 +P 4650 2175 +F 0 "R11" V 4730 2175 50 0000 C CNN +F 1 "1k" V 4650 2175 50 0000 C CNN +F 2 "Resistor_SMD:R_0805_2012Metric_Pad1.15x1.50mm_HandSolder" V 4580 2175 50 0001 C CNN +F 3 "" H 4650 2175 50 0001 C CNN + 1 4650 2175 + 0 1 1 0 +$EndComp +$Comp +L Connector_Generic:Conn_01x03 J5 +U 1 1 5C9581BA +P 4200 2175 +F 0 "J5" H 4120 1850 50 0000 C CNN +F 1 "Conn_01x03" H 4120 1941 50 0000 C CNN +F 2 "Connector_PinHeader_2.54mm:PinHeader_1x03_P2.54mm_Vertical" H 4200 2175 50 0001 C CNN +F 3 "~" H 4200 2175 50 0001 C CNN + 1 4200 2175 + -1 0 0 1 +$EndComp +$Comp +L Servo_control-rescue:GND-Chiller_control-rescue #PWR021 +U 1 1 5C95874A +P 4400 2275 +F 0 "#PWR021" H 4400 2025 50 0001 C CNN +F 1 "GND" H 4400 2125 50 0000 C CNN +F 2 "" H 4400 2275 50 0000 C CNN +F 3 "" H 4400 2275 50 0000 C CNN + 1 4400 2275 + 1 0 0 -1 +$EndComp +Wire Wire Line + 4400 2175 4500 2175 +Wire Wire Line + 4400 2075 4500 2075 +Wire Wire Line + 4500 2075 4500 2000 +Wire Wire Line + 4800 2175 4900 2175 +Wire Wire Line + 4900 2175 4900 2225 +Wire Wire Line + 4800 2000 5175 2000 +Wire Wire Line + 5175 2000 5175 2225 +Wire Wire Line + 4900 2175 5250 2175 +Connection ~ 4900 2175 +Wire Wire Line + 5175 2000 5250 2000 +Connection ~ 5175 2000 +Text Label 10475 2075 0 60 ~ 0 +DigIn0 +Text Label 10475 2175 0 60 ~ 0 +DigIn1 +Text Label 5250 2175 0 60 ~ 0 +DigIn0 +Text Label 5250 2000 0 60 ~ 0 +DigIn1 +Wire Notes Line + 4000 1800 5575 1800 +Wire Notes Line + 5575 1800 5575 2575 +Wire Notes Line + 5575 2575 4000 2575 +Wire Notes Line + 4000 2575 4000 1800 +Text Label 10475 2675 0 60 ~ 0 +Jumper0 +Text Label 10475 2775 0 60 ~ 0 +Jumper1 +Text Label 4325 2950 0 60 ~ 0 +Jumper0 +Text Label 4325 3475 0 60 ~ 0 +Jumper1 +$Comp +L Connector_Generic:Conn_01x02 J3 +U 1 1 5C98F117 +P 4125 3050 +F 0 "J3" H 4045 2725 50 0000 C CNN +F 1 "Jumper0" H 4045 2816 50 0000 C CNN +F 2 "Connector_PinHeader_2.54mm:PinHeader_1x02_P2.54mm_Vertical" H 4125 3050 50 0001 C CNN +F 3 "~" H 4125 3050 50 0001 C CNN + 1 4125 3050 + -1 0 0 1 +$EndComp +$Comp +L Connector_Generic:Conn_01x02 J4 +U 1 1 5C98F3D6 +P 4125 3575 +F 0 "J4" H 4045 3250 50 0000 C CNN +F 1 "Jumper1" H 4045 3341 50 0000 C CNN +F 2 "Connector_PinHeader_2.54mm:PinHeader_1x02_P2.54mm_Vertical" H 4125 3575 50 0001 C CNN +F 3 "~" H 4125 3575 50 0001 C CNN + 1 4125 3575 + -1 0 0 1 +$EndComp +$Comp +L Servo_control-rescue:GND-Chiller_control-rescue #PWR019 +U 1 1 5C9901F3 +P 4325 3050 +F 0 "#PWR019" H 4325 2800 50 0001 C CNN +F 1 "GND" H 4325 2900 50 0000 C CNN +F 2 "" H 4325 3050 50 0000 C CNN +F 3 "" H 4325 3050 50 0000 C CNN + 1 4325 3050 + 1 0 0 -1 +$EndComp +$Comp +L Servo_control-rescue:GND-Chiller_control-rescue #PWR020 +U 1 1 5C9902E2 +P 4325 3575 +F 0 "#PWR020" H 4325 3325 50 0001 C CNN +F 1 "GND" H 4325 3425 50 0000 C CNN +F 2 "" H 4325 3575 50 0000 C CNN +F 3 "" H 4325 3575 50 0000 C CNN + 1 4325 3575 + 1 0 0 -1 +$EndComp +Wire Notes Line + 4000 2650 4750 2650 +Wire Notes Line + 4750 2650 4750 3800 +Wire Notes Line + 4750 3800 4000 3800 +Wire Notes Line + 4000 3800 4000 2650 +Wire Wire Line + 4900 2525 5175 2525 +Wire Wire Line + 4900 2525 4500 2525 +Wire Wire Line + 4500 2525 4500 2275 +Wire Wire Line + 4500 2275 4400 2275 +Connection ~ 4900 2525 +Connection ~ 4400 2275 +$Comp +L Connector_Specialized:USB_B_Micro J1 +U 1 1 5C8BC41C +P 850 4650 +F 0 "J1" H 905 5117 50 0000 C CNN +F 1 "USB_B_Micro" H 905 5026 50 0000 C CNN +F 2 "Connector_USB:USB_Micro-B_Wuerth-629105150521" H 1000 4600 50 0001 C CNN +F 3 "~" H 1000 4600 50 0001 C CNN + 1 850 4650 + 1 0 0 -1 +$EndComp +$Comp +L elements:USB6B1 D1 +U 1 1 5C9BF24E +P 1750 4700 +F 0 "D1" H 1750 5215 50 0000 C CNN +F 1 "USB6B1" H 1750 5124 50 0000 C CNN +F 2 "Package_SOIC:SOIC-8_3.9x4.9mm_P1.27mm" H 1750 5124 50 0001 C CNN +F 3 "" V 1950 4600 50 0000 C CNN + 1 1750 4700 + 1 0 0 -1 +$EndComp +Wire Wire Line + 1250 4400 1150 4400 +Wire Wire Line + 850 5050 1250 5050 +Wire Wire Line + 1250 5000 1250 5050 +Wire Wire Line + 2250 4800 2400 4800 +Wire Wire Line + 2250 4600 2950 4600 +Wire Wire Line + 2250 4400 2250 4275 +Wire Wire Line + 2250 4275 2175 4275 +Wire Wire Line + 1150 4750 1250 4750 +Wire Wire Line + 1250 4750 1250 4600 +Wire Wire Line + 1150 4650 1200 4650 +Wire Wire Line + 1200 4650 1200 4800 +Wire Wire Line + 1200 4800 1250 4800 +$EndSCHEMATC diff --git a/F0-nolib/Servo/kicad/ch34x.lib b/F0-nolib/Servo/kicad/ch34x.lib new file mode 100644 index 0000000..978ba40 --- /dev/null +++ b/F0-nolib/Servo/kicad/ch34x.lib @@ -0,0 +1,32 @@ +EESchema-LIBRARY Version 2.3 +#encoding utf-8 +# +# CH340G +# +DEF CH340G U 0 40 Y Y 1 F N +F0 "U" 25 475 60 H V C CNN +F1 "CH340G" 0 -475 60 H V C CNN +F2 "" 100 -200 60 H V C CNN +F3 "" 100 -200 60 H V C CNN +DRAW +S -250 400 250 -400 0 1 0 N +X GND 1 -450 350 200 R 50 50 1 1 W +X TX 2 -450 250 200 R 50 50 1 1 O +X RX 3 -450 150 200 R 50 50 1 1 I +X V3 4 -450 50 200 R 50 50 1 1 P +X D+ 5 -450 -50 200 R 50 50 1 1 B +X D- 6 -450 -150 200 R 50 50 1 1 B +X XI 7 -450 -250 200 R 50 50 1 1 I +X XO 8 -450 -350 200 R 50 50 1 1 I +X CTS 9 450 -350 200 L 50 50 1 1 O +X DSR 10 450 -250 200 L 50 50 1 1 O +X RI 11 450 -150 200 L 50 50 1 1 O +X DCD 12 450 -50 200 L 50 50 1 1 O +X DTR 13 450 50 200 L 50 50 1 1 O +X RTS 14 450 150 200 L 50 50 1 1 O +X RS232 15 450 250 200 L 50 50 1 1 I +X VCC 16 450 350 200 L 50 50 1 1 W +ENDDRAW +ENDDEF +# +#End Library diff --git a/F0-nolib/Servo/kicad/elements.lib b/F0-nolib/Servo/kicad/elements.lib new file mode 100644 index 0000000..9ada38f --- /dev/null +++ b/F0-nolib/Servo/kicad/elements.lib @@ -0,0 +1,190 @@ +EESchema-LIBRARY Version 2.3 +#encoding utf-8 +# +# 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 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 +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 +ENDDRAW +ENDDEF +# +# D_Schottky_x2_ACom_AKK +# +DEF D_Schottky_x2_ACom_AKK D 0 30 Y N 1 F N +F0 "D" 50 -100 50 H V C CNN +F1 "D_Schottky_x2_ACom_AKK" 0 100 50 H V C CNN +F2 "" 0 0 50 H V C CNN +F3 "" 0 0 50 H V C CNN +DRAW +P 2 0 1 0 -140 0 150 0 N +P 2 0 1 0 0 0 0 -100 N +P 3 0 1 8 -150 50 -150 -50 -150 -50 N +P 3 0 1 8 150 50 150 -50 150 -50 N +P 4 0 1 8 -150 50 -170 50 -170 40 -170 40 N +P 4 0 1 8 150 -50 170 -50 170 -40 170 -40 N +P 4 0 1 8 150 50 130 50 130 40 130 40 N +P 5 0 1 8 -130 -40 -130 -50 -150 -50 -150 -50 -150 -50 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 50 150 0 50 -50 50 50 50 50 50 50 N +X A 1 0 -200 100 U 50 50 0 1 P +X K 2 -300 0 150 R 50 50 0 1 P +X K 3 300 0 150 L 50 50 0 1 P +ENDDRAW +ENDDEF +# +# LM1117-ADJ +# +DEF LM1117-ADJ U 0 30 Y Y 1 F N +F0 "U" 100 -250 50 H V C CNN +F1 "LM1117-ADJ" 0 250 50 H V C CNN +F2 "" 0 0 50 H V C CNN +F3 "" 0 0 50 H V C CNN +ALIAS LM1117-1.8 LM1117-2.5 LM1117-3.3 LM1117-5.0 +$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 0 100 L 50 50 1 1 w +X VI 3 -300 0 100 R 50 50 1 1 W +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 +# +# 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 +# +#End Library diff --git a/F0-nolib/Servo/kicad/fp-info-cache b/F0-nolib/Servo/kicad/fp-info-cache new file mode 100644 index 0000000..5a3a8b2 --- /dev/null +++ b/F0-nolib/Servo/kicad/fp-info-cache @@ -0,0 +1,14183 @@ +3089057598695452 +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_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_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_KMR2 +CK components KMR2 tactile switch http://www.ckswitches.com/media/1479/kmr2.pdf +tactile switch kmr2 +0 +4 +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 +Buzzer_Beeper +BUZZER +Generic Buzzer +buzzer +0 +2 +2 +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_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 +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_ProjectsUnlimited_AI-4228-TWT-R +Buzzer, Elektromagnetic Beeper, Summer, 3-28V-DC, +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 +SMD 8540 +0 +4 +4 +Capacitor_SMD +CP_Elec_3x5.4 +SMT capacitor, aluminium electrolytic, 3x5.4, Nichicon +Capacitor Electrolytic +0 +2 +2 +Capacitor_SMD +CP_Elec_4x3 +SMT capacitor, aluminium electrolytic, 4x3, Nichicon +Capacitor Electrolytic +0 +2 +2 +Capacitor_SMD +CP_Elec_4x3.9 +SMT capacitor, aluminium electrolytic, 4x3.9, Nichicon +Capacitor Electrolytic +0 +2 +2 +Capacitor_SMD +CP_Elec_4x4.5 +SMT capacitor, aluminium electrolytic, 4x4.5, Nichicon +Capacitor Electrolytic +0 +2 +2 +Capacitor_SMD +CP_Elec_4x5.4 +SMT capacitor, aluminium electrolytic, 4x5.4, Panasonic A5, Nichicon +Capacitor Electrolytic +0 +2 +2 +Capacitor_SMD +CP_Elec_5x3 +SMT capacitor, aluminium electrolytic, 5x3, Nichicon +Capacitor Electrolytic +0 +2 +2 +Capacitor_SMD +CP_Elec_5x3.9 +SMT capacitor, aluminium electrolytic, 5x3.9, Nichicon +Capacitor Electrolytic +0 +2 +2 +Capacitor_SMD +CP_Elec_5x4.4 +SMT capacitor, aluminium electrolytic, 5x4.4, Panasonic B45 +Capacitor Electrolytic +0 +2 +2 +Capacitor_SMD +CP_Elec_5x4.5 +SMT capacitor, aluminium electrolytic, 5x4.5, Nichicon +Capacitor Electrolytic +0 +2 +2 +Capacitor_SMD +CP_Elec_5x5.4 +SMT capacitor, aluminium electrolytic, 5x5.4, Nichicon +Capacitor Electrolytic +0 +2 +2 +Capacitor_SMD +CP_Elec_5x5.9 +SMT capacitor, aluminium electrolytic, 5x5.9, Panasonic B6 +Capacitor Electrolytic +0 +2 +2 +Capacitor_SMD +CP_Elec_6.3x3 +SMT capacitor, aluminium electrolytic, 6.3x3, Nichicon +Capacitor Electrolytic +0 +2 +2 +Capacitor_SMD +CP_Elec_6.3x3.9 +SMT capacitor, aluminium electrolytic, 6.3x3.9, Nichicon +Capacitor Electrolytic +0 +2 +2 +Capacitor_SMD +CP_Elec_6.3x4.5 +SMT capacitor, aluminium electrolytic, 6.3x4.5, Nichicon +Capacitor Electrolytic +0 +2 +2 +Capacitor_SMD +CP_Elec_6.3x4.9 +SMT capacitor, aluminium electrolytic, 6.3x4.9, Panasonic C5 +Capacitor Electrolytic +0 +2 +2 +Capacitor_SMD +CP_Elec_6.3x5.4 +SMT capacitor, aluminium electrolytic, 6.3x5.4, Panasonic C55 +Capacitor Electrolytic +0 +2 +2 +Capacitor_SMD +CP_Elec_6.3x5.4_Nichicon +SMT capacitor, aluminium electrolytic, 6.3x5.4, Nichicon +Capacitor Electrolytic +0 +2 +2 +Capacitor_SMD +CP_Elec_6.3x5.8 +SMT capacitor, aluminium electrolytic, 6.3x5.8, Nichicon +Capacitor Electrolytic +0 +2 +2 +Capacitor_SMD +CP_Elec_6.3x5.9 +SMT capacitor, aluminium electrolytic, 6.3x5.9, Panasonic C6 +Capacitor Electrolytic +0 +2 +2 +Capacitor_SMD +CP_Elec_6.3x7.7 +SMT capacitor, aluminium electrolytic, 6.3x7.7, Nichicon +Capacitor Electrolytic +0 +2 +2 +Capacitor_SMD +CP_Elec_6.3x9.9 +SMT capacitor, aluminium electrolytic, 6.3x9.9, Panasonic C10 +Capacitor Electrolytic +0 +2 +2 +Capacitor_SMD +CP_Elec_8x5.4 +SMT capacitor, aluminium electrolytic, 8x5.4, Nichicon +Capacitor Electrolytic +0 +2 +2 +Capacitor_SMD +CP_Elec_8x6.2 +SMT capacitor, aluminium electrolytic, 8x6.2, Nichicon +Capacitor Electrolytic +0 +2 +2 +Capacitor_SMD +CP_Elec_8x6.9 +SMT capacitor, aluminium electrolytic, 8x6.9, Panasonic E7 +Capacitor Electrolytic +0 +2 +2 +Capacitor_SMD +CP_Elec_8x10 +SMT capacitor, aluminium electrolytic, 8x10, Nichicon +Capacitor Electrolytic +0 +2 +2 +Capacitor_SMD +CP_Elec_8x10.5 +SMT capacitor, aluminium electrolytic, 8x10.5, Vishay 0810 http://www.vishay.com/docs/28395/150crz.pdf +Capacitor Electrolytic +0 +2 +2 +Capacitor_SMD +CP_Elec_8x11.9 +SMT capacitor, aluminium electrolytic, 8x11.9, Panasonic E12 +Capacitor Electrolytic +0 +2 +2 +Capacitor_SMD +CP_Elec_10x7.9 +SMT capacitor, aluminium electrolytic, 10x7.9, Panasonic F8 +Capacitor Electrolytic +0 +2 +2 +Capacitor_SMD +CP_Elec_10x10 +SMT capacitor, aluminium electrolytic, 10x10, Nichicon +Capacitor Electrolytic +0 +2 +2 +Capacitor_SMD +CP_Elec_10x10.5 +SMT capacitor, aluminium electrolytic, 10x10, Vishay 1010 http://www.vishay.com/docs/28395/150crz.pdf +Capacitor Electrolytic +0 +2 +2 +Capacitor_SMD +CP_Elec_10x12.5 +SMT capacitor, aluminium electrolytic, 10x12.5, Vishay 1012 http://www.vishay.com/docs/28395/150crz.pdf +Capacitor Electrolytic +0 +2 +2 +Capacitor_SMD +CP_Elec_10x12.6 +SMT capacitor, aluminium electrolytic, 10x12.6, Panasonic F12 +Capacitor Electrolytic +0 +2 +2 +Capacitor_SMD +CP_Elec_10x14.3 +SMT capacitor, aluminium electrolytic, 10x14.3, Vishay 1014 http://www.vishay.com/docs/28395/150crz.pdf +Capacitor Electrolytic +0 +2 +2 +Capacitor_SMD +CP_Elec_16x17.5 +SMT capacitor, aluminium electrolytic, 16x17.5, Vishay 1616 http://www.vishay.com/docs/28395/150crz.pdf +Capacitor Electrolytic +0 +2 +2 +Capacitor_SMD +CP_Elec_16x22 +SMT capacitor, aluminium electrolytic, 16x22, Vishay 1621 http://www.vishay.com/docs/28395/150crz.pdf +Capacitor Electrolytic +0 +2 +2 +Capacitor_SMD +CP_Elec_18x17.5 +SMT capacitor, aluminium electrolytic, 18x17.5, Vishay 1816 http://www.vishay.com/docs/28395/150crz.pdf +Capacitor Electrolytic +0 +2 +2 +Capacitor_SMD +CP_Elec_18x22 +SMT capacitor, aluminium electrolytic, 18x22, Vishay 1821 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_Pad0.99x1.00mm_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: http://www.tortai-tech.com/upload/download/2011102023233369053.pdf), generated with kicad-footprint-generator +capacitor +0 +2 +2 +Capacitor_SMD +C_0805_2012Metric_Pad1.29x1.40mm_HandSolder +Capacitor SMD 0805 (2012 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_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.39x1.80mm_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.39x2.70mm_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.68x1.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.38x3.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_Pad2.07x6.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.49x2.70mm_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_Pad2.17x5.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.93x6.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.49x3.40mm_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_Pad2.55x4.50mm_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.25x10.50mm_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_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.15x1.10mm_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.15x1.10mm_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.25x1.10mm_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.25x1.10mm_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.53x1.40mm_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.53x1.40mm_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.53x1.40mm_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.63x2.40mm_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.63x2.40mm_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.63x2.40mm_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.24x2.40mm_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.24x2.40mm_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.24x2.40mm_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.23x2.60mm_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.23x2.60mm_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.23x2.60mm_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.23x2.60mm_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.23x2.60mm_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.23x2.60mm_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.23x4.30mm_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.14x3.40mm_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.14x3.40mm_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_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 +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 +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 +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_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_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_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_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_Tensility_54-00023_Vertical +http://www.tensility.com/pdffiles/54-00023.pdf +usb mini receptacle vertical +0 +7 +6 +Connectors_USB +USB_Micro-B_Tensility_54-00023_Vertical_CircularHoles +http://www.tensility.com/pdffiles/54-00023.pdf +usb mini receptacle vertical +0 +7 +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_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 +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 +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_Pad0.82x1.00mm_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: http://www.tortai-tech.com/upload/download/2011102023233369053.pdf), 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: http://www.tortai-tech.com/upload/download/2011102023233369053.pdf), generated with kicad-footprint-generator +diode castellated +0 +2 +2 +Diode_SMD +D_0805_2012Metric_Pad1.12x1.40mm_HandSolder +Diode SMD 0805 (2012 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_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.22x1.80mm_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.22x2.70mm_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.51x1.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.21x3.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.32x2.70mm_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.67x3.70mm_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.32x3.40mm_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_Pad2.38x4.50mm_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.47x5.10mm_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_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_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_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_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_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_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 +modules +DB9-F +Connecteur DB9 femelle couche +CONN DB9 +0 +11 +9 +modules +hole_3mm + + +0 +1 +0 +modules +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 +4 +3 +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_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 +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_Pad0.99x1.00mm_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.25x3.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: http://www.tortai-tech.com/upload/download/2011102023233369053.pdf), generated with kicad-footprint-generator +resistor +0 +2 +2 +Resistor_SMD +R_0805_2012Metric_Pad1.29x1.40mm_HandSolder +Resistor SMD 0805 (2012 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_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.64x4.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.40x5.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.39x1.80mm_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.39x2.70mm_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.29x5.80mm_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.68x1.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.38x3.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.49x2.70mm_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.49x3.40mm_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_Pad2.55x4.50mm_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.71x5.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_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_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_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 +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 +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-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 +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_Housing +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_Housing_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-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-665 +SOT665 +SOT-665 +0 +5 +5 +TO_SOT_Packages_SMD +SOT-666 +SOT666 +SOT-666 +0 +6 +6 +TO_SOT_Packages_SMD +SOT-669_LFPAK +LFPAK https://assets.nexperia.com/documents/leaflet/939775016838_LR.pdf +LFPAK SOT-669 Power-SO8 +0 +19 +5 +TO_SOT_Packages_SMD +SOT-669_LFPAK_ThermalVias-1 +LFPAK https://assets.nexperia.com/documents/leaflet/939775016838_LR.pdf +LFPAK SOT669 Thermal Vias 0.4mm Power-SO8 +0 +63 +5 +TO_SOT_Packages_SMD +SOT-669_LFPAK_ThermalVias-2 +LFPAK https://assets.nexperia.com/documents/leaflet/939775016838_LR.pdf +LFPAK SOT669 Thermical Vias Power-SO8 +0 +30 +5 +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-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-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 +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 +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/F0-nolib/Servo/kicad/fp-lib-table b/F0-nolib/Servo/kicad/fp-lib-table new file mode 100644 index 0000000..7fc0f57 --- /dev/null +++ b/F0-nolib/Servo/kicad/fp-lib-table @@ -0,0 +1,3 @@ +(fp_lib_table + (lib (name modules)(type KiCad)(uri modules.pretty)(options "")(descr "")) +) diff --git a/F0-nolib/Servo/kicad/modules.pretty/DB9-F.kicad_mod b/F0-nolib/Servo/kicad/modules.pretty/DB9-F.kicad_mod new file mode 100644 index 0000000..f92db0c --- /dev/null +++ b/F0-nolib/Servo/kicad/modules.pretty/DB9-F.kicad_mod @@ -0,0 +1,31 @@ +(module DB9-F (layer F.Cu) (tedit 546362FD) + (descr "Connecteur DB9 femelle couche") + (tags "CONN DB9") + (fp_text reference XP** (at -6.3 -5.3) (layer F.SilkS) + (effects (font (thickness 0.3048))) + ) + (fp_text value DB9F (at 7.7 -5.1) (layer F.SilkS) + (effects (font (thickness 0.3048))) + ) + (fp_line (start -16.129 2.286) (end 16.383 2.286) (layer F.SilkS) (width 0.3048)) + (fp_line (start 16.383 2.286) (end 16.383 -9.494) (layer F.SilkS) (width 0.3048)) + (fp_line (start 16.383 -9.494) (end -16.129 -9.494) (layer F.SilkS) (width 0.3048)) + (fp_line (start -16.129 -9.494) (end -16.129 2.286) (layer F.SilkS) (width 0.3048)) + (fp_line (start -9.017 -7.874) (end 9.271 -7.874) (layer F.SilkS) (width 0.3048)) + (pad "" thru_hole circle (at 12.827 -1.27) (size 3.81 3.81) (drill 3.048) (layers *.Cu *.Mask F.SilkS)) + (pad "" thru_hole circle (at -12.573 -1.27) (size 3.81 3.81) (drill 3.048) (layers *.Cu *.Mask F.SilkS)) + (pad 1 thru_hole rect (at -5.461 1.27) (size 1.524 1.524) (drill 1.016) (layers *.Cu *.Mask F.SilkS)) + (pad 2 thru_hole circle (at -2.667 1.27) (size 1.524 1.524) (drill 1.016) (layers *.Cu *.Mask F.SilkS)) + (pad 3 thru_hole circle (at 0 1.27) (size 1.524 1.524) (drill 1.016) (layers *.Cu *.Mask F.SilkS)) + (pad 4 thru_hole circle (at 2.794 1.27) (size 1.524 1.524) (drill 1.016) (layers *.Cu *.Mask F.SilkS)) + (pad 5 thru_hole circle (at 5.588 1.27) (size 1.524 1.524) (drill 1.016) (layers *.Cu *.Mask F.SilkS)) + (pad 6 thru_hole circle (at -4.064 -1.27) (size 1.524 1.524) (drill 1.016) (layers *.Cu *.Mask F.SilkS)) + (pad 7 thru_hole circle (at -1.27 -1.27) (size 1.524 1.524) (drill 1.016) (layers *.Cu *.Mask F.SilkS)) + (pad 8 thru_hole circle (at 1.397 -1.27) (size 1.524 1.524) (drill 1.016) (layers *.Cu *.Mask F.SilkS)) + (pad 9 thru_hole circle (at 4.191 -1.27) (size 1.524 1.524) (drill 1.016) (layers *.Cu *.Mask F.SilkS)) + (model conn_DBxx/db9_female_pin90deg.wrl + (at (xyz 0 0 0)) + (scale (xyz 1 1 1)) + (rotate (xyz 0 0 0)) + ) +) diff --git a/F0-nolib/Servo/kicad/modules.pretty/TO-220-3_Horizontal_TabDown.kicad_mod b/F0-nolib/Servo/kicad/modules.pretty/TO-220-3_Horizontal_TabDown.kicad_mod new file mode 100644 index 0000000..3e7e7d7 --- /dev/null +++ b/F0-nolib/Servo/kicad/modules.pretty/TO-220-3_Horizontal_TabDown.kicad_mod @@ -0,0 +1,45 @@ +(module TO-220-3_Horizontal_TabDown (layer F.Cu) (tedit 5BEBD722) + (descr "TO-220-3, Horizontal, RM 2.54mm, see https://www.vishay.com/docs/66542/to-220-1.pdf") + (tags "TO-220-3 Horizontal RM 2.54mm") + (fp_text reference Q1 (at 2.54 -20.58) (layer F.SilkS) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_text value IRL3303 (at 2.54 2) (layer F.Fab) + (effects (font (size 1 1) (thickness 0.15))) + ) + (fp_circle (center 2.54 -16.66) (end 4.39 -16.66) (layer F.Fab) (width 0.1)) + (fp_line (start -2.46 -13.06) (end -2.46 -19.46) (layer F.Fab) (width 0.1)) + (fp_line (start -2.46 -19.46) (end 7.54 -19.46) (layer F.Fab) (width 0.1)) + (fp_line (start 7.54 -19.46) (end 7.54 -13.06) (layer F.Fab) (width 0.1)) + (fp_line (start 7.54 -13.06) (end -2.46 -13.06) (layer F.Fab) (width 0.1)) + (fp_line (start -2.46 -3.81) (end -2.46 -13.06) (layer F.Fab) (width 0.1)) + (fp_line (start -2.46 -13.06) (end 7.54 -13.06) (layer F.Fab) (width 0.1)) + (fp_line (start 7.54 -13.06) (end 7.54 -3.81) (layer F.Fab) (width 0.1)) + (fp_line (start 7.54 -3.81) (end -2.46 -3.81) (layer F.Fab) (width 0.1)) + (fp_line (start 0 -3.81) (end 0 0) (layer F.Fab) (width 0.1)) + (fp_line (start 2.54 -3.81) (end 2.54 0) (layer F.Fab) (width 0.1)) + (fp_line (start 5.08 -3.81) (end 5.08 0) (layer F.Fab) (width 0.1)) + (fp_line (start -2.58 -3.69) (end 7.66 -3.69) (layer F.SilkS) (width 0.12)) + (fp_line (start -2.58 -19.58) (end 7.66 -19.58) (layer F.SilkS) (width 0.12)) + (fp_line (start -2.58 -19.58) (end -2.58 -3.69) (layer F.SilkS) (width 0.12)) + (fp_line (start 7.66 -19.58) (end 7.66 -3.69) (layer F.SilkS) (width 0.12)) + (fp_line (start 0 -3.69) (end 0 -1.15) (layer F.SilkS) (width 0.12)) + (fp_line (start 2.54 -3.69) (end 2.54 -1.15) (layer F.SilkS) (width 0.12)) + (fp_line (start 5.08 -3.69) (end 5.08 -1.15) (layer F.SilkS) (width 0.12)) + (fp_line (start -2.71 -19.71) (end -2.71 1.25) (layer F.CrtYd) (width 0.05)) + (fp_line (start -2.71 1.25) (end 7.79 1.25) (layer F.CrtYd) (width 0.05)) + (fp_line (start 7.79 1.25) (end 7.79 -19.71) (layer F.CrtYd) (width 0.05)) + (fp_line (start 7.79 -19.71) (end -2.71 -19.71) (layer F.CrtYd) (width 0.05)) + (fp_text user %R (at 2.54 -20.58) (layer F.Fab) + (effects (font (size 1 1) (thickness 0.15))) + ) + (pad 2 thru_hole rect (at 2.54 -16.66) (size 12 7) (drill 3.5) (layers *.Cu *.Mask)) + (pad 1 thru_hole rect (at 0 0) (size 1.905 2) (drill 1.1) (layers *.Cu *.Mask)) + (pad 2 thru_hole oval (at 2.54 0) (size 1.905 2) (drill 1.1) (layers *.Cu *.Mask)) + (pad 3 thru_hole oval (at 5.08 0) (size 1.905 2) (drill 1.1) (layers *.Cu *.Mask)) + (model ${KISYS3DMOD}/Package_TO_SOT_THT.3dshapes/TO-220-3_Horizontal_TabDown.wrl + (at (xyz 0 0 0)) + (scale (xyz 1 1 1)) + (rotate (xyz 0 0 0)) + ) +) diff --git a/F0-nolib/Servo/kicad/modules.pretty/hole_3mm.kicad_mod b/F0-nolib/Servo/kicad/modules.pretty/hole_3mm.kicad_mod new file mode 100644 index 0000000..50ce72c --- /dev/null +++ b/F0-nolib/Servo/kicad/modules.pretty/hole_3mm.kicad_mod @@ -0,0 +1,14 @@ +(module hole_3mm (layer F.Cu) (tedit 5BF13739) + (fp_text reference hole_3mm (at 0 -2.54) (layer F.SilkS) hide + (effects (font (size 1.5 1.5) (thickness 0.3))) + ) + (fp_text value Val** (at 0 3.175) (layer F.SilkS) hide + (effects (font (size 1.5 1.5) (thickness 0.3))) + ) + (fp_line (start 0 2.5) (end 0 1.5) (layer F.SilkS) (width 0.3)) + (fp_line (start -2.5 0) (end -1.5 0) (layer F.SilkS) (width 0.3)) + (fp_line (start 2.5 0) (end 1.5 0) (layer F.SilkS) (width 0.3)) + (fp_line (start 0 -1.5) (end 0 -2.5) (layer F.SilkS) (width 0.3)) + (fp_circle (center 0 0) (end 2.5 0) (layer F.SilkS) (width 0.3)) + (pad "" np_thru_hole circle (at 0 0) (size 3 3) (drill 1) (layers *.Cu *.Mask)) +) diff --git a/F0-nolib/Servo/kicad/sym-lib-table b/F0-nolib/Servo/kicad/sym-lib-table new file mode 100644 index 0000000..50cfefe --- /dev/null +++ b/F0-nolib/Servo/kicad/sym-lib-table @@ -0,0 +1,6 @@ +(sym_lib_table + (lib (name Chiller_control-rescue)(type Legacy)(uri ${KIPRJMOD}/Chiller_control-rescue.lib)(options "")(descr "")) + (lib (name Servo_control-rescue)(type Legacy)(uri ${KIPRJMOD}/Servo_control-rescue.lib)(options "")(descr "")) + (lib (name ch34x)(type Legacy)(uri ${KIPRJMOD}/ch34x.lib)(options "")(descr "")) + (lib (name elements)(type Legacy)(uri ${KIPRJMOD}/elements.lib)(options "")(descr "")) +) diff --git a/F0-nolib/Servo/main.c b/F0-nolib/Servo/main.c new file mode 100644 index 0000000..63eebf4 --- /dev/null +++ b/F0-nolib/Servo/main.c @@ -0,0 +1,63 @@ +/* + * main.c + * + * Copyright 2018 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 "hardware.h" +#include "mainloop.h" +#include "protocol.h" +#include "usart.h" +#include // memcpy +#include + + +volatile uint32_t Tms = 0; + +// Called when systick fires +void sys_tick_handler(void){ + ++Tms; +} + +int main(void){ + char *txt; + hw_setup(); + SysTick_Config(6000, 1); + SEND_BLK("Servos controller v0.1\n"); + if(RCC->CSR & RCC_CSR_IWDGRSTF){ // watchdog reset occured + SEND_BLK("WDGRESET=1"); + } + if(RCC->CSR & RCC_CSR_SFTRSTF){ // software reset occured + SEND_BLK("SOFTRESET=1"); + } + RCC->CSR |= RCC_CSR_RMVF; // remove reset flags + while (1){ + IWDG->KR = IWDG_REFRESH; + if(usart1_getline(&txt)){ // usart1 received command, process it + txt = process_command(txt); + }else txt = NULL; + if(txt){ // text waits for sending + while(ALL_OK != usart1_send(txt, 0)){ + IWDG->KR = IWDG_REFRESH; + } + } + mainloop(); + IWDG->KR = IWDG_REFRESH; + usart1_sendbuf(); + } +} diff --git a/F0-nolib/Servo/mainloop.c b/F0-nolib/Servo/mainloop.c new file mode 100644 index 0000000..9c00691 --- /dev/null +++ b/F0-nolib/Servo/mainloop.c @@ -0,0 +1,29 @@ +/* + * This file is part of the Chiller 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 "adc.h" +#include "hardware.h" +#include "mainloop.h" + +/** + * @brief mainloop - the main servos loop + * by timer check current states & change them + */ +void mainloop(){ + ; +} diff --git a/F0-nolib/Servo/mainloop.h b/F0-nolib/Servo/mainloop.h new file mode 100644 index 0000000..40e35f8 --- /dev/null +++ b/F0-nolib/Servo/mainloop.h @@ -0,0 +1,21 @@ +/* + * This file is part of the Chiller 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 + +void mainloop(); + diff --git a/F0-nolib/Servo/protocol.c b/F0-nolib/Servo/protocol.c new file mode 100644 index 0000000..52f8c85 --- /dev/null +++ b/F0-nolib/Servo/protocol.c @@ -0,0 +1,99 @@ +/* + * This file is part of the Chiller 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 "hardware.h" +#include "protocol.h" +#include "usart.h" +#include "adc.h" +#include "mainloop.h" + +extern uint8_t crit_error; + +#ifdef EBUG +/** + * @brief debugging_proc - debugging functions + * @param command - rest of cmd + */ +static void debugging_proc(const char *command){ + const char *ptr = command; + int i; + switch(*ptr++){ + case 'w': + usart1_send("Test watchdog", 0); + while(1){nop();} + break; + case 'A': // raw ADC values depending on next symbol + i = *ptr++ - '0'; + if(i < 0 || i > NUMBER_OF_ADC_CHANNELS){ + usart1_send("Wrong channel nuber!", 0); + return; + } + put_string("ADC value: "); + put_uint(getADCval(i)); + put_string(", "); + usart1_sendbuf(); + break; + default: + break; + } +} +#endif + +/** + * @brief process_command - command parser + * @param command - command text (all inside [] without spaces) + * @return text to send over terminal or NULL + */ +char *process_command(const char *command){ + const char *ptr = command; + char *ret = NULL; + usart1_sendbuf(); // send buffer (if it is already filled) + switch(*ptr++){ + case '?': // help + SEND_BLK( + "R - reset\n" + "t - get MCU temperature (approx.)\n" + "V - get Vdd" + ); +#ifdef EBUG + SEND_BLK("d -> goto debug:\n" + "\tAx - get raw ADCx value\n" + "\tw - test watchdog" + ); +#endif + break; + case 'R': // reset MCU + NVIC_SystemReset(); + break; + case 't': // get mcu T + put_string("MCUTEMP10="); + put_int(getMCUtemp()); + break; + case 'V': // get Vdd + put_string("VDD100="); + put_uint(getVdd()); + break; +#ifdef EBUG + case 'd': + debugging_proc(ptr); + return NULL; + break; +#endif + } + usart1_sendbuf(); + return ret; +} diff --git a/F0-nolib/Servo/protocol.h b/F0-nolib/Servo/protocol.h new file mode 100644 index 0000000..d3ededf --- /dev/null +++ b/F0-nolib/Servo/protocol.h @@ -0,0 +1,24 @@ +/* + * This file is part of the Chiller 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 PROTOCOL_C +#define PROTOCOL_C +#include + +char *process_command(const char *command); + +#endif // PROTOCOL_C diff --git a/F0-nolib/Servo/servo.bin b/F0-nolib/Servo/servo.bin new file mode 100755 index 0000000..c00bb13 Binary files /dev/null and b/F0-nolib/Servo/servo.bin differ diff --git a/F0-nolib/Servo/usart.c b/F0-nolib/Servo/usart.c new file mode 100644 index 0000000..ec54a86 --- /dev/null +++ b/F0-nolib/Servo/usart.c @@ -0,0 +1,294 @@ +/* + * usart.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 "usart.h" +#include // memcpy + +extern volatile uint32_t Tms; + +static int datalen[2] = {0,0}; // received data line length (including '\n') + +uint8_t bufovr = 0; // input buffer overfull + +static uint8_t linerdy = 0 // received data ready + ,dlen = 0 // length of data in current buffer + ,txrdy = 1 // transmission done +; + +static int rbufno = 0; // current rbuf number +static char rbuf[2][UARTBUFSZ+1], tbuf[UARTBUFSZ]; // receive & transmit buffers +static char *recvdata = NULL; + +static char trbuf[UARTBUFSZ+1]; // auxiliary buffer for data transmission +static int trbufidx = 0; + +int put_char(char c){ + if(trbufidx >= UARTBUFSZ - 1){ + if(ALL_OK != usart1_sendbuf()) return 1; + } + trbuf[trbufidx++] = c; + return 0; +} +// write zero-terminated string +int put_string(const char *str){ + while(*str){ + if(put_char(*str++)) return 1; //error! shouldn't be!!! + } + return 0; // all OK +} +/** + * Fill trbuf with integer value + * @param N - integer value + * @return 1 if buffer overflow; oterwise return 0 + */ +int put_int(int32_t N){ + if(N < 0){ + if(put_char('-')) return 1; + N = -N; + } + return put_uint((uint32_t) N); +} +int put_uint(uint32_t N){ + char buf[10]; + int L = 0; + if(N){ + while(N){ + buf[L++] = N % 10 + '0'; + N /= 10; + } + while(L--) if(put_char(buf[L])) return 1; + }else if(put_char('0')) return 1; + return 0; +} +/** + * @brief usart1_sendbuf - send temporary transmission buffer (trbuf) over USART + * @return Tx status + */ +TXstatus usart1_sendbuf(){ + int len = trbufidx; + trbufidx = 0; + if(len == 0) return ALL_OK; + else if(len > UARTBUFSZ) len = UARTBUFSZ; + return usart1_send(trbuf, len); +} + +void USART1_config(){ + /* Enable the peripheral clock of GPIOA */ + RCC->AHBENR |= RCC_AHBENR_GPIOAEN; + /* GPIO configuration for USART1 signals */ + /* (1) Select AF mode (10) on PA9 and PA10 */ + /* (2) AF1 for USART1 signals */ + GPIOA->MODER = (GPIOA->MODER & ~(GPIO_MODER_MODER9|GPIO_MODER_MODER10))\ + | (GPIO_MODER_MODER9_1 | GPIO_MODER_MODER10_1); /* (1) */ + GPIOA->AFR[1] = (GPIOA->AFR[1] &~ (GPIO_AFRH_AFRH1 | GPIO_AFRH_AFRH2))\ + | (1 << (1 * 4)) | (1 << (2 * 4)); /* (2) */ + /* Enable the peripheral clock USART1 */ + RCC->APB2ENR |= RCC_APB2ENR_USART1EN; + /* Configure USART1 */ + /* (1) oversampling by 16, 115200 baud */ + /* (2) 8 data bit, 1 start bit, 1 stop bit, no parity */ + USART1->BRR = 480000 / 1152; /* (1) */ + USART1->CR1 = USART_CR1_TE | USART_CR1_RE | USART_CR1_UE; /* (2) */ + /* polling idle frame Transmission */ + while(!(USART1->ISR & USART_ISR_TC)){} + USART1->ICR |= USART_ICR_TCCF; /* clear TC flag */ + USART1->CR1 |= USART_CR1_RXNEIE; /* enable TC, TXE & RXNE interrupt */ + RCC->AHBENR |= RCC_AHBENR_DMA1EN; + DMA1_Channel2->CPAR = (uint32_t) &(USART1->TDR); // periph + DMA1_Channel2->CMAR = (uint32_t) tbuf; // mem + DMA1_Channel2->CCR |= DMA_CCR_MINC | DMA_CCR_DIR | DMA_CCR_TCIE; // 8bit, mem++, mem->per, transcompl irq + USART1->CR3 = USART_CR3_DMAT; + NVIC_SetPriority(DMA1_Channel2_3_IRQn, 3); + NVIC_EnableIRQ(DMA1_Channel2_3_IRQn); + /* Configure IT */ + /* (3) Set priority for USART1_IRQn */ + /* (4) Enable USART1_IRQn */ + NVIC_SetPriority(USART1_IRQn, 0); /* (3) */ + NVIC_EnableIRQ(USART1_IRQn); /* (4) */ +} + +void usart1_isr(){ + static uint8_t timeout = 1 // == 0 for human interface without timeout + ,nctr = 0 // counter of '#' received + ,incmd = 0 // ==1 - inside command + ; + static uint32_t tmout = 0; + if(USART1->ISR & USART_ISR_RXNE){ // RX not emty - receive next char + // read RDR clears flag + uint8_t rb = USART1->RDR; + if(timeout && rb == '#'){ // chek '#' without timeout + if(++nctr == 4){ // "####" received - turn off timeout + timeout = 0; + nctr = 0; + datalen[rbufno] = 0; // reset all incoming data + incmd = 0; + return; + } + }else nctr = 0; + if(!incmd){ + if(rb == '['){ // open command or reset previoud input + datalen[rbufno] = 0; + incmd = 1; + } + return; + } + if(timeout){ // check timeout only inside commands + if(tmout && Tms >= tmout){ // set overflow flag + bufovr = 1; + datalen[rbufno] = 0; + }else{ + tmout = Tms + TIMEOUT_MS; + if(!tmout) tmout = 1; // prevent 0 + } + } + switch(rb){ + case '[': + datalen[rbufno] = 0; + tmout = 0; + break; + case ']': // close command - line ready! + dlen = datalen[rbufno]; + if(dlen){ + linerdy = 1; + incmd = 0; + recvdata = rbuf[rbufno]; + rbuf[rbufno][dlen] = 0; + rbufno = !rbufno; + datalen[rbufno] = 0; + } + tmout = 0; + break; + case '\r': + case '\n': + case ' ': + case '\t': + return; + break; + default: + break; + } + + if(datalen[rbufno] < UARTBUFSZ){ // put next char into buf + rbuf[rbufno][datalen[rbufno]++] = rb; + }else{ // buffer overrun + bufovr = 1; + datalen[rbufno] = 0; + incmd = 0; + tmout = 0; + } + } +} + +void dma1_channel2_3_isr(){ + if(DMA1->ISR & DMA_ISR_TCIF2){ // Tx + DMA1->IFCR |= DMA_IFCR_CTCIF2; // clear TC flag + txrdy = 1; + } +} + +/** + * return length of received data (without trailing zero) + */ +int usart1_getline(char **line){ + if(!linerdy) return 0; + linerdy = 0; + if(bufovr){ + bufovr = 0; + return 0; + } + *line = recvdata; + return dlen; +} + +/** + * @brief usart1_send send buffer `str` adding trailing '\n' + * @param str - string to send (without '\n' at end) + * @param len - its length or 0 to auto count + * @return + */ +TXstatus usart1_send(const char *str, int len){ + if(!txrdy) return LINE_BUSY; + if(len > UARTBUFSZ - 1) return STR_TOO_LONG; + txrdy = 0; + if(len == 0){ + const char *ptr = str; + while(*ptr++) ++len; + } + if(len == 0) return ALL_OK; + DMA1_Channel2->CCR &= ~DMA_CCR_EN; + memcpy(tbuf, str, len); + tbuf[len++] = '\n'; + DMA1_Channel2->CNDTR = len; + DMA1_Channel2->CCR |= DMA_CCR_EN; // start transmission + return ALL_OK; +} + +TXstatus usart1_send_blocking(const char *str, int len){ + if(!txrdy) return LINE_BUSY; + if(len == 0){ + const char *ptr = str; + while(*ptr++) ++len; + } + if(len == 0) return ALL_OK; + for(int i = 0; i < len; ++i){ + USART1->TDR = *str++; + while(!(USART1->ISR & USART_ISR_TXE)); + } + USART1->TDR = '\n'; + while(!(USART1->ISR & USART_ISR_TC)); + txrdy = 1; + return ALL_OK; +} + +// read `buf` and get first integer `N` in it +// @return pointer to first non-number if all OK or NULL if first symbol isn't a space or number +char *getnum(const char *buf, int32_t *N){ + char c; + int positive = -1; + int32_t val = 0; + //usart1_send_blocking(buf, 0); + while((c = *buf++)){ + if(c == '\t' || c == ' '){ + if(positive < 0) continue; // beginning spaces + else break; // spaces after number + } + if(c == '-'){ + if(positive < 0){ + positive = 0; + continue; + }else break; // there already was `-` or number + } + if(c < '0' || c > '9') break; + if(positive < 0) positive = 1; + val = val * 10 + (int32_t)(c - '0'); + } + if(positive != -1){ + if(positive == 0){ + if(val == 0) return NULL; // single '-' + val = -val; + } + *N = val; + }else return NULL; +/* usart1_sendbuf(); + put_uint(val); + put_char('\n');*/ + return (char*)buf-1; +} diff --git a/F0-nolib/Servo/usart.h b/F0-nolib/Servo/usart.h new file mode 100644 index 0000000..9b7f8dd --- /dev/null +++ b/F0-nolib/Servo/usart.h @@ -0,0 +1,59 @@ +/* + * usart.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 __USART_H__ +#define __USART_H__ + +#include "stm32f0.h" + +// input and output buffers size +#define UARTBUFSZ (64) +// timeout between data bytes +#define TIMEOUT_MS (100) + +typedef enum{ + ALL_OK, + LINE_BUSY, + STR_TOO_LONG +} TXstatus; + +#define usart1ovr() (bufovr) + +// send constant string +#define SEND_BLK(x) do{while(LINE_BUSY == usart1_send_blocking(x, sizeof(x)-1));}while(0) +#define SEND(x) do{while(LINE_BUSY == usart1_send(x, sizeof(x)-1));}while(0) + +extern uint8_t bufovr; + +void USART1_config(); +int usart1_getline(char **line); +TXstatus usart1_send(const char *str, int len); +TXstatus usart1_send_blocking(const char *str, int len); +TXstatus usart1_sendbuf(); + +int put_char(char c); +int put_string(const char *str); +int put_int(int32_t N); +int put_uint(uint32_t N); + +char *getnum(const char *buf, int32_t *N); + +#endif // __USART_H__ diff --git a/F0-nolib/canbus/kicad/fp-info-cache b/F0-nolib/canbus/kicad/fp-info-cache new file mode 100644 index 0000000..573541a --- /dev/null +++ b/F0-nolib/canbus/kicad/fp-info-cache @@ -0,0 +1 @@ +0 diff --git a/F0-nolib/canbus/kicad/stm32.pro b/F0-nolib/canbus/kicad/stm32.pro index 1aa9434..3401bde 100644 --- a/F0-nolib/canbus/kicad/stm32.pro +++ b/F0-nolib/canbus/kicad/stm32.pro @@ -1,4 +1,4 @@ -update=Ср 30 янв 2019 22:57:36 +update=Вс 10 мар 2019 23:57:48 version=1 last_client=kicad [pcbnew] diff --git a/F0-nolib/inc/F0/stm32f0.h b/F0-nolib/inc/F0/stm32f0.h index 763ccef..3b99a87 100644 --- a/F0-nolib/inc/F0/stm32f0.h +++ b/F0-nolib/inc/F0/stm32f0.h @@ -105,19 +105,19 @@ TRUE_INLINE void sysreset(void){ /* Wait till PLL is used as system clock source */ while ((RCC->CFGR & RCC_CFGR_SWS) != RCC_CFGR_SWS_PLL){} } - +/* wrong TRUE_INLINE void StartHSE(){ // disable PLL RCC->CR &= ~RCC_CR_PLLON; RCC->CR |= RCC_CR_HSEON; - while ((RCC->CIR & RCC_CIR_HSERDYF) != 0); + while ((RCC->CIR & RCC_CIR_HSERDYF) == 0); RCC->CIR |= RCC_CIR_HSERDYC; // clear rdy flag - /* PLL configuration = (HSE) * 12 = ~48 MHz */ + // PLL configuration = (HSE) * 12 = ~48 MHz RCC->CFGR &= ~(RCC_CFGR_PLLSRC | RCC_CFGR_PLLMUL); RCC->CFGR |= RCC_CFGR_PLLSRC_HSE_PREDIV | RCC_CFGR_PLLMUL12; RCC->CR |= RCC_CR_PLLON; while ((RCC->CFGR & (uint32_t)RCC_CFGR_SWS) != (uint32_t)RCC_CFGR_SWS_PLL){} -} +} */ #if !defined (STM32F030x4) && !defined (STM32F030x6) && !defined (STM32F030x8) && !defined (STM32F031x6) && !defined (STM32F038xx) && !defined (STM32F030xC) TRUE_INLINE void StartHSI48(){