add Two sensors measurement for PCB with screen

This commit is contained in:
eddyem 2019-07-30 16:56:43 +03:00
parent b0dccf956b
commit 4bd57d704a
50 changed files with 54479 additions and 0 deletions

View File

@ -3,4 +3,5 @@
- src4multiplexer - source code for I2C multiplexer (48 channels * 2 sensors)
- Tcalc - test code for temperature calculation inside MCU
- Tcalc_screen - Tcalc displaying T on OLED screen
- Tcalc_screen_ver2 - version for ../kicad/Sensors_tester_with_screen
- TSYS_controller - MAIN controller code (USB, CAN, UART1)

View File

@ -0,0 +1,149 @@
BINARY = tcalc_screen
BOOTPORT ?= /dev/ttyUSB0
BOOTSPEED ?= 9600
# MCU FAMILY
FAMILY = F0
# MCU code
MCU = F042x6
# hardware definitions
#DEFS := -DUSARTNUM=2 -DI2CPINS=A9A10
DEFS := -DUSARTNUM=1 -DI2CPINS=67
DEFS += -DEBUG
# change this linking script depending on particular MCU model,
# for example, if you have STM32F103VBT6, you should write:
LDSCRIPT = ld/stm32f042k.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
OPREFIX ?= /opt/bin/arm-none-eabi
#PREFIX ?= /usr/x86_64-pc-linux-gnu/arm-none-eabi/gcc-bin/7.3.0/arm-none-eabi
PREFIX ?= $(OPREFIX)
RM := rm -f
RMDIR := rmdir
CC := $(PREFIX)-gcc
LD := $(PREFIX)-gcc
AR := $(PREFIX)-ar
AS := $(PREFIX)-as
OBJCOPY := $(OPREFIX)-objcopy
OBJDUMP := $(OPREFIX)-objdump
GDB := $(OPREFIX)-gdb
STFLASH := $(shell which st-flash)
STBOOT := $(shell which stm32flash)
DFUUTIL := $(shell which dfu-util)
###############################################################################
# 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)/F0 -I$(INC_DIR)/cm
LIB_DIR := $(INC_DIR)/ld
###############################################################################
# C flags
CFLAGS += -O2 -g -MD -D__thumb2__=1
CFLAGS += -Wall -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 $<
#$(OBJDIR)/%.d: %.c $(OBJDIR)
# $(CC) -MM -MG $< | sed -e 's,^\([^:]*\)\.o[ ]*:,$(@D)/\1.o $(@D)/\1.d:,' >$@
$(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
dfuboot: $(BIN)
@echo " LOAD $(BIN) THROUGH DFU"
$(DFUUTIL) -a0 -D $(BIN) -s 0x08000000
flash: $(BIN)
@echo " FLASH $(BIN)"
$(STFLASH) write $(BIN) 0x8000000
boot: $(BIN)
@echo " LOAD $(BIN) through bootloader"
$(STBOOT) -b$(BOOTSPEED) $(BOOTPORT) -w $(BIN)
gentags:
CFLAGS="$(CFLAGS) $(DEFS)" geany -g $(BINARY).c.tags *[hc] 2>/dev/null
.PHONY: clean flash boot dfuboot gentags

View File

@ -0,0 +1,8 @@
# Check temperature on sensors pair and show values of T @ 0.96'' oLED display
# also test by USART (115200).
Code for NUCLEO-042
### PINOUT
- I2C: PA9 (SCL) & PA10 (SDA)
- USART2: PA2 (Tx) & PA15 (Rx)
- SPI for screen: PA4 (CS), PA5 (SCL), PA7 (MOSI), PB4 (RST), PB5 (D/C)

View File

@ -0,0 +1,106 @@
/*
* geany_encoding=koi8-r
* hardware.c - hardware-dependent macros & functions
*
* Copyright 2018 Edward V. Emelianov <eddy@sao.ru, edward.emelianoff@gmail.com>
*
* 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 "hardware.h"
static I2C_SPEED curI2Cspeed = LOW_SPEED;
void gpio_setup(void){
RCC->AHBENR |= RCC_AHBENR_GPIOCEN | RCC_AHBENR_GPIOBEN | RCC_AHBENR_GPIOAEN;
// Set LEDS (PA14/15)
GPIOA->MODER = GPIO_MODER_MODER14_O | GPIO_MODER_MODER15_O;
// PC13 - digital output - poweron
GPIOC->OTYPER = 1 << 13; // opendrain
GPIOC->MODER = GPIO_MODER_MODER13_O;
// D/C & Reset pins: D/C - PB1, Reset - PB0, CS - PB2
GPIOB->MODER |= GPIO_MODER_MODER0_O | GPIO_MODER_MODER1_O | GPIO_MODER_MODER2_O;
}
void spi_setup(){
/* Enable the peripheral clock of GPIOA */
RCC->AHBENR |= RCC_AHBENR_GPIOAEN;
/* (1) Select AF mode (10) on PA5, PA7, push-pull @PA4. MISO disabled (simplex mode)*/
/* (2) AF0 for SPI1 signals */
GPIOA->MODER = (GPIOA->MODER
& ~(GPIO_MODER_MODER5 | GPIO_MODER_MODER7)) \
| (GPIO_MODER_MODER5_AF | GPIO_MODER_MODER7_AF); /* (1) */
GPIOA->AFR[0] = (GPIOA->AFR[0] & \
~(GPIO_AFRL_AFRL5 | GPIO_AFRL_AFRL7)); /* (2) */
/* Enable the peripheral clock SPI1 */
RCC->APB2ENR |= RCC_APB2ENR_SPI1EN;
/* Configure SPI1 in master */
/* (1) Master selection, BR: Fpclk/256, software SS management
CPOL and CPHA at zero (rising first edge) */
/* (2) Slave select output disabled, 8-bit Rx fifo */
/* (3) Enable SPI1 */
SPI1->CR1 = SPI_CR1_MSTR | SPI_CR1_BR | SPI_CR1_SSM | SPI_CR1_SSI; /* (1) */
SPI1->CR2 = SPI_CR2_FRXTH | SPI_CR2_DS_2 | SPI_CR2_DS_1 | SPI_CR2_DS_0; /* (2) */
SPI1->CR1 |= SPI_CR1_SPE; /* (3) */
CS_HI(); RST_HI();
}
void i2c_setup(I2C_SPEED speed){
if(speed == CURRENT_SPEED){
speed = curI2Cspeed;
}else{
curI2Cspeed = speed;
}
I2C1->CR1 = 0;
#if I2CPINS == 910
/*
* GPIO Resources: I2C1_SCL - PA9, I2C1_SDA - PA10
* GPIOA->AFR[1]
*/
GPIOA->AFR[1] &= ~0xff0; // alternate function F4 for PA9/PA10
GPIOA->AFR[1] |= 0x440;
GPIOA->MODER &= ~(GPIO_MODER_MODER9 | GPIO_MODER_MODER10);
GPIOA->MODER |= GPIO_MODER_MODER9_AF | GPIO_MODER_MODER10_AF; // alternate function
GPIOA->OTYPER |= GPIO_OTYPER_OT_9 | GPIO_OTYPER_OT_10; // opendrain
//GPIOA->OTYPER |= GPIO_OTYPER_OT_10; // opendrain
#elif I2CPINS == 67
/*
* GPIO Resources: I2C1_SCL - PB6, I2C1_SDA - PB7 (AF1)
* GPIOB->AFR[0] -> 1<<6*4 | 1<<7*4 = 0x11000000
*/
GPIOB->AFR[0] = (GPIOB->AFR[0] & ~0xff000000) | 0x11000000;
GPIOB->MODER = (GPIOB->MODER & ~(GPIO_MODER_MODER6 | GPIO_MODER_MODER7)) |
GPIO_MODER_MODER6_AF | GPIO_MODER_MODER7_AF;
GPIOB->OTYPER |= GPIO_OTYPER_OT_6 | GPIO_OTYPER_OT_7;
#else // undefined
#error "Not implemented"
#endif
// I2C
RCC->APB1ENR |= RCC_APB1ENR_I2C1EN; // timing
RCC->CFGR3 |= RCC_CFGR3_I2C1SW; // use sysclock for timing
if(speed == LOW_SPEED){ // 10kHz
// PRESC=B, SCLDEL=4, SDADEL=2, SCLH=0xC3, SCLL=0xB0
I2C1->TIMINGR = (0xB<<28) | (4<<20) | (2<<16) | (0xC3<<8) | (0xB0);
}else if(speed == HIGH_SPEED){ // 100kHz
I2C1->TIMINGR = (0xB<<28) | (4<<20) | (2<<16) | (0x12<<8) | (0x11);
}else{ // VERYLOW_SPEED - the lowest speed by STM register: 5.8kHz (presc = 16-1 = 15; )
I2C1->TIMINGR = (0xf<<28) | (4<<20) | (2<<16) | (0xff<<8) | (0xff);
}
I2C1->CR1 = I2C_CR1_PE;// | I2C_CR1_RXIE; // Enable I2C & (interrupt on receive - not supported yet)
}

View File

@ -0,0 +1,81 @@
/*
* geany_encoding=koi8-r
* hardware.h
*
* Copyright 2018 Edward V. Emelianov <eddy@sao.ru, edward.emelianoff@gmail.com>
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; if not, write to the Free Software
* Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston,
* MA 02110-1301, USA.
*
*/
#pragma once
#ifndef __HARDWARE_H__
#define __HARDWARE_H__
#include "stm32f0.h"
// poweroff after 15s when powering by battery
#define UPTIME (33)
// LED0 - PA14
#define LED0_port GPIOA
#define LED0_pin (1<<14)
// LED1 - PA15
#define LED1_port GPIOA
#define LED1_pin (1<<15)
#define CONCAT(a,b) a ## b
#define STR_HELPER(s) #s
#define STR(s) STR_HELPER(s)
#define FORMUSART(X) CONCAT(USART, X)
#define USARTX FORMUSART(USARTNUM)
#define LED_blink(x) pin_toggle(x ## _port, x ## _pin)
#define LED_on(x) pin_clear(x ## _port, x ## _pin)
#define LED_off(x) pin_set(x ## _port, x ## _pin)
// PA1 - USB On (in)
#define USBisOn() (GPIOA->IDR & 1<<1)
// PC13 - power on
#define POWERON() pin_clear(GPIOC, 1<<13)
#define POWEROFF() pin_set(GPIOC, 1<<13)
// oLED
#define RST_PORT GPIOB
#define RST_PIN (1<<0)
#define DC_PORT GPIOB
#define DC_PIN (1<<1)
#define CS_PORT GPIOB
#define CS_PIN (1<<2)
#define RST_HI() do{pin_set(RST_PORT, RST_PIN);}while(0)
#define RST_LO() do{pin_clear(RST_PORT, RST_PIN);}while(0)
#define DC_HI() do{pin_set(DC_PORT, DC_PIN);}while(0)
#define DC_LO() do{pin_clear(DC_PORT, DC_PIN);}while(0)
#define CS_HI() do{pin_set(CS_PORT, CS_PIN);}while(0)
#define CS_LO() do{pin_clear(CS_PORT, CS_PIN);}while(0)
typedef enum{
VERYLOW_SPEED,
LOW_SPEED,
HIGH_SPEED,
CURRENT_SPEED
} I2C_SPEED;
void gpio_setup(void);
void i2c_setup(I2C_SPEED speed);
void spi_setup();
#endif // __HARDWARE_H__

View File

@ -0,0 +1,129 @@
/*
* geany_encoding=koi8-r
* i2c.c
*
* Copyright 2017 Edward V. Emelianov <eddy@sao.ru, edward.emelianoff@gmail.com>
*
* 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 "hardware.h"
#include "i2c.h"
/**
* I2C for TSYS01
* Speed <= 400kHz (200)
* t_SCLH > 21ns
* t_SCLL > 21ns
* while reading, sends NACK
* after reading get 24bits of T value, we need upper 2 bytes: ADC16 = ADC>>8
* T = (-2) * k4 * 10^{-21} * ADC16^4
* + 4 * k3 * 10^{-16} * ADC16^3
* + (-2) * k2 * 10^{-11} * ADC16^2
* + 1 * k1 * 10^{-6} * ADC16
* +(-1.5)* k0 * 10^{-2}
* All coefficiens are in registers:
* k4 - 0xA2, k3 - 0xA4, k2 - 0xA6, k1 - 0xA8, k0 - 0xAA
*/
extern volatile uint32_t Tms;
static uint32_t cntr;
/**
* write command byte to I2C
* @param addr - device address (TSYS01_ADDR0 or TSYS01_ADDR1)
* @param data - byte to write
* @return 0 if error
*/
uint8_t write_i2c(uint8_t addr, uint8_t data){
cntr = Tms;
I2C1->ICR = 0x3f38; // clear all errors
while(I2C1->ISR & I2C_ISR_BUSY){
IWDG->KR = IWDG_REFRESH;
if(Tms - cntr > I2C_TIMEOUT){
return 0; // check busy
}}
cntr = Tms;
while(I2C1->CR2 & I2C_CR2_START){
IWDG->KR = IWDG_REFRESH;
if(Tms - cntr > I2C_TIMEOUT){
return 0; // check start
}}
//I2C1->ICR = 0x3f38; // clear all errors
I2C1->CR2 = 1<<16 | addr | I2C_CR2_AUTOEND; // 1 byte, autoend
// now start transfer
I2C1->CR2 |= I2C_CR2_START;
cntr = Tms;
while(!(I2C1->ISR & I2C_ISR_TXIS)){ // ready to transmit
IWDG->KR = IWDG_REFRESH;
if(I2C1->ISR & I2C_ISR_NACKF){
I2C1->ICR |= I2C_ICR_NACKCF;
return 0;
}
if(Tms - cntr > I2C_TIMEOUT){
return 0;
}
}
I2C1->TXDR = data; // send data
// wait for data gone
while(I2C1->ISR & I2C_ISR_BUSY){
IWDG->KR = IWDG_REFRESH;
if(Tms - cntr > I2C_TIMEOUT){break;}
}
return 1;
}
/**
* read nbytes (2 or 3) of data from I2C line
* @return 1 if all OK, 0 if NACK or no device found
*/
uint8_t read_i2c(uint8_t addr, uint32_t *data, uint8_t nbytes){
uint32_t result = 0;
cntr = Tms;
//MSG("read_i2c\n");
while(I2C1->ISR & I2C_ISR_BUSY){
IWDG->KR = IWDG_REFRESH;
if(Tms - cntr > I2C_TIMEOUT){
return 0; // check busy
}}
cntr = Tms;
while(I2C1->CR2 & I2C_CR2_START){
IWDG->KR = IWDG_REFRESH;
if(Tms - cntr > I2C_TIMEOUT){
return 0; // check start
}}
// I2C1->ICR = 0x3f38; // clear all errors
// read N bytes
I2C1->CR2 = (nbytes<<16) | addr | 1 | I2C_CR2_AUTOEND | I2C_CR2_RD_WRN;
I2C1->CR2 |= I2C_CR2_START;
uint8_t i;
cntr = Tms;
for(i = 0; i < nbytes; ++i){
while(!(I2C1->ISR & I2C_ISR_RXNE)){ // wait for data
IWDG->KR = IWDG_REFRESH;
if(I2C1->ISR & I2C_ISR_NACKF){
I2C1->ICR |= I2C_ICR_NACKCF;
return 0;
}
if(Tms - cntr > I2C_TIMEOUT){
return 0;
}
}
result = (result << 8) | I2C1->RXDR;
}
*data = result;
return 1;
}

View File

@ -0,0 +1,43 @@
/*
* geany_encoding=koi8-r
* i2c.h
*
* Copyright 2017 Edward V. Emelianov <eddy@sao.ru, edward.emelianoff@gmail.com>
*
* 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 "stm32f0.h"
// timeout of I2C bus in ms
#define I2C_TIMEOUT (100)
// waiting between reads - 2s
#define WAIT_TIME (2000)
// CSB=1, address 1110110
#define TSYS01_ADDR0 (0x76 << 1)
// CSB=0, address 1110111
#define TSYS01_ADDR1 (0x77 << 1)
// registers: reset, read ADC value, start converstion, start of PROM
#define TSYS01_RESET (0x1E)
#define TSYS01_ADC_READ (0x00)
#define TSYS01_START_CONV (0x48)
#define TSYS01_PROM_ADDR0 (0xA0)
// conversion time (with reserve)
#define CONV_TIME (15)
uint8_t read_i2c(uint8_t addr, uint32_t *data, uint8_t nbytes);
uint8_t write_i2c(uint8_t addr, uint8_t data);

View File

@ -0,0 +1,12 @@
/* Linker script for STM32F042x6, 32K flash, 6K RAM. */
/* Define memory regions. */
MEMORY
{
rom (rx) : ORIGIN = 0x08000000, LENGTH = 32K
ram (rwx) : ORIGIN = 0x20000000, LENGTH = 6K
}
/* Include the common ld script. */
INCLUDE stm32f0.ld

View File

@ -0,0 +1,254 @@
/*
* main.c
*
* Copyright 2017 Edward V. Emelianoff <eddy@sao.ru, edward.emelianoff@gmail.com>
*
* 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 "hardware.h"
#include "i2c.h"
#include "proto.h"
#include "ssd1306.h"
#include "usart.h"
#include "usb.h"
static uint16_t coefficients[2][5]; // Coefficients for given sensors
static const uint8_t Taddr[2] = {TSYS01_ADDR0, TSYS01_ADDR1};
volatile uint32_t Tms = 0;
#define TBUFLEN 11
static char Tbuf[2][TBUFLEN] = {0}; // buffer for temperatures
static uint8_t refreshdisplay = 0;
/* Called when systick fires */
void sys_tick_handler(void){
++Tms;
}
uint8_t sprintu(char *buf, uint8_t buflen, uint32_t val){
uint8_t i, l = 0, bpos = 0;
char rbuf[10];
if(!val){
buf[0] = '0';
buf[1] = 0;
return 1;
}else{
while(val){
rbuf[l++] = val % 10 + '0';
val /= 10;
}
if(buflen < l+1) return 0;
bpos = l;
buf[l] = 0;
for(i = 0; i < l; ++i){
buf[--bpos] = rbuf[i];
}
}
return l;
}
/*
// print 32bit unsigned int
void printu(uint32_t val){
char buf[11];
uint8_t l = sprintu(buf, 11, val);
while(LINE_BUSY == usart_send_blocking(buf, l));
}*/
void getcoeffs(uint8_t addr){ // show norm coefficiens
int i;
const uint8_t regs[5] = {0xAA, 0xA8, 0xA6, 0xA4, 0xA2}; // commands for coefficients
uint32_t K;
char numbr = (addr == TSYS01_ADDR0) ? '0' : '1';
uint16_t *coef = coefficients[numbr-'0'];
for(i = 0; i < 5; ++i){
if(write_i2c(addr, regs[i])){
if(read_i2c(addr, &K, 2)){
coef[i] = K;
}
}
}
}
/**
* Get temperature & calculate it by polinome
* T = (-2) * k4 * 10^{-21} * ADC16^4
* + 4 * k3 * 10^{-16} * ADC16^3
* + (-2) * k2 * 10^{-11} * ADC16^2
* + 1 * k1 * 10^{-6} * ADC16
* +(-1.5)* k0 * 10^{-2}
* k0*(-1.5e-2) + 1e-6*val*(k1 + 1e-5*val*(-2*k2 + 1e-5*val*(4*k3 + -2e-5*k4*val)))
* answer is in 100th
*/
uint8_t calc_t(uint32_t t, int i){
if(coefficients[i][0] == 0){
getcoeffs(Taddr[i]);
}
if(coefficients[i][0] == 0){
USEND("no sensor\n");
return 0;
}
if (t < 6500000 || t > 13000000) return 0; // wrong value - too small or too large
int j;
double d = (double)t/256., tmp = 0.;
// k0*(-1.5e-2) + 0.1*1e-5*val*(1*k1 + 1e-5*val*(-2.*k2 + 1e-5*val*(4*k3 + 1e-5*val*(-2*k4))))
const double mul[5] = {-1.5e-2, 1., -2., 4., -2.};
for(j = 4; j > 0; --j){
tmp += mul[j] * (double)coefficients[i][j];
tmp *= 1e-5*d;
}
tmp = tmp/10. + mul[0]*coefficients[i][0];
Tbuf[i][0] = 'T'; Tbuf[i][1] = i + '0';
Tbuf[i][2] = '='; Tbuf[i][3] = ' ';
char *ptr = &Tbuf[i][4];
uint8_t l = TBUFLEN - 4, s;
if(tmp < 0.){
*ptr++ = '-';
tmp = -tmp;
}
uint32_t x = (uint32_t)tmp;
if(x > 120){
*ptr = 0;
return 0; // wrong value
}
s = sprintu(ptr, l, x);
ptr += s; l -= s;
tmp -= x;
*ptr++ = '.'; --l;
x = (uint32_t)(tmp*100);
if(x < 10){
*ptr++ = '0'; --l;
}
s += sprintu(ptr, l, x);
refreshdisplay = 1;
return 1;
}
int main(void){
uint32_t lastT = 0;
int16_t uptime = 0;
uint8_t i;
uint32_t started[2] = {0, 0}; // time of measurements for given sensor started
uint32_t tgot[2] = {0, 0}; // time of last measurements
uint8_t errcnt[2] = {0,0};
sysreset();
SysTick_Config(6000, 1);
gpio_setup();
LED_on(LED0);
usart_setup();
USB_setup();
i2c_setup(LOW_SPEED);
spi_setup();
// reset on start
write_i2c(TSYS01_ADDR0, TSYS01_RESET);
write_i2c(TSYS01_ADDR1, TSYS01_RESET);
ssd1306_Fill(0);
while (1){
IWDG->KR = IWDG_REFRESH; // refresh watchdog
if(refreshdisplay && uptime < UPTIME - 3){
ssd1306_Fill(0);
ssd1306_WriteString(Tbuf[0], Font_11x18, 1);
ssd1306_SetCursor(0, 32);
ssd1306_WriteString(Tbuf[1], Font_11x18, 1);
ssd1306_UpdateScreen();
refreshdisplay = 0;
}
if(lastT > Tms || Tms - lastT > 499){
LED_blink(LED0);
lastT = Tms;
ssd1306_UpdateScreen();
if(USBisOn()){
LED_on(LED1);
uptime = 0;
}else{
LED_off(LED1);
if(++uptime > UPTIME - 3){
ssd1306_Fill(0);
ssd1306_WriteString("Power off!", Font_16x26, 1);
ssd1306_UpdateScreen();
}
if(uptime > UPTIME) POWEROFF();
}
}
ssd1306_process();
for(i = 0; i < 2; ++i){
uint8_t err = 1;
if(started[i]){
if(Tms - started[i] > CONV_TIME){ // poll sensor i
if(write_i2c(Taddr[i], TSYS01_ADC_READ)){
uint32_t t;
if(read_i2c(Taddr[i], &t, 3) && t){
if(!calc_t(t, i)){
//USEND("!calc ");
write_i2c(Taddr[i], TSYS01_RESET);
}else{
err = 0;
tgot[i] = Tms;
}
started[i] = 0;
}else{
//USEND("can't read ");
}
}else{
//USEND("can't write ");
}
}else{
err = 0;
}
}else{
if(Tms - tgot[i] > WAIT_TIME){
if(write_i2c(Taddr[i], TSYS01_START_CONV)){
started[i] = Tms ? Tms : 1;
err = 0;
}else{
//USEND("can't start conv\n");
started[i] = 0;
}
}
}
if(err){
if(!write_i2c(Taddr[i], TSYS01_RESET)){ // sensor's absent? clear its coeff.
i2c_setup(LOW_SPEED);
if(++errcnt[i] > 10){
errcnt[i] = 0;
Tbuf[i][0] = '-';
tgot[i] = 0;
Tbuf[i][1] = 0;
coefficients[i][0] = 0;
refreshdisplay = 1;
}
}
}else errcnt[i] = 0;
}
usb_proc();
uint8_t r = 0;
char inbuf[256];
if((r = USB_receive(inbuf, 255))){
inbuf[r] = 0;
cmd_parser(inbuf, 1);
}
if(usartrx()){ // usart1 received data, store in in buffer
char *txt = NULL;
r = usart_getline(&txt);
txt[r] = 0;
cmd_parser(txt, 0);
}
}
return 0;
}

View File

@ -0,0 +1,164 @@
/*
* geany_encoding=koi8-r
* proto.c
*
* Copyright 2018 Edward V. Emelianov <eddy@sao.ru, edward.emelianoff@gmail.com>
*
* 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 "hardware.h"
#include "i2c.h"
#include "proto.h"
#include "ssd1306.h"
#include "usart.h"
#include "usb.h"
#include <string.h> // strlen, strcpy(
extern volatile uint8_t canerror;
static char buff[UARTBUFSZ+1], *bptr = buff;
static uint8_t blen = 0, USBcmd = 0;
// LEDs are OFF by default
uint8_t noLED = 1;
void sendbuf(){
IWDG->KR = IWDG_REFRESH;
if(blen == 0) return;
*bptr = 0;
if(USBcmd) USB_send(buff);
else while(LINE_BUSY == usart_send(buff, blen)){IWDG->KR = IWDG_REFRESH;}
bptr = buff;
blen = 0;
}
void addtobuf(const char *txt){
IWDG->KR = IWDG_REFRESH;
int l = strlen(txt);
if(l > UARTBUFSZ){
sendbuf();
if(USBcmd) USB_send(txt);
else while(LINE_BUSY == usart_send_blocking(txt, l)){IWDG->KR = IWDG_REFRESH;}
}else{
if(blen+l > UARTBUFSZ){
sendbuf();
}
strcpy(bptr, txt);
bptr += l;
}
*bptr = 0;
blen += l;
}
void bufputchar(char ch){
if(blen > UARTBUFSZ-1){
sendbuf();
}
*bptr++ = ch;
++blen;
}
/**
* @brief cmd_parser - command parsing
* @param txt - buffer with commands & data
* @param isUSB - == 1 if data got from USB
*/
void cmd_parser(char *txt, uint8_t isUSB){
USBcmd = isUSB;
char _1st = txt[0];
sendbuf();
switch(_1st){
case 'b':
ssd1306_Fill(0);
ssd1306_UpdateScreen();
SEND("Clear screen\n");
break;
case 'c':
ssd1306_Fill(0xff);
ssd1306_UpdateScreen();
SEND("Fill screen white\n");
break;
case 'D':
if(write_i2c(TSYS01_ADDR0, TSYS01_RESET)) SEND("Found 0\n");
if(write_i2c(TSYS01_ADDR1, TSYS01_RESET)) SEND("Found 1\n");
break;
case 'h':
i2c_setup(HIGH_SPEED);
SEND("Set I2C speed to high\n");
break;
case 'l':
i2c_setup(LOW_SPEED);
SEND("Set I2C speed to low\n");
break;
case 'r':
i2c_setup(CURRENT_SPEED);
SEND("Reinit I2C with current speed\n");
break;
case 'R': // 'R' - reset both
SEND("Reset\n");
write_i2c(TSYS01_ADDR0, TSYS01_RESET);
write_i2c(TSYS01_ADDR1, TSYS01_RESET);
break;
case 'v':
i2c_setup(VERYLOW_SPEED);
SEND("Set I2C speed to very low\n");
break;
default: // help
SEND(
"ALL little letters - without CAN messaging\n"
"b - clear screen\n"
"c - fill screen white\n"
"D - discovery sensors\n"
"h - high I2C speed\n"
"l - low I2C speed\n"
"r - reinit I2C\n"
"R - reset sensors\n"
"v - very low I2C speed\n"
);
break;
}
sendbuf();
}
// print 32bit unsigned int
void printu(uint32_t val){
char buf[11], *bufptr = &buf[10];
*bufptr = 0;
if(!val){
*(--bufptr) = '0';
}else{
while(val){
*(--bufptr) = val % 10 + '0';
val /= 10;
}
}
addtobuf(bufptr);
}
// print 32bit unsigned int as hex
void printuhex(uint32_t val){
addtobuf("0x");
uint8_t *ptr = (uint8_t*)&val + 3;
int i, j;
for(i = 0; i < 4; ++i, --ptr){
for(j = 1; j > -1; --j){
uint8_t half = (*ptr >> (4*j)) & 0x0f;
if(half < 10) bufputchar(half + '0');
else bufputchar(half - 10 + 'a');
}
}
}

View File

@ -0,0 +1,48 @@
/*
* geany_encoding=koi8-r
* proto.h
*
* Copyright 2018 Edward V. Emelianov <eddy@sao.ru, edward.emelianoff@gmail.com>
*
* 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 __PROTO_H__
#define __PROTO_H__
#include "stm32f0.h"
// macro for static strings
#define SEND(str) do{addtobuf(str);}while(0)
#ifdef EBUG
#define MSG(str) do{addtobuf(__FILE__ " (L" STR(__LINE__) "): " str);}while(0)
#else
#define MSG(str)
#endif
#define newline() do{bufputchar('\n');}while(0)
extern uint8_t noLED;
void cmd_parser(char *buf, uint8_t isUSB);
void addtobuf(const char *txt);
void bufputchar(char ch);
void printu(uint32_t val);
void printuhex(uint32_t val);
void sendbuf();
#endif // __PROTO_H__

View File

@ -0,0 +1,60 @@
/*
* geany_encoding=koi8-r
* spi.c
*
* Copyright 2018 Edward V. Emelianov <eddy@sao.ru, edward.emelianoff@gmail.com>
*
* 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 "spi.h"
#include "usart.h"
extern volatile uint32_t Tms;
static uint32_t tstart;
extern void printu(uint32_t val);
#define CHK(x, msg) do{tstart = Tms; do{if(Tms - tstart > 2){/*printu(SPI1->SR); SEND(msg);*/ return;}}while(x);}while(0)
/**
* send 1 byte blocking
* return 1 on success
*/
void spi_write_byte(uint8_t data){
CHK(!(SPI1->SR & SPI_SR_TXE), "TXEb1\n");
// AHTUNG! without *((uint8_t*) STM32 will try to send TWO bytes (with second byte == 0)
*((uint8_t*)&(SPI1->DR)) = data;
CHK(!(SPI1->SR & SPI_SR_TXE), "TXEb2\n");
CHK(SPI1->SR & SPI_SR_BSY, "BSYb\n");
}
/**
* Blocking rite data to current SPI
* @param data - buffer with data
* @param len - buffer length
* @return 0 in case of error (or 1 in case of success)
*/
void spiWrite(uint8_t *data, uint16_t len){
uint16_t i;
CHK(!(SPI1->SR & SPI_SR_TXE), "TXE1\n");
for(i = 0; i < len; ++i){
*((uint8_t*)&(SPI1->DR)) = data[i];
CHK(!(SPI1->SR & SPI_SR_TXE), "TXE2\n");
}
CHK(SPI1->SR & SPI_SR_BSY, "BSY\n");
}

View File

@ -0,0 +1,33 @@
/*
* geany_encoding=koi8-r
* spi.h
*
* Copyright 2018 Edward V. Emelianov <eddy@sao.ru, edward.emelianoff@gmail.com>
*
* 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 __SPI_H__
#define __SPI_H__
#include "hardware.h"
void spiWrite(uint8_t *data, uint16_t len);
void spi_write_byte(uint8_t data);
#endif // __SPI_H__

View File

@ -0,0 +1,233 @@
/*
* geany_encoding=koi8-r
* ssd1306.c
*
* Copyright 2018 Edward V. Emelianov <eddy@sao.ru, edward.emelianoff@gmail.com>
*
* 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 "spi.h"
#include "ssd1306.h"
#include "usart.h"
#include <string.h> // memset
#define RST_PAUSE (10)
#define BOOT_PAUSE (100)
extern volatile uint32_t Tms;
static uint32_t Tloc;
static uint8_t curx, cury;
typedef enum{
ST_UNINITIALIZED,
ST_RSTSTART,
ST_RESETED,
ST_NEED4UPDATE,
ST_IDLE
} SSD1306_STATE;
static SSD1306_STATE state = ST_UNINITIALIZED;
static uint8_t SSD1306_Buffer[SSD1306_WIDTH * SSD1306_HEIGHT / 8];
static void ssd1306_WriteCommand(uint8_t byte){
CS_LO(); DC_LO();
spi_write_byte(byte);
CS_HI();
}
static void ssd1306_WriteData(uint8_t* buffer, uint16_t len){
CS_LO(); DC_HI();
spiWrite(buffer, len);
CS_HI();
}
// colr == 0 for black or 0xff for white or other values for vertical patterns
void ssd1306_Fill(uint8_t colr){
memset(SSD1306_Buffer, colr, sizeof(SSD1306_Buffer));
curx = 0; cury = 0;
}
// Write ful; screenbuffer to the screen
static void ssd1306_UpdateScreen_(){
uint8_t i;
for(i = 0; i < SSD1306_HEIGHT/8; i++){
ssd1306_WriteCommand(0xB0 + i);
ssd1306_WriteCommand(0x00);
ssd1306_WriteCommand(0x10);
ssd1306_WriteData(&SSD1306_Buffer[SSD1306_WIDTH*i], SSD1306_WIDTH);
}
}
// change status to need4update, return 1 if can't
uint8_t ssd1306_UpdateScreen(){
if(state != ST_IDLE) return 1;
state = ST_NEED4UPDATE;
return 0;
}
static void ssd1306_init(){
const uint8_t cmds[] = {
0xAE, // display off
0x20, // Set memory address
0x10, // 0x00: horizontal addressing mode, 0x01: vertical addressing mode
// 0x10: Page addressing mode(RESET), 0x11: invalid
0xB0, // Set page start address for page addressing mode: 0 ~ 7
0xC8, // Set COM output scan direction
0x00, // Set low column address
0x10, // Set height column address
0x40, // Set start line address
0x81, // Set contrast control register
0xFF,
0xA1, // Set segment re-map 0 to 127
0xA6, // Set normal display
0xA8, // Set multiplex ratio(1 to 64)
0x3F,
0xA4, // 0xa4: ouput follows RAM content, 0xa5: ouput ignores RAM content
0xD3, // Set display offset
0x00, // Not offset
0xD5, // Set display clock divide ratio/oscillator frequency
0xF0, // Set divide ration
0xD9, // Set pre-charge period
0x22,
0xDA, // Set COM pins hardware configuration
0x12,
0xDB, // Set VCOMH
0x20, // 0x20: 0.77*Vcc
0x8D, // Set DC-DC enable
0x14,
0xAF, // turn on SSD1306panel
};
uint8_t idx;
for (idx = 0; idx < sizeof(cmds); ++idx){
ssd1306_WriteCommand(cmds[idx]);
}
}
void ssd1306_Reset(){
state = ST_UNINITIALIZED;
}
void ssd1306_process(){
switch (state){
case ST_UNINITIALIZED: // reset screen
//SEND("ST_UNINITIALIZED\n");
state = ST_RSTSTART;
Tloc = Tms;
// high CS, low RST
CS_HI(); RST_LO();
break;
case ST_RSTSTART: // reset procedure is over
//SEND("ST_RSTSTART\n");
if(Tms - Tloc > RST_PAUSE){
state = ST_RESETED;
RST_HI();
Tloc = Tms;
}
break;
case ST_RESETED: // initialize screen
//SEND("ST_RESETED\n");
if(Tms - Tloc > BOOT_PAUSE){
ssd1306_init();
state = ST_IDLE;
}
break;
case ST_NEED4UPDATE:
//SEND("ST_NEED4UPDATE\n");
ssd1306_UpdateScreen_();
state = ST_IDLE;
break;
case ST_IDLE:
default:
break;
}
;
}
/**
* Draw one pixel in the screenbuffer
* @parameter x, y - coordinate (Y from top to bottom)
* @parameter color == 0 for black
*/
void ssd1306_DrawPixel(uint8_t x, uint8_t y, uint8_t color){
if(x >= SSD1306_WIDTH || y >= SSD1306_HEIGHT) return;
// Check if pixel should be inverted
if(color){
SSD1306_Buffer[x + (y / 8) * SSD1306_WIDTH] |= 1 << (y % 8);
}else{
SSD1306_Buffer[x + (y / 8) * SSD1306_WIDTH] &= ~(1 << (y % 8));
}
}
/**
* Draw 1 char to the screen buffer
* @parameter ch - given char
* @parameter Font - selected font
* @parameter color == 0 for black
* @return 1 if all OK
*/
char ssd1306_WriteChar(char ch, FontDef Font, uint8_t color){
uint32_t i, b, j;
// Check remaining space on current line
if(SSD1306_WIDTH <= (curx + Font.FontWidth)){
if(SSD1306_HEIGHT <= (cury + 2*Font.FontHeight)) return 0;
cury += Font.FontHeight;
curx = 0;
}
if(SSD1306_HEIGHT <= (cury + Font.FontHeight)) return 0;
if(ch == '\n'){
cury += Font.FontHeight;
curx = 0;
}
if(ch < ' ' || ch > '~') return 0; // wrong symbol
// Use the font to write
for(i = 0; i < Font.FontHeight; i++) {
b = Font.data[(ch - 32) * Font.FontHeight + i];
for(j = 0; j < Font.FontWidth; j++){
if((b << j) & 0x8000) {
ssd1306_DrawPixel(curx + j, (cury + i), color);
} else {
ssd1306_DrawPixel(curx + j, (cury + i), !color);
}
}
}
curx += Font.FontWidth;
return ch;
}
// Write full string to screenbuffer
char ssd1306_WriteString(char* str, FontDef Font, uint8_t color){
// Write until null-byte
while (*str){
if(!ssd1306_WriteChar(*str, Font, color)){
// Char could not be written
return *str;
}
// Next char
str++;
}
// Everything ok - return 0
return 0;
}
// Position the cursor
void ssd1306_SetCursor(uint8_t x, uint8_t y){
if(x >= SSD1306_WIDTH || y > SSD1306_HEIGHT) return;
curx = x;
cury = y;
}

View File

@ -0,0 +1,50 @@
/*
* geany_encoding=koi8-r
* ssd1306.h
*
* Copyright 2018 Edward V. Emelianov <eddy@sao.ru, edward.emelianoff@gmail.com>
*
* 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 __SSD1306_H__
#define __SSD1306_H__
#include "ssd1306_fonts.h"
// SSD1306 OLED height in pixels
#ifndef SSD1306_HEIGHT
#define SSD1306_HEIGHT 64
#endif
// SSD1306 width in pixels
#ifndef SSD1306_WIDTH
#define SSD1306_WIDTH 128
#endif
void ssd1306_process();
uint8_t ssd1306_UpdateScreen();
void ssd1306_Reset();
void ssd1306_DrawPixel(uint8_t x, uint8_t y, uint8_t color);
char ssd1306_WriteChar(char ch, FontDef Font, uint8_t color);
void ssd1306_Fill(uint8_t colr);
char ssd1306_WriteString(char* str, FontDef Font, uint8_t color);
void ssd1306_SetCursor(uint8_t x, uint8_t y);
#endif // __SSD1306_H__

View File

@ -0,0 +1,301 @@
#include "ssd1306_fonts.h"
static const uint16_t Font7x10 [] = {
0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, // sp
0x1000, 0x1000, 0x1000, 0x1000, 0x1000, 0x1000, 0x0000, 0x1000, 0x0000, 0x0000, // !
0x2800, 0x2800, 0x2800, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, // "
0x2400, 0x2400, 0x7C00, 0x2400, 0x4800, 0x7C00, 0x4800, 0x4800, 0x0000, 0x0000, // #
0x3800, 0x5400, 0x5000, 0x3800, 0x1400, 0x5400, 0x5400, 0x3800, 0x1000, 0x0000, // $
0x2000, 0x5400, 0x5800, 0x3000, 0x2800, 0x5400, 0x1400, 0x0800, 0x0000, 0x0000, // %
0x1000, 0x2800, 0x2800, 0x1000, 0x3400, 0x4800, 0x4800, 0x3400, 0x0000, 0x0000, // &
0x1000, 0x1000, 0x1000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, // '
0x0800, 0x1000, 0x2000, 0x2000, 0x2000, 0x2000, 0x2000, 0x2000, 0x1000, 0x0800, // (
0x2000, 0x1000, 0x0800, 0x0800, 0x0800, 0x0800, 0x0800, 0x0800, 0x1000, 0x2000, // )
0x1000, 0x3800, 0x1000, 0x2800, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, // *
0x0000, 0x0000, 0x1000, 0x1000, 0x7C00, 0x1000, 0x1000, 0x0000, 0x0000, 0x0000, // +
0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x1000, 0x1000, 0x1000, // ,
0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x3800, 0x0000, 0x0000, 0x0000, 0x0000, // -
0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x1000, 0x0000, 0x0000, // .
0x0800, 0x0800, 0x1000, 0x1000, 0x1000, 0x1000, 0x2000, 0x2000, 0x0000, 0x0000, // /
0x3800, 0x4400, 0x4400, 0x5400, 0x4400, 0x4400, 0x4400, 0x3800, 0x0000, 0x0000, // 0
0x1000, 0x3000, 0x5000, 0x1000, 0x1000, 0x1000, 0x1000, 0x1000, 0x0000, 0x0000, // 1
0x3800, 0x4400, 0x4400, 0x0400, 0x0800, 0x1000, 0x2000, 0x7C00, 0x0000, 0x0000, // 2
0x3800, 0x4400, 0x0400, 0x1800, 0x0400, 0x0400, 0x4400, 0x3800, 0x0000, 0x0000, // 3
0x0800, 0x1800, 0x2800, 0x2800, 0x4800, 0x7C00, 0x0800, 0x0800, 0x0000, 0x0000, // 4
0x7C00, 0x4000, 0x4000, 0x7800, 0x0400, 0x0400, 0x4400, 0x3800, 0x0000, 0x0000, // 5
0x3800, 0x4400, 0x4000, 0x7800, 0x4400, 0x4400, 0x4400, 0x3800, 0x0000, 0x0000, // 6
0x7C00, 0x0400, 0x0800, 0x1000, 0x1000, 0x2000, 0x2000, 0x2000, 0x0000, 0x0000, // 7
0x3800, 0x4400, 0x4400, 0x3800, 0x4400, 0x4400, 0x4400, 0x3800, 0x0000, 0x0000, // 8
0x3800, 0x4400, 0x4400, 0x4400, 0x3C00, 0x0400, 0x4400, 0x3800, 0x0000, 0x0000, // 9
0x0000, 0x0000, 0x1000, 0x0000, 0x0000, 0x0000, 0x0000, 0x1000, 0x0000, 0x0000, // :
0x0000, 0x0000, 0x0000, 0x1000, 0x0000, 0x0000, 0x0000, 0x1000, 0x1000, 0x1000, // ;
0x0000, 0x0000, 0x0C00, 0x3000, 0x4000, 0x3000, 0x0C00, 0x0000, 0x0000, 0x0000, // <
0x0000, 0x0000, 0x0000, 0x7C00, 0x0000, 0x7C00, 0x0000, 0x0000, 0x0000, 0x0000, // =
0x0000, 0x0000, 0x6000, 0x1800, 0x0400, 0x1800, 0x6000, 0x0000, 0x0000, 0x0000, // >
0x3800, 0x4400, 0x0400, 0x0800, 0x1000, 0x1000, 0x0000, 0x1000, 0x0000, 0x0000, // ?
0x3800, 0x4400, 0x4C00, 0x5400, 0x5C00, 0x4000, 0x4000, 0x3800, 0x0000, 0x0000, // @
0x1000, 0x2800, 0x2800, 0x2800, 0x2800, 0x7C00, 0x4400, 0x4400, 0x0000, 0x0000, // A
0x7800, 0x4400, 0x4400, 0x7800, 0x4400, 0x4400, 0x4400, 0x7800, 0x0000, 0x0000, // B
0x3800, 0x4400, 0x4000, 0x4000, 0x4000, 0x4000, 0x4400, 0x3800, 0x0000, 0x0000, // C
0x7000, 0x4800, 0x4400, 0x4400, 0x4400, 0x4400, 0x4800, 0x7000, 0x0000, 0x0000, // D
0x7C00, 0x4000, 0x4000, 0x7C00, 0x4000, 0x4000, 0x4000, 0x7C00, 0x0000, 0x0000, // E
0x7C00, 0x4000, 0x4000, 0x7800, 0x4000, 0x4000, 0x4000, 0x4000, 0x0000, 0x0000, // F
0x3800, 0x4400, 0x4000, 0x4000, 0x5C00, 0x4400, 0x4400, 0x3800, 0x0000, 0x0000, // G
0x4400, 0x4400, 0x4400, 0x7C00, 0x4400, 0x4400, 0x4400, 0x4400, 0x0000, 0x0000, // H
0x3800, 0x1000, 0x1000, 0x1000, 0x1000, 0x1000, 0x1000, 0x3800, 0x0000, 0x0000, // I
0x0400, 0x0400, 0x0400, 0x0400, 0x0400, 0x0400, 0x4400, 0x3800, 0x0000, 0x0000, // J
0x4400, 0x4800, 0x5000, 0x6000, 0x5000, 0x4800, 0x4800, 0x4400, 0x0000, 0x0000, // K
0x4000, 0x4000, 0x4000, 0x4000, 0x4000, 0x4000, 0x4000, 0x7C00, 0x0000, 0x0000, // L
0x4400, 0x6C00, 0x6C00, 0x5400, 0x4400, 0x4400, 0x4400, 0x4400, 0x0000, 0x0000, // M
0x4400, 0x6400, 0x6400, 0x5400, 0x5400, 0x4C00, 0x4C00, 0x4400, 0x0000, 0x0000, // N
0x3800, 0x4400, 0x4400, 0x4400, 0x4400, 0x4400, 0x4400, 0x3800, 0x0000, 0x0000, // O
0x7800, 0x4400, 0x4400, 0x4400, 0x7800, 0x4000, 0x4000, 0x4000, 0x0000, 0x0000, // P
0x3800, 0x4400, 0x4400, 0x4400, 0x4400, 0x4400, 0x5400, 0x3800, 0x0400, 0x0000, // Q
0x7800, 0x4400, 0x4400, 0x4400, 0x7800, 0x4800, 0x4800, 0x4400, 0x0000, 0x0000, // R
0x3800, 0x4400, 0x4000, 0x3000, 0x0800, 0x0400, 0x4400, 0x3800, 0x0000, 0x0000, // S
0x7C00, 0x1000, 0x1000, 0x1000, 0x1000, 0x1000, 0x1000, 0x1000, 0x0000, 0x0000, // T
0x4400, 0x4400, 0x4400, 0x4400, 0x4400, 0x4400, 0x4400, 0x3800, 0x0000, 0x0000, // U
0x4400, 0x4400, 0x4400, 0x2800, 0x2800, 0x2800, 0x1000, 0x1000, 0x0000, 0x0000, // V
0x4400, 0x4400, 0x5400, 0x5400, 0x5400, 0x6C00, 0x2800, 0x2800, 0x0000, 0x0000, // W
0x4400, 0x2800, 0x2800, 0x1000, 0x1000, 0x2800, 0x2800, 0x4400, 0x0000, 0x0000, // X
0x4400, 0x4400, 0x2800, 0x2800, 0x1000, 0x1000, 0x1000, 0x1000, 0x0000, 0x0000, // Y
0x7C00, 0x0400, 0x0800, 0x1000, 0x1000, 0x2000, 0x4000, 0x7C00, 0x0000, 0x0000, // Z
0x1800, 0x1000, 0x1000, 0x1000, 0x1000, 0x1000, 0x1000, 0x1000, 0x1000, 0x1800, // [
0x2000, 0x2000, 0x1000, 0x1000, 0x1000, 0x1000, 0x0800, 0x0800, 0x0000, 0x0000, /* \ */
0x3000, 0x1000, 0x1000, 0x1000, 0x1000, 0x1000, 0x1000, 0x1000, 0x1000, 0x3000, // ]
0x1000, 0x2800, 0x2800, 0x4400, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, // ^
0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xFE00, // _
0x2000, 0x1000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, // `
0x0000, 0x0000, 0x3800, 0x4400, 0x3C00, 0x4400, 0x4C00, 0x3400, 0x0000, 0x0000, // a
0x4000, 0x4000, 0x5800, 0x6400, 0x4400, 0x4400, 0x6400, 0x5800, 0x0000, 0x0000, // b
0x0000, 0x0000, 0x3800, 0x4400, 0x4000, 0x4000, 0x4400, 0x3800, 0x0000, 0x0000, // c
0x0400, 0x0400, 0x3400, 0x4C00, 0x4400, 0x4400, 0x4C00, 0x3400, 0x0000, 0x0000, // d
0x0000, 0x0000, 0x3800, 0x4400, 0x7C00, 0x4000, 0x4400, 0x3800, 0x0000, 0x0000, // e
0x0C00, 0x1000, 0x7C00, 0x1000, 0x1000, 0x1000, 0x1000, 0x1000, 0x0000, 0x0000, // f
0x0000, 0x0000, 0x3400, 0x4C00, 0x4400, 0x4400, 0x4C00, 0x3400, 0x0400, 0x7800, // g
0x4000, 0x4000, 0x5800, 0x6400, 0x4400, 0x4400, 0x4400, 0x4400, 0x0000, 0x0000, // h
0x1000, 0x0000, 0x7000, 0x1000, 0x1000, 0x1000, 0x1000, 0x1000, 0x0000, 0x0000, // i
0x1000, 0x0000, 0x7000, 0x1000, 0x1000, 0x1000, 0x1000, 0x1000, 0x1000, 0xE000, // j
0x4000, 0x4000, 0x4800, 0x5000, 0x6000, 0x5000, 0x4800, 0x4400, 0x0000, 0x0000, // k
0x7000, 0x1000, 0x1000, 0x1000, 0x1000, 0x1000, 0x1000, 0x1000, 0x0000, 0x0000, // l
0x0000, 0x0000, 0x7800, 0x5400, 0x5400, 0x5400, 0x5400, 0x5400, 0x0000, 0x0000, // m
0x0000, 0x0000, 0x5800, 0x6400, 0x4400, 0x4400, 0x4400, 0x4400, 0x0000, 0x0000, // n
0x0000, 0x0000, 0x3800, 0x4400, 0x4400, 0x4400, 0x4400, 0x3800, 0x0000, 0x0000, // o
0x0000, 0x0000, 0x5800, 0x6400, 0x4400, 0x4400, 0x6400, 0x5800, 0x4000, 0x4000, // p
0x0000, 0x0000, 0x3400, 0x4C00, 0x4400, 0x4400, 0x4C00, 0x3400, 0x0400, 0x0400, // q
0x0000, 0x0000, 0x5800, 0x6400, 0x4000, 0x4000, 0x4000, 0x4000, 0x0000, 0x0000, // r
0x0000, 0x0000, 0x3800, 0x4400, 0x3000, 0x0800, 0x4400, 0x3800, 0x0000, 0x0000, // s
0x2000, 0x2000, 0x7800, 0x2000, 0x2000, 0x2000, 0x2000, 0x1800, 0x0000, 0x0000, // t
0x0000, 0x0000, 0x4400, 0x4400, 0x4400, 0x4400, 0x4C00, 0x3400, 0x0000, 0x0000, // u
0x0000, 0x0000, 0x4400, 0x4400, 0x2800, 0x2800, 0x2800, 0x1000, 0x0000, 0x0000, // v
0x0000, 0x0000, 0x5400, 0x5400, 0x5400, 0x6C00, 0x2800, 0x2800, 0x0000, 0x0000, // w
0x0000, 0x0000, 0x4400, 0x2800, 0x1000, 0x1000, 0x2800, 0x4400, 0x0000, 0x0000, // x
0x0000, 0x0000, 0x4400, 0x4400, 0x2800, 0x2800, 0x1000, 0x1000, 0x1000, 0x6000, // y
0x0000, 0x0000, 0x7C00, 0x0800, 0x1000, 0x2000, 0x4000, 0x7C00, 0x0000, 0x0000, // z
0x1800, 0x1000, 0x1000, 0x1000, 0x2000, 0x2000, 0x1000, 0x1000, 0x1000, 0x1800, // {
0x1000, 0x1000, 0x1000, 0x1000, 0x1000, 0x1000, 0x1000, 0x1000, 0x1000, 0x1000, // |
0x3000, 0x1000, 0x1000, 0x1000, 0x0800, 0x0800, 0x1000, 0x1000, 0x1000, 0x3000, // }
0x0000, 0x0000, 0x0000, 0x7400, 0x4C00, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, // ~
};
static const uint16_t Font11x18 [] = {
0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, // sp
0x0000, 0x0C00, 0x0C00, 0x0C00, 0x0C00, 0x0C00, 0x0C00, 0x0C00, 0x0C00, 0x0C00, 0x0C00, 0x0C00, 0x0000, 0x0C00, 0x0C00, 0x0000, 0x0000, 0x0000, // !
0x0000, 0x1B00, 0x1B00, 0x1B00, 0x1B00, 0x1B00, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, // "
0x0000, 0x1980, 0x1980, 0x1980, 0x1980, 0x7FC0, 0x7FC0, 0x1980, 0x3300, 0x7FC0, 0x7FC0, 0x3300, 0x3300, 0x3300, 0x3300, 0x0000, 0x0000, 0x0000, // #
0x0000, 0x1E00, 0x3F00, 0x7580, 0x6580, 0x7400, 0x3C00, 0x1E00, 0x0700, 0x0580, 0x6580, 0x6580, 0x7580, 0x3F00, 0x1E00, 0x0400, 0x0400, 0x0000, // $
0x0000, 0x7000, 0xD800, 0xD840, 0xD8C0, 0xD980, 0x7300, 0x0600, 0x0C00, 0x1B80, 0x36C0, 0x66C0, 0x46C0, 0x06C0, 0x0380, 0x0000, 0x0000, 0x0000, // %
0x0000, 0x1E00, 0x3F00, 0x3300, 0x3300, 0x3300, 0x1E00, 0x0C00, 0x3CC0, 0x66C0, 0x6380, 0x6180, 0x6380, 0x3EC0, 0x1C80, 0x0000, 0x0000, 0x0000, // &
0x0000, 0x0C00, 0x0C00, 0x0C00, 0x0C00, 0x0C00, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, // '
0x0080, 0x0100, 0x0300, 0x0600, 0x0600, 0x0400, 0x0C00, 0x0C00, 0x0C00, 0x0C00, 0x0C00, 0x0C00, 0x0400, 0x0600, 0x0600, 0x0300, 0x0100, 0x0080, // (
0x2000, 0x1000, 0x1800, 0x0C00, 0x0C00, 0x0400, 0x0600, 0x0600, 0x0600, 0x0600, 0x0600, 0x0600, 0x0400, 0x0C00, 0x0C00, 0x1800, 0x1000, 0x2000, // )
0x0000, 0x0C00, 0x2D00, 0x3F00, 0x1E00, 0x3300, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, // *
0x0000, 0x0000, 0x0000, 0x0C00, 0x0C00, 0x0C00, 0x0C00, 0xFFC0, 0xFFC0, 0x0C00, 0x0C00, 0x0C00, 0x0C00, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, // +
0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0C00, 0x0C00, 0x0400, 0x0400, 0x0800, // ,
0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x1E00, 0x1E00, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, // -
0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0C00, 0x0C00, 0x0000, 0x0000, 0x0000, // .
0x0000, 0x0300, 0x0300, 0x0300, 0x0600, 0x0600, 0x0600, 0x0600, 0x0C00, 0x0C00, 0x0C00, 0x0C00, 0x1800, 0x1800, 0x1800, 0x0000, 0x0000, 0x0000, // /
0x0000, 0x1E00, 0x3F00, 0x3300, 0x6180, 0x6180, 0x6180, 0x6D80, 0x6D80, 0x6180, 0x6180, 0x6180, 0x3300, 0x3F00, 0x1E00, 0x0000, 0x0000, 0x0000, // 0
0x0000, 0x0600, 0x0E00, 0x1E00, 0x3600, 0x2600, 0x0600, 0x0600, 0x0600, 0x0600, 0x0600, 0x0600, 0x0600, 0x0600, 0x0600, 0x0000, 0x0000, 0x0000, // 1
0x0000, 0x1E00, 0x3F00, 0x7380, 0x6180, 0x6180, 0x0180, 0x0300, 0x0600, 0x0C00, 0x1800, 0x3000, 0x6000, 0x7F80, 0x7F80, 0x0000, 0x0000, 0x0000, // 2
0x0000, 0x1C00, 0x3E00, 0x6300, 0x6300, 0x0300, 0x0E00, 0x0E00, 0x0300, 0x0180, 0x0180, 0x6180, 0x7380, 0x3F00, 0x1E00, 0x0000, 0x0000, 0x0000, // 3
0x0000, 0x0600, 0x0E00, 0x0E00, 0x1E00, 0x1E00, 0x1600, 0x3600, 0x3600, 0x6600, 0x7F80, 0x7F80, 0x0600, 0x0600, 0x0600, 0x0000, 0x0000, 0x0000, // 4
0x0000, 0x7F00, 0x7F00, 0x6000, 0x6000, 0x6000, 0x6E00, 0x7F00, 0x6380, 0x0180, 0x0180, 0x6180, 0x7380, 0x3F00, 0x1E00, 0x0000, 0x0000, 0x0000, // 5
0x0000, 0x1E00, 0x3F00, 0x3380, 0x6180, 0x6000, 0x6E00, 0x7F00, 0x7380, 0x6180, 0x6180, 0x6180, 0x3380, 0x3F00, 0x1E00, 0x0000, 0x0000, 0x0000, // 6
0x0000, 0x7F80, 0x7F80, 0x0180, 0x0300, 0x0300, 0x0600, 0x0600, 0x0C00, 0x0C00, 0x0C00, 0x0800, 0x1800, 0x1800, 0x1800, 0x0000, 0x0000, 0x0000, // 7
0x0000, 0x1E00, 0x3F00, 0x6380, 0x6180, 0x6180, 0x2100, 0x1E00, 0x3F00, 0x6180, 0x6180, 0x6180, 0x6180, 0x3F00, 0x1E00, 0x0000, 0x0000, 0x0000, // 8
0x0000, 0x1E00, 0x3F00, 0x7300, 0x6180, 0x6180, 0x6180, 0x7380, 0x3F80, 0x1D80, 0x0180, 0x6180, 0x7300, 0x3F00, 0x1E00, 0x0000, 0x0000, 0x0000, // 9
0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0C00, 0x0C00, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0C00, 0x0C00, 0x0000, 0x0000, 0x0000, // :
0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0C00, 0x0C00, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0C00, 0x0C00, 0x0400, 0x0400, 0x0800, // ;
0x0000, 0x0000, 0x0000, 0x0000, 0x0080, 0x0380, 0x0E00, 0x3800, 0x6000, 0x3800, 0x0E00, 0x0380, 0x0080, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, // <
0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x7F80, 0x7F80, 0x0000, 0x0000, 0x7F80, 0x7F80, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, // =
0x0000, 0x0000, 0x0000, 0x0000, 0x4000, 0x7000, 0x1C00, 0x0700, 0x0180, 0x0700, 0x1C00, 0x7000, 0x4000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, // >
0x0000, 0x1F00, 0x3F80, 0x71C0, 0x60C0, 0x00C0, 0x01C0, 0x0380, 0x0700, 0x0E00, 0x0C00, 0x0C00, 0x0000, 0x0C00, 0x0C00, 0x0000, 0x0000, 0x0000, // ?
0x0000, 0x1E00, 0x3F00, 0x3180, 0x7180, 0x6380, 0x6F80, 0x6D80, 0x6D80, 0x6F80, 0x6780, 0x6000, 0x3200, 0x3E00, 0x1C00, 0x0000, 0x0000, 0x0000, // @
0x0000, 0x0E00, 0x0E00, 0x1B00, 0x1B00, 0x1B00, 0x1B00, 0x3180, 0x3180, 0x3F80, 0x3F80, 0x3180, 0x60C0, 0x60C0, 0x60C0, 0x0000, 0x0000, 0x0000, // A
0x0000, 0x7C00, 0x7E00, 0x6300, 0x6300, 0x6300, 0x6300, 0x7E00, 0x7E00, 0x6300, 0x6180, 0x6180, 0x6380, 0x7F00, 0x7E00, 0x0000, 0x0000, 0x0000, // B
0x0000, 0x1E00, 0x3F00, 0x3180, 0x6180, 0x6000, 0x6000, 0x6000, 0x6000, 0x6000, 0x6000, 0x6180, 0x3180, 0x3F00, 0x1E00, 0x0000, 0x0000, 0x0000, // C
0x0000, 0x7C00, 0x7F00, 0x6300, 0x6380, 0x6180, 0x6180, 0x6180, 0x6180, 0x6180, 0x6180, 0x6300, 0x6300, 0x7E00, 0x7C00, 0x0000, 0x0000, 0x0000, // D
0x0000, 0x7F80, 0x7F80, 0x6000, 0x6000, 0x6000, 0x6000, 0x7F00, 0x7F00, 0x6000, 0x6000, 0x6000, 0x6000, 0x7F80, 0x7F80, 0x0000, 0x0000, 0x0000, // E
0x0000, 0x7F80, 0x7F80, 0x6000, 0x6000, 0x6000, 0x6000, 0x7F00, 0x7F00, 0x6000, 0x6000, 0x6000, 0x6000, 0x6000, 0x6000, 0x0000, 0x0000, 0x0000, // F
0x0000, 0x1E00, 0x3F00, 0x3180, 0x6180, 0x6000, 0x6000, 0x6000, 0x6380, 0x6380, 0x6180, 0x6180, 0x3180, 0x3F80, 0x1E00, 0x0000, 0x0000, 0x0000, // G
0x0000, 0x6180, 0x6180, 0x6180, 0x6180, 0x6180, 0x6180, 0x7F80, 0x7F80, 0x6180, 0x6180, 0x6180, 0x6180, 0x6180, 0x6180, 0x0000, 0x0000, 0x0000, // H
0x0000, 0x3F00, 0x3F00, 0x0C00, 0x0C00, 0x0C00, 0x0C00, 0x0C00, 0x0C00, 0x0C00, 0x0C00, 0x0C00, 0x0C00, 0x3F00, 0x3F00, 0x0000, 0x0000, 0x0000, // I
0x0000, 0x0180, 0x0180, 0x0180, 0x0180, 0x0180, 0x0180, 0x0180, 0x0180, 0x0180, 0x6180, 0x6180, 0x7380, 0x3F00, 0x1E00, 0x0000, 0x0000, 0x0000, // J
0x0000, 0x60C0, 0x6180, 0x6300, 0x6600, 0x6600, 0x6C00, 0x7800, 0x7C00, 0x6600, 0x6600, 0x6300, 0x6180, 0x6180, 0x60C0, 0x0000, 0x0000, 0x0000, // K
0x0000, 0x6000, 0x6000, 0x6000, 0x6000, 0x6000, 0x6000, 0x6000, 0x6000, 0x6000, 0x6000, 0x6000, 0x6000, 0x7F80, 0x7F80, 0x0000, 0x0000, 0x0000, // L
0x0000, 0x71C0, 0x71C0, 0x7BC0, 0x7AC0, 0x6AC0, 0x6AC0, 0x6EC0, 0x64C0, 0x60C0, 0x60C0, 0x60C0, 0x60C0, 0x60C0, 0x60C0, 0x0000, 0x0000, 0x0000, // M
0x0000, 0x7180, 0x7180, 0x7980, 0x7980, 0x7980, 0x6D80, 0x6D80, 0x6D80, 0x6580, 0x6780, 0x6780, 0x6780, 0x6380, 0x6380, 0x0000, 0x0000, 0x0000, // N
0x0000, 0x1E00, 0x3F00, 0x3300, 0x6180, 0x6180, 0x6180, 0x6180, 0x6180, 0x6180, 0x6180, 0x6180, 0x3300, 0x3F00, 0x1E00, 0x0000, 0x0000, 0x0000, // O
0x0000, 0x7E00, 0x7F00, 0x6380, 0x6180, 0x6180, 0x6180, 0x6380, 0x7F00, 0x7E00, 0x6000, 0x6000, 0x6000, 0x6000, 0x6000, 0x0000, 0x0000, 0x0000, // P
0x0000, 0x1E00, 0x3F00, 0x3300, 0x6180, 0x6180, 0x6180, 0x6180, 0x6180, 0x6180, 0x6580, 0x6780, 0x3300, 0x3F80, 0x1E40, 0x0000, 0x0000, 0x0000, // Q
0x0000, 0x7E00, 0x7F00, 0x6380, 0x6180, 0x6180, 0x6380, 0x7F00, 0x7E00, 0x6600, 0x6300, 0x6300, 0x6180, 0x6180, 0x60C0, 0x0000, 0x0000, 0x0000, // R
0x0000, 0x0E00, 0x1F00, 0x3180, 0x3180, 0x3000, 0x3800, 0x1E00, 0x0700, 0x0380, 0x6180, 0x6180, 0x3180, 0x3F00, 0x1E00, 0x0000, 0x0000, 0x0000, // S
0x0000, 0xFFC0, 0xFFC0, 0x0C00, 0x0C00, 0x0C00, 0x0C00, 0x0C00, 0x0C00, 0x0C00, 0x0C00, 0x0C00, 0x0C00, 0x0C00, 0x0C00, 0x0000, 0x0000, 0x0000, // T
0x0000, 0x6180, 0x6180, 0x6180, 0x6180, 0x6180, 0x6180, 0x6180, 0x6180, 0x6180, 0x6180, 0x6180, 0x7380, 0x3F00, 0x1E00, 0x0000, 0x0000, 0x0000, // U
0x0000, 0x60C0, 0x60C0, 0x60C0, 0x3180, 0x3180, 0x3180, 0x1B00, 0x1B00, 0x1B00, 0x1B00, 0x0E00, 0x0E00, 0x0E00, 0x0400, 0x0000, 0x0000, 0x0000, // V
0x0000, 0xC0C0, 0xC0C0, 0xC0C0, 0xC0C0, 0xC0C0, 0xCCC0, 0x4C80, 0x4C80, 0x5E80, 0x5280, 0x5280, 0x7380, 0x6180, 0x6180, 0x0000, 0x0000, 0x0000, // W
0x0000, 0xC0C0, 0x6080, 0x6180, 0x3300, 0x3B00, 0x1E00, 0x0C00, 0x0C00, 0x1E00, 0x1F00, 0x3B00, 0x7180, 0x6180, 0xC0C0, 0x0000, 0x0000, 0x0000, // X
0x0000, 0xC0C0, 0x6180, 0x6180, 0x3300, 0x3300, 0x1E00, 0x1E00, 0x0C00, 0x0C00, 0x0C00, 0x0C00, 0x0C00, 0x0C00, 0x0C00, 0x0000, 0x0000, 0x0000, // Y
0x0000, 0x3F80, 0x3F80, 0x0180, 0x0300, 0x0300, 0x0600, 0x0C00, 0x0C00, 0x1800, 0x1800, 0x3000, 0x6000, 0x7F80, 0x7F80, 0x0000, 0x0000, 0x0000, // Z
0x0F00, 0x0F00, 0x0C00, 0x0C00, 0x0C00, 0x0C00, 0x0C00, 0x0C00, 0x0C00, 0x0C00, 0x0C00, 0x0C00, 0x0C00, 0x0C00, 0x0C00, 0x0C00, 0x0F00, 0x0F00, // [
0x0000, 0x1800, 0x1800, 0x1800, 0x0C00, 0x0C00, 0x0C00, 0x0C00, 0x0600, 0x0600, 0x0600, 0x0600, 0x0300, 0x0300, 0x0300, 0x0000, 0x0000, 0x0000, /* \ */
0x1E00, 0x1E00, 0x0600, 0x0600, 0x0600, 0x0600, 0x0600, 0x0600, 0x0600, 0x0600, 0x0600, 0x0600, 0x0600, 0x0600, 0x0600, 0x0600, 0x1E00, 0x1E00, // ]
0x0000, 0x0C00, 0x0C00, 0x1E00, 0x1200, 0x3300, 0x3300, 0x6180, 0x6180, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, // ^
0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xFFE0, 0x0000, // _
0x0000, 0x3800, 0x1800, 0x0C00, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, // `
0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x1F00, 0x3F80, 0x6180, 0x0180, 0x1F80, 0x3F80, 0x6180, 0x6380, 0x7F80, 0x38C0, 0x0000, 0x0000, 0x0000, // a
0x0000, 0x6000, 0x6000, 0x6000, 0x6000, 0x6E00, 0x7F00, 0x7380, 0x6180, 0x6180, 0x6180, 0x6180, 0x7380, 0x7F00, 0x6E00, 0x0000, 0x0000, 0x0000, // b
0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x1E00, 0x3F00, 0x7380, 0x6180, 0x6000, 0x6000, 0x6180, 0x7380, 0x3F00, 0x1E00, 0x0000, 0x0000, 0x0000, // c
0x0000, 0x0180, 0x0180, 0x0180, 0x0180, 0x1D80, 0x3F80, 0x7380, 0x6180, 0x6180, 0x6180, 0x6180, 0x7380, 0x3F80, 0x1D80, 0x0000, 0x0000, 0x0000, // d
0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x1E00, 0x3F00, 0x7300, 0x6180, 0x7F80, 0x7F80, 0x6000, 0x7180, 0x3F00, 0x1E00, 0x0000, 0x0000, 0x0000, // e
0x0000, 0x07C0, 0x0FC0, 0x0C00, 0x0C00, 0x7F80, 0x7F80, 0x0C00, 0x0C00, 0x0C00, 0x0C00, 0x0C00, 0x0C00, 0x0C00, 0x0C00, 0x0000, 0x0000, 0x0000, // f
0x0000, 0x0000, 0x0000, 0x0000, 0x1D80, 0x3F80, 0x7380, 0x6180, 0x6180, 0x6180, 0x6180, 0x7380, 0x3F80, 0x1D80, 0x0180, 0x6380, 0x7F00, 0x3E00, // g
0x0000, 0x6000, 0x6000, 0x6000, 0x6000, 0x6F00, 0x7F80, 0x7180, 0x6180, 0x6180, 0x6180, 0x6180, 0x6180, 0x6180, 0x6180, 0x0000, 0x0000, 0x0000, // h
0x0000, 0x0600, 0x0600, 0x0000, 0x0000, 0x3E00, 0x3E00, 0x0600, 0x0600, 0x0600, 0x0600, 0x0600, 0x0600, 0x0600, 0x0600, 0x0000, 0x0000, 0x0000, // i
0x0600, 0x0600, 0x0000, 0x0000, 0x3E00, 0x3E00, 0x0600, 0x0600, 0x0600, 0x0600, 0x0600, 0x0600, 0x0600, 0x0600, 0x0600, 0x4600, 0x7E00, 0x3C00, // j
0x0000, 0x6000, 0x6000, 0x6000, 0x6000, 0x6180, 0x6300, 0x6600, 0x6C00, 0x7C00, 0x7600, 0x6300, 0x6300, 0x6180, 0x60C0, 0x0000, 0x0000, 0x0000, // k
0x0000, 0x3E00, 0x3E00, 0x0600, 0x0600, 0x0600, 0x0600, 0x0600, 0x0600, 0x0600, 0x0600, 0x0600, 0x0600, 0x0600, 0x0600, 0x0000, 0x0000, 0x0000, // l
0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xDD80, 0xFFC0, 0xCEC0, 0xCCC0, 0xCCC0, 0xCCC0, 0xCCC0, 0xCCC0, 0xCCC0, 0xCCC0, 0x0000, 0x0000, 0x0000, // m
0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x6F00, 0x7F80, 0x7180, 0x6180, 0x6180, 0x6180, 0x6180, 0x6180, 0x6180, 0x6180, 0x0000, 0x0000, 0x0000, // n
0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x1E00, 0x3F00, 0x7380, 0x6180, 0x6180, 0x6180, 0x6180, 0x7380, 0x3F00, 0x1E00, 0x0000, 0x0000, 0x0000, // o
0x0000, 0x0000, 0x0000, 0x0000, 0x6E00, 0x7F00, 0x7380, 0x6180, 0x6180, 0x6180, 0x6180, 0x7380, 0x7F00, 0x6E00, 0x6000, 0x6000, 0x6000, 0x6000, // p
0x0000, 0x0000, 0x0000, 0x0000, 0x1D80, 0x3F80, 0x7380, 0x6180, 0x6180, 0x6180, 0x6180, 0x7380, 0x3F80, 0x1D80, 0x0180, 0x0180, 0x0180, 0x0180, // q
0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x6700, 0x3F80, 0x3900, 0x3000, 0x3000, 0x3000, 0x3000, 0x3000, 0x3000, 0x3000, 0x0000, 0x0000, 0x0000, // r
0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x1E00, 0x3F80, 0x6180, 0x6000, 0x7F00, 0x3F80, 0x0180, 0x6180, 0x7F00, 0x1E00, 0x0000, 0x0000, 0x0000, // s
0x0000, 0x0000, 0x0800, 0x1800, 0x1800, 0x7F00, 0x7F00, 0x1800, 0x1800, 0x1800, 0x1800, 0x1800, 0x1800, 0x1F80, 0x0F80, 0x0000, 0x0000, 0x0000, // t
0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x6180, 0x6180, 0x6180, 0x6180, 0x6180, 0x6180, 0x6180, 0x6380, 0x7F80, 0x3D80, 0x0000, 0x0000, 0x0000, // u
0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x60C0, 0x3180, 0x3180, 0x3180, 0x1B00, 0x1B00, 0x1B00, 0x0E00, 0x0E00, 0x0600, 0x0000, 0x0000, 0x0000, // v
0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xDD80, 0xDD80, 0xDD80, 0x5500, 0x5500, 0x5500, 0x7700, 0x7700, 0x2200, 0x2200, 0x0000, 0x0000, 0x0000, // w
0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x6180, 0x3300, 0x3300, 0x1E00, 0x0C00, 0x0C00, 0x1E00, 0x3300, 0x3300, 0x6180, 0x0000, 0x0000, 0x0000, // x
0x0000, 0x0000, 0x0000, 0x0000, 0x6180, 0x6180, 0x3180, 0x3300, 0x3300, 0x1B00, 0x1B00, 0x1B00, 0x0E00, 0x0E00, 0x0E00, 0x1C00, 0x7C00, 0x7000, // y
0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x7FC0, 0x7FC0, 0x0180, 0x0300, 0x0600, 0x0C00, 0x1800, 0x3000, 0x7FC0, 0x7FC0, 0x0000, 0x0000, 0x0000, // z
0x0380, 0x0780, 0x0600, 0x0600, 0x0600, 0x0600, 0x0600, 0x0E00, 0x1C00, 0x1C00, 0x0E00, 0x0600, 0x0600, 0x0600, 0x0600, 0x0600, 0x0780, 0x0380, // {
0x0600, 0x0600, 0x0600, 0x0600, 0x0600, 0x0600, 0x0600, 0x0600, 0x0600, 0x0600, 0x0600, 0x0600, 0x0600, 0x0600, 0x0600, 0x0600, 0x0600, 0x0600, // |
0x3800, 0x3C00, 0x0C00, 0x0C00, 0x0C00, 0x0C00, 0x0C00, 0x0E00, 0x0700, 0x0700, 0x0E00, 0x0C00, 0x0C00, 0x0C00, 0x0C00, 0x0C00, 0x3C00, 0x3800, // }
0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x3880, 0x7F80, 0x4700, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, // ~
};
static const uint16_t Font16x26 [] = {
0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000, // Ascii = [ ]
0x03E0,0x03E0,0x03E0,0x03E0,0x03E0,0x03E0,0x03E0,0x03E0,0x03C0,0x03C0,0x01C0,0x01C0,0x01C0,0x01C0,0x01C0,0x0000,0x0000,0x0000,0x03E0,0x03E0,0x03E0,0x0000,0x0000,0x0000,0x0000,0x0000, // Ascii = [!]
0x1E3C,0x1E3C,0x1E3C,0x1E3C,0x1E3C,0x1E3C,0x1E3C,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000, // Ascii = ["]
0x01CE,0x03CE,0x03DE,0x039E,0x039C,0x079C,0x3FFF,0x7FFF,0x0738,0x0F38,0x0F78,0x0F78,0x0E78,0xFFFF,0xFFFF,0x1EF0,0x1CF0,0x1CE0,0x3CE0,0x3DE0,0x39E0,0x0000,0x0000,0x0000,0x0000,0x0000, // Ascii = [#]
0x03FC,0x0FFE,0x1FEE,0x1EE0,0x1EE0,0x1EE0,0x1EE0,0x1FE0,0x0FE0,0x07E0,0x03F0,0x01FC,0x01FE,0x01FE,0x01FE,0x01FE,0x01FE,0x01FE,0x3DFE,0x3FFC,0x0FF0,0x01E0,0x01E0,0x0000,0x0000,0x0000, // Ascii = [$]
0x3E03,0xF707,0xE78F,0xE78E,0xE39E,0xE3BC,0xE7B8,0xE7F8,0xF7F0,0x3FE0,0x01C0,0x03FF,0x07FF,0x07F3,0x0FF3,0x1EF3,0x3CF3,0x38F3,0x78F3,0xF07F,0xE03F,0x0000,0x0000,0x0000,0x0000,0x0000, // Ascii = [%]
0x07E0,0x0FF8,0x0F78,0x1F78,0x1F78,0x1F78,0x0F78,0x0FF0,0x0FE0,0x1F80,0x7FC3,0xFBC3,0xF3E7,0xF1F7,0xF0F7,0xF0FF,0xF07F,0xF83E,0x7C7F,0x3FFF,0x1FEF,0x0000,0x0000,0x0000,0x0000,0x0000, // Ascii = [&]
0x03E0,0x03E0,0x03E0,0x03E0,0x03E0,0x03C0,0x01C0,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000, // Ascii = [']
0x003F,0x007C,0x01F0,0x01E0,0x03C0,0x07C0,0x0780,0x0780,0x0F80,0x0F00,0x0F00,0x0F00,0x0F00,0x0F00,0x0F00,0x0F80,0x0780,0x0780,0x07C0,0x03C0,0x01E0,0x01F0,0x007C,0x003F,0x000F,0x0000, // Ascii = [(]
0x7E00,0x1F00,0x07C0,0x03C0,0x01E0,0x01F0,0x00F0,0x00F0,0x00F8,0x0078,0x0078,0x0078,0x0078,0x0078,0x0078,0x00F8,0x00F0,0x00F0,0x01F0,0x01E0,0x03C0,0x07C0,0x1F00,0x7E00,0x7800,0x0000, // Ascii = [)]
0x03E0,0x03C0,0x01C0,0x39CE,0x3FFF,0x3F7F,0x0320,0x0370,0x07F8,0x0F78,0x1F3C,0x0638,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000, // Ascii = [*]
0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x01C0,0x01C0,0x01C0,0x01C0,0x01C0,0x01C0,0x01C0,0xFFFF,0xFFFF,0x01C0,0x01C0,0x01C0,0x01C0,0x01C0,0x01C0,0x0000,0x0000,0x0000,0x0000,0x0000, // Ascii = [+]
0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x03E0,0x03E0,0x03E0,0x03E0,0x01E0,0x01E0,0x01E0,0x01C0,0x0380, // Ascii = [,]
0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x3FFE,0x3FFE,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000, // Ascii = [-]
0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x03E0,0x03E0,0x03E0,0x03E0,0x0000,0x0000,0x0000,0x0000,0x0000, // Ascii = [.]
0x000F,0x000F,0x001E,0x001E,0x003C,0x003C,0x0078,0x0078,0x00F0,0x00F0,0x01E0,0x01E0,0x03C0,0x03C0,0x0780,0x0780,0x0F00,0x0F00,0x1E00,0x1E00,0x3C00,0x3C00,0x7800,0x7800,0xF000,0x0000, // Ascii = [/]
0x07F0,0x0FF8,0x1F7C,0x3E3E,0x3C1E,0x7C1F,0x7C1F,0x780F,0x780F,0x780F,0x780F,0x780F,0x780F,0x780F,0x7C1F,0x7C1F,0x3C1E,0x3E3E,0x1F7C,0x0FF8,0x07F0,0x0000,0x0000,0x0000,0x0000,0x0000, // Ascii = [0]
0x00F0,0x07F0,0x3FF0,0x3FF0,0x01F0,0x01F0,0x01F0,0x01F0,0x01F0,0x01F0,0x01F0,0x01F0,0x01F0,0x01F0,0x01F0,0x01F0,0x01F0,0x01F0,0x01F0,0x3FFF,0x3FFF,0x0000,0x0000,0x0000,0x0000,0x0000, // Ascii = [1]
0x0FE0,0x3FF8,0x3C7C,0x003C,0x003E,0x003E,0x003E,0x003C,0x003C,0x007C,0x00F8,0x01F0,0x03E0,0x07C0,0x0780,0x0F00,0x1E00,0x3E00,0x3C00,0x3FFE,0x3FFE,0x0000,0x0000,0x0000,0x0000,0x0000, // Ascii = [2]
0x0FF0,0x1FF8,0x1C7C,0x003E,0x003E,0x003E,0x003C,0x003C,0x00F8,0x0FF0,0x0FF8,0x007C,0x003E,0x001E,0x001E,0x001E,0x001E,0x003E,0x1C7C,0x1FF8,0x1FE0,0x0000,0x0000,0x0000,0x0000,0x0000, // Ascii = [3]
0x0078,0x00F8,0x00F8,0x01F8,0x03F8,0x07F8,0x07F8,0x0F78,0x1E78,0x1E78,0x3C78,0x7878,0x7878,0xFFFF,0xFFFF,0x0078,0x0078,0x0078,0x0078,0x0078,0x0078,0x0000,0x0000,0x0000,0x0000,0x0000, // Ascii = [4]
0x1FFC,0x1FFC,0x1FFC,0x1E00,0x1E00,0x1E00,0x1E00,0x1E00,0x1FE0,0x1FF8,0x00FC,0x007C,0x003E,0x003E,0x001E,0x003E,0x003E,0x003C,0x1C7C,0x1FF8,0x1FE0,0x0000,0x0000,0x0000,0x0000,0x0000, // Ascii = [5]
0x01FC,0x07FE,0x0F8E,0x1F00,0x1E00,0x3E00,0x3C00,0x3C00,0x3DF8,0x3FFC,0x7F3E,0x7E1F,0x3C0F,0x3C0F,0x3C0F,0x3C0F,0x3E0F,0x1E1F,0x1F3E,0x0FFC,0x03F0,0x0000,0x0000,0x0000,0x0000,0x0000, // Ascii = [6]
0x3FFF,0x3FFF,0x3FFF,0x000F,0x001E,0x001E,0x003C,0x0038,0x0078,0x00F0,0x00F0,0x01E0,0x01E0,0x03C0,0x03C0,0x0780,0x0F80,0x0F80,0x0F00,0x1F00,0x1F00,0x0000,0x0000,0x0000,0x0000,0x0000, // Ascii = [7]
0x07F8,0x0FFC,0x1F3E,0x1E1E,0x3E1E,0x3E1E,0x1E1E,0x1F3C,0x0FF8,0x07F0,0x0FF8,0x1EFC,0x3E3E,0x3C1F,0x7C1F,0x7C0F,0x7C0F,0x3C1F,0x3F3E,0x1FFC,0x07F0,0x0000,0x0000,0x0000,0x0000,0x0000, // Ascii = [8]
0x07F0,0x0FF8,0x1E7C,0x3C3E,0x3C1E,0x7C1F,0x7C1F,0x7C1F,0x7C1F,0x3C1F,0x3E3F,0x1FFF,0x07EF,0x001F,0x001E,0x001E,0x003E,0x003C,0x38F8,0x3FF0,0x1FE0,0x0000,0x0000,0x0000,0x0000,0x0000, // Ascii = [9]
0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x03E0,0x03E0,0x03E0,0x03E0,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x03E0,0x03E0,0x03E0,0x03E0,0x0000,0x0000,0x0000,0x0000,0x0000, // Ascii = [:]
0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x03E0,0x03E0,0x03E0,0x03E0,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x03E0,0x03E0,0x03E0,0x03E0,0x01E0,0x01E0,0x01E0,0x03C0,0x0380, // Ascii = [;]
0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0003,0x000F,0x003F,0x00FC,0x03F0,0x0FC0,0x3F00,0xFE00,0x3F00,0x0FC0,0x03F0,0x00FC,0x003F,0x000F,0x0003,0x0000,0x0000,0x0000,0x0000,0x0000, // Ascii = [<]
0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0xFFFF,0xFFFF,0x0000,0x0000,0x0000,0xFFFF,0xFFFF,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000, // Ascii = [=]
0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0xE000,0xF800,0x7E00,0x1F80,0x07E0,0x01F8,0x007E,0x001F,0x007E,0x01F8,0x07E0,0x1F80,0x7E00,0xF800,0xE000,0x0000,0x0000,0x0000,0x0000,0x0000, // Ascii = [>]
0x1FF0,0x3FFC,0x383E,0x381F,0x381F,0x001E,0x001E,0x003C,0x0078,0x00F0,0x01E0,0x03C0,0x03C0,0x07C0,0x07C0,0x0000,0x0000,0x0000,0x07C0,0x07C0,0x07C0,0x0000,0x0000,0x0000,0x0000,0x0000, // Ascii = [?]
0x03F8,0x0FFE,0x1F1E,0x3E0F,0x3C7F,0x78FF,0x79EF,0x73C7,0xF3C7,0xF38F,0xF38F,0xF38F,0xF39F,0xF39F,0x73FF,0x7BFF,0x79F7,0x3C00,0x1F1C,0x0FFC,0x03F8,0x0000,0x0000,0x0000,0x0000,0x0000, // Ascii = [@]
0x0000,0x0000,0x0000,0x03E0,0x03E0,0x07F0,0x07F0,0x07F0,0x0F78,0x0F78,0x0E7C,0x1E3C,0x1E3C,0x3C3E,0x3FFE,0x3FFF,0x781F,0x780F,0xF00F,0xF007,0xF007,0x0000,0x0000,0x0000,0x0000,0x0000, // Ascii = [A]
0x0000,0x0000,0x0000,0x3FF8,0x3FFC,0x3C3E,0x3C1E,0x3C1E,0x3C1E,0x3C3E,0x3C7C,0x3FF0,0x3FF8,0x3C7E,0x3C1F,0x3C1F,0x3C0F,0x3C0F,0x3C1F,0x3FFE,0x3FF8,0x0000,0x0000,0x0000,0x0000,0x0000, // Ascii = [B]
0x0000,0x0000,0x0000,0x01FF,0x07FF,0x1F87,0x3E00,0x3C00,0x7C00,0x7800,0x7800,0x7800,0x7800,0x7800,0x7C00,0x7C00,0x3E00,0x3F00,0x1F83,0x07FF,0x01FF,0x0000,0x0000,0x0000,0x0000,0x0000, // Ascii = [C]
0x0000,0x0000,0x0000,0x7FF0,0x7FFC,0x787E,0x781F,0x781F,0x780F,0x780F,0x780F,0x780F,0x780F,0x780F,0x780F,0x780F,0x781F,0x781E,0x787E,0x7FF8,0x7FE0,0x0000,0x0000,0x0000,0x0000,0x0000, // Ascii = [D]
0x0000,0x0000,0x0000,0x3FFF,0x3FFF,0x3E00,0x3E00,0x3E00,0x3E00,0x3E00,0x3E00,0x3FFE,0x3FFE,0x3E00,0x3E00,0x3E00,0x3E00,0x3E00,0x3E00,0x3FFF,0x3FFF,0x0000,0x0000,0x0000,0x0000,0x0000, // Ascii = [E]
0x0000,0x0000,0x0000,0x1FFF,0x1FFF,0x1E00,0x1E00,0x1E00,0x1E00,0x1E00,0x1E00,0x1FFF,0x1FFF,0x1E00,0x1E00,0x1E00,0x1E00,0x1E00,0x1E00,0x1E00,0x1E00,0x0000,0x0000,0x0000,0x0000,0x0000, // Ascii = [F]
0x0000,0x0000,0x0000,0x03FE,0x0FFF,0x1F87,0x3E00,0x7C00,0x7C00,0x7800,0xF800,0xF800,0xF87F,0xF87F,0x780F,0x7C0F,0x7C0F,0x3E0F,0x1F8F,0x0FFF,0x03FE,0x0000,0x0000,0x0000,0x0000,0x0000, // Ascii = [G]
0x0000,0x0000,0x0000,0x7C1F,0x7C1F,0x7C1F,0x7C1F,0x7C1F,0x7C1F,0x7C1F,0x7C1F,0x7FFF,0x7FFF,0x7C1F,0x7C1F,0x7C1F,0x7C1F,0x7C1F,0x7C1F,0x7C1F,0x7C1F,0x0000,0x0000,0x0000,0x0000,0x0000, // Ascii = [H]
0x0000,0x0000,0x0000,0x3FFF,0x3FFF,0x03E0,0x03E0,0x03E0,0x03E0,0x03E0,0x03E0,0x03E0,0x03E0,0x03E0,0x03E0,0x03E0,0x03E0,0x03E0,0x03E0,0x3FFF,0x3FFF,0x0000,0x0000,0x0000,0x0000,0x0000, // Ascii = [I]
0x0000,0x0000,0x0000,0x1FFC,0x1FFC,0x007C,0x007C,0x007C,0x007C,0x007C,0x007C,0x007C,0x007C,0x007C,0x007C,0x007C,0x0078,0x0078,0x38F8,0x3FF0,0x3FC0,0x0000,0x0000,0x0000,0x0000,0x0000, // Ascii = [J]
0x0000,0x0000,0x0000,0x3C1F,0x3C1E,0x3C3C,0x3C78,0x3CF0,0x3DE0,0x3FE0,0x3FC0,0x3F80,0x3FC0,0x3FE0,0x3DF0,0x3CF0,0x3C78,0x3C7C,0x3C3E,0x3C1F,0x3C0F,0x0000,0x0000,0x0000,0x0000,0x0000, // Ascii = [K]
0x0000,0x0000,0x0000,0x3E00,0x3E00,0x3E00,0x3E00,0x3E00,0x3E00,0x3E00,0x3E00,0x3E00,0x3E00,0x3E00,0x3E00,0x3E00,0x3E00,0x3E00,0x3E00,0x3FFF,0x3FFF,0x0000,0x0000,0x0000,0x0000,0x0000, // Ascii = [L]
0x0000,0x0000,0x0000,0xF81F,0xFC1F,0xFC1F,0xFE3F,0xFE3F,0xFE3F,0xFF7F,0xFF77,0xFF77,0xF7F7,0xF7E7,0xF3E7,0xF3E7,0xF3C7,0xF007,0xF007,0xF007,0xF007,0x0000,0x0000,0x0000,0x0000,0x0000, // Ascii = [M]
0x0000,0x0000,0x0000,0x7C0F,0x7C0F,0x7E0F,0x7F0F,0x7F0F,0x7F8F,0x7F8F,0x7FCF,0x7BEF,0x79EF,0x79FF,0x78FF,0x78FF,0x787F,0x783F,0x783F,0x781F,0x781F,0x0000,0x0000,0x0000,0x0000,0x0000, // Ascii = [N]
0x0000,0x0000,0x0000,0x07F0,0x1FFC,0x3E3E,0x7C1F,0x780F,0x780F,0xF80F,0xF80F,0xF80F,0xF80F,0xF80F,0xF80F,0x780F,0x780F,0x7C1F,0x3E3E,0x1FFC,0x07F0,0x0000,0x0000,0x0000,0x0000,0x0000, // Ascii = [O]
0x0000,0x0000,0x0000,0x3FFC,0x3FFF,0x3E1F,0x3E0F,0x3E0F,0x3E0F,0x3E0F,0x3E1F,0x3E3F,0x3FFC,0x3FF0,0x3E00,0x3E00,0x3E00,0x3E00,0x3E00,0x3E00,0x3E00,0x0000,0x0000,0x0000,0x0000,0x0000, // Ascii = [P]
0x0000,0x0000,0x0000,0x07F0,0x1FFC,0x3E3E,0x7C1F,0x780F,0x780F,0xF80F,0xF80F,0xF80F,0xF80F,0xF80F,0xF80F,0x780F,0x780F,0x7C1F,0x3E3E,0x1FFC,0x07F8,0x007C,0x003F,0x000F,0x0003,0x0000, // Ascii = [Q]
0x0000,0x0000,0x0000,0x3FF0,0x3FFC,0x3C7E,0x3C3E,0x3C1E,0x3C1E,0x3C3E,0x3C3C,0x3CFC,0x3FF0,0x3FE0,0x3DF0,0x3CF8,0x3C7C,0x3C3E,0x3C1E,0x3C1F,0x3C0F,0x0000,0x0000,0x0000,0x0000,0x0000, // Ascii = [R]
0x0000,0x0000,0x0000,0x07FC,0x1FFE,0x3E0E,0x3C00,0x3C00,0x3C00,0x3E00,0x1FC0,0x0FF8,0x03FE,0x007F,0x001F,0x000F,0x000F,0x201F,0x3C3E,0x3FFC,0x1FF0,0x0000,0x0000,0x0000,0x0000,0x0000, // Ascii = [S]
0x0000,0x0000,0x0000,0xFFFF,0xFFFF,0x03E0,0x03E0,0x03E0,0x03E0,0x03E0,0x03E0,0x03E0,0x03E0,0x03E0,0x03E0,0x03E0,0x03E0,0x03E0,0x03E0,0x03E0,0x03E0,0x0000,0x0000,0x0000,0x0000,0x0000, // Ascii = [T]
0x0000,0x0000,0x0000,0x7C0F,0x7C0F,0x7C0F,0x7C0F,0x7C0F,0x7C0F,0x7C0F,0x7C0F,0x7C0F,0x7C0F,0x7C0F,0x7C0F,0x7C0F,0x3C1E,0x3C1E,0x3E3E,0x1FFC,0x07F0,0x0000,0x0000,0x0000,0x0000,0x0000, // Ascii = [U]
0x0000,0x0000,0x0000,0xF007,0xF007,0xF807,0x780F,0x7C0F,0x3C1E,0x3C1E,0x3E1E,0x1E3C,0x1F3C,0x1F78,0x0F78,0x0FF8,0x07F0,0x07F0,0x07F0,0x03E0,0x03E0,0x0000,0x0000,0x0000,0x0000,0x0000, // Ascii = [V]
0x0000,0x0000,0x0000,0xE003,0xF003,0xF003,0xF007,0xF3E7,0xF3E7,0xF3E7,0x73E7,0x7BF7,0x7FF7,0x7FFF,0x7F7F,0x7F7F,0x7F7E,0x3F7E,0x3E3E,0x3E3E,0x3E3E,0x0000,0x0000,0x0000,0x0000,0x0000, // Ascii = [W]
0x0000,0x0000,0x0000,0xF807,0x7C0F,0x3E1E,0x3E3E,0x1F3C,0x0FF8,0x07F0,0x07E0,0x03E0,0x03E0,0x07F0,0x0FF8,0x0F7C,0x1E7C,0x3C3E,0x781F,0x780F,0xF00F,0x0000,0x0000,0x0000,0x0000,0x0000, // Ascii = [X]
0x0000,0x0000,0x0000,0xF807,0x7807,0x7C0F,0x3C1E,0x3E1E,0x1F3C,0x0F78,0x0FF8,0x07F0,0x03E0,0x03E0,0x03E0,0x03E0,0x03E0,0x03E0,0x03E0,0x03E0,0x03E0,0x0000,0x0000,0x0000,0x0000,0x0000, // Ascii = [Y]
0x0000,0x0000,0x0000,0x7FFF,0x7FFF,0x000F,0x001F,0x003E,0x007C,0x00F8,0x00F0,0x01E0,0x03E0,0x07C0,0x0F80,0x0F00,0x1E00,0x3E00,0x7C00,0x7FFF,0x7FFF,0x0000,0x0000,0x0000,0x0000,0x0000, // Ascii = [Z]
0x07FF,0x0780,0x0780,0x0780,0x0780,0x0780,0x0780,0x0780,0x0780,0x0780,0x0780,0x0780,0x0780,0x0780,0x0780,0x0780,0x0780,0x0780,0x0780,0x0780,0x0780,0x0780,0x0780,0x07FF,0x07FF,0x0000, // Ascii = [[]
0x7800,0x7800,0x3C00,0x3C00,0x1E00,0x1E00,0x0F00,0x0F00,0x0780,0x0780,0x03C0,0x03C0,0x01E0,0x01E0,0x00F0,0x00F0,0x0078,0x0078,0x003C,0x003C,0x001E,0x001E,0x000F,0x000F,0x0007,0x0000, // Ascii = [\]
0x7FF0,0x00F0,0x00F0,0x00F0,0x00F0,0x00F0,0x00F0,0x00F0,0x00F0,0x00F0,0x00F0,0x00F0,0x00F0,0x00F0,0x00F0,0x00F0,0x00F0,0x00F0,0x00F0,0x00F0,0x00F0,0x00F0,0x00F0,0x7FF0,0x7FF0,0x0000, // Ascii = []]
0x00C0,0x01C0,0x01C0,0x03E0,0x03E0,0x07F0,0x07F0,0x0778,0x0F78,0x0F38,0x1E3C,0x1E3C,0x3C1E,0x3C1E,0x380F,0x780F,0x7807,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000, // Ascii = [^]
0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0xFFFF,0xFFFF,0x0000,0x0000,0x0000, // Ascii = [_]
0x00F0,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000, // Ascii = [`]
0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0FF8,0x3FFC,0x3C7C,0x003E,0x003E,0x003E,0x07FE,0x1FFE,0x3E3E,0x7C3E,0x783E,0x7C3E,0x7C7E,0x3FFF,0x1FCF,0x0000,0x0000,0x0000,0x0000,0x0000, // Ascii = [a]
0x3C00,0x3C00,0x3C00,0x3C00,0x3C00,0x3C00,0x3DF8,0x3FFE,0x3F3E,0x3E1F,0x3C0F,0x3C0F,0x3C0F,0x3C0F,0x3C0F,0x3C0F,0x3C1F,0x3C1E,0x3F3E,0x3FFC,0x3BF0,0x0000,0x0000,0x0000,0x0000,0x0000, // Ascii = [b]
0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x03FE,0x0FFF,0x1F87,0x3E00,0x3E00,0x3C00,0x7C00,0x7C00,0x7C00,0x3C00,0x3E00,0x3E00,0x1F87,0x0FFF,0x03FE,0x0000,0x0000,0x0000,0x0000,0x0000, // Ascii = [c]
0x001F,0x001F,0x001F,0x001F,0x001F,0x001F,0x07FF,0x1FFF,0x3E3F,0x3C1F,0x7C1F,0x7C1F,0x7C1F,0x781F,0x781F,0x7C1F,0x7C1F,0x3C3F,0x3E7F,0x1FFF,0x0FDF,0x0000,0x0000,0x0000,0x0000,0x0000, // Ascii = [d]
0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x03F8,0x0FFC,0x1F3E,0x3E1E,0x3C1F,0x7C1F,0x7FFF,0x7FFF,0x7C00,0x7C00,0x3C00,0x3E00,0x1F07,0x0FFF,0x03FE,0x0000,0x0000,0x0000,0x0000,0x0000, // Ascii = [e]
0x01FF,0x03E1,0x03C0,0x07C0,0x07C0,0x07C0,0x7FFF,0x7FFF,0x07C0,0x07C0,0x07C0,0x07C0,0x07C0,0x07C0,0x07C0,0x07C0,0x07C0,0x07C0,0x07C0,0x07C0,0x07C0,0x0000,0x0000,0x0000,0x0000,0x0000, // Ascii = [f]
0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x07EF,0x1FFF,0x3E7F,0x3C1F,0x7C1F,0x7C1F,0x781F,0x781F,0x781F,0x7C1F,0x7C1F,0x3C3F,0x3E7F,0x1FFF,0x0FDF,0x001E,0x001E,0x001E,0x387C,0x3FF8, // Ascii = [g]
0x3C00,0x3C00,0x3C00,0x3C00,0x3C00,0x3C00,0x3DFC,0x3FFE,0x3F9E,0x3F1F,0x3E1F,0x3C1F,0x3C1F,0x3C1F,0x3C1F,0x3C1F,0x3C1F,0x3C1F,0x3C1F,0x3C1F,0x3C1F,0x0000,0x0000,0x0000,0x0000,0x0000, // Ascii = [h]
0x01F0,0x01F0,0x0000,0x0000,0x0000,0x0000,0x7FE0,0x7FE0,0x01E0,0x01E0,0x01E0,0x01E0,0x01E0,0x01E0,0x01E0,0x01E0,0x01E0,0x01E0,0x01E0,0x01E0,0x01E0,0x0000,0x0000,0x0000,0x0000,0x0000, // Ascii = [i]
0x00F8,0x00F8,0x0000,0x0000,0x0000,0x0000,0x3FF8,0x3FF8,0x00F8,0x00F8,0x00F8,0x00F8,0x00F8,0x00F8,0x00F8,0x00F8,0x00F8,0x00F8,0x00F8,0x00F8,0x00F8,0x00F8,0x00F8,0x00F0,0x71F0,0x7FE0, // Ascii = [j]
0x3C00,0x3C00,0x3C00,0x3C00,0x3C00,0x3C00,0x3C1F,0x3C3E,0x3C7C,0x3CF8,0x3DF0,0x3DE0,0x3FC0,0x3FC0,0x3FE0,0x3DF0,0x3CF8,0x3C7C,0x3C3E,0x3C1F,0x3C1F,0x0000,0x0000,0x0000,0x0000,0x0000, // Ascii = [k]
0x7FF0,0x01F0,0x01F0,0x01F0,0x01F0,0x01F0,0x01F0,0x01F0,0x01F0,0x01F0,0x01F0,0x01F0,0x01F0,0x01F0,0x01F0,0x01F0,0x01F0,0x01F0,0x01F0,0x01F0,0x01F0,0x0000,0x0000,0x0000,0x0000,0x0000, // Ascii = [l]
0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0xF79E,0xFFFF,0xFFFF,0xFFFF,0xFBE7,0xF9E7,0xF1C7,0xF1C7,0xF1C7,0xF1C7,0xF1C7,0xF1C7,0xF1C7,0xF1C7,0xF1C7,0x0000,0x0000,0x0000,0x0000,0x0000, // Ascii = [m]
0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x3DFC,0x3FFE,0x3F9E,0x3F1F,0x3E1F,0x3C1F,0x3C1F,0x3C1F,0x3C1F,0x3C1F,0x3C1F,0x3C1F,0x3C1F,0x3C1F,0x3C1F,0x0000,0x0000,0x0000,0x0000,0x0000, // Ascii = [n]
0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x07F0,0x1FFC,0x3E3E,0x3C1F,0x7C1F,0x780F,0x780F,0x780F,0x780F,0x780F,0x7C1F,0x3C1F,0x3E3E,0x1FFC,0x07F0,0x0000,0x0000,0x0000,0x0000,0x0000, // Ascii = [o]
0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x3DF8,0x3FFE,0x3F3E,0x3E1F,0x3C0F,0x3C0F,0x3C0F,0x3C0F,0x3C0F,0x3C0F,0x3C1F,0x3E1E,0x3F3E,0x3FFC,0x3FF8,0x3C00,0x3C00,0x3C00,0x3C00,0x3C00, // Ascii = [p]
0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x07EE,0x1FFE,0x3E7E,0x3C1E,0x7C1E,0x781E,0x781E,0x781E,0x781E,0x781E,0x7C1E,0x7C3E,0x3E7E,0x1FFE,0x0FDE,0x001E,0x001E,0x001E,0x001E,0x001E, // Ascii = [q]
0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x1F7F,0x1FFF,0x1FE7,0x1FC7,0x1F87,0x1F00,0x1F00,0x1F00,0x1F00,0x1F00,0x1F00,0x1F00,0x1F00,0x1F00,0x1F00,0x0000,0x0000,0x0000,0x0000,0x0000, // Ascii = [r]
0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x07FC,0x1FFE,0x1E0E,0x3E00,0x3E00,0x3F00,0x1FE0,0x07FC,0x00FE,0x003E,0x001E,0x001E,0x3C3E,0x3FFC,0x1FF0,0x0000,0x0000,0x0000,0x0000,0x0000, // Ascii = [s]
0x0000,0x0000,0x0000,0x0780,0x0780,0x0780,0x7FFF,0x7FFF,0x0780,0x0780,0x0780,0x0780,0x0780,0x0780,0x0780,0x0780,0x0780,0x0780,0x07C0,0x03FF,0x01FF,0x0000,0x0000,0x0000,0x0000,0x0000, // Ascii = [t]
0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x3C1E,0x3C1E,0x3C1E,0x3C1E,0x3C1E,0x3C1E,0x3C1E,0x3C1E,0x3C1E,0x3C1E,0x3C3E,0x3C7E,0x3EFE,0x1FFE,0x0FDE,0x0000,0x0000,0x0000,0x0000,0x0000, // Ascii = [u]
0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0xF007,0x780F,0x780F,0x3C1E,0x3C1E,0x3E1E,0x1E3C,0x1E3C,0x0F78,0x0F78,0x0FF0,0x07F0,0x07F0,0x03E0,0x03E0,0x0000,0x0000,0x0000,0x0000,0x0000, // Ascii = [v]
0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0xF003,0xF1E3,0xF3E3,0xF3E7,0xF3F7,0xF3F7,0x7FF7,0x7F77,0x7F7F,0x7F7F,0x7F7F,0x3E3E,0x3E3E,0x3E3E,0x3E3E,0x0000,0x0000,0x0000,0x0000,0x0000, // Ascii = [w]
0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x7C0F,0x3E1E,0x3E3C,0x1F3C,0x0FF8,0x07F0,0x07F0,0x03E0,0x07F0,0x07F8,0x0FF8,0x1E7C,0x3E3E,0x3C1F,0x781F,0x0000,0x0000,0x0000,0x0000,0x0000, // Ascii = [x]
0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0xF807,0x780F,0x7C0F,0x3C1E,0x3C1E,0x1E3C,0x1E3C,0x1F3C,0x0F78,0x0FF8,0x07F0,0x07F0,0x03E0,0x03E0,0x03C0,0x03C0,0x03C0,0x0780,0x0F80,0x7F00, // Ascii = [y]
0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x3FFF,0x3FFF,0x001F,0x003E,0x007C,0x00F8,0x01F0,0x03E0,0x07C0,0x0F80,0x1F00,0x1E00,0x3C00,0x7FFF,0x7FFF,0x0000,0x0000,0x0000,0x0000,0x0000, // Ascii = [z]
0x01FE,0x03E0,0x03C0,0x03C0,0x03C0,0x03C0,0x01E0,0x01E0,0x01E0,0x01C0,0x03C0,0x3F80,0x3F80,0x03C0,0x01C0,0x01E0,0x01E0,0x01E0,0x03C0,0x03C0,0x03C0,0x03C0,0x03E0,0x01FE,0x007E,0x0000, // Ascii = [{]
0x01C0,0x01C0,0x01C0,0x01C0,0x01C0,0x01C0,0x01C0,0x01C0,0x01C0,0x01C0,0x01C0,0x01C0,0x01C0,0x01C0,0x01C0,0x01C0,0x01C0,0x01C0,0x01C0,0x01C0,0x01C0,0x01C0,0x01C0,0x01C0,0x01C0,0x0000, // Ascii = [|]
0x3FC0,0x03E0,0x01E0,0x01E0,0x01E0,0x01E0,0x01C0,0x03C0,0x03C0,0x01C0,0x01E0,0x00FE,0x00FE,0x01E0,0x01C0,0x03C0,0x03C0,0x01C0,0x01E0,0x01E0,0x01E0,0x01E0,0x03E0,0x3FC0,0x3F00,0x0000, // Ascii = [}]
0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x3F07,0x7FC7,0x73E7,0xF1FF,0xF07E,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000, // Ascii = [~]
};
FontDef Font_7x10 = {7,10,Font7x10};
FontDef Font_11x18 = {11,18,Font11x18};
FontDef Font_16x26 = {16,26,Font16x26};

View File

@ -0,0 +1,17 @@
#include <stdint.h>
#ifndef __SSD1306_FONTS_H__
#define __SSD1306_FONTS_H__
typedef struct {
const uint8_t FontWidth; /*!< Font width in pixels */
uint8_t FontHeight; /*!< Font height in pixels */
const uint16_t *data; /*!< Pointer to data font data array */
} FontDef;
extern FontDef Font_7x10;
extern FontDef Font_11x18;
extern FontDef Font_16x26;
#endif // __SSD1306_FONTS_H__

Binary file not shown.

View File

@ -0,0 +1,213 @@
/*
* usart.c
*
* Copyright 2017 Edward V. Emelianoff <eddy@sao.ru, edward.emelianoff@gmail.com>
*
* 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 "stm32f0.h"
#include "hardware.h"
#include "usart.h"
#include <string.h>
extern volatile uint32_t Tms;
static int datalen[2] = {0,0}; // received data line length (including '\n')
volatile int linerdy = 0, // received data ready
dlen = 0, // length of data (including '\n') in current buffer
bufovr = 0, // input buffer overfull
txrdy = 1 // transmission done
;
int rbufno = 0; // current rbuf number
static char rbuf[UARTBUFSZ][2], tbuf[UARTBUFSZ]; // receive & transmit buffers
static char *recvdata = NULL;
/**
* return length of received data (without trailing zero
*/
int usart_getline(char **line){
if(bufovr){
bufovr = 0;
linerdy = 0;
return 0;
}
*line = recvdata;
linerdy = 0;
return dlen;
}
TXstatus usart_send(const char *str, int len){
if(!txrdy) return LINE_BUSY;
if(len > UARTBUFSZ) return STR_TOO_LONG;
txrdy = 0;
memcpy(tbuf, str, len);
#if USARTNUM == 2
DMA1_Channel4->CCR &= ~DMA_CCR_EN;
DMA1_Channel4->CNDTR = len;
DMA1_Channel4->CCR |= DMA_CCR_EN; // start transmission
#elif USARTNUM == 1
DMA1_Channel2->CCR &= ~DMA_CCR_EN;
DMA1_Channel2->CNDTR = len;
DMA1_Channel2->CCR |= DMA_CCR_EN;
#else
#error "Not implemented"
#endif
return ALL_OK;
}
TXstatus usart_send_blocking(const char *str, int len){
if(!txrdy) return LINE_BUSY;
int i;
bufovr = 0;
for(i = 0; i < len; ++i){
USARTX -> TDR = *str++;
while(!(USARTX->ISR & USART_ISR_TXE)){IWDG->KR = IWDG_REFRESH;};
}
return ALL_OK;
}
void usart_send_blck(const char *str){
while(!txrdy){IWDG->KR = IWDG_REFRESH;}
bufovr = 0;
while(*str){
USARTX -> TDR = *str++;
while(!(USARTX->ISR & USART_ISR_TXE)){IWDG->KR = IWDG_REFRESH;};
}
}
void usart_setup(){
// Nucleo's USART2 connected to VCP proxy of st-link
#if USARTNUM == 2
// setup pins: PA2 (Tx - AF1), PA15 (Rx - AF1)
// AF mode (AF1)
GPIOA->MODER = (GPIOA->MODER & ~(GPIO_MODER_MODER2|GPIO_MODER_MODER15))\
| (GPIO_MODER_MODER2_AF | GPIO_MODER_MODER15_AF);
GPIOA->AFR[0] = (GPIOA->AFR[0] &~GPIO_AFRH_AFRH2) | 1 << (2 * 4); // PA2
GPIOA->AFR[1] = (GPIOA->AFR[1] &~GPIO_AFRH_AFRH7) | 1 << (7 * 4); // PA15
// DMA: Tx - Ch4
DMA1_Channel4->CPAR = (uint32_t) &USART2->TDR; // periph
DMA1_Channel4->CMAR = (uint32_t) tbuf; // mem
DMA1_Channel4->CCR |= DMA_CCR_MINC | DMA_CCR_DIR | DMA_CCR_TCIE; // 8bit, mem++, mem->per, transcompl irq
// Tx CNDTR set @ each transmission due to data size
NVIC_SetPriority(DMA1_Channel4_5_IRQn, 3);
NVIC_EnableIRQ(DMA1_Channel4_5_IRQn);
NVIC_SetPriority(USART2_IRQn, 0);
// setup usart2
RCC->APB1ENR |= RCC_APB1ENR_USART2EN; // clock
// oversampling by16, 115200bps (fck=48mHz)
//USART2_BRR = 0x1a1; // 48000000 / 115200
USART2->BRR = 480000 / 1152;
USART2->CR3 = USART_CR3_DMAT; // enable DMA Tx
USART2->CR1 = USART_CR1_TE | USART_CR1_RE | USART_CR1_UE; // 1start,8data,nstop; enable Rx,Tx,USART
while(!(USART2->ISR & USART_ISR_TC)); // polling idle frame Transmission
USART2->ICR |= USART_ICR_TCCF; // clear TC flag
USART2->CR1 |= USART_CR1_RXNEIE;
NVIC_EnableIRQ(USART2_IRQn);
// USART1 of main board
#elif USARTNUM == 1
// PA9 - Tx, PA10 - Rx (AF1)
GPIOA->MODER = (GPIOA->MODER & ~(GPIO_MODER_MODER9 | GPIO_MODER_MODER10))\
| (GPIO_MODER_MODER9_AF | GPIO_MODER_MODER10_AF);
GPIOA->AFR[1] = (GPIOA->AFR[1] & ~(GPIO_AFRH_AFRH1 | GPIO_AFRH_AFRH2)) |
1 << (1 * 4) | 1 << (2 * 4); // PA9, PA10
// USART1 Tx DMA - Channel2 (default value in SYSCFG_CFGR1)
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
// Tx CNDTR set @ each transmission due to data size
NVIC_SetPriority(DMA1_Channel2_3_IRQn, 3);
NVIC_EnableIRQ(DMA1_Channel2_3_IRQn);
NVIC_SetPriority(USART1_IRQn, 0);
// setup usart1
RCC->APB2ENR |= RCC_APB2ENR_USART1EN;
USART1->BRR = 480000 / 1152;
USART1->CR3 = USART_CR3_DMAT; // enable DMA Tx
USART1->CR1 = USART_CR1_TE | USART_CR1_RE | USART_CR1_UE; // 1start,8data,nstop; enable Rx,Tx,USART
while(!(USART1->ISR & USART_ISR_TC)); // polling idle frame Transmission
USART1->ICR |= USART_ICR_TCCF; // clear TC flag
USART1->CR1 |= USART_CR1_RXNEIE;
NVIC_EnableIRQ(USART1_IRQn);
#else
#error "Not implemented"
#endif
}
#if USARTNUM == 2
void usart2_isr(){
// USART1
#elif USARTNUM == 1
void usart1_isr(){
#else
#error "Not implemented"
#endif
#ifdef CHECK_TMOUT
static uint32_t tmout = 0;
#endif
if(USARTX->ISR & USART_ISR_RXNE){ // RX not emty - receive next char
#ifdef CHECK_TMOUT
if(tmout && Tms >= tmout){ // set overflow flag
bufovr = 1;
datalen[rbufno] = 0;
}
tmout = Tms + TIMEOUT_MS;
if(!tmout) tmout = 1; // prevent 0
#endif
// read RDR clears flag
uint8_t rb = USARTX->RDR;
if(datalen[rbufno] < UARTBUFSZ){ // put next char into buf
rbuf[rbufno][datalen[rbufno]++] = rb;
if(rb == '\n'){ // got newline - line ready
linerdy = 1;
dlen = datalen[rbufno];
recvdata = rbuf[rbufno];
// prepare other buffer
rbufno = !rbufno;
datalen[rbufno] = 0;
#ifdef CHECK_TMOUT
// clear timeout at line end
tmout = 0;
#endif
}
}else{ // buffer overrun
bufovr = 1;
datalen[rbufno] = 0;
#ifdef CHECK_TMOUT
tmout = 0;
#endif
}
}
}
#if USARTNUM == 2
void dma1_channel4_5_isr(){
if(DMA1->ISR & DMA_ISR_TCIF4){ // Tx
DMA1->IFCR |= DMA_IFCR_CTCIF4; // clear TC flag
txrdy = 1;
}
}
// USART1
#elif USARTNUM == 1
void dma1_channel2_3_isr(){
if(DMA1->ISR & DMA_ISR_TCIF2){ // Tx
DMA1->IFCR |= DMA_IFCR_CTCIF2; // clear TC flag
txrdy = 1;
}
}
#else
#error "Not implemented"
#endif

View File

@ -0,0 +1,52 @@
/*
* usart.h
*
* Copyright 2017 Edward V. Emelianoff <eddy@sao.ru, edward.emelianoff@gmail.com>
*
* 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__
// input and output buffers size
#define UARTBUFSZ (64)
// timeout between data bytes
#ifndef TIMEOUT_MS
#define TIMEOUT_MS (1500)
#endif
typedef enum{
ALL_OK,
LINE_BUSY,
STR_TOO_LONG
} TXstatus;
#define usartrx() (linerdy)
#define usartovr() (bufovr)
extern volatile int linerdy, bufovr, txrdy;
void usart_setup();
int usart_getline(char **line);
TXstatus usart_send(const char *str, int len);
TXstatus usart_send_blocking(const char *str, int len);
void usart_send_blck(const char *str);
#define USEND(str) do{}while(LINE_BUSY == usart_send(str, sizeof(str)-1))
#define UNEWLINE() do{}while(LINE_BUSY == usart_send("\n", 1))
#endif // __USART_H__

View File

@ -0,0 +1,191 @@
/*
* geany_encoding=koi8-r
* usb.c - base functions for different USB types
*
* Copyright 2018 Edward V. Emelianov <eddy@sao.ru, edward.emelianoff@gmail.com>
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; if not, write to the Free Software
* Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston,
* MA 02110-1301, USA.
*
*/
#include "usb.h"
#include "usb_lib.h"
#include "usart.h"
#include <string.h> // memcpy, memmove
// incoming buffer size
#define IDATASZ (256)
static uint8_t incoming_data[IDATASZ];
static uint8_t ovfl = 0;
static uint16_t idatalen = 0;
static int8_t usbON = 0; // ==1 when USB fully configured
static volatile uint8_t tx_succesfull = 0;
// interrupt IN handler (never used?)
static uint16_t EP1_Handler(ep_t ep){
uint8_t ep0buf[11];
if (ep.rx_flag){
EP_Read(1, ep0buf);
ep.status = SET_VALID_TX(ep.status);
ep.status = KEEP_STAT_RX(ep.status);
}else if (ep.tx_flag){
ep.status = SET_VALID_RX(ep.status);
ep.status = SET_STALL_TX(ep.status);
}
return ep.status;
}
// data IN/OUT handler
static uint16_t EP23_Handler(ep_t ep){
MSG("EP2\n");
if(ep.rx_flag){
int rd = ep.rx_cnt, rest = IDATASZ - idatalen;
if(rd){
if(rd <= rest){
idatalen += EP_Read(2, &incoming_data[idatalen]);
ovfl = 0;
}else{
ep.status = SET_NAK_RX(ep.status);
ovfl = 1;
return ep.status;
}
}
// end of transaction: clear DTOGs
ep.status = CLEAR_DTOG_RX(ep.status);
ep.status = CLEAR_DTOG_TX(ep.status);
ep.status = SET_STALL_TX(ep.status);
}else if (ep.tx_flag){
ep.status = KEEP_STAT_TX(ep.status);
tx_succesfull = 1;
}
ep.status = SET_VALID_RX(ep.status);
return ep.status;
}
void USB_setup(){
RCC->APB1ENR |= RCC_APB1ENR_CRSEN | RCC_APB1ENR_USBEN; // enable CRS (hsi48 sync) & USB
RCC->CFGR3 &= ~RCC_CFGR3_USBSW; // reset USB
RCC->CR2 |= RCC_CR2_HSI48ON; // turn ON HSI48
uint32_t tmout = 16000000;
while(!(RCC->CR2 & RCC_CR2_HSI48RDY)){if(--tmout == 0) break;}
FLASH->ACR = FLASH_ACR_PRFTBE | FLASH_ACR_LATENCY;
CRS->CFGR &= ~CRS_CFGR_SYNCSRC;
CRS->CFGR |= CRS_CFGR_SYNCSRC_1; // USB SOF selected as sync source
CRS->CR |= CRS_CR_AUTOTRIMEN; // enable auto trim
CRS->CR |= CRS_CR_CEN; // enable freq counter & block CRS->CFGR as read-only
RCC->CFGR |= RCC_CFGR_SW;
// allow RESET and CTRM interrupts
USB->CNTR = USB_CNTR_RESETM | USB_CNTR_CTRM;
// clear flags
USB->ISTR = 0;
// and activate pullup
USB->BCDR |= USB_BCDR_DPPU;
NVIC_EnableIRQ(USB_IRQn);
}
void usb_proc(){
if(USB_GetState() == USB_CONFIGURE_STATE){ // USB configured - activate other endpoints
if(!usbON){ // endpoints not activated
// make new BULK endpoint
// Buffer have 1024 bytes, but last 256 we use for CAN bus (30.2 of RM: USB main features)
EP_Init(1, EP_TYPE_INTERRUPT, 10, 0, EP1_Handler); // IN1 - transmit
EP_Init(2, EP_TYPE_BULK, 0, USB_RXBUFSZ, EP23_Handler); // OUT2 - receive data
EP_Init(3, EP_TYPE_BULK, USB_TXBUFSZ, 0, EP23_Handler); // IN3 - transmit data
usbON = 1;
}
}else{
usbON = 0;
}
}
void USB_send(const char *buf){
uint16_t l = 0, ctr = 0;
const char *p = buf;
while(*p++) ++l;
while(l){
uint16_t s = (l > USB_TXBUFSZ) ? USB_TXBUFSZ : l;
tx_succesfull = 0;
EP_Write(3, (uint8_t*)&buf[ctr], s);
uint32_t ctra = 1000000;
while(--ctra && tx_succesfull == 0);
l -= s;
ctr += s;
}
}
/**
* @brief USB_receive
* @param buf (i) - buffer for received data
* @param bufsize - its size
* @return amount of received bytes
*
int USB_receive(char *buf, int bufsize){
if(!bufsize || !idatalen) return 0;
USB->CNTR = 0;
int sz = (idatalen > bufsize) ? bufsize : idatalen, rest = idatalen - sz;
memcpy(buf, incoming_data, sz);
if(rest > 0){
memmove(incoming_data, &incoming_data[sz], rest);
idatalen = rest;
}else idatalen = 0;
if(ovfl){
EP23_Handler(endpoints[2]);
uint16_t epstatus = USB->EPnR[2];
epstatus = CLEAR_DTOG_RX(epstatus);
epstatus = SET_VALID_RX(epstatus);
USB->EPnR[2] = epstatus;
}
USB->CNTR = USB_CNTR_RESETM | USB_CNTR_CTRM;
return sz;
}*/
int USB_receive(char *buf, int bufsize){
if(bufsize<1 || !idatalen) return 0;
IWDG->KR = IWDG_REFRESH;
int stlen = 0;
for(int i = 0; i < idatalen; ++i){
if(incoming_data[i] == '\n'){
stlen = i+1;
incoming_data[i] = 0;
break;
}
}
if(stlen == 0) return 0;
USB->CNTR = 0;
int sz = (stlen > bufsize) ? bufsize : stlen, rest = idatalen - sz;
memcpy(buf, incoming_data, sz);
if(rest > 0){
memmove(incoming_data, &incoming_data[sz], rest);
idatalen = rest;
}else idatalen = 0;
if(ovfl){
EP23_Handler(endpoints[2]);
uint16_t epstatus = USB->EPnR[2];
epstatus = CLEAR_DTOG_RX(epstatus);
epstatus = SET_VALID_RX(epstatus);
USB->EPnR[2] = epstatus;
}
USB->CNTR = USB_CNTR_RESETM | USB_CNTR_CTRM;
return sz;
}
/**
* @brief USB_configured
* @return 1 if USB is in configured state
*/
int USB_configured(){
return usbON;
}

View File

@ -0,0 +1,37 @@
/*
* geany_encoding=koi8-r
* usb.h
*
* Copyright 2018 Edward V. Emelianov <eddy@sao.ru, edward.emelianoff@gmail.com>
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; if not, write to the Free Software
* Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston,
* MA 02110-1301, USA.
*
*/
#pragma once
#ifndef __USB_H__
#define __USB_H__
#include "hardware.h"
#define BUFFSIZE (64)
void USB_setup();
void usb_proc();
void USB_send(const char *buf);
int USB_receive(char *buf, int bufsize);
int USB_configured();
#endif // __USB_H__

View File

@ -0,0 +1,108 @@
/*
* geany_encoding=koi8-r
* usb_defs.h
*
* Copyright 2018 Edward V. Emelianov <eddy@sao.ru, edward.emelianoff@gmail.com>
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; if not, write to the Free Software
* Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston,
* MA 02110-1301, USA.
*
*/
#pragma once
#ifndef __USB_DEFS_H__
#define __USB_DEFS_H__
#include <stm32f0xx.h>
#define MSG(str)
/**
* Buffers size definition
**/
// !!! when working with CAN bus change USB_BTABLE_SIZE to 768 !!!
#define USB_BTABLE_SIZE 1024
// first 64 bytes of USB_BTABLE are registers!
#define USB_EP0_BASEADDR 64
// for USB FS EP0 buffers are from 8 to 64 bytes long (64 for PL2303)
#define USB_EP0_BUFSZ 64
// USB transmit buffer size (64 for PL2303)
#define USB_TXBUFSZ 64
// USB receive buffer size (64 for PL2303)
#define USB_RXBUFSZ 64
#define USB_BTABLE_BASE 0x40006000
#undef USB_BTABLE
#define USB_BTABLE ((USB_BtableDef *)(USB_BTABLE_BASE))
#define USB_ISTR_EPID 0x0000000F
#define USB_FNR_LSOF_0 0x00000800
#define USB_FNR_lSOF_1 0x00001000
#define USB_LPMCSR_BESL_0 0x00000010
#define USB_LPMCSR_BESL_1 0x00000020
#define USB_LPMCSR_BESL_2 0x00000040
#define USB_LPMCSR_BESL_3 0x00000080
#define USB_EPnR_CTR_RX 0x00008000
#define USB_EPnR_DTOG_RX 0x00004000
#define USB_EPnR_STAT_RX 0x00003000
#define USB_EPnR_STAT_RX_0 0x00001000
#define USB_EPnR_STAT_RX_1 0x00002000
#define USB_EPnR_SETUP 0x00000800
#define USB_EPnR_EP_TYPE 0x00000600
#define USB_EPnR_EP_TYPE_0 0x00000200
#define USB_EPnR_EP_TYPE_1 0x00000400
#define USB_EPnR_EP_KIND 0x00000100
#define USB_EPnR_CTR_TX 0x00000080
#define USB_EPnR_DTOG_TX 0x00000040
#define USB_EPnR_STAT_TX 0x00000030
#define USB_EPnR_STAT_TX_0 0x00000010
#define USB_EPnR_STAT_TX_1 0x00000020
#define USB_EPnR_EA 0x0000000F
#define USB_COUNTn_RX_BLSIZE 0x00008000
#define USB_COUNTn_NUM_BLOCK 0x00007C00
#define USB_COUNTn_RX 0x0000003F
#define USB_TypeDef USB_TypeDef_custom
typedef struct{
__IO uint32_t EPnR[8];
__IO uint32_t RESERVED1;
__IO uint32_t RESERVED2;
__IO uint32_t RESERVED3;
__IO uint32_t RESERVED4;
__IO uint32_t RESERVED5;
__IO uint32_t RESERVED6;
__IO uint32_t RESERVED7;
__IO uint32_t RESERVED8;
__IO uint32_t CNTR;
__IO uint32_t ISTR;
__IO uint32_t FNR;
__IO uint32_t DADDR;
__IO uint32_t BTABLE;
__IO uint32_t LPMCSR;
__IO uint32_t BCDR;
} USB_TypeDef;
typedef struct{
__IO uint16_t USB_ADDR_TX;
__IO uint16_t USB_COUNT_TX;
__IO uint16_t USB_ADDR_RX;
__IO uint16_t USB_COUNT_RX;
} USB_EPDATA_TypeDef;
typedef struct{
__IO USB_EPDATA_TypeDef EP[8];
} USB_BtableDef;
#endif // __USB_DEFS_H__

View File

@ -0,0 +1,504 @@
/*
* geany_encoding=koi8-r
* usb_lib.c
*
* Copyright 2018 Edward V. Emelianov <eddy@sao.ru, edward.emelianoff@gmail.com>
*
* 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 <stdint.h>
#include "usb_lib.h"
#include <string.h> // memcpy
#include "usart.h"
ep_t endpoints[ENDPOINTS_NUM];
static usb_dev_t USB_Dev;
static usb_LineCoding lineCoding = {115200, 0, 0, 8};
static config_pack_t setup_packet;
static uint8_t ep0databuf[EP0DATABUF_SIZE];
static uint8_t ep0dbuflen = 0;
usb_LineCoding getLineCoding(){return lineCoding;}
// definition of parts common for USB_DeviceDescriptor & USB_DeviceQualifierDescriptor
#define bcdUSB_L 0x10
#define bcdUSB_H 0x01
#define bDeviceClass 0
#define bDeviceSubClass 0
#define bDeviceProtocol 0
#define bNumConfigurations 1
static const uint8_t USB_DeviceDescriptor[] = {
18, // bLength
0x01, // bDescriptorType - Device descriptor
bcdUSB_L, // bcdUSB_L - 1.10
bcdUSB_H, // bcdUSB_H
bDeviceClass, // bDeviceClass - USB_COMM
bDeviceSubClass, // bDeviceSubClass
bDeviceProtocol, // bDeviceProtocol
USB_EP0_BUFSZ, // bMaxPacketSize
0x7b, // idVendor_L PL2303: VID=0x067b, PID=0x2303
0x06, // idVendor_H
0x03, // idProduct_L
0x23, // idProduct_H
0x00, // bcdDevice_Ver_L
0x03, // bcdDevice_Ver_H
0x01, // iManufacturer
0x02, // iProduct
0x00, // iSerialNumber
bNumConfigurations // bNumConfigurations
};
static const uint8_t USB_DeviceQualifierDescriptor[] = {
10, //bLength
0x06, // bDescriptorType - Device qualifier
bcdUSB_L, // bcdUSB_L
bcdUSB_H, // bcdUSB_H
bDeviceClass, // bDeviceClass
bDeviceSubClass, // bDeviceSubClass
bDeviceProtocol, // bDeviceProtocol
USB_EP0_BUFSZ, // bMaxPacketSize0
bNumConfigurations, // bNumConfigurations
0x00 // Reserved
};
static const uint8_t USB_ConfigDescriptor[] = {
/*Configuration Descriptor*/
0x09, /* bLength: Configuration Descriptor size */
0x02, /* bDescriptorType: Configuration */
39, /* wTotalLength:no of returned bytes */
0x00,
0x01, /* bNumInterfaces: 1 interface */
0x01, /* bConfigurationValue: Configuration value */
0x00, /* iConfiguration: Index of string descriptor describing the configuration */
0xa0, /* bmAttributes - Bus powered, Remote wakeup */
0x32, /* MaxPower 100 mA */
/*---------------------------------------------------------------------------*/
/*Interface Descriptor */
0x09, /* bLength: Interface Descriptor size */
0x04, /* bDescriptorType: Interface */
0x00, /* bInterfaceNumber: Number of Interface */
0x00, /* bAlternateSetting: Alternate setting */
0x03, /* bNumEndpoints: 3 endpoints used */
0xff, /* bInterfaceClass */
0x00, /* bInterfaceSubClass */
0x00, /* bInterfaceProtocol */
0x00, /* iInterface: */
///////////////////////////////////////////////////
/*Endpoint 1 Descriptor*/
0x07, /* bLength: Endpoint Descriptor size */
0x05, /* bDescriptorType: Endpoint */
0x81, /* bEndpointAddress IN1 */
0x03, /* bmAttributes: Interrupt */
0x0a, /* wMaxPacketSize LO: */
0x00, /* wMaxPacketSize HI: */
0x01, /* bInterval: */
/*Endpoint OUT2 Descriptor*/
0x07, /* bLength: Endpoint Descriptor size */
0x05, /* bDescriptorType: Endpoint */
0x02, /* bEndpointAddress: OUT2 */
0x02, /* bmAttributes: Bulk */
(USB_RXBUFSZ & 0xff), /* wMaxPacketSize: 64 */
(USB_RXBUFSZ >> 8),
0x00, /* bInterval: ignore for Bulk transfer */
/*Endpoint IN3 Descriptor*/
0x07, /* bLength: Endpoint Descriptor size */
0x05, /* bDescriptorType: Endpoint */
0x83, /* bEndpointAddress IN3 */
0x02, /* bmAttributes: Bulk */
(USB_TXBUFSZ & 0xff), /* wMaxPacketSize: 64 */
(USB_TXBUFSZ >> 8),
0x00, /* bInterval: ignore for Bulk transfer */
};
_USB_LANG_ID_(USB_StringLangDescriptor, LANG_US);
// these descriptors are not used in PL2303 emulator!
_USB_STRING_(USB_StringSerialDescriptor, u"0");
_USB_STRING_(USB_StringManufacturingDescriptor, u"Prolific Technology Inc.");
_USB_STRING_(USB_StringProdDescriptor, u"USB-Serial Controller");
/*
* default handlers
*/
// SET_LINE_CODING
void WEAK linecoding_handler(usb_LineCoding __attribute__((unused)) *lc){
MSG("linecoding_handler\n");
}
// SET_CONTROL_LINE_STATE
void WEAK clstate_handler(uint16_t __attribute__((unused)) val){
MSG("clstate_handler\n");
}
// SEND_BREAK
void WEAK break_handler(){
MSG("break_handler\n");
}
// handler of vendor requests
void WEAK vendor_handler(config_pack_t *packet){
if(packet->bmRequestType & 0x80){ // read
//SEND("Read");
uint8_t c;
switch(packet->wValue){
case 0x8484:
c = 2;
break;
case 0x0080:
c = 1;
break;
case 0x8686:
c = 0xaa;
break;
default:
c = 0;
}
EP_WriteIRQ(0, &c, 1);
}else{ // write ZLP
//SEND("Write");
EP_WriteIRQ(0, (uint8_t *)0, 0);
}
/*SEND(" vendor, reqt=");
printuhex(packet->bmRequestType);
SEND(", wval=");
printuhex(packet->wValue);
usart_putchar('\n');*/
}
#define WRITEDUMP(str)
static void wr0(const uint8_t *buf, uint16_t size){
if(setup_packet.wLength < size) size = setup_packet.wLength;
EP_WriteIRQ(0, buf, size);
}
static inline void get_descriptor(){
switch(setup_packet.wValue){
case DEVICE_DESCRIPTOR:
wr0(USB_DeviceDescriptor, sizeof(USB_DeviceDescriptor));
break;
case CONFIGURATION_DESCRIPTOR:
wr0(USB_ConfigDescriptor, sizeof(USB_ConfigDescriptor));
break;
case STRING_LANG_DESCRIPTOR:
wr0((const uint8_t *)&USB_StringLangDescriptor, STRING_LANG_DESCRIPTOR_SIZE_BYTE);
break;
case STRING_MAN_DESCRIPTOR:
wr0((const uint8_t *)&USB_StringManufacturingDescriptor, USB_StringManufacturingDescriptor.bLength);
break;
case STRING_PROD_DESCRIPTOR:
wr0((const uint8_t *)&USB_StringProdDescriptor, USB_StringProdDescriptor.bLength);
break;
case STRING_SN_DESCRIPTOR:
wr0((const uint8_t *)&USB_StringSerialDescriptor, USB_StringSerialDescriptor.bLength);
break;
case DEVICE_QUALIFIER_DESCRIPTOR:
wr0(USB_DeviceQualifierDescriptor, USB_DeviceQualifierDescriptor[0]);
break;
default:
WRITEDUMP("UNK_DES");
break;
}
}
static uint8_t configuration = 0; // reply for GET_CONFIGURATION (==1 if configured)
static inline void std_d2h_req(){
uint16_t status = 0; // bus powered
switch(setup_packet.bRequest){
case GET_DESCRIPTOR:
get_descriptor();
break;
case GET_STATUS:
EP_WriteIRQ(0, (uint8_t *)&status, 2); // send status: Bus Powered
break;
case GET_CONFIGURATION:
WRITEDUMP("GET_CONFIGURATION");
EP_WriteIRQ(0, &configuration, 1);
break;
default:
WRITEDUMP("80:WR_REQ");
break;
}
}
static inline void std_h2d_req(){
switch(setup_packet.bRequest){
case SET_ADDRESS:
// new address will be assigned later - after acknowlegement or request to host
USB_Dev.USB_Addr = setup_packet.wValue;
break;
case SET_CONFIGURATION:
// Now device configured
USB_Dev.USB_Status = USB_CONFIGURE_STATE;
configuration = setup_packet.wValue;
break;
default:
WRITEDUMP("0:WR_REQ");
break;
}
}
/*
bmRequestType: 76543210
7 direction: 0 - host->device, 1 - device->host
65 type: 0 - standard, 1 - class, 2 - vendor
4..0 getter: 0 - device, 1 - interface, 2 - endpoint, 3 - other
*/
/**
* Endpoint0 (control) handler
* @param ep - endpoint state
* @return data written to EP0R
*/
static uint16_t EP0_Handler(ep_t ep){
uint16_t epstatus = ep.status; // EP0R on input -> return this value after modifications
uint8_t reqtype = setup_packet.bmRequestType & 0x7f;
uint8_t dev2host = (setup_packet.bmRequestType & 0x80) ? 1 : 0;
if ((ep.rx_flag) && (ep.setup_flag)){
switch(reqtype){
case STANDARD_DEVICE_REQUEST_TYPE: // standard device request
if(dev2host){
std_d2h_req();
}else{
std_h2d_req();
// send ZLP
EP_WriteIRQ(0, (uint8_t *)0, 0);
}
epstatus = SET_NAK_RX(epstatus);
epstatus = SET_VALID_TX(epstatus);
break;
case STANDARD_ENDPOINT_REQUEST_TYPE: // standard endpoint request
if (setup_packet.bRequest == CLEAR_FEATURE){
// send ZLP
EP_WriteIRQ(0, (uint8_t *)0, 0);
epstatus = SET_NAK_RX(epstatus);
epstatus = SET_VALID_TX(epstatus);
}else{
WRITEDUMP("02:WR_REQ");
}
break;
case VENDOR_REQUEST_TYPE:
vendor_handler(&setup_packet);
epstatus = SET_NAK_RX(epstatus);
epstatus = SET_VALID_TX(epstatus);
break;
case CONTROL_REQUEST_TYPE:
switch(setup_packet.bRequest){
case GET_LINE_CODING:
EP_WriteIRQ(0, (uint8_t*)&lineCoding, sizeof(lineCoding));
break;
case SET_LINE_CODING: // omit this for next stage, when data will come
break;
case SET_CONTROL_LINE_STATE:
clstate_handler(setup_packet.wValue);
break;
case SEND_BREAK:
break_handler();
break;
default:
WRITEDUMP("undef control req");
}
if(!dev2host) EP_WriteIRQ(0, (uint8_t *)0, 0); // write acknowledgement
epstatus = SET_VALID_RX(epstatus);
epstatus = SET_VALID_TX(epstatus);
break;
default:
EP_WriteIRQ(0, (uint8_t *)0, 0);
epstatus = SET_NAK_RX(epstatus);
epstatus = SET_VALID_TX(epstatus);
}
}else if (ep.rx_flag){ // got data over EP0 or host acknowlegement
if(ep.rx_cnt){
// EP_WriteIRQ(0, (uint8_t *)0, 0);
if(setup_packet.bRequest == SET_LINE_CODING){
//WRITEDUMP("SET_LINE_CODING");
linecoding_handler((usb_LineCoding*)ep0databuf);
}
}
// Close transaction
epstatus = CLEAR_DTOG_RX(epstatus);
epstatus = CLEAR_DTOG_TX(epstatus);
// wait for new data from host
epstatus = SET_VALID_RX(epstatus);
epstatus = SET_STALL_TX(epstatus);
} else if (ep.tx_flag){ // package transmitted
// now we can change address after enumeration
if ((USB->DADDR & USB_DADDR_ADD) != USB_Dev.USB_Addr){
USB->DADDR = USB_DADDR_EF | USB_Dev.USB_Addr;
// change state to ADRESSED
USB_Dev.USB_Status = USB_ADRESSED_STATE;
}
// end of transaction
epstatus = CLEAR_DTOG_RX(epstatus);
epstatus = CLEAR_DTOG_TX(epstatus);
epstatus = SET_VALID_RX(epstatus);
epstatus = SET_VALID_TX(epstatus);
}
return epstatus;
}
#undef WRITEDUMP
static uint16_t lastaddr = USB_EP0_BASEADDR;
/**
* Endpoint initialisation
* !!! when working with CAN bus change USB_BTABLE_SIZE to 768 !!!
* @param number - EP num (0...7)
* @param type - EP type (EP_TYPE_BULK, EP_TYPE_CONTROL, EP_TYPE_ISO, EP_TYPE_INTERRUPT)
* @param txsz - transmission buffer size @ USB/CAN buffer
* @param rxsz - reception buffer size @ USB/CAN buffer
* @param uint16_t (*func)(ep_t *ep) - EP handler function
* @return 0 if all OK
*/
int EP_Init(uint8_t number, uint8_t type, uint16_t txsz, uint16_t rxsz, uint16_t (*func)(ep_t ep)){
if(number >= ENDPOINTS_NUM) return 4; // out of configured amount
if(txsz > USB_BTABLE_SIZE || rxsz > USB_BTABLE_SIZE) return 1; // buffer too large
if(lastaddr + txsz + rxsz >= USB_BTABLE_SIZE) return 2; // out of btable
USB->EPnR[number] = (type << 9) | (number & USB_EPnR_EA);
USB->EPnR[number] ^= USB_EPnR_STAT_RX | USB_EPnR_STAT_TX_1;
if(rxsz & 1 || rxsz > 992) return 3; // wrong rx buffer size
uint16_t countrx = 0;
if(rxsz < 64) countrx = rxsz / 2;
else{
if(rxsz & 0x1f) return 3; // should be multiple of 32
countrx = 31 + rxsz / 32;
}
USB_BTABLE->EP[number].USB_ADDR_TX = lastaddr;
endpoints[number].tx_buf = (uint16_t *)(USB_BTABLE_BASE + lastaddr);
lastaddr += txsz;
USB_BTABLE->EP[number].USB_COUNT_TX = 0;
USB_BTABLE->EP[number].USB_ADDR_RX = lastaddr;
endpoints[number].rx_buf = (uint8_t *)(USB_BTABLE_BASE + lastaddr);
lastaddr += rxsz;
// buffer size: Table127 of RM
USB_BTABLE->EP[number].USB_COUNT_RX = countrx << 10;
endpoints[number].func = func;
return 0;
}
// standard IRQ handler
void usb_isr(){
if (USB->ISTR & USB_ISTR_RESET){
// Reinit registers
USB->CNTR = USB_CNTR_RESETM | USB_CNTR_CTRM;
USB->ISTR = 0;
// Endpoint 0 - CONTROL
// ON USB LS size of EP0 may be 8 bytes, but on FS it should be 64 bytes!
lastaddr = USB_EP0_BASEADDR; // roll back to beginning of buffer
EP_Init(0, EP_TYPE_CONTROL, USB_EP0_BUFSZ, USB_EP0_BUFSZ, EP0_Handler);
// clear address, leave only enable bit
USB->DADDR = USB_DADDR_EF;
// state is default - wait for enumeration
USB_Dev.USB_Status = USB_DEFAULT_STATE;
}
if(USB->ISTR & USB_ISTR_CTR){
// EP number
uint8_t n = USB->ISTR & USB_ISTR_EPID;
// copy status register
uint16_t epstatus = USB->EPnR[n];
// Calculate flags
endpoints[n].rx_flag = (epstatus & USB_EPnR_CTR_RX) ? 1 : 0;
endpoints[n].setup_flag = (epstatus & USB_EPnR_SETUP) ? 1 : 0;
endpoints[n].tx_flag = (epstatus & USB_EPnR_CTR_TX) ? 1 : 0;
// copy received bytes amount
endpoints[n].rx_cnt = USB_BTABLE->EP[n].USB_COUNT_RX & 0x3FF; // low 10 bits is counter
// check direction
if(USB->ISTR & USB_ISTR_DIR){ // OUT interrupt - receive data, CTR_RX==1 (if CTR_TX == 1 - two pending transactions: receive following by transmit)
if(n == 0){ // control endpoint
if(epstatus & USB_EPnR_SETUP){ // setup packet -> copy data to conf_pack
memcpy(&setup_packet, endpoints[0].rx_buf, sizeof(setup_packet));
ep0dbuflen = 0;
// interrupt handler will be called later
}else if(epstatus & USB_EPnR_CTR_RX){ // data packet -> push received data to ep0databuf
ep0dbuflen = endpoints[0].rx_cnt;
memcpy(ep0databuf, endpoints[0].rx_buf, ep0dbuflen);
}
}
}else{ // IN interrupt - transmit data, only CTR_TX == 1
// enumeration end could be here (if EP0)
}
// prepare status field for EP handler
endpoints[n].status = epstatus;
// call EP handler (even if it will change EPnR, it should return new status)
epstatus = endpoints[n].func(endpoints[n]);
// keep DTOG state
epstatus = KEEP_DTOG_TX(epstatus);
epstatus = KEEP_DTOG_RX(epstatus);
// clear all RX/TX flags
epstatus = CLEAR_CTR_RX(epstatus);
epstatus = CLEAR_CTR_TX(epstatus);
// refresh EPnR
USB->EPnR[n] = epstatus;
}
}
/**
* Write data to EP buffer (called from IRQ handler)
* @param number - EP number
* @param *buf - array with data
* @param size - its size
*/
void EP_WriteIRQ(uint8_t number, const uint8_t *buf, uint16_t size){
uint8_t i;
if(size > USB_TXBUFSZ) size = USB_TXBUFSZ;
uint16_t N2 = (size + 1) >> 1;
// the buffer is 16-bit, so we should copy data as it would be uint16_t
uint16_t *buf16 = (uint16_t *)buf;
for (i = 0; i < N2; i++){
endpoints[number].tx_buf[i] = buf16[i];
}
USB_BTABLE->EP[number].USB_COUNT_TX = size;
}
/**
* Write data to EP buffer (called outside IRQ handler)
* @param number - EP number
* @param *buf - array with data
* @param size - its size
*/
void EP_Write(uint8_t number, const uint8_t *buf, uint16_t size){
uint16_t status = USB->EPnR[number];
EP_WriteIRQ(number, buf, size);
status = SET_NAK_RX(status);
status = SET_VALID_TX(status);
status = KEEP_DTOG_TX(status);
status = KEEP_DTOG_RX(status);
USB->EPnR[number] = status;
}
/*
* Copy data from EP buffer into user buffer area
* @param *buf - user array for data
* @return amount of data read
*/
int EP_Read(uint8_t number, uint8_t *buf){
int n = endpoints[number].rx_cnt;
if(n){
for(int i = 0; i < n; ++i)
buf[i] = endpoints[number].rx_buf[i];
}
return n;
}
// USB status
uint8_t USB_GetState(){
return USB_Dev.USB_Status;
}

View File

@ -0,0 +1,202 @@
/*
* geany_encoding=koi8-r
* usb_lib.h
*
* Copyright 2018 Edward V. Emelianov <eddy@sao.ru, edward.emelianoff@gmail.com>
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; if not, write to the Free Software
* Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston,
* MA 02110-1301, USA.
*
*/
#pragma once
#ifndef __USB_LIB_H__
#define __USB_LIB_H__
#include <wchar.h>
#include "usb_defs.h"
#define EP0DATABUF_SIZE (64)
// Max EP amount (EP0 + other used)
#define ENDPOINTS_NUM 4
// bmRequestType & 0x7f
#define STANDARD_DEVICE_REQUEST_TYPE 0
#define STANDARD_ENDPOINT_REQUEST_TYPE 2
#define VENDOR_REQUEST_TYPE 0x40
#define CONTROL_REQUEST_TYPE 0x21
// bRequest, standard; for bmRequestType == 0x80
#define GET_STATUS 0x00
#define GET_DESCRIPTOR 0x06
#define GET_CONFIGURATION 0x08
// for bmRequestType == 0
#define CLEAR_FEATURE 0x01
#define SET_FEATURE 0x03 // unused
#define SET_ADDRESS 0x05
#define SET_DESCRIPTOR 0x07 // unused
#define SET_CONFIGURATION 0x09
// for bmRequestType == 0x81, 1 or 0xB2
#define GET_INTERFACE 0x0A // unused
#define SET_INTERFACE 0x0B // unused
#define SYNC_FRAME 0x0C // unused
#define VENDOR_REQUEST 0x01 // unused
// Class-Specific Control Requests
#define SEND_ENCAPSULATED_COMMAND 0x00 // unused
#define GET_ENCAPSULATED_RESPONSE 0x01 // unused
#define SET_COMM_FEATURE 0x02 // unused
#define GET_COMM_FEATURE 0x03 // unused
#define CLEAR_COMM_FEATURE 0x04 // unused
#define SET_LINE_CODING 0x20
#define GET_LINE_CODING 0x21
#define SET_CONTROL_LINE_STATE 0x22
#define SEND_BREAK 0x23
// control line states
#define CONTROL_DTR 0x01
#define CONTROL_RTS 0x02
// wValue
#define DEVICE_DESCRIPTOR 0x100
#define CONFIGURATION_DESCRIPTOR 0x200
#define STRING_LANG_DESCRIPTOR 0x300
#define STRING_MAN_DESCRIPTOR 0x301
#define STRING_PROD_DESCRIPTOR 0x302
#define STRING_SN_DESCRIPTOR 0x303
#define DEVICE_QUALIFIER_DESCRIPTOR 0x600
// EPnR bits manipulation
#define CLEAR_DTOG_RX(R) (R & USB_EPnR_DTOG_RX) ? R : (R & (~USB_EPnR_DTOG_RX))
#define SET_DTOG_RX(R) (R & USB_EPnR_DTOG_RX) ? (R & (~USB_EPnR_DTOG_RX)) : R
#define TOGGLE_DTOG_RX(R) (R | USB_EPnR_DTOG_RX)
#define KEEP_DTOG_RX(R) (R & (~USB_EPnR_DTOG_RX))
#define CLEAR_DTOG_TX(R) (R & USB_EPnR_DTOG_TX) ? R : (R & (~USB_EPnR_DTOG_TX))
#define SET_DTOG_TX(R) (R & USB_EPnR_DTOG_TX) ? (R & (~USB_EPnR_DTOG_TX)) : R
#define TOGGLE_DTOG_TX(R) (R | USB_EPnR_DTOG_TX)
#define KEEP_DTOG_TX(R) (R & (~USB_EPnR_DTOG_TX))
#define SET_VALID_RX(R) ((R & USB_EPnR_STAT_RX) ^ USB_EPnR_STAT_RX) | (R & (~USB_EPnR_STAT_RX))
#define SET_NAK_RX(R) ((R & USB_EPnR_STAT_RX) ^ USB_EPnR_STAT_RX_1) | (R & (~USB_EPnR_STAT_RX))
#define SET_STALL_RX(R) ((R & USB_EPnR_STAT_RX) ^ USB_EPnR_STAT_RX_0) | (R & (~USB_EPnR_STAT_RX))
#define KEEP_STAT_RX(R) (R & (~USB_EPnR_STAT_RX))
#define SET_VALID_TX(R) ((R & USB_EPnR_STAT_TX) ^ USB_EPnR_STAT_TX) | (R & (~USB_EPnR_STAT_TX))
#define SET_NAK_TX(R) ((R & USB_EPnR_STAT_TX) ^ USB_EPnR_STAT_TX_1) | (R & (~USB_EPnR_STAT_TX))
#define SET_STALL_TX(R) ((R & USB_EPnR_STAT_TX) ^ USB_EPnR_STAT_TX_0) | (R & (~USB_EPnR_STAT_TX))
#define KEEP_STAT_TX(R) (R & (~USB_EPnR_STAT_TX))
#define CLEAR_CTR_RX(R) (R & (~USB_EPnR_CTR_RX))
#define CLEAR_CTR_TX(R) (R & (~USB_EPnR_CTR_TX))
#define CLEAR_CTR_RX_TX(R) (R & (~(USB_EPnR_CTR_TX | USB_EPnR_CTR_RX)))
// USB state: uninitialized, addressed, ready for use
#define USB_DEFAULT_STATE 0
#define USB_ADRESSED_STATE 1
#define USB_CONFIGURE_STATE 2
// EP types
#define EP_TYPE_BULK 0x00
#define EP_TYPE_CONTROL 0x01
#define EP_TYPE_ISO 0x02
#define EP_TYPE_INTERRUPT 0x03
#define LANG_US (uint16_t)0x0409
#define _USB_STRING_(name, str) \
static const struct name \
{ \
uint8_t bLength; \
uint8_t bDescriptorType; \
uint16_t bString[(sizeof(str) - 2) / 2]; \
\
} \
name = {sizeof(name), 0x03, str}
#define _USB_LANG_ID_(name, lng_id) \
\
static const struct name \
{ \
uint8_t bLength; \
uint8_t bDescriptorType; \
uint16_t bString; \
\
} \
name = {0x04, 0x03, lng_id}
#define STRING_LANG_DESCRIPTOR_SIZE_BYTE (4)
// EP0 configuration packet
typedef struct {
uint8_t bmRequestType;
uint8_t bRequest;
uint16_t wValue;
uint16_t wIndex;
uint16_t wLength;
} config_pack_t;
// endpoints state
typedef struct __ep_t{
uint16_t *tx_buf; // transmission buffer address
uint8_t *rx_buf; // reception buffer address
uint16_t (*func)(); // endpoint action function
uint16_t status; // status flags
unsigned rx_cnt : 10; // received data counter
unsigned tx_flag : 1; // transmission flag
unsigned rx_flag : 1; // reception flag
unsigned setup_flag : 1; // this is setup packet (only for EP0)
} ep_t;
// USB status & its address
typedef struct {
uint8_t USB_Status;
uint16_t USB_Addr;
}usb_dev_t;
typedef struct {
uint32_t dwDTERate;
uint8_t bCharFormat;
#define USB_CDC_1_STOP_BITS 0
#define USB_CDC_1_5_STOP_BITS 1
#define USB_CDC_2_STOP_BITS 2
uint8_t bParityType;
#define USB_CDC_NO_PARITY 0
#define USB_CDC_ODD_PARITY 1
#define USB_CDC_EVEN_PARITY 2
#define USB_CDC_MARK_PARITY 3
#define USB_CDC_SPACE_PARITY 4
uint8_t bDataBits;
} __attribute__ ((packed)) usb_LineCoding;
typedef struct {
uint8_t bmRequestType;
uint8_t bNotificationType;
uint16_t wValue;
uint16_t wIndex;
uint16_t wLength;
} __attribute__ ((packed)) usb_cdc_notification;
extern ep_t endpoints[];
void USB_Init();
uint8_t USB_GetState();
int EP_Init(uint8_t number, uint8_t type, uint16_t txsz, uint16_t rxsz, uint16_t (*func)(ep_t ep));
void EP_WriteIRQ(uint8_t number, const uint8_t *buf, uint16_t size);
void EP_Write(uint8_t number, const uint8_t *buf, uint16_t size);
int EP_Read(uint8_t number, uint8_t *buf);
usb_LineCoding getLineCoding();
void WEAK linecoding_handler(usb_LineCoding *lc);
void WEAK clstate_handler(uint16_t val);
void WEAK break_handler();
void WEAK vendor_handler(config_pack_t *packet);
#endif // __USB_LIB_H__

View File

@ -0,0 +1,9 @@
(module Hole_3mm (layer F.Cu) (tedit 5913F6E4)
(fp_text reference REF** (at 0 3.81) (layer F.SilkS) hide
(effects (font (size 1 1) (thickness 0.15)))
)
(fp_text value Hole_3mm (at 0 -7.62) (layer F.Fab) hide
(effects (font (size 1 1) (thickness 0.15)))
)
(pad 1 thru_hole circle (at 0 0) (size 5 5) (drill 3) (layers *.Cu *.Mask))
)

View File

@ -0,0 +1,31 @@
(module RJ9-4P4C (layer F.Cu) (tedit 555F7A30)
(fp_text reference J** (at 0 -10.1346) (layer F.SilkS)
(effects (font (size 1 1) (thickness 0.15)))
)
(fp_text value RJ9-4P4C (at 0 10.2108) (layer F.Fab) hide
(effects (font (size 1 1) (thickness 0.15)))
)
(fp_circle (center 0 0) (end -0.25 0) (layer F.CrtYd) (width 0.05))
(fp_line (start -5.84 -9.25) (end 5.84 -9.25) (layer F.CrtYd) (width 0.05))
(fp_line (start 5.84 -9.25) (end 5.84 9.25) (layer F.CrtYd) (width 0.05))
(fp_line (start 5.84 9.25) (end -5.84 9.25) (layer F.CrtYd) (width 0.05))
(fp_line (start -5.84 9.25) (end -5.84 -9.25) (layer F.CrtYd) (width 0.05))
(fp_line (start 0 -0.35) (end 0 0.35) (layer F.CrtYd) (width 0.05))
(fp_line (start -0.35 0) (end 0.35 0) (layer F.CrtYd) (width 0.05))
(fp_line (start -5.59 9) (end -5.59 -9) (layer F.Fab) (width 0.12))
(fp_line (start -5.59 -9) (end 5.59 -9) (layer F.Fab) (width 0.12))
(fp_line (start 5.59 -9) (end 5.59 9) (layer F.Fab) (width 0.12))
(fp_line (start 5.59 9) (end -5.59 9) (layer F.Fab) (width 0.12))
(fp_line (start -5.59 8.8) (end -5.59 -9) (layer F.SilkS) (width 0.12))
(fp_line (start -5.59 -9) (end 5.59 -9) (layer F.SilkS) (width 0.12))
(fp_line (start 5.59 -9) (end 5.59 8.8) (layer F.SilkS) (width 0.12))
(fp_circle (center 3.81 1.15) (end 5.75 1.15) (layer B.CrtYd) (width 0.05))
(fp_circle (center -3.81 1.15) (end -5.75 1.15) (layer B.CrtYd) (width 0.05))
(fp_circle (center -1.905 -6.12) (end -1.805 -6.12) (layer F.SilkS) (width 0.2))
(pad 1 thru_hole circle (at -1.905 -5.2) (size 1.2 1.2) (drill 0.8) (layers *.Cu *.Mask))
(pad 2 thru_hole circle (at -0.635 -7.74) (size 1.2 1.2) (drill 0.8) (layers *.Cu *.Mask))
(pad 3 thru_hole circle (at 0.635 -5.2) (size 1.2 1.2) (drill 0.8) (layers *.Cu *.Mask))
(pad 4 thru_hole circle (at 1.905 -7.74) (size 1.2 1.2) (drill 0.8) (layers *.Cu *.Mask))
(pad "" np_thru_hole circle (at -3.81 1.15) (size 3.2 3.2) (drill 3.2) (layers *.Cu *.Mask))
(pad "" np_thru_hole circle (at 3.81 1.15) (size 3.2 3.2) (drill 3.2) (layers *.Cu *.Mask))
)

View File

@ -0,0 +1,12 @@
(module SMD_conn_4x2.5mm (layer F.Cu) (tedit 58B86145)
(fp_text reference REF** (at 0 3.81) (layer F.SilkS)
(effects (font (size 1 1) (thickness 0.15)))
)
(fp_text value SMD_conn_4x2.5mm (at 0 -3.81) (layer F.Fab)
(effects (font (size 1 1) (thickness 0.15)))
)
(pad 1 smd rect (at -3.81 0) (size 1.5 5) (layers F.Cu F.Paste F.Mask))
(pad 2 smd rect (at -1.27 0) (size 1.5 5) (layers F.Cu F.Paste F.Mask))
(pad 3 smd rect (at 1.27 0) (size 1.5 5) (layers F.Cu F.Paste F.Mask))
(pad 4 smd rect (at 3.81 0) (size 1.5 5) (layers F.Cu F.Paste F.Mask))
)

View File

@ -0,0 +1,10 @@
(module VIA (layer F.Cu) (tedit 5D2D6442)
(fp_text reference "" (at 0 0.5) (layer F.SilkS)
(effects (font (size 1 1) (thickness 0.15)))
)
(fp_text value VIA (at 0 -1.5) (layer F.Fab)
(effects (font (size 1 1) (thickness 0.15)))
)
(pad ~ thru_hole circle (at 0 0) (size 1.5 1.5) (drill 0.6) (layers *.Cu)
(clearance 0.2) (zone_connect 1))
)

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,4 @@
(fp_lib_table
(lib (name my_footprints)(type KiCad)(uri /home/eddy/Docs/SAO/BTA/MIRROR_CONTROL_termo/Project/kicad/Sensors_tester_with_screen/my_footprints.pretty)(options "")(descr ""))
(lib (name Battery)(type KiCad)(uri ${KISYSMOD}/Battery.pretty)(options "")(descr ""))
)

File diff suppressed because it is too large Load Diff

After

Width:  |  Height:  |  Size: 79 KiB

View File

@ -0,0 +1,607 @@
<?xml version="1.0" standalone="no"?>
<!DOCTYPE svg PUBLIC "-//W3C//DTD SVG 1.1//EN"
"http://www.w3.org/Graphics/SVG/1.1/DTD/svg11.dtd">
<svg xmlns="http://www.w3.org/2000/svg" version="1.1"
width="29.7002cm" height="21.0007cm" viewBox="0 0 116930 82680 ">
<title>SVG Picture created as stm32f042-B_SilkS.svg date 2019/07/16 08:50:21 </title>
<desc>Picture generated by PCBNEW </desc>
<g style="fill:#000000; fill-opacity:1;stroke:#000000; stroke-opacity:1;
stroke-linecap:round; stroke-linejoin:round; "
transform="translate(0 0) scale(1 1)">
</g>
<g style="fill:#000000; fill-opacity:0.0;
stroke:#000000; stroke-width:-0.000393701; stroke-opacity:1;
stroke-linecap:round; stroke-linejoin:round;">
</g>
<g style="fill:#000000; fill-opacity:0.0;
stroke:#000000; stroke-width:19.685; stroke-opacity:1;
stroke-linecap:round; stroke-linejoin:round;">
<path d="M90748 55118
L90748 54921
" />
<path d="M90748 29724
L90748 54921
" />
<path d="M59843 29724
L90748 29724
" />
<path d="M59843 55118
L59843 29724
" />
<path d="M90748 55118
L59843 55118
" />
</g>
<g style="fill:#000000; fill-opacity:0.0;
stroke:#000000; stroke-width:47.2441; stroke-opacity:1;
stroke-linecap:round; stroke-linejoin:round;">
<path d="M79266 48768
L80874 48768
" />
<path d="M80874 48768
L80874 48031
" />
<path d="M80874 48031
L79266 48031
" />
<path d="M65208 49748
L66901 49748
" />
<path d="M66901 49748
L66901 46874
" />
<path d="M65208 49748
L65208 46874
" />
<path d="M65183 53936
L65183 51062
" />
<path d="M66876 53936
L66876 51062
" />
<path d="M65183 53936
L66876 53936
" />
<path d="M76480 45651
L76480 46698
" />
<path d="M76480 45651
L70456 45651
" />
<path d="M70456 45651
L70456 46698
" />
<path d="M76480 46698
L70456 46698
" />
<path d="M77503 46698
L76980 46698
" />
<path d="M77503 46175
L77503 46698
" />
<path d="M63807 44458
L65484 44458
" />
<path d="M65484 44458
L65484 39607
" />
<path d="M65484 39607
L63807 39607
" />
<path d="M62193 44458
L58902 44458
" />
<path d="M58902 44458
L58902 39607
" />
<path d="M58902 39607
L62193 39607
" />
<path d="M65571 42525
L65768 42721
" />
<path d="M65768 42721
L65768 42328
" />
<path d="M65768 42328
L65571 42525
" />
<path d="M68531 46698
L69578 46698
" />
<path d="M68531 44675
L68531 46698
" />
<path d="M69578 44675
L69578 46698
" />
<path d="M68531 44675
L69578 44675
" />
<path d="M68531 44175
L68531 43651
" />
<path d="M68531 43651
L69055 43651
" />
<path d="M87351 43803
L87717 43803
" />
<path d="M88595 43803
L88229 43803
" />
<path d="M88595 43803
L88595 42559
" />
<path d="M87351 43803
L87351 43228
" />
<path d="M77141 32900
L77007 32900
" />
<path d="M77141 32499
L77007 32499
" />
<path d="M79230 34947
L79230 34813
" />
<path d="M78829 34947
L78829 34813
" />
<path d="M79729 35636
L79729 35502
" />
<path d="M80130 35636
L80130 35502
" />
<path d="M87343 40663
L87477 40663
" />
<path d="M87343 40262
L87477 40262
" />
<path d="M88179 41660
L88179 41525
" />
<path d="M88580 41660
L88580 41525
" />
<path d="M81803 45307
L81306 45307
" />
<path d="M79117 45307
L79614 45307
" />
<path d="M81803 46788
L81803 45307
" />
<path d="M79117 47674
L79117 45307
" />
<path d="M81102 49600
L80968 49600
" />
<path d="M81102 49199
L80968 49199
" />
</g>
<g style="fill:#000000; fill-opacity:0.0;
stroke:#000000; stroke-width:59.0551; stroke-opacity:1;
stroke-linecap:round; stroke-linejoin:round;">
<path d="M79830 49229
L79811 49248
L79755 49267
L79717 49267
L79661 49248
L79624 49210
L79605 49173
L79586 49098
L79586 49042
L79605 48967
L79624 48929
L79661 48892
L79717 48873
L79755 48873
L79811 48892
L79830 48910
" />
<path d="M79961 48873
L80224 48873
L80055 49267
" />
<path d="M64695 47646
L65089 47646
L65089 47740
L65070 47796
L65033 47833
L64995 47852
L64920 47871
L64864 47871
L64789 47852
L64752 47833
L64714 47796
L64695 47740
L64695 47646
" />
<path d="M65089 48002
L65089 48246
L64939 48115
L64939 48171
L64920 48208
L64902 48227
L64864 48246
L64770 48246
L64733 48227
L64714 48208
L64695 48171
L64695 48058
L64714 48021
L64733 48002
" />
<path d="M64670 51834
L65064 51834
L65064 51928
L65045 51984
L65008 52021
L64970 52040
L64895 52059
L64839 52059
L64764 52040
L64727 52021
L64689 51984
L64670 51928
L64670 51834
" />
<path d="M64933 52396
L64670 52396
" />
<path d="M65083 52303
L64802 52209
L64802 52453
" />
<path d="M74098 46959
L74098 47240
L74080 47296
L74042 47334
L73986 47353
L73948 47353
" />
<path d="M74454 47090
L74454 47353
" />
<path d="M74361 46940
L74267 47221
L74511 47221
" />
<path d="M61902 45762
L61902 45368
L62052 45368
L62090 45387
L62109 45405
L62127 45443
L62127 45499
L62109 45537
L62090 45555
L62052 45574
L61902 45574
" />
<path d="M62502 45762
L62277 45762
" />
<path d="M62390 45762
L62390 45368
L62352 45424
L62315 45462
L62277 45480
" />
<path d="M68814 47378
L68814 46984
L68964 46984
L69001 47003
L69020 47021
L69039 47059
L69039 47115
L69020 47153
L69001 47171
L68964 47190
L68814 47190
" />
<path d="M69189 47021
L69208 47003
L69245 46984
L69339 46984
L69376 47003
L69395 47021
L69414 47059
L69414 47096
L69395 47153
L69170 47378
L69414 47378
" />
<path d="M88741 43466
L88760 43428
L88798 43391
L88854 43335
L88873 43297
L88873 43260
" />
<path d="M88779 43278
L88798 43241
L88835 43203
L88910 43185
L89041 43185
L89116 43203
L89154 43241
L89173 43278
L89173 43353
L89154 43391
L89116 43428
L89041 43447
L88910 43447
L88835 43428
L88798 43391
L88779 43353
L88779 43278
" />
<path d="M88779 43822
L88779 43597
" />
<path d="M88779 43710
L89173 43710
L89116 43672
L89079 43635
L89060 43597
" />
<path d="M77008 33441
L76877 33253
" />
<path d="M76783 33441
L76783 33047
L76933 33047
L76971 33066
L76990 33084
L77008 33122
L77008 33178
L76990 33216
L76971 33234
L76933 33253
L76783 33253
" />
<path d="M77140 33047
L77402 33047
L77233 33441
" />
<path d="M78288 34814
L78476 34683
" />
<path d="M78288 34589
L78682 34589
L78682 34739
L78663 34777
L78645 34796
L78607 34814
L78551 34814
L78513 34796
L78495 34777
L78476 34739
L78476 34589
" />
<path d="M78513 35039
L78532 35002
L78551 34983
L78588 34964
L78607 34964
L78645 34983
L78663 35002
L78682 35039
L78682 35114
L78663 35152
L78645 35171
L78607 35189
L78588 35189
L78551 35171
L78532 35152
L78513 35114
L78513 35039
L78495 35002
L78476 34983
L78438 34964
L78363 34964
L78326 34983
L78307 35002
L78288 35039
L78288 35114
L78307 35152
L78326 35171
L78363 35189
L78438 35189
L78476 35171
L78495 35152
L78513 35114
" />
<path d="M79188 35503
L79376 35372
" />
<path d="M79188 35278
L79582 35278
L79582 35428
L79563 35466
L79545 35485
L79507 35503
L79451 35503
L79413 35485
L79395 35466
L79376 35428
L79376 35278
" />
<path d="M79188 35691
L79188 35766
L79207 35803
L79226 35822
L79282 35860
L79357 35878
L79507 35878
L79545 35860
L79563 35841
L79582 35803
L79582 35728
L79563 35691
L79545 35672
L79507 35653
L79413 35653
L79376 35672
L79357 35691
L79338 35728
L79338 35803
L79357 35841
L79376 35860
L79413 35878
" />
<path d="M87157 40077
L87026 39890
" />
<path d="M86932 40077
L86932 39684
L87082 39684
L87119 39702
L87138 39721
L87157 39759
L87157 39815
L87138 39852
L87119 39871
L87082 39890
L86932 39890
" />
<path d="M87532 40077
L87307 40077
" />
<path d="M87419 40077
L87419 39684
L87382 39740
L87344 39777
L87307 39796
" />
<path d="M87907 40077
L87682 40077
" />
<path d="M87794 40077
L87794 39684
L87757 39740
L87719 39777
L87682 39796
" />
<path d="M87638 41340
L87826 41208
" />
<path d="M87638 41115
L88032 41115
L88032 41265
L88013 41302
L87995 41321
L87957 41340
L87901 41340
L87863 41321
L87845 41302
L87826 41265
L87826 41115
" />
<path d="M87638 41715
L87638 41490
" />
<path d="M87638 41602
L88032 41602
L87976 41565
L87938 41527
L87920 41490
" />
<path d="M87995 41865
L88013 41883
L88032 41921
L88032 42015
L88013 42052
L87995 42071
L87957 42090
L87920 42090
L87863 42071
L87638 41846
L87638 42090
" />
<path d="M78904 45759
L78585 45759
L78548 45778
L78529 45797
L78510 45834
L78510 45909
L78529 45947
L78548 45966
L78585 45984
L78904 45984
" />
<path d="M78904 46134
L78904 46378
L78754 46247
L78754 46303
L78735 46341
L78716 46359
L78679 46378
L78585 46378
L78548 46359
L78529 46341
L78510 46303
L78510 46191
L78529 46153
L78548 46134
" />
<path d="M80969 50103
L80951 50122
L80894 50141
L80857 50141
L80801 50122
L80763 50084
L80744 50047
L80726 49972
L80726 49916
L80744 49841
L80763 49803
L80801 49766
L80857 49747
L80894 49747
L80951 49766
L80969 49784
" />
<path d="M81194 49916
L81157 49897
L81138 49878
L81119 49841
L81119 49822
L81138 49784
L81157 49766
L81194 49747
L81269 49747
L81307 49766
L81326 49784
L81344 49822
L81344 49841
L81326 49878
L81307 49897
L81269 49916
L81194 49916
L81157 49934
L81138 49953
L81119 49991
L81119 50066
L81138 50103
L81157 50122
L81194 50141
L81269 50141
L81307 50122
L81326 50103
L81344 50066
L81344 49991
L81326 49953
L81307 49934
L81269 49916
" />
</g>
</svg>

After

Width:  |  Height:  |  Size: 8.6 KiB

File diff suppressed because one or more lines are too long

After

Width:  |  Height:  |  Size: 268 KiB

File diff suppressed because it is too large Load Diff

After

Width:  |  Height:  |  Size: 147 KiB

File diff suppressed because it is too large Load Diff

After

Width:  |  Height:  |  Size: 15 KiB

File diff suppressed because it is too large Load Diff

After

Width:  |  Height:  |  Size: 183 KiB

View File

@ -0,0 +1,297 @@
EESchema-LIBRARY Version 2.4
#encoding utf-8
#
# +3.3V-stm32-rescue
#
DEF +3.3V-stm32-rescue #PWR 0 0 Y Y 1 F P
F0 "#PWR" 0 -150 50 H I C CNN
F1 "+3.3V-stm32-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
#
# C-stm32-rescue
#
DEF C-stm32-rescue C 0 10 N Y 1 F N
F0 "C" 25 100 50 H V L CNN
F1 "C-stm32-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
#
# CONN_01X01-stm32-rescue
#
DEF CONN_01X01-stm32-rescue J 0 40 Y N 1 F N
F0 "J" 0 100 50 H V C CNN
F1 "CONN_01X01-stm32-rescue" 100 0 50 V V C CNN
F2 "" 0 0 50 H I C CNN
F3 "" 0 0 50 H I C CNN
$FPLIST
Pin_Header_Straight_1X*
Pin_Header_Angled_1X*
Socket_Strip_Straight_1X*
Socket_Strip_Angled_1X*
$ENDFPLIST
DRAW
S -50 5 10 -5 0 1 0 N
S -50 50 50 -50 0 1 0 N
X P1 1 -200 0 150 R 50 50 1 1 P
ENDDRAW
ENDDEF
#
# CONN_01X03-stm32-rescue
#
DEF CONN_01X03-stm32-rescue J 0 40 Y N 1 F N
F0 "J" 0 200 50 H V C CNN
F1 "CONN_01X03-stm32-rescue" 100 0 50 V V C CNN
F2 "" 0 0 50 H I C CNN
F3 "" 0 0 50 H I C CNN
$FPLIST
Pin_Header_Straight_1X*
Pin_Header_Angled_1X*
Socket_Strip_Straight_1X*
Socket_Strip_Angled_1X*
$ENDFPLIST
DRAW
S -50 -95 10 -105 0 1 0 N
S -50 5 10 -5 0 1 0 N
S -50 105 10 95 0 1 0 N
S -50 150 50 -150 0 1 0 N
X P1 1 -200 100 150 R 50 50 1 1 P
X P2 2 -200 0 150 R 50 50 1 1 P
X P3 3 -200 -100 150 R 50 50 1 1 P
ENDDRAW
ENDDEF
#
# CP-stm32-rescue
#
DEF CP-stm32-rescue C 0 10 N Y 1 F N
F0 "C" 25 100 50 H V L CNN
F1 "CP-stm32-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
#
# D_Schottky-stm32-rescue
#
DEF D_Schottky-stm32-rescue D 0 40 N N 1 F N
F0 "D" 0 100 50 H V C CNN
F1 "D_Schottky-stm32-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 0 50 0 -50 0 N
P 4 0 1 8 50 50 50 -50 -50 0 50 50 N
P 6 0 1 8 -75 25 -75 50 -50 50 -50 -50 -25 -50 -25 -25 N
X K 1 -150 0 100 R 50 50 1 1 P
X A 2 150 0 100 L 50 50 1 1 P
ENDDRAW
ENDDEF
#
# GND-stm32-rescue
#
DEF GND-stm32-rescue #PWR 0 0 Y Y 1 F P
F0 "#PWR" 0 -250 50 H I C CNN
F1 "GND-stm32-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
#
# LED-RESCUE-stm32-stm32-rescue
#
DEF LED-RESCUE-stm32-stm32-rescue D 0 40 Y N 1 F N
F0 "D" 0 100 50 H V C CNN
F1 "LED-RESCUE-stm32-stm32-rescue" 0 -100 50 H V C CNN
F2 "" 0 0 50 H V C CNN
F3 "" 0 0 50 H V C CNN
$FPLIST
LED*
$ENDFPLIST
DRAW
P 2 0 1 8 -50 -50 -50 50 N
P 2 0 1 0 -50 0 50 0 N
P 4 0 1 8 50 -50 50 50 -50 0 50 -50 N
P 5 0 1 0 -120 -30 -180 -90 -150 -90 -180 -90 -180 -60 N
P 5 0 1 0 -70 -30 -130 -90 -100 -90 -130 -90 -130 -60 N
X K 1 -150 0 100 R 50 50 1 1 P
X A 2 150 0 100 L 50 50 1 1 P
ENDDRAW
ENDDEF
#
# LM1117-3.3-RESCUE-stm32-stm32-rescue
#
DEF LM1117-3.3-RESCUE-stm32-stm32-rescue U 0 30 Y Y 1 F N
F0 "U" 100 -250 50 H V C CNN
F1 "LM1117-3.3-RESCUE-stm32-stm32-rescue" 0 250 50 H V C CNN
F2 "" 0 0 50 H I C CNN
F3 "" 0 0 50 H I C CNN
$FPLIST
SOT-223*
TO-263*
TO-252*
$ENDFPLIST
DRAW
S -200 -200 200 200 0 1 10 f
X GND/ADJ 1 0 -300 100 U 50 50 1 1 W
X VO 2 300 50 100 L 50 50 1 1 P
X VI 3 -300 0 100 R 50 50 1 1 W
X VO 4 300 -50 100 L 50 50 1 1 w
ENDDRAW
ENDDEF
#
# PWR_FLAG-stm32-rescue
#
DEF PWR_FLAG-stm32-rescue #FLG 0 0 N N 1 F P
F0 "#FLG" 0 75 50 H I C CNN
F1 "PWR_FLAG-stm32-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
#
# R-stm32-rescue
#
DEF R-stm32-rescue R 0 0 N Y 1 F N
F0 "R" 80 0 50 V V C CNN
F1 "R-stm32-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
#
# STM32F042C6Tx-stm32-rescue
#
DEF STM32F042C6Tx-stm32-rescue U 0 40 Y Y 1 L N
F0 "U" -3000 1725 50 H V L BNN
F1 "STM32F042C6Tx-stm32-rescue" 3000 1725 50 H V R BNN
F2 "LQFP48" 3000 1675 50 H V R TNN
F3 "" 0 0 50 H V C CNN
DRAW
S -3000 -1700 3000 1700 0 1 10 f
X VBAT 1 -3100 1100 100 R 50 50 1 1 W
X ADC_IN0/RTC_TAMP2/SYS_WKUP1/TIM2_CH1/TIM2_ETR/TSC_G1_IO1/USART2_CTS/PA0 10 3100 100 100 L 50 50 1 1 B
X ADC_IN1/TIM2_CH2/TSC_G1_IO2/USART2_DE/USART2_RTS/PA1 11 3100 0 100 L 50 50 1 1 B
X ADC_IN2/SYS_WKUP4/TIM2_CH3/TSC_G1_IO3/USART2_TX/PA2 12 3100 -100 100 L 50 50 1 1 B
X ADC_IN3/TIM2_CH4/TSC_G1_IO4/USART2_RX/PA3 13 3100 -200 100 L 50 50 1 1 B
X ADC_IN4/I2S1_WS/SPI1_NSS/TIM14_CH1/TSC_G2_IO1/USART2_CK/USB_OE/PA4 14 3100 -300 100 L 50 50 1 1 B
X ADC_IN5/CEC/I2S1_CK/SPI1_SCK/TIM2_CH1/TIM2_ETR/TSC_G2_IO2/PA5 15 3100 -400 100 L 50 50 1 1 B
X ADC_IN6/I2S1_MCK/SPI1_MISO/TIM16_CH1/TIM1_BKIN/TIM3_CH1/TSC_G2_IO3/PA6 16 3100 -500 100 L 50 50 1 1 B
X ADC_IN7/I2S1_SD/SPI1_MOSI/TIM14_CH1/TIM17_CH1/TIM1_CH1N/TIM3_CH2/TSC_G2_IO4/PA7 17 3100 -600 100 L 50 50 1 1 B
X PB0/ADC_IN8/TIM1_CH2N/TIM3_CH3/TSC_G3_IO2 18 -3100 100 100 R 50 50 1 1 B
X PB1/ADC_IN9/TIM14_CH1/TIM1_CH3N/TIM3_CH4/TSC_G3_IO3 19 -3100 0 100 R 50 50 1 1 B
X PC13/RTC_OUT_ALARM/RTC_OUT_CALIB/RTC_TAMP1/RTC_TS/SYS_WKUP2 2 -3100 500 100 R 50 50 1 1 B
X PB2/TSC_G3_IO4 20 -3100 -100 100 R 50 50 1 1 B
X PB10/CEC/I2C1_SCL/SPI2_SCK/TIM2_CH3/TSC_SYNC 21 -3100 -900 100 R 50 50 1 1 B
X PB11/I2C1_SDA/TIM2_CH4 22 -3100 -1000 100 R 50 50 1 1 B
X VSS 23 -200 -1800 100 U 50 50 1 1 W
X VDD 24 -200 1800 100 D 50 50 1 1 W
X PB12/SPI2_NSS/TIM1_BKIN 25 -3100 -1100 100 R 50 50 1 1 B
X PB13/I2C1_SCL/SPI2_SCK/TIM1_CH1N 26 -3100 -1200 100 R 50 50 1 1 B
X PB14/I2C1_SDA/SPI2_MISO/TIM1_CH2N 27 -3100 -1300 100 R 50 50 1 1 B
X PB15/RTC_REFIN/SPI2_MOSI/SYS_WKUP7/TIM1_CH3N 28 -3100 -1400 100 R 50 50 1 1 B
X CRS_SYNC/RCC_MCO/TIM1_CH1/USART1_CK/PA8 29 3100 -700 100 L 50 50 1 1 B
X PC14/RCC_OSC32_IN 3 -3100 400 100 R 50 50 1 1 B
X I2C1_SCL/TIM1_CH2/TSC_G4_IO1/USART1_TX/PA9 30 3100 -800 100 L 50 50 1 1 B
X I2C1_SDA/TIM17_BKIN/TIM1_CH3/TSC_G4_IO2/USART1_RX/PA10 31 3100 -900 100 L 50 50 1 1 B
X CAN_RX/I2C1_SCL/TIM1_CH4/TSC_G4_IO3/USART1_CTS/USB_DM/PA11 32 3100 -1000 100 L 50 50 1 1 B
X CAN_TX/I2C1_SDA/TIM1_ETR/TSC_G4_IO4/USART1_DE/USART1_RTS/USB_DP/PA12 33 3100 -1100 100 L 50 50 1 1 B
X IR_OUT/SYS_SWDIO/USB_OE/PA13 34 3100 -1200 100 L 50 50 1 1 B
X VSS 35 -100 -1800 100 U 50 50 1 1 W
X VDDIO2 36 100 1800 100 D 50 50 1 1 W
X SYS_SWCLK/USART2_TX/PA14 37 3100 -1300 100 L 50 50 1 1 B
X I2S1_WS/SPI1_NSS/TIM2_CH1/TIM2_ETR/USART2_RX/USB_OE/PA15 38 3100 -1400 100 L 50 50 1 1 B
X PB3/I2S1_CK/SPI1_SCK/TIM2_CH2/TSC_G5_IO1 39 -3100 -200 100 R 50 50 1 1 B
X PC15/RCC_OSC32_OUT 4 -3100 300 100 R 50 50 1 1 B
X PB4/I2S1_MCK/SPI1_MISO/TIM17_BKIN/TIM3_CH1/TSC_G5_IO2 40 -3100 -300 100 R 50 50 1 1 B
X PB5/I2C1_SMBA/I2S1_SD/SPI1_MOSI/SYS_WKUP6/TIM16_BKIN/TIM3_CH2 41 -3100 -400 100 R 50 50 1 1 B
X PB6/I2C1_SCL/TIM16_CH1N/TSC_G5_IO3/USART1_TX 42 -3100 -500 100 R 50 50 1 1 B
X PB7/I2C1_SDA/TIM17_CH1N/TSC_G5_IO4/USART1_RX 43 -3100 -600 100 R 50 50 1 1 B
X PF11 44 -3100 700 100 R 50 50 1 1 B
X PB8/CAN_RX/CEC/I2C1_SCL/TIM16_CH1/TSC_SYNC 45 -3100 -700 100 R 50 50 1 1 B
X PB9/CAN_TX/I2C1_SDA/IR_OUT/SPI2_NSS/TIM17_CH1 46 -3100 -800 100 R 50 50 1 1 B
X VSS 47 0 -1800 100 U 50 50 1 1 W
X VDD 48 -100 1800 100 D 50 50 1 1 W
X PF0/CRS_SYNC/I2C1_SDA/RCC_OSC_IN 5 -3100 900 100 R 50 50 1 1 I
X PF1/I2C1_SCL/RCC_OSC_OUT 6 -3100 800 100 R 50 50 1 1 I
X NRST 7 -3100 1300 100 R 50 50 1 1 I
X VSSA 8 100 -1800 100 U 50 50 1 1 W
X VDDA 9 0 1800 100 D 50 50 1 1 W
ENDDRAW
ENDDEF
#
# USB_A-RESCUE-stm32-stm32-rescue
#
DEF USB_A-RESCUE-stm32-stm32-rescue P 0 40 Y Y 1 F N
F0 "P" 200 -200 50 H V C CNN
F1 "USB_A-RESCUE-stm32-stm32-rescue" -50 200 50 H V C CNN
F2 "" -50 -100 50 V V C CNN
F3 "" -50 -100 50 V V C CNN
$FPLIST
USB*
$ENDFPLIST
DRAW
S -250 -150 150 150 0 1 0 N
S -205 -150 -195 -120 0 1 0 N
S -105 -150 -95 -120 0 1 0 N
S -5 -150 5 -120 0 1 0 N
S 95 -150 105 -120 0 1 0 N
X VBUS 1 -200 -300 150 U 50 50 1 1 W
X D- 2 -100 -300 150 U 50 50 1 1 P
X D+ 3 0 -300 150 U 50 50 1 1 P
X GND 4 100 -300 150 U 50 50 1 1 W
X shield 5 300 100 150 L 50 50 1 1 P
ENDDRAW
ENDDEF
#
#End Library

View File

@ -0,0 +1,82 @@
"Source:","/home/eddy/Docs/SAO/BTA/MIRROR_CONTROL_termo/Project/kicad/Sensors_tester_with_screen/stm32f042/stm32f042.sch"
"Date:","÷Ô 16 ÉÀÌ 2019 08:53:19"
"Tool:","Eeschema (6.0.0-rc1-dev-1613-ga55d9819b)"
"Generator:","/usr/local/share/kicad/plugins/bom_csv_grouped_by_value.py"
"Component Count:","42"
"Individual Components:"
"Item","Qty","Reference(s)","Value","LibPart","Footprint","Datasheet"
"","","BT1","Battery_Cell","Device:Battery_Cell","Battery:BatteryHolder_MPD_BH-18650-PC2","~"
"","","C1","0.1","stm32-rescue:C","Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder",""
"","","C2","0.1","stm32-rescue:C","Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder",""
"","","C3","0.1","stm32-rescue:C","Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder",""
"","","C4","0.1","stm32-rescue:C","Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder",""
"","","C5","0.1","stm32-rescue:C","Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder",""
"","","C6","0.1","stm32-rescue:C","Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder",""
"","","C7","47u","stm32-rescue:CP","Capacitor_Tantalum_SMD:CP_EIA-3216-18_Kemet-A_Pad1.58x1.35mm_HandSolder",""
"","","C8","0.1","stm32-rescue:C","Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder",""
"","","D1","LED0","stm32-rescue:LED-RESCUE-stm32","LED_SMD:LED_0805_2012Metric_Pad1.15x1.40mm_HandSolder",""
"","","D2","LED1","stm32-rescue:LED-RESCUE-stm32","LED_SMD:LED_0805_2012Metric_Pad1.15x1.40mm_HandSolder",""
"","","D3","SS14","Device:D_Schottky","Diode_SMD:D_SMB_Handsoldering","~"
"","","D4","SS14","stm32-rescue:D_Schottky","Diode_SMD:D_SMB_Handsoldering",""
"","","J1","4P4C","Connector:4P4C","my_footprints:RJ9-4P4C","~"
"","","J2","Conn","Connector_Generic:Conn_01x02","TerminalBlock_Phoenix:TerminalBlock_Phoenix_MKDS-1,5-2-5.08_1x02_P5.08mm_Horizontal","~"
"","","J3","Conn","Connector_Generic:Conn_01x02","TerminalBlock_Phoenix:TerminalBlock_Phoenix_MKDS-1,5-2-5.08_1x02_P5.08mm_Horizontal","~"
"","","J4","SPI_screen","Connector:Conn_01x07_Female","Connector_PinSocket_2.54mm:PinSocket_1x07_P2.54mm_Vertical","~"
"","","P1","USB_B","stm32-rescue:USB_A-RESCUE-stm32","Connectors_USB:USB_B_OST_USB-B1HSxx_Horizontal",""
"","","P2","USART_BOOT","stm32-rescue:CONN_01X03","Connector_PinHeader_2.54mm:PinHeader_1x03_P2.54mm_Vertical",""
"","","P3","Hole","stm32-rescue:CONN_01X01","my_footprints:Hole_3mm",""
"","","P4","Hole","stm32-rescue:CONN_01X01","my_footprints:Hole_3mm",""
"","","P5","Hole","stm32-rescue:CONN_01X01","my_footprints:Hole_3mm",""
"","","P6","Hole","stm32-rescue:CONN_01X01","my_footprints:Hole_3mm",""
"","","Q1","AO3407","Device:Q_PMOS_GSD","TO_SOT_Packages_SMD:SOT-23_Handsoldering","~"
"","","R1","22","stm32-rescue:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder",""
"","","R2","22","stm32-rescue:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder",""
"","","R3","51k","stm32-rescue:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder",""
"","","R4","51k","stm32-rescue:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder",""
"","","R5","330","stm32-rescue:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder",""
"","","R6","330","stm32-rescue:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder",""
"","","R7","4k7","Device:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder","~"
"","","R8","4k7","Device:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder","~"
"","","R9","22","Device:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder","~"
"","","R10","10k","stm32-rescue:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder",""
"","","R11","10k","stm32-rescue:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder",""
"","","R12","510","Device:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder","~"
"","","SW1","Reset","Switch:SW_Push","Buttons_Switches_SMD:SW_SPST_FSMSM",""
"","","SW2","Boot","Switch:SW_Push","Buttons_Switches_SMD:SW_SPST_FSMSM",""
"","","SW3","Poweron","Switch:SW_Push","Button_Switch_THT:SW_PUSH_6mm_H13mm",""
"","","U1","USBLC6-2SC6","Power_Protection:USBLC6-2SC6","TO_SOT_Packages_SMD:SOT-23-6_Handsoldering","http://www2.st.com/resource/en/datasheet/CD00050750.pdf"
"","","U2","STM32F042C6Tx","stm32-rescue:STM32F042C6Tx","Package_QFP:LQFP-48_7x7mm_P0.5mm",""
"","","U3","LM1117-3.3","stm32-rescue:LM1117-3.3-RESCUE-stm32","TO_SOT_Packages_SMD:SOT-223",""
"Collated Components:"
"Item","Qty","Reference(s)","Value","LibPart","Footprint","Datasheet"
"1","1","BT1","Battery_Cell","Device:Battery_Cell","Battery:BatteryHolder_MPD_BH-18650-PC2","~"
"2","7","C1, C2, C3, C4, C5, C6, C8","0.1","stm32-rescue:C","Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder",""
"3","1","C7","47u","stm32-rescue:CP","Capacitor_Tantalum_SMD:CP_EIA-3216-18_Kemet-A_Pad1.58x1.35mm_HandSolder",""
"4","1","D1","LED0","stm32-rescue:LED-RESCUE-stm32","LED_SMD:LED_0805_2012Metric_Pad1.15x1.40mm_HandSolder",""
"5","1","D2","LED1","stm32-rescue:LED-RESCUE-stm32","LED_SMD:LED_0805_2012Metric_Pad1.15x1.40mm_HandSolder",""
"6","2","D3, D4","SS14","stm32-rescue:D_Schottky","Diode_SMD:D_SMB_Handsoldering","~"
"7","1","J1","4P4C","Connector:4P4C","my_footprints:RJ9-4P4C","~"
"8","2","J2, J3","Conn","Connector_Generic:Conn_01x02","TerminalBlock_Phoenix:TerminalBlock_Phoenix_MKDS-1,5-2-5.08_1x02_P5.08mm_Horizontal","~"
"9","1","J4","SPI_screen","Connector:Conn_01x07_Female","Connector_PinSocket_2.54mm:PinSocket_1x07_P2.54mm_Vertical","~"
"10","1","P1","USB_B","stm32-rescue:USB_A-RESCUE-stm32","Connectors_USB:USB_B_OST_USB-B1HSxx_Horizontal",""
"11","1","P2","USART_BOOT","stm32-rescue:CONN_01X03","Connector_PinHeader_2.54mm:PinHeader_1x03_P2.54mm_Vertical",""
"12","4","P3, P4, P5, P6","Hole","stm32-rescue:CONN_01X01","my_footprints:Hole_3mm",""
"13","1","Q1","AO3407","Device:Q_PMOS_GSD","TO_SOT_Packages_SMD:SOT-23_Handsoldering","~"
"14","3","R1, R2, R9","22","Device:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder","~"
"15","2","R3, R4","51k","stm32-rescue:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder",""
"16","2","R5, R6","330","stm32-rescue:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder",""
"17","2","R7, R8","4k7","Device:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder","~"
"18","2","R10, R11","10k","stm32-rescue:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder",""
"19","1","R12","510","Device:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder","~"
"20","1","SW1","Reset","Switch:SW_Push","Buttons_Switches_SMD:SW_SPST_FSMSM",""
"21","1","SW2","Boot","Switch:SW_Push","Buttons_Switches_SMD:SW_SPST_FSMSM",""
"22","1","SW3","Poweron","Switch:SW_Push","Button_Switch_THT:SW_PUSH_6mm_H13mm",""
"23","1","U1","USBLC6-2SC6","Power_Protection:USBLC6-2SC6","TO_SOT_Packages_SMD:SOT-23-6_Handsoldering","http://www2.st.com/resource/en/datasheet/CD00050750.pdf"
"24","1","U2","STM32F042C6Tx","stm32-rescue:STM32F042C6Tx","Package_QFP:LQFP-48_7x7mm_P0.5mm",""
"25","1","U3","LM1117-3.3","stm32-rescue:LM1117-3.3-RESCUE-stm32","TO_SOT_Packages_SMD:SOT-223",""
Can't render this file because it has a wrong number of fields in line 7.

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,766 @@
(export (version D)
(design
(source /home/eddy/Docs/SAO/BTA/MIRROR_CONTROL_termo/Project/kicad/Sensors_tester_with_screen/stm32f042/stm32f042.sch)
(date "Пн 15 июл 2019 17:19:38")
(tool "Eeschema (6.0.0-rc1-dev-1613-ga55d9819b)")
(sheet (number 1) (name /) (tstamps /)
(title_block
(title)
(company)
(rev)
(date)
(source stm32f042.sch)
(comment (number 1) (value ""))
(comment (number 2) (value ""))
(comment (number 3) (value ""))
(comment (number 4) (value "")))))
(components
(comp (ref R10)
(value 10k)
(footprint Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder)
(libsource (lib stm32-rescue) (part R) (description ""))
(sheetpath (names /) (tstamps /))
(tstamp 5D347863))
(comp (ref C2)
(value 0.1)
(footprint Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder)
(libsource (lib stm32-rescue) (part C) (description ""))
(sheetpath (names /) (tstamps /))
(tstamp 590D4150))
(comp (ref C1)
(value 0.1)
(footprint Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder)
(libsource (lib stm32-rescue) (part C) (description ""))
(sheetpath (names /) (tstamps /))
(tstamp 5D4AE2B9))
(comp (ref SW2)
(value Boot)
(footprint Buttons_Switches_SMD:SW_SPST_FSMSM)
(libsource (lib Switch) (part SW_Push) (description "Push button switch, generic, two pins"))
(sheetpath (names /) (tstamps /))
(tstamp 5D34785A))
(comp (ref SW1)
(value Reset)
(footprint Buttons_Switches_SMD:SW_SPST_FSMSM)
(libsource (lib Switch) (part SW_Push) (description "Push button switch, generic, two pins"))
(sheetpath (names /) (tstamps /))
(tstamp 5D34785B))
(comp (ref P1)
(value USB_B)
(footprint Connectors_USB:USB_B_OST_USB-B1HSxx_Horizontal)
(libsource (lib stm32-rescue) (part USB_A-RESCUE-stm32) (description ""))
(sheetpath (names /) (tstamps /))
(tstamp 5CEABE76))
(comp (ref R1)
(value 22)
(footprint Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder)
(libsource (lib stm32-rescue) (part R) (description ""))
(sheetpath (names /) (tstamps /))
(tstamp 5CEABEA6))
(comp (ref R2)
(value 22)
(footprint Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder)
(libsource (lib stm32-rescue) (part R) (description ""))
(sheetpath (names /) (tstamps /))
(tstamp 5CEABEAC))
(comp (ref U1)
(value USBLC6-2SC6)
(footprint TO_SOT_Packages_SMD:SOT-23-6_Handsoldering)
(datasheet http://www2.st.com/resource/en/datasheet/CD00050750.pdf)
(libsource (lib Power_Protection) (part USBLC6-2SC6) (description "Bidirectional ESD Protection Diode, SOT-23-6"))
(sheetpath (names /) (tstamps /))
(tstamp 5CED0250))
(comp (ref D3)
(value SS14)
(footprint Diode_SMD:D_SMB_Handsoldering)
(datasheet ~)
(libsource (lib Device) (part D_Schottky) (description "Schottky diode"))
(sheetpath (names /) (tstamps /))
(tstamp 5D89B9B8))
(comp (ref J2)
(value Conn)
(footprint TerminalBlock_Phoenix:TerminalBlock_Phoenix_MKDS-1,5-2-5.08_1x02_P5.08mm_Horizontal)
(datasheet ~)
(libsource (lib Connector_Generic) (part Conn_01x02) (description "Generic connector, single row, 01x02, script generated (kicad-library-utils/schlib/autogen/connector/)"))
(sheetpath (names /) (tstamps /))
(tstamp 5D2DE414))
(comp (ref U2)
(value STM32F042C6Tx)
(footprint Package_QFP:LQFP-48_7x7mm_P0.5mm)
(libsource (lib stm32-rescue) (part STM32F042C6Tx) (description ""))
(sheetpath (names /) (tstamps /))
(tstamp 58C42C0E))
(comp (ref C3)
(value 0.1)
(footprint Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder)
(libsource (lib stm32-rescue) (part C) (description ""))
(sheetpath (names /) (tstamps /))
(tstamp 58C42D39))
(comp (ref C4)
(value 0.1)
(footprint Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder)
(libsource (lib stm32-rescue) (part C) (description ""))
(sheetpath (names /) (tstamps /))
(tstamp 5D6B4F1F))
(comp (ref C5)
(value 0.1)
(footprint Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder)
(libsource (lib stm32-rescue) (part C) (description ""))
(sheetpath (names /) (tstamps /))
(tstamp 59093675))
(comp (ref C6)
(value 0.1)
(footprint Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder)
(libsource (lib stm32-rescue) (part C) (description ""))
(sheetpath (names /) (tstamps /))
(tstamp 5D6B4F23))
(comp (ref P2)
(value USART_BOOT)
(footprint Connector_PinHeader_2.54mm:PinHeader_1x03_P2.54mm_Vertical)
(libsource (lib stm32-rescue) (part CONN_01X03) (description ""))
(sheetpath (names /) (tstamps /))
(tstamp 5D6B4F24))
(comp (ref P3)
(value Hole)
(footprint my_footprints:Hole_3mm)
(libsource (lib stm32-rescue) (part CONN_01X01) (description ""))
(sheetpath (names /) (tstamps /))
(tstamp 59143415))
(comp (ref P4)
(value Hole)
(footprint my_footprints:Hole_3mm)
(libsource (lib stm32-rescue) (part CONN_01X01) (description ""))
(sheetpath (names /) (tstamps /))
(tstamp 5914456D))
(comp (ref P5)
(value Hole)
(footprint my_footprints:Hole_3mm)
(libsource (lib stm32-rescue) (part CONN_01X01) (description ""))
(sheetpath (names /) (tstamps /))
(tstamp 5D6B4F29))
(comp (ref P6)
(value Hole)
(footprint my_footprints:Hole_3mm)
(libsource (lib stm32-rescue) (part CONN_01X01) (description ""))
(sheetpath (names /) (tstamps /))
(tstamp 5D6B4F2A))
(comp (ref J1)
(value 4P4C)
(footprint my_footprints:RJ9-4P4C)
(datasheet ~)
(libsource (lib Connector) (part 4P4C) (description "RJ connector, 4P4C (4 positions 4 connected), RJ9/RJ10/RJ22"))
(sheetpath (names /) (tstamps /))
(tstamp 5D692FC5))
(comp (ref J3)
(value Conn)
(footprint TerminalBlock_Phoenix:TerminalBlock_Phoenix_MKDS-1,5-2-5.08_1x02_P5.08mm_Horizontal)
(datasheet ~)
(libsource (lib Connector_Generic) (part Conn_01x02) (description "Generic connector, single row, 01x02, script generated (kicad-library-utils/schlib/autogen/connector/)"))
(sheetpath (names /) (tstamps /))
(tstamp 5D6A6D23))
(comp (ref U3)
(value LM1117-3.3)
(footprint TO_SOT_Packages_SMD:SOT-223)
(libsource (lib stm32-rescue) (part LM1117-3.3-RESCUE-stm32) (description ""))
(sheetpath (names /) (tstamps /))
(tstamp 58C431FC))
(comp (ref C7)
(value 47u)
(footprint Capacitor_Tantalum_SMD:CP_EIA-3216-18_Kemet-A_Pad1.58x1.35mm_HandSolder)
(libsource (lib stm32-rescue) (part CP) (description ""))
(sheetpath (names /) (tstamps /))
(tstamp 58C454F6))
(comp (ref D1)
(value LED0)
(footprint LED_SMD:LED_0805_2012Metric_Pad1.15x1.40mm_HandSolder)
(libsource (lib stm32-rescue) (part LED-RESCUE-stm32) (description ""))
(sheetpath (names /) (tstamps /))
(tstamp 5908EA64))
(comp (ref R5)
(value 330)
(footprint Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder)
(libsource (lib stm32-rescue) (part R) (description ""))
(sheetpath (names /) (tstamps /))
(tstamp 5908EB17))
(comp (ref D2)
(value LED1)
(footprint LED_SMD:LED_0805_2012Metric_Pad1.15x1.40mm_HandSolder)
(libsource (lib stm32-rescue) (part LED-RESCUE-stm32) (description ""))
(sheetpath (names /) (tstamps /))
(tstamp 5909AF9A))
(comp (ref R6)
(value 330)
(footprint Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder)
(libsource (lib stm32-rescue) (part R) (description ""))
(sheetpath (names /) (tstamps /))
(tstamp 5909AFA0))
(comp (ref D4)
(value SS14)
(footprint Diode_SMD:D_SMB_Handsoldering)
(libsource (lib stm32-rescue) (part D_Schottky) (description ""))
(sheetpath (names /) (tstamps /))
(tstamp 5A545B43))
(comp (ref BT1)
(value Battery_Cell)
(footprint Battery:BatteryHolder_MPD_BH-18650-PC2)
(datasheet ~)
(libsource (lib Device) (part Battery_Cell) (description "Single-cell battery"))
(sheetpath (names /) (tstamps /))
(tstamp 5D7DDF56))
(comp (ref R8)
(value 4k7)
(footprint Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder)
(datasheet ~)
(libsource (lib Device) (part R) (description Resistor))
(sheetpath (names /) (tstamps /))
(tstamp 5D850AD1))
(comp (ref R7)
(value 4k7)
(footprint Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder)
(datasheet ~)
(libsource (lib Device) (part R) (description Resistor))
(sheetpath (names /) (tstamps /))
(tstamp 5D85121F))
(comp (ref R9)
(value 22)
(footprint Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder)
(datasheet ~)
(libsource (lib Device) (part R) (description Resistor))
(sheetpath (names /) (tstamps /))
(tstamp 5D86E056))
(comp (ref Q1)
(value AO3407)
(footprint TO_SOT_Packages_SMD:SOT-23_Handsoldering)
(datasheet ~)
(libsource (lib Device) (part Q_PMOS_GSD) (description "P-MOSFET transistor, gate/source/drain"))
(sheetpath (names /) (tstamps /))
(tstamp 5D886416))
(comp (ref R11)
(value 10k)
(footprint Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder)
(libsource (lib stm32-rescue) (part R) (description ""))
(sheetpath (names /) (tstamps /))
(tstamp 5D89C1EC))
(comp (ref R12)
(value 510)
(footprint Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder)
(datasheet ~)
(libsource (lib Device) (part R) (description Resistor))
(sheetpath (names /) (tstamps /))
(tstamp 5D89C918))
(comp (ref SW3)
(value Poweron)
(footprint Button_Switch_THT:SW_PUSH_6mm_H13mm)
(libsource (lib Switch) (part SW_Push) (description "Push button switch, generic, two pins"))
(sheetpath (names /) (tstamps /))
(tstamp 5D8C5989))
(comp (ref R4)
(value 51k)
(footprint Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder)
(libsource (lib stm32-rescue) (part R) (description ""))
(sheetpath (names /) (tstamps /))
(tstamp 5D93631F))
(comp (ref R3)
(value 51k)
(footprint Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder)
(libsource (lib stm32-rescue) (part R) (description ""))
(sheetpath (names /) (tstamps /))
(tstamp 5D936816))
(comp (ref J4)
(value SPI_screen)
(footprint Connector_PinSocket_2.54mm:PinSocket_1x07_P2.54mm_Vertical)
(datasheet ~)
(libsource (lib Connector) (part Conn_01x07_Female) (description "Generic connector, single row, 01x07, script generated (kicad-library-utils/schlib/autogen/connector/)"))
(sheetpath (names /) (tstamps /))
(tstamp 5D96F1EC))
(comp (ref C8)
(value 0.1)
(footprint Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder)
(libsource (lib stm32-rescue) (part C) (description ""))
(sheetpath (names /) (tstamps /))
(tstamp 5DA0ADC1)))
(libparts
(libpart (lib Connector) (part 4P4C)
(aliases
(alias RJ9)
(alias RJ10)
(alias RJ22))
(description "RJ connector, 4P4C (4 positions 4 connected), RJ9/RJ10/RJ22")
(docs ~)
(footprints
(fp 4P4C*)
(fp RJ9*)
(fp RJ10*)
(fp RJ22*))
(fields
(field (name Reference) J)
(field (name Value) 4P4C))
(pins
(pin (num 1) (name ~) (type passive))
(pin (num 2) (name ~) (type passive))
(pin (num 3) (name ~) (type passive))
(pin (num 4) (name ~) (type passive))))
(libpart (lib Connector) (part Conn_01x07_Female)
(description "Generic connector, single row, 01x07, script generated (kicad-library-utils/schlib/autogen/connector/)")
(docs ~)
(footprints
(fp Connector*:*_1x??_*))
(fields
(field (name Reference) J)
(field (name Value) Conn_01x07_Female))
(pins
(pin (num 1) (name Pin_1) (type passive))
(pin (num 2) (name Pin_2) (type passive))
(pin (num 3) (name Pin_3) (type passive))
(pin (num 4) (name Pin_4) (type passive))
(pin (num 5) (name Pin_5) (type passive))
(pin (num 6) (name Pin_6) (type passive))
(pin (num 7) (name Pin_7) (type passive))))
(libpart (lib Connector_Generic) (part Conn_01x02)
(description "Generic connector, single row, 01x02, script generated (kicad-library-utils/schlib/autogen/connector/)")
(docs ~)
(footprints
(fp Connector*:*_1x??_*))
(fields
(field (name Reference) J)
(field (name Value) Conn_01x02))
(pins
(pin (num 1) (name Pin_1) (type passive))
(pin (num 2) (name Pin_2) (type passive))))
(libpart (lib Device) (part Battery_Cell)
(description "Single-cell battery")
(docs ~)
(fields
(field (name Reference) BT)
(field (name Value) Battery_Cell))
(pins
(pin (num 1) (name +) (type passive))
(pin (num 2) (name -) (type passive))))
(libpart (lib Device) (part D_Schottky)
(description "Schottky diode")
(docs ~)
(footprints
(fp TO-???*)
(fp *_Diode_*)
(fp *SingleDiode*)
(fp D_*))
(fields
(field (name Reference) D)
(field (name Value) D_Schottky))
(pins
(pin (num 1) (name K) (type passive))
(pin (num 2) (name A) (type passive))))
(libpart (lib Device) (part Q_PMOS_GSD)
(description "P-MOSFET transistor, gate/source/drain")
(docs ~)
(fields
(field (name Reference) Q)
(field (name Value) Q_PMOS_GSD))
(pins
(pin (num 1) (name G) (type input))
(pin (num 2) (name S) (type passive))
(pin (num 3) (name D) (type passive))))
(libpart (lib Device) (part R)
(description Resistor)
(docs ~)
(footprints
(fp R_*))
(fields
(field (name Reference) R)
(field (name Value) R))
(pins
(pin (num 1) (name ~) (type passive))
(pin (num 2) (name ~) (type passive))))
(libpart (lib Power_Protection) (part USBLC6-2SC6)
(description "Bidirectional ESD Protection Diode, SOT-23-6")
(docs http://www2.st.com/resource/en/datasheet/CD00050750.pdf)
(footprints
(fp SOT?23*))
(fields
(field (name Reference) U)
(field (name Value) USBLC6-2SC6)
(field (name Footprint) Package_TO_SOT_SMD:SOT-23-6))
(pins
(pin (num 1) (name IO1) (type passive))
(pin (num 2) (name GND) (type passive))
(pin (num 3) (name IO2) (type passive))
(pin (num 4) (name IO2) (type passive))
(pin (num 5) (name VBUS) (type passive))
(pin (num 6) (name IO1) (type passive))))
(libpart (lib Switch) (part SW_Push)
(description "Push button switch, generic, two pins")
(docs ~)
(fields
(field (name Reference) SW)
(field (name Value) SW_Push))
(pins
(pin (num 1) (name 1) (type passive))
(pin (num 2) (name 2) (type passive))))
(libpart (lib stm32-rescue) (part C)
(footprints
(fp C_*))
(fields
(field (name Reference) C)
(field (name Value) C))
(pins
(pin (num 1) (name ~) (type passive))
(pin (num 2) (name ~) (type passive))))
(libpart (lib stm32-rescue) (part CONN_01X01)
(footprints
(fp Pin_Header_Straight_1X*)
(fp Pin_Header_Angled_1X*)
(fp Socket_Strip_Straight_1X*)
(fp Socket_Strip_Angled_1X*))
(fields
(field (name Reference) J)
(field (name Value) CONN_01X01))
(pins
(pin (num 1) (name P1) (type passive))))
(libpart (lib stm32-rescue) (part CONN_01X03)
(footprints
(fp Pin_Header_Straight_1X*)
(fp Pin_Header_Angled_1X*)
(fp Socket_Strip_Straight_1X*)
(fp Socket_Strip_Angled_1X*))
(fields
(field (name Reference) J)
(field (name Value) CONN_01X03))
(pins
(pin (num 1) (name P1) (type passive))
(pin (num 2) (name P2) (type passive))
(pin (num 3) (name P3) (type passive))))
(libpart (lib stm32-rescue) (part CP)
(footprints
(fp CP_*))
(fields
(field (name Reference) C)
(field (name Value) CP))
(pins
(pin (num 1) (name ~) (type passive))
(pin (num 2) (name ~) (type passive))))
(libpart (lib stm32-rescue) (part D_Schottky)
(footprints
(fp TO-???*)
(fp *SingleDiode)
(fp *_Diode_*)
(fp *SingleDiode*)
(fp D_*))
(fields
(field (name Reference) D)
(field (name Value) D_Schottky))
(pins
(pin (num 1) (name K) (type passive))
(pin (num 2) (name A) (type passive))))
(libpart (lib stm32-rescue) (part LED-RESCUE-stm32)
(footprints
(fp LED*))
(fields
(field (name Reference) D)
(field (name Value) LED-RESCUE-stm32))
(pins
(pin (num 1) (name K) (type passive))
(pin (num 2) (name A) (type passive))))
(libpart (lib stm32-rescue) (part LM1117-3.3-RESCUE-stm32)
(footprints
(fp SOT-223*)
(fp TO-263*)
(fp TO-252*))
(fields
(field (name Reference) U)
(field (name Value) LM1117-3.3-RESCUE-stm32))
(pins
(pin (num 1) (name GND/ADJ) (type power_in))
(pin (num 2) (name VO) (type passive))
(pin (num 3) (name VI) (type power_in))
(pin (num 4) (name VO) (type power_out))))
(libpart (lib stm32-rescue) (part R)
(footprints
(fp R_*)
(fp R_*))
(fields
(field (name Reference) R)
(field (name Value) R))
(pins
(pin (num 1) (name ~) (type passive))
(pin (num 2) (name ~) (type passive))))
(libpart (lib stm32-rescue) (part STM32F042C6Tx)
(fields
(field (name Reference) U)
(field (name Value) STM32F042C6Tx)
(field (name Footprint) LQFP48))
(pins
(pin (num 1) (name VBAT) (type power_in))
(pin (num 2) (name PC13/RTC_OUT_ALARM/RTC_OUT_CALIB/RTC_TAMP1/RTC_TS/SYS_WKUP2) (type BiDi))
(pin (num 3) (name PC14/RCC_OSC32_IN) (type BiDi))
(pin (num 4) (name PC15/RCC_OSC32_OUT) (type BiDi))
(pin (num 5) (name PF0/CRS_SYNC/I2C1_SDA/RCC_OSC_IN) (type input))
(pin (num 6) (name PF1/I2C1_SCL/RCC_OSC_OUT) (type input))
(pin (num 7) (name NRST) (type input))
(pin (num 8) (name VSSA) (type power_in))
(pin (num 9) (name VDDA) (type power_in))
(pin (num 10) (name ADC_IN0/RTC_TAMP2/SYS_WKUP1/TIM2_CH1/TIM2_ETR/TSC_G1_IO1/USART2_CTS/PA0) (type BiDi))
(pin (num 11) (name ADC_IN1/TIM2_CH2/TSC_G1_IO2/USART2_DE/USART2_RTS/PA1) (type BiDi))
(pin (num 12) (name ADC_IN2/SYS_WKUP4/TIM2_CH3/TSC_G1_IO3/USART2_TX/PA2) (type BiDi))
(pin (num 13) (name ADC_IN3/TIM2_CH4/TSC_G1_IO4/USART2_RX/PA3) (type BiDi))
(pin (num 14) (name ADC_IN4/I2S1_WS/SPI1_NSS/TIM14_CH1/TSC_G2_IO1/USART2_CK/USB_OE/PA4) (type BiDi))
(pin (num 15) (name ADC_IN5/CEC/I2S1_CK/SPI1_SCK/TIM2_CH1/TIM2_ETR/TSC_G2_IO2/PA5) (type BiDi))
(pin (num 16) (name ADC_IN6/I2S1_MCK/SPI1_MISO/TIM16_CH1/TIM1_BKIN/TIM3_CH1/TSC_G2_IO3/PA6) (type BiDi))
(pin (num 17) (name ADC_IN7/I2S1_SD/SPI1_MOSI/TIM14_CH1/TIM17_CH1/TIM1_CH1N/TIM3_CH2/TSC_G2_IO4/PA7) (type BiDi))
(pin (num 18) (name PB0/ADC_IN8/TIM1_CH2N/TIM3_CH3/TSC_G3_IO2) (type BiDi))
(pin (num 19) (name PB1/ADC_IN9/TIM14_CH1/TIM1_CH3N/TIM3_CH4/TSC_G3_IO3) (type BiDi))
(pin (num 20) (name PB2/TSC_G3_IO4) (type BiDi))
(pin (num 21) (name PB10/CEC/I2C1_SCL/SPI2_SCK/TIM2_CH3/TSC_SYNC) (type BiDi))
(pin (num 22) (name PB11/I2C1_SDA/TIM2_CH4) (type BiDi))
(pin (num 23) (name VSS) (type power_in))
(pin (num 24) (name VDD) (type power_in))
(pin (num 25) (name PB12/SPI2_NSS/TIM1_BKIN) (type BiDi))
(pin (num 26) (name PB13/I2C1_SCL/SPI2_SCK/TIM1_CH1N) (type BiDi))
(pin (num 27) (name PB14/I2C1_SDA/SPI2_MISO/TIM1_CH2N) (type BiDi))
(pin (num 28) (name PB15/RTC_REFIN/SPI2_MOSI/SYS_WKUP7/TIM1_CH3N) (type BiDi))
(pin (num 29) (name CRS_SYNC/RCC_MCO/TIM1_CH1/USART1_CK/PA8) (type BiDi))
(pin (num 30) (name I2C1_SCL/TIM1_CH2/TSC_G4_IO1/USART1_TX/PA9) (type BiDi))
(pin (num 31) (name I2C1_SDA/TIM17_BKIN/TIM1_CH3/TSC_G4_IO2/USART1_RX/PA10) (type BiDi))
(pin (num 32) (name CAN_RX/I2C1_SCL/TIM1_CH4/TSC_G4_IO3/USART1_CTS/USB_DM/PA11) (type BiDi))
(pin (num 33) (name CAN_TX/I2C1_SDA/TIM1_ETR/TSC_G4_IO4/USART1_DE/USART1_RTS/USB_DP/PA12) (type BiDi))
(pin (num 34) (name IR_OUT/SYS_SWDIO/USB_OE/PA13) (type BiDi))
(pin (num 35) (name VSS) (type power_in))
(pin (num 36) (name VDDIO2) (type power_in))
(pin (num 37) (name SYS_SWCLK/USART2_TX/PA14) (type BiDi))
(pin (num 38) (name I2S1_WS/SPI1_NSS/TIM2_CH1/TIM2_ETR/USART2_RX/USB_OE/PA15) (type BiDi))
(pin (num 39) (name PB3/I2S1_CK/SPI1_SCK/TIM2_CH2/TSC_G5_IO1) (type BiDi))
(pin (num 40) (name PB4/I2S1_MCK/SPI1_MISO/TIM17_BKIN/TIM3_CH1/TSC_G5_IO2) (type BiDi))
(pin (num 41) (name PB5/I2C1_SMBA/I2S1_SD/SPI1_MOSI/SYS_WKUP6/TIM16_BKIN/TIM3_CH2) (type BiDi))
(pin (num 42) (name PB6/I2C1_SCL/TIM16_CH1N/TSC_G5_IO3/USART1_TX) (type BiDi))
(pin (num 43) (name PB7/I2C1_SDA/TIM17_CH1N/TSC_G5_IO4/USART1_RX) (type BiDi))
(pin (num 44) (name PF11) (type BiDi))
(pin (num 45) (name PB8/CAN_RX/CEC/I2C1_SCL/TIM16_CH1/TSC_SYNC) (type BiDi))
(pin (num 46) (name PB9/CAN_TX/I2C1_SDA/IR_OUT/SPI2_NSS/TIM17_CH1) (type BiDi))
(pin (num 47) (name VSS) (type power_in))
(pin (num 48) (name VDD) (type power_in))))
(libpart (lib stm32-rescue) (part USB_A-RESCUE-stm32)
(footprints
(fp USB*))
(fields
(field (name Reference) P)
(field (name Value) USB_A-RESCUE-stm32))
(pins
(pin (num 1) (name VBUS) (type power_in))
(pin (num 2) (name D-) (type passive))
(pin (num 3) (name D+) (type passive))
(pin (num 4) (name GND) (type power_in))
(pin (num 5) (name shield) (type passive)))))
(libraries
(library (logical Connector)
(uri /usr/share/kicad/kicad-symbols//Connector.lib))
(library (logical Connector_Generic)
(uri /usr/share/kicad/kicad-symbols//Connector_Generic.lib))
(library (logical Device)
(uri /usr/share/kicad/kicad-symbols//Device.lib))
(library (logical Power_Protection)
(uri /usr/share/kicad/kicad-symbols//Power_Protection.lib))
(library (logical Switch)
(uri /usr/share/kicad/kicad-symbols//Switch.lib))
(library (logical stm32-rescue)
(uri /home/eddy/Docs/SAO/ELECTRONICS/STM32/F1-srcs/chronometer/kicad/chrono/stm32-rescue.lib)))
(nets
(net (code 1) (name "Net-(D1-Pad2)")
(node (ref R5) (pin 1))
(node (ref D1) (pin 2)))
(net (code 2) (name +3V3)
(node (ref C6) (pin 2))
(node (ref U2) (pin 36))
(node (ref U2) (pin 24))
(node (ref U3) (pin 4))
(node (ref J4) (pin 2))
(node (ref R9) (pin 1))
(node (ref U3) (pin 2))
(node (ref SW2) (pin 2))
(node (ref C2) (pin 2))
(node (ref C7) (pin 1))
(node (ref R5) (pin 2))
(node (ref C4) (pin 2))
(node (ref C5) (pin 2))
(node (ref R6) (pin 2))
(node (ref U2) (pin 9))
(node (ref U2) (pin 48))
(node (ref C3) (pin 2)))
(net (code 3) (name "Net-(D2-Pad2)")
(node (ref R6) (pin 1))
(node (ref D2) (pin 2)))
(net (code 4) (name /LED1)
(node (ref D2) (pin 1))
(node (ref U2) (pin 38)))
(net (code 5) (name /LED0)
(node (ref U2) (pin 37))
(node (ref D1) (pin 1)))
(net (code 6) (name "Net-(U2-Pad16)")
(node (ref U2) (pin 16)))
(net (code 7) (name /SCL)
(node (ref U2) (pin 42))
(node (ref J3) (pin 2))
(node (ref J1) (pin 2))
(node (ref R8) (pin 2)))
(net (code 8) (name /SDA)
(node (ref J1) (pin 1))
(node (ref U2) (pin 43))
(node (ref J2) (pin 1))
(node (ref R7) (pin 2)))
(net (code 9) (name "Net-(U2-Pad13)")
(node (ref U2) (pin 13)))
(net (code 10) (name "Net-(U2-Pad39)")
(node (ref U2) (pin 39)))
(net (code 11) (name "Net-(U2-Pad46)")
(node (ref U2) (pin 46)))
(net (code 12) (name "Net-(U2-Pad28)")
(node (ref U2) (pin 28)))
(net (code 13) (name GND)
(node (ref R4) (pin 1))
(node (ref J1) (pin 4))
(node (ref U1) (pin 2))
(node (ref BT1) (pin 2))
(node (ref U2) (pin 35))
(node (ref P2) (pin 1))
(node (ref C6) (pin 1))
(node (ref J4) (pin 1))
(node (ref J3) (pin 1))
(node (ref C8) (pin 2))
(node (ref C5) (pin 1))
(node (ref C4) (pin 1))
(node (ref U2) (pin 47))
(node (ref SW1) (pin 2))
(node (ref U3) (pin 1))
(node (ref C3) (pin 1))
(node (ref U2) (pin 8))
(node (ref C1) (pin 2))
(node (ref R10) (pin 2))
(node (ref U2) (pin 23))
(node (ref C7) (pin 2))
(node (ref P1) (pin 4))
(node (ref P1) (pin 5)))
(net (code 14) (name "Net-(BT1-Pad1)")
(node (ref R11) (pin 1))
(node (ref D4) (pin 1))
(node (ref SW3) (pin 1))
(node (ref BT1) (pin 1))
(node (ref Q1) (pin 2)))
(net (code 15) (name /USBDM)
(node (ref U2) (pin 32))
(node (ref R2) (pin 2)))
(net (code 16) (name /USBDP)
(node (ref R1) (pin 2))
(node (ref U2) (pin 33)))
(net (code 17) (name "Net-(U2-Pad29)")
(node (ref U2) (pin 29)))
(net (code 18) (name "Net-(U2-Pad34)")
(node (ref U2) (pin 34)))
(net (code 19) (name "Net-(U2-Pad12)")
(node (ref U2) (pin 12)))
(net (code 20) (name "Net-(P2-Pad3)")
(node (ref P2) (pin 3))
(node (ref U2) (pin 30)))
(net (code 21) (name /D-C)
(node (ref U2) (pin 19))
(node (ref J4) (pin 6)))
(net (code 22) (name /RST)
(node (ref U2) (pin 18))
(node (ref J4) (pin 5)))
(net (code 23) (name /MOSI)
(node (ref U2) (pin 17))
(node (ref J4) (pin 4)))
(net (code 24) (name /SCK)
(node (ref U2) (pin 15))
(node (ref J4) (pin 3)))
(net (code 25) (name "Net-(U2-Pad26)")
(node (ref U2) (pin 26)))
(net (code 26) (name "Net-(U2-Pad10)")
(node (ref U2) (pin 10)))
(net (code 27) (name "Net-(U2-Pad25)")
(node (ref U2) (pin 25)))
(net (code 28) (name "Net-(U2-Pad22)")
(node (ref U2) (pin 22)))
(net (code 29) (name "Net-(U2-Pad21)")
(node (ref U2) (pin 21)))
(net (code 30) (name "Net-(U2-Pad14)")
(node (ref U2) (pin 14)))
(net (code 31) (name "Net-(U2-Pad41)")
(node (ref U2) (pin 41)))
(net (code 32) (name "Net-(U2-Pad40)")
(node (ref U2) (pin 40)))
(net (code 33) (name "Net-(U2-Pad45)")
(node (ref U2) (pin 45)))
(net (code 34) (name "Net-(Q1-Pad1)")
(node (ref R12) (pin 1))
(node (ref Q1) (pin 1)))
(net (code 35) (name /5Vusb)
(node (ref D4) (pin 2))
(node (ref D3) (pin 1))
(node (ref Q1) (pin 3))
(node (ref SW3) (pin 2))
(node (ref C8) (pin 1))
(node (ref U3) (pin 3)))
(net (code 36) (name "Net-(P2-Pad2)")
(node (ref P2) (pin 2))
(node (ref U2) (pin 31)))
(net (code 37) (name "Net-(P1-Pad2)")
(node (ref P1) (pin 2))
(node (ref U1) (pin 4)))
(net (code 38) (name /U5V)
(node (ref D3) (pin 2))
(node (ref U1) (pin 5))
(node (ref R3) (pin 2))
(node (ref P1) (pin 1)))
(net (code 39) (name "Net-(R2-Pad1)")
(node (ref R2) (pin 1))
(node (ref U1) (pin 3)))
(net (code 40) (name "Net-(R1-Pad1)")
(node (ref U1) (pin 1))
(node (ref R1) (pin 1)))
(net (code 41) (name "Net-(P1-Pad3)")
(node (ref U1) (pin 6))
(node (ref P1) (pin 3)))
(net (code 42) (name /CS)
(node (ref J4) (pin 7))
(node (ref U2) (pin 20)))
(net (code 43) (name /POWERON)
(node (ref U2) (pin 2))
(node (ref R12) (pin 2))
(node (ref R11) (pin 2)))
(net (code 44) (name /USBON)
(node (ref U2) (pin 11))
(node (ref R3) (pin 1))
(node (ref R4) (pin 2)))
(net (code 45) (name "Net-(U2-Pad1)")
(node (ref U2) (pin 1)))
(net (code 46) (name /3V3Sensors)
(node (ref R8) (pin 1))
(node (ref R7) (pin 1))
(node (ref R9) (pin 2))
(node (ref J2) (pin 2))
(node (ref J1) (pin 3)))
(net (code 47) (name /BOOT0)
(node (ref R10) (pin 1))
(node (ref U2) (pin 44))
(node (ref SW2) (pin 1))
(node (ref C2) (pin 1)))
(net (code 48) (name "Net-(P3-Pad1)")
(node (ref P3) (pin 1)))
(net (code 49) (name "Net-(P6-Pad1)")
(node (ref P6) (pin 1)))
(net (code 50) (name "Net-(P5-Pad1)")
(node (ref P5) (pin 1)))
(net (code 51) (name "Net-(P4-Pad1)")
(node (ref P4) (pin 1)))
(net (code 52) (name "Net-(U2-Pad5)")
(node (ref U2) (pin 5)))
(net (code 53) (name "Net-(U2-Pad6)")
(node (ref U2) (pin 6)))
(net (code 54) (name "Net-(U2-Pad3)")
(node (ref U2) (pin 3)))
(net (code 55) (name "Net-(U2-Pad4)")
(node (ref U2) (pin 4)))
(net (code 56) (name "Net-(U2-Pad27)")
(node (ref U2) (pin 27)))
(net (code 57) (name /NRST)
(node (ref U2) (pin 7))
(node (ref C1) (pin 1))
(node (ref SW1) (pin 1)))))

View File

@ -0,0 +1,65 @@
update=Пн 15 июл 2019 16:25:43
version=1
last_client=kicad
[general]
version=1
RootSch=
BoardNm=
[cvpcb]
version=1
NetIExt=net
[eeschema]
version=1
LibDir=
[eeschema/libraries]
[pcbnew]
version=1
PageLayoutDescrFile=
LastNetListRead=stm32f042.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.3
TrackWidth2=0.3
TrackWidth3=0.5
TrackWidth4=1
ViaDiameter1=1.5
ViaDrill1=0.6
ViaDiameter2=1.5
ViaDrill2=0.6
dPairWidth1=0.2
dPairGap1=0.25
dPairViaGap1=0.25
SilkLineWidth=0.12
SilkTextSizeV=1
SilkTextSizeH=1
SilkTextSizeThickness=0.15
SilkTextItalic=0
SilkTextUpright=1
CopperLineWidth=0.2
CopperTextSizeV=1.5
CopperTextSizeH=1.5
CopperTextThickness=0.3
CopperTextItalic=0
CopperTextUpright=1
EdgeCutLineWidth=0.05
CourtyardLineWidth=0.05
OthersLineWidth=0.15
OthersTextSizeV=1
OthersTextSizeH=1
OthersTextSizeThickness=0.15
OthersTextItalic=0
OthersTextUpright=1
SolderMaskClearance=0.051
SolderMaskMinWidth=0.25
SolderPasteClearance=0
SolderPasteRatio=-0

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,953 @@
<?xml version="1.0" encoding="UTF-8"?>
<export version="D">
<design>
<source>/home/eddy/Docs/SAO/BTA/MIRROR_CONTROL_termo/Project/kicad/Sensors_tester_with_screen/stm32f042/stm32f042.sch</source>
<date>Вт 16 июл 2019 08:53:19</date>
<tool>Eeschema (6.0.0-rc1-dev-1613-ga55d9819b)</tool>
<sheet number="1" name="/" tstamps="/">
<title_block>
<title/>
<company/>
<rev/>
<date/>
<source>stm32f042.sch</source>
<comment number="1" value=""/>
<comment number="2" value=""/>
<comment number="3" value=""/>
<comment number="4" value=""/>
</title_block>
</sheet>
</design>
<components>
<comp ref="R10">
<value>10k</value>
<footprint>Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder</footprint>
<libsource lib="stm32-rescue" part="R" description=""/>
<sheetpath names="/" tstamps="/"/>
<tstamp>5D347863</tstamp>
</comp>
<comp ref="C2">
<value>0.1</value>
<footprint>Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder</footprint>
<libsource lib="stm32-rescue" part="C" description=""/>
<sheetpath names="/" tstamps="/"/>
<tstamp>590D4150</tstamp>
</comp>
<comp ref="C1">
<value>0.1</value>
<footprint>Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder</footprint>
<libsource lib="stm32-rescue" part="C" description=""/>
<sheetpath names="/" tstamps="/"/>
<tstamp>5D4AE2B9</tstamp>
</comp>
<comp ref="SW2">
<value>Boot</value>
<footprint>Buttons_Switches_SMD:SW_SPST_FSMSM</footprint>
<libsource lib="Switch" part="SW_Push" description="Push button switch, generic, two pins"/>
<sheetpath names="/" tstamps="/"/>
<tstamp>5D34785A</tstamp>
</comp>
<comp ref="SW1">
<value>Reset</value>
<footprint>Buttons_Switches_SMD:SW_SPST_FSMSM</footprint>
<libsource lib="Switch" part="SW_Push" description="Push button switch, generic, two pins"/>
<sheetpath names="/" tstamps="/"/>
<tstamp>5D34785B</tstamp>
</comp>
<comp ref="P1">
<value>USB_B</value>
<footprint>Connectors_USB:USB_B_OST_USB-B1HSxx_Horizontal</footprint>
<libsource lib="stm32-rescue" part="USB_A-RESCUE-stm32" description=""/>
<sheetpath names="/" tstamps="/"/>
<tstamp>5CEABE76</tstamp>
</comp>
<comp ref="R1">
<value>22</value>
<footprint>Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder</footprint>
<libsource lib="stm32-rescue" part="R" description=""/>
<sheetpath names="/" tstamps="/"/>
<tstamp>5CEABEA6</tstamp>
</comp>
<comp ref="R2">
<value>22</value>
<footprint>Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder</footprint>
<libsource lib="stm32-rescue" part="R" description=""/>
<sheetpath names="/" tstamps="/"/>
<tstamp>5CEABEAC</tstamp>
</comp>
<comp ref="U1">
<value>USBLC6-2SC6</value>
<footprint>TO_SOT_Packages_SMD:SOT-23-6_Handsoldering</footprint>
<datasheet>http://www2.st.com/resource/en/datasheet/CD00050750.pdf</datasheet>
<libsource lib="Power_Protection" part="USBLC6-2SC6" description="Bidirectional ESD Protection Diode, SOT-23-6"/>
<sheetpath names="/" tstamps="/"/>
<tstamp>5CED0250</tstamp>
</comp>
<comp ref="D3">
<value>SS14</value>
<footprint>Diode_SMD:D_SMB_Handsoldering</footprint>
<datasheet>~</datasheet>
<libsource lib="Device" part="D_Schottky" description="Schottky diode"/>
<sheetpath names="/" tstamps="/"/>
<tstamp>5D89B9B8</tstamp>
</comp>
<comp ref="J2">
<value>Conn</value>
<footprint>TerminalBlock_Phoenix:TerminalBlock_Phoenix_MKDS-1,5-2-5.08_1x02_P5.08mm_Horizontal</footprint>
<datasheet>~</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>5D2DE414</tstamp>
</comp>
<comp ref="U2">
<value>STM32F042C6Tx</value>
<footprint>Package_QFP:LQFP-48_7x7mm_P0.5mm</footprint>
<libsource lib="stm32-rescue" part="STM32F042C6Tx" description=""/>
<sheetpath names="/" tstamps="/"/>
<tstamp>58C42C0E</tstamp>
</comp>
<comp ref="C3">
<value>0.1</value>
<footprint>Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder</footprint>
<libsource lib="stm32-rescue" part="C" description=""/>
<sheetpath names="/" tstamps="/"/>
<tstamp>58C42D39</tstamp>
</comp>
<comp ref="C4">
<value>0.1</value>
<footprint>Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder</footprint>
<libsource lib="stm32-rescue" part="C" description=""/>
<sheetpath names="/" tstamps="/"/>
<tstamp>5D6B4F1F</tstamp>
</comp>
<comp ref="C5">
<value>0.1</value>
<footprint>Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder</footprint>
<libsource lib="stm32-rescue" part="C" description=""/>
<sheetpath names="/" tstamps="/"/>
<tstamp>59093675</tstamp>
</comp>
<comp ref="C6">
<value>0.1</value>
<footprint>Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder</footprint>
<libsource lib="stm32-rescue" part="C" description=""/>
<sheetpath names="/" tstamps="/"/>
<tstamp>5D6B4F23</tstamp>
</comp>
<comp ref="P2">
<value>USART_BOOT</value>
<footprint>Connector_PinHeader_2.54mm:PinHeader_1x03_P2.54mm_Vertical</footprint>
<libsource lib="stm32-rescue" part="CONN_01X03" description=""/>
<sheetpath names="/" tstamps="/"/>
<tstamp>5D6B4F24</tstamp>
</comp>
<comp ref="P3">
<value>Hole</value>
<footprint>my_footprints:Hole_3mm</footprint>
<libsource lib="stm32-rescue" part="CONN_01X01" description=""/>
<sheetpath names="/" tstamps="/"/>
<tstamp>59143415</tstamp>
</comp>
<comp ref="P4">
<value>Hole</value>
<footprint>my_footprints:Hole_3mm</footprint>
<libsource lib="stm32-rescue" part="CONN_01X01" description=""/>
<sheetpath names="/" tstamps="/"/>
<tstamp>5914456D</tstamp>
</comp>
<comp ref="P5">
<value>Hole</value>
<footprint>my_footprints:Hole_3mm</footprint>
<libsource lib="stm32-rescue" part="CONN_01X01" description=""/>
<sheetpath names="/" tstamps="/"/>
<tstamp>5D6B4F29</tstamp>
</comp>
<comp ref="P6">
<value>Hole</value>
<footprint>my_footprints:Hole_3mm</footprint>
<libsource lib="stm32-rescue" part="CONN_01X01" description=""/>
<sheetpath names="/" tstamps="/"/>
<tstamp>5D6B4F2A</tstamp>
</comp>
<comp ref="J1">
<value>4P4C</value>
<footprint>my_footprints:RJ9-4P4C</footprint>
<datasheet>~</datasheet>
<libsource lib="Connector" part="4P4C" description="RJ connector, 4P4C (4 positions 4 connected), RJ9/RJ10/RJ22"/>
<sheetpath names="/" tstamps="/"/>
<tstamp>5D692FC5</tstamp>
</comp>
<comp ref="J3">
<value>Conn</value>
<footprint>TerminalBlock_Phoenix:TerminalBlock_Phoenix_MKDS-1,5-2-5.08_1x02_P5.08mm_Horizontal</footprint>
<datasheet>~</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>5D6A6D23</tstamp>
</comp>
<comp ref="U3">
<value>LM1117-3.3</value>
<footprint>TO_SOT_Packages_SMD:SOT-223</footprint>
<libsource lib="stm32-rescue" part="LM1117-3.3-RESCUE-stm32" description=""/>
<sheetpath names="/" tstamps="/"/>
<tstamp>58C431FC</tstamp>
</comp>
<comp ref="C7">
<value>47u</value>
<footprint>Capacitor_Tantalum_SMD:CP_EIA-3216-18_Kemet-A_Pad1.58x1.35mm_HandSolder</footprint>
<libsource lib="stm32-rescue" part="CP" description=""/>
<sheetpath names="/" tstamps="/"/>
<tstamp>58C454F6</tstamp>
</comp>
<comp ref="D1">
<value>LED0</value>
<footprint>LED_SMD:LED_0805_2012Metric_Pad1.15x1.40mm_HandSolder</footprint>
<libsource lib="stm32-rescue" part="LED-RESCUE-stm32" description=""/>
<sheetpath names="/" tstamps="/"/>
<tstamp>5908EA64</tstamp>
</comp>
<comp ref="R5">
<value>330</value>
<footprint>Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder</footprint>
<libsource lib="stm32-rescue" part="R" description=""/>
<sheetpath names="/" tstamps="/"/>
<tstamp>5908EB17</tstamp>
</comp>
<comp ref="D2">
<value>LED1</value>
<footprint>LED_SMD:LED_0805_2012Metric_Pad1.15x1.40mm_HandSolder</footprint>
<libsource lib="stm32-rescue" part="LED-RESCUE-stm32" description=""/>
<sheetpath names="/" tstamps="/"/>
<tstamp>5909AF9A</tstamp>
</comp>
<comp ref="R6">
<value>330</value>
<footprint>Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder</footprint>
<libsource lib="stm32-rescue" part="R" description=""/>
<sheetpath names="/" tstamps="/"/>
<tstamp>5909AFA0</tstamp>
</comp>
<comp ref="D4">
<value>SS14</value>
<footprint>Diode_SMD:D_SMB_Handsoldering</footprint>
<libsource lib="stm32-rescue" part="D_Schottky" description=""/>
<sheetpath names="/" tstamps="/"/>
<tstamp>5A545B43</tstamp>
</comp>
<comp ref="BT1">
<value>Battery_Cell</value>
<footprint>Battery:BatteryHolder_MPD_BH-18650-PC2</footprint>
<datasheet>~</datasheet>
<libsource lib="Device" part="Battery_Cell" description="Single-cell battery"/>
<sheetpath names="/" tstamps="/"/>
<tstamp>5D7DDF56</tstamp>
</comp>
<comp ref="R8">
<value>4k7</value>
<footprint>Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder</footprint>
<datasheet>~</datasheet>
<libsource lib="Device" part="R" description="Resistor"/>
<sheetpath names="/" tstamps="/"/>
<tstamp>5D850AD1</tstamp>
</comp>
<comp ref="R7">
<value>4k7</value>
<footprint>Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder</footprint>
<datasheet>~</datasheet>
<libsource lib="Device" part="R" description="Resistor"/>
<sheetpath names="/" tstamps="/"/>
<tstamp>5D85121F</tstamp>
</comp>
<comp ref="R9">
<value>22</value>
<footprint>Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder</footprint>
<datasheet>~</datasheet>
<libsource lib="Device" part="R" description="Resistor"/>
<sheetpath names="/" tstamps="/"/>
<tstamp>5D86E056</tstamp>
</comp>
<comp ref="Q1">
<value>AO3407</value>
<footprint>TO_SOT_Packages_SMD:SOT-23_Handsoldering</footprint>
<datasheet>~</datasheet>
<libsource lib="Device" part="Q_PMOS_GSD" description="P-MOSFET transistor, gate/source/drain"/>
<sheetpath names="/" tstamps="/"/>
<tstamp>5D886416</tstamp>
</comp>
<comp ref="R11">
<value>10k</value>
<footprint>Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder</footprint>
<libsource lib="stm32-rescue" part="R" description=""/>
<sheetpath names="/" tstamps="/"/>
<tstamp>5D89C1EC</tstamp>
</comp>
<comp ref="R12">
<value>510</value>
<footprint>Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder</footprint>
<datasheet>~</datasheet>
<libsource lib="Device" part="R" description="Resistor"/>
<sheetpath names="/" tstamps="/"/>
<tstamp>5D89C918</tstamp>
</comp>
<comp ref="SW3">
<value>Poweron</value>
<footprint>Button_Switch_THT:SW_PUSH_6mm_H13mm</footprint>
<libsource lib="Switch" part="SW_Push" description="Push button switch, generic, two pins"/>
<sheetpath names="/" tstamps="/"/>
<tstamp>5D8C5989</tstamp>
</comp>
<comp ref="R4">
<value>51k</value>
<footprint>Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder</footprint>
<libsource lib="stm32-rescue" part="R" description=""/>
<sheetpath names="/" tstamps="/"/>
<tstamp>5D93631F</tstamp>
</comp>
<comp ref="R3">
<value>51k</value>
<footprint>Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder</footprint>
<libsource lib="stm32-rescue" part="R" description=""/>
<sheetpath names="/" tstamps="/"/>
<tstamp>5D936816</tstamp>
</comp>
<comp ref="J4">
<value>SPI_screen</value>
<footprint>Connector_PinSocket_2.54mm:PinSocket_1x07_P2.54mm_Vertical</footprint>
<datasheet>~</datasheet>
<libsource lib="Connector" part="Conn_01x07_Female" description="Generic connector, single row, 01x07, script generated (kicad-library-utils/schlib/autogen/connector/)"/>
<sheetpath names="/" tstamps="/"/>
<tstamp>5D96F1EC</tstamp>
</comp>
<comp ref="C8">
<value>0.1</value>
<footprint>Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder</footprint>
<libsource lib="stm32-rescue" part="C" description=""/>
<sheetpath names="/" tstamps="/"/>
<tstamp>5DA0ADC1</tstamp>
</comp>
</components>
<libparts>
<libpart lib="Connector" part="4P4C">
<aliases>
<alias>RJ9</alias>
<alias>RJ10</alias>
<alias>RJ22</alias>
</aliases>
<description>RJ connector, 4P4C (4 positions 4 connected), RJ9/RJ10/RJ22</description>
<docs>~</docs>
<footprints>
<fp>4P4C*</fp>
<fp>RJ9*</fp>
<fp>RJ10*</fp>
<fp>RJ22*</fp>
</footprints>
<fields>
<field name="Reference">J</field>
<field name="Value">4P4C</field>
</fields>
<pins>
<pin num="1" name="~" type="passive"/>
<pin num="2" name="~" type="passive"/>
<pin num="3" name="~" type="passive"/>
<pin num="4" name="~" type="passive"/>
</pins>
</libpart>
<libpart lib="Connector" part="Conn_01x07_Female">
<description>Generic connector, single row, 01x07, script generated (kicad-library-utils/schlib/autogen/connector/)</description>
<docs>~</docs>
<footprints>
<fp>Connector*:*_1x??_*</fp>
</footprints>
<fields>
<field name="Reference">J</field>
<field name="Value">Conn_01x07_Female</field>
</fields>
<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"/>
<pin num="7" name="Pin_7" type="passive"/>
</pins>
</libpart>
<libpart lib="Connector_Generic" part="Conn_01x02">
<description>Generic connector, single row, 01x02, script generated (kicad-library-utils/schlib/autogen/connector/)</description>
<docs>~</docs>
<footprints>
<fp>Connector*:*_1x??_*</fp>
</footprints>
<fields>
<field name="Reference">J</field>
<field name="Value">Conn_01x02</field>
</fields>
<pins>
<pin num="1" name="Pin_1" type="passive"/>
<pin num="2" name="Pin_2" type="passive"/>
</pins>
</libpart>
<libpart lib="Device" part="Battery_Cell">
<description>Single-cell battery</description>
<docs>~</docs>
<fields>
<field name="Reference">BT</field>
<field name="Value">Battery_Cell</field>
</fields>
<pins>
<pin num="1" name="+" type="passive"/>
<pin num="2" name="-" type="passive"/>
</pins>
</libpart>
<libpart lib="Device" part="D_Schottky">
<description>Schottky diode</description>
<docs>~</docs>
<footprints>
<fp>TO-???*</fp>
<fp>*_Diode_*</fp>
<fp>*SingleDiode*</fp>
<fp>D_*</fp>
</footprints>
<fields>
<field name="Reference">D</field>
<field name="Value">D_Schottky</field>
</fields>
<pins>
<pin num="1" name="K" type="passive"/>
<pin num="2" name="A" type="passive"/>
</pins>
</libpart>
<libpart lib="Device" part="Q_PMOS_GSD">
<description>P-MOSFET transistor, gate/source/drain</description>
<docs>~</docs>
<fields>
<field name="Reference">Q</field>
<field name="Value">Q_PMOS_GSD</field>
</fields>
<pins>
<pin num="1" name="G" type="input"/>
<pin num="2" name="S" type="passive"/>
<pin num="3" name="D" type="passive"/>
</pins>
</libpart>
<libpart lib="Device" part="R">
<description>Resistor</description>
<docs>~</docs>
<footprints>
<fp>R_*</fp>
</footprints>
<fields>
<field name="Reference">R</field>
<field name="Value">R</field>
</fields>
<pins>
<pin num="1" name="~" type="passive"/>
<pin num="2" name="~" type="passive"/>
</pins>
</libpart>
<libpart lib="Power_Protection" part="USBLC6-2SC6">
<description>Bidirectional ESD Protection Diode, SOT-23-6</description>
<docs>http://www2.st.com/resource/en/datasheet/CD00050750.pdf</docs>
<footprints>
<fp>SOT?23*</fp>
</footprints>
<fields>
<field name="Reference">U</field>
<field name="Value">USBLC6-2SC6</field>
<field name="Footprint">Package_TO_SOT_SMD:SOT-23-6</field>
</fields>
<pins>
<pin num="1" name="IO1" type="passive"/>
<pin num="2" name="GND" type="passive"/>
<pin num="3" name="IO2" type="passive"/>
<pin num="4" name="IO2" type="passive"/>
<pin num="5" name="VBUS" type="passive"/>
<pin num="6" name="IO1" type="passive"/>
</pins>
</libpart>
<libpart lib="Switch" part="SW_Push">
<description>Push button switch, generic, two pins</description>
<docs>~</docs>
<fields>
<field name="Reference">SW</field>
<field name="Value">SW_Push</field>
</fields>
<pins>
<pin num="1" name="1" type="passive"/>
<pin num="2" name="2" type="passive"/>
</pins>
</libpart>
<libpart lib="stm32-rescue" part="C">
<footprints>
<fp>C_*</fp>
</footprints>
<fields>
<field name="Reference">C</field>
<field name="Value">C</field>
</fields>
<pins>
<pin num="1" name="~" type="passive"/>
<pin num="2" name="~" type="passive"/>
</pins>
</libpart>
<libpart lib="stm32-rescue" part="CONN_01X01">
<footprints>
<fp>Pin_Header_Straight_1X*</fp>
<fp>Pin_Header_Angled_1X*</fp>
<fp>Socket_Strip_Straight_1X*</fp>
<fp>Socket_Strip_Angled_1X*</fp>
</footprints>
<fields>
<field name="Reference">J</field>
<field name="Value">CONN_01X01</field>
</fields>
<pins>
<pin num="1" name="P1" type="passive"/>
</pins>
</libpart>
<libpart lib="stm32-rescue" part="CONN_01X03">
<footprints>
<fp>Pin_Header_Straight_1X*</fp>
<fp>Pin_Header_Angled_1X*</fp>
<fp>Socket_Strip_Straight_1X*</fp>
<fp>Socket_Strip_Angled_1X*</fp>
</footprints>
<fields>
<field name="Reference">J</field>
<field name="Value">CONN_01X03</field>
</fields>
<pins>
<pin num="1" name="P1" type="passive"/>
<pin num="2" name="P2" type="passive"/>
<pin num="3" name="P3" type="passive"/>
</pins>
</libpart>
<libpart lib="stm32-rescue" part="CP">
<footprints>
<fp>CP_*</fp>
</footprints>
<fields>
<field name="Reference">C</field>
<field name="Value">CP</field>
</fields>
<pins>
<pin num="1" name="~" type="passive"/>
<pin num="2" name="~" type="passive"/>
</pins>
</libpart>
<libpart lib="stm32-rescue" part="D_Schottky">
<footprints>
<fp>TO-???*</fp>
<fp>*SingleDiode</fp>
<fp>*_Diode_*</fp>
<fp>*SingleDiode*</fp>
<fp>D_*</fp>
</footprints>
<fields>
<field name="Reference">D</field>
<field name="Value">D_Schottky</field>
</fields>
<pins>
<pin num="1" name="K" type="passive"/>
<pin num="2" name="A" type="passive"/>
</pins>
</libpart>
<libpart lib="stm32-rescue" part="LED-RESCUE-stm32">
<footprints>
<fp>LED*</fp>
</footprints>
<fields>
<field name="Reference">D</field>
<field name="Value">LED-RESCUE-stm32</field>
</fields>
<pins>
<pin num="1" name="K" type="passive"/>
<pin num="2" name="A" type="passive"/>
</pins>
</libpart>
<libpart lib="stm32-rescue" part="LM1117-3.3-RESCUE-stm32">
<footprints>
<fp>SOT-223*</fp>
<fp>TO-263*</fp>
<fp>TO-252*</fp>
</footprints>
<fields>
<field name="Reference">U</field>
<field name="Value">LM1117-3.3-RESCUE-stm32</field>
</fields>
<pins>
<pin num="1" name="GND/ADJ" type="power_in"/>
<pin num="2" name="VO" type="passive"/>
<pin num="3" name="VI" type="power_in"/>
<pin num="4" name="VO" type="power_out"/>
</pins>
</libpart>
<libpart lib="stm32-rescue" part="R">
<footprints>
<fp>R_*</fp>
<fp>R_*</fp>
</footprints>
<fields>
<field name="Reference">R</field>
<field name="Value">R</field>
</fields>
<pins>
<pin num="1" name="~" type="passive"/>
<pin num="2" name="~" type="passive"/>
</pins>
</libpart>
<libpart lib="stm32-rescue" part="STM32F042C6Tx">
<fields>
<field name="Reference">U</field>
<field name="Value">STM32F042C6Tx</field>
<field name="Footprint">LQFP48</field>
</fields>
<pins>
<pin num="1" name="VBAT" type="power_in"/>
<pin num="2" name="PC13/RTC_OUT_ALARM/RTC_OUT_CALIB/RTC_TAMP1/RTC_TS/SYS_WKUP2" type="BiDi"/>
<pin num="3" name="PC14/RCC_OSC32_IN" type="BiDi"/>
<pin num="4" name="PC15/RCC_OSC32_OUT" type="BiDi"/>
<pin num="5" name="PF0/CRS_SYNC/I2C1_SDA/RCC_OSC_IN" type="input"/>
<pin num="6" name="PF1/I2C1_SCL/RCC_OSC_OUT" type="input"/>
<pin num="7" name="NRST" type="input"/>
<pin num="8" name="VSSA" type="power_in"/>
<pin num="9" name="VDDA" type="power_in"/>
<pin num="10" name="ADC_IN0/RTC_TAMP2/SYS_WKUP1/TIM2_CH1/TIM2_ETR/TSC_G1_IO1/USART2_CTS/PA0" type="BiDi"/>
<pin num="11" name="ADC_IN1/TIM2_CH2/TSC_G1_IO2/USART2_DE/USART2_RTS/PA1" type="BiDi"/>
<pin num="12" name="ADC_IN2/SYS_WKUP4/TIM2_CH3/TSC_G1_IO3/USART2_TX/PA2" type="BiDi"/>
<pin num="13" name="ADC_IN3/TIM2_CH4/TSC_G1_IO4/USART2_RX/PA3" type="BiDi"/>
<pin num="14" name="ADC_IN4/I2S1_WS/SPI1_NSS/TIM14_CH1/TSC_G2_IO1/USART2_CK/USB_OE/PA4" type="BiDi"/>
<pin num="15" name="ADC_IN5/CEC/I2S1_CK/SPI1_SCK/TIM2_CH1/TIM2_ETR/TSC_G2_IO2/PA5" type="BiDi"/>
<pin num="16" name="ADC_IN6/I2S1_MCK/SPI1_MISO/TIM16_CH1/TIM1_BKIN/TIM3_CH1/TSC_G2_IO3/PA6" type="BiDi"/>
<pin num="17" name="ADC_IN7/I2S1_SD/SPI1_MOSI/TIM14_CH1/TIM17_CH1/TIM1_CH1N/TIM3_CH2/TSC_G2_IO4/PA7" type="BiDi"/>
<pin num="18" name="PB0/ADC_IN8/TIM1_CH2N/TIM3_CH3/TSC_G3_IO2" type="BiDi"/>
<pin num="19" name="PB1/ADC_IN9/TIM14_CH1/TIM1_CH3N/TIM3_CH4/TSC_G3_IO3" type="BiDi"/>
<pin num="20" name="PB2/TSC_G3_IO4" type="BiDi"/>
<pin num="21" name="PB10/CEC/I2C1_SCL/SPI2_SCK/TIM2_CH3/TSC_SYNC" type="BiDi"/>
<pin num="22" name="PB11/I2C1_SDA/TIM2_CH4" type="BiDi"/>
<pin num="23" name="VSS" type="power_in"/>
<pin num="24" name="VDD" type="power_in"/>
<pin num="25" name="PB12/SPI2_NSS/TIM1_BKIN" type="BiDi"/>
<pin num="26" name="PB13/I2C1_SCL/SPI2_SCK/TIM1_CH1N" type="BiDi"/>
<pin num="27" name="PB14/I2C1_SDA/SPI2_MISO/TIM1_CH2N" type="BiDi"/>
<pin num="28" name="PB15/RTC_REFIN/SPI2_MOSI/SYS_WKUP7/TIM1_CH3N" type="BiDi"/>
<pin num="29" name="CRS_SYNC/RCC_MCO/TIM1_CH1/USART1_CK/PA8" type="BiDi"/>
<pin num="30" name="I2C1_SCL/TIM1_CH2/TSC_G4_IO1/USART1_TX/PA9" type="BiDi"/>
<pin num="31" name="I2C1_SDA/TIM17_BKIN/TIM1_CH3/TSC_G4_IO2/USART1_RX/PA10" type="BiDi"/>
<pin num="32" name="CAN_RX/I2C1_SCL/TIM1_CH4/TSC_G4_IO3/USART1_CTS/USB_DM/PA11" type="BiDi"/>
<pin num="33" name="CAN_TX/I2C1_SDA/TIM1_ETR/TSC_G4_IO4/USART1_DE/USART1_RTS/USB_DP/PA12" type="BiDi"/>
<pin num="34" name="IR_OUT/SYS_SWDIO/USB_OE/PA13" type="BiDi"/>
<pin num="35" name="VSS" type="power_in"/>
<pin num="36" name="VDDIO2" type="power_in"/>
<pin num="37" name="SYS_SWCLK/USART2_TX/PA14" type="BiDi"/>
<pin num="38" name="I2S1_WS/SPI1_NSS/TIM2_CH1/TIM2_ETR/USART2_RX/USB_OE/PA15" type="BiDi"/>
<pin num="39" name="PB3/I2S1_CK/SPI1_SCK/TIM2_CH2/TSC_G5_IO1" type="BiDi"/>
<pin num="40" name="PB4/I2S1_MCK/SPI1_MISO/TIM17_BKIN/TIM3_CH1/TSC_G5_IO2" type="BiDi"/>
<pin num="41" name="PB5/I2C1_SMBA/I2S1_SD/SPI1_MOSI/SYS_WKUP6/TIM16_BKIN/TIM3_CH2" type="BiDi"/>
<pin num="42" name="PB6/I2C1_SCL/TIM16_CH1N/TSC_G5_IO3/USART1_TX" type="BiDi"/>
<pin num="43" name="PB7/I2C1_SDA/TIM17_CH1N/TSC_G5_IO4/USART1_RX" type="BiDi"/>
<pin num="44" name="PF11" type="BiDi"/>
<pin num="45" name="PB8/CAN_RX/CEC/I2C1_SCL/TIM16_CH1/TSC_SYNC" type="BiDi"/>
<pin num="46" name="PB9/CAN_TX/I2C1_SDA/IR_OUT/SPI2_NSS/TIM17_CH1" type="BiDi"/>
<pin num="47" name="VSS" type="power_in"/>
<pin num="48" name="VDD" type="power_in"/>
</pins>
</libpart>
<libpart lib="stm32-rescue" part="USB_A-RESCUE-stm32">
<footprints>
<fp>USB*</fp>
</footprints>
<fields>
<field name="Reference">P</field>
<field name="Value">USB_A-RESCUE-stm32</field>
</fields>
<pins>
<pin num="1" name="VBUS" type="power_in"/>
<pin num="2" name="D-" type="passive"/>
<pin num="3" name="D+" type="passive"/>
<pin num="4" name="GND" type="power_in"/>
<pin num="5" name="shield" type="passive"/>
</pins>
</libpart>
</libparts>
<libraries>
<library logical="Connector">
<uri>/usr/share/kicad/kicad-symbols//Connector.lib</uri>
</library>
<library logical="Connector_Generic">
<uri>/usr/share/kicad/kicad-symbols//Connector_Generic.lib</uri>
</library>
<library logical="Device">
<uri>/usr/share/kicad/kicad-symbols//Device.lib</uri>
</library>
<library logical="Power_Protection">
<uri>/usr/share/kicad/kicad-symbols//Power_Protection.lib</uri>
</library>
<library logical="Switch">
<uri>/usr/share/kicad/kicad-symbols//Switch.lib</uri>
</library>
<library logical="stm32-rescue">
<uri>/home/eddy/Docs/SAO/ELECTRONICS/STM32/F1-srcs/chronometer/kicad/chrono/stm32-rescue.lib</uri>
</library>
</libraries>
<nets>
<net code="1" name="Net-(D1-Pad2)">
<node ref="R5" pin="1"/>
<node ref="D1" pin="2"/>
</net>
<net code="2" name="+3V3">
<node ref="C6" pin="2"/>
<node ref="U2" pin="36"/>
<node ref="U2" pin="24"/>
<node ref="U3" pin="4"/>
<node ref="J4" pin="2"/>
<node ref="R9" pin="1"/>
<node ref="U3" pin="2"/>
<node ref="SW2" pin="2"/>
<node ref="C2" pin="2"/>
<node ref="C7" pin="1"/>
<node ref="R5" pin="2"/>
<node ref="C4" pin="2"/>
<node ref="C5" pin="2"/>
<node ref="R6" pin="2"/>
<node ref="U2" pin="9"/>
<node ref="U2" pin="48"/>
<node ref="C3" pin="2"/>
</net>
<net code="3" name="Net-(D2-Pad2)">
<node ref="R6" pin="1"/>
<node ref="D2" pin="2"/>
</net>
<net code="4" name="/LED1">
<node ref="D2" pin="1"/>
<node ref="U2" pin="38"/>
</net>
<net code="5" name="/LED0">
<node ref="U2" pin="37"/>
<node ref="D1" pin="1"/>
</net>
<net code="6" name="Net-(U2-Pad16)">
<node ref="U2" pin="16"/>
</net>
<net code="7" name="/SCL">
<node ref="U2" pin="42"/>
<node ref="J3" pin="2"/>
<node ref="J1" pin="2"/>
<node ref="R8" pin="2"/>
</net>
<net code="8" name="/SDA">
<node ref="J1" pin="1"/>
<node ref="U2" pin="43"/>
<node ref="J2" pin="1"/>
<node ref="R7" pin="2"/>
</net>
<net code="9" name="Net-(U2-Pad13)">
<node ref="U2" pin="13"/>
</net>
<net code="10" name="Net-(U2-Pad39)">
<node ref="U2" pin="39"/>
</net>
<net code="11" name="Net-(U2-Pad46)">
<node ref="U2" pin="46"/>
</net>
<net code="12" name="Net-(U2-Pad28)">
<node ref="U2" pin="28"/>
</net>
<net code="13" name="GND">
<node ref="R4" pin="1"/>
<node ref="J1" pin="4"/>
<node ref="U1" pin="2"/>
<node ref="BT1" pin="2"/>
<node ref="U2" pin="35"/>
<node ref="P2" pin="1"/>
<node ref="C6" pin="1"/>
<node ref="J4" pin="1"/>
<node ref="J3" pin="1"/>
<node ref="C8" pin="2"/>
<node ref="C5" pin="1"/>
<node ref="C4" pin="1"/>
<node ref="U2" pin="47"/>
<node ref="SW1" pin="2"/>
<node ref="U3" pin="1"/>
<node ref="C3" pin="1"/>
<node ref="U2" pin="8"/>
<node ref="C1" pin="2"/>
<node ref="R10" pin="2"/>
<node ref="U2" pin="23"/>
<node ref="C7" pin="2"/>
<node ref="P1" pin="4"/>
<node ref="P1" pin="5"/>
</net>
<net code="14" name="Net-(BT1-Pad1)">
<node ref="R11" pin="1"/>
<node ref="D4" pin="1"/>
<node ref="SW3" pin="1"/>
<node ref="BT1" pin="1"/>
<node ref="Q1" pin="2"/>
</net>
<net code="15" name="/USBDM">
<node ref="U2" pin="32"/>
<node ref="R2" pin="2"/>
</net>
<net code="16" name="/USBDP">
<node ref="R1" pin="2"/>
<node ref="U2" pin="33"/>
</net>
<net code="17" name="Net-(U2-Pad29)">
<node ref="U2" pin="29"/>
</net>
<net code="18" name="Net-(U2-Pad34)">
<node ref="U2" pin="34"/>
</net>
<net code="19" name="Net-(U2-Pad12)">
<node ref="U2" pin="12"/>
</net>
<net code="20" name="Net-(P2-Pad3)">
<node ref="P2" pin="3"/>
<node ref="U2" pin="30"/>
</net>
<net code="21" name="/D-C">
<node ref="U2" pin="19"/>
<node ref="J4" pin="6"/>
</net>
<net code="22" name="/RST">
<node ref="U2" pin="18"/>
<node ref="J4" pin="5"/>
</net>
<net code="23" name="/MOSI">
<node ref="U2" pin="17"/>
<node ref="J4" pin="4"/>
</net>
<net code="24" name="/SCK">
<node ref="U2" pin="15"/>
<node ref="J4" pin="3"/>
</net>
<net code="25" name="Net-(U2-Pad26)">
<node ref="U2" pin="26"/>
</net>
<net code="26" name="Net-(U2-Pad10)">
<node ref="U2" pin="10"/>
</net>
<net code="27" name="Net-(U2-Pad25)">
<node ref="U2" pin="25"/>
</net>
<net code="28" name="Net-(U2-Pad22)">
<node ref="U2" pin="22"/>
</net>
<net code="29" name="Net-(U2-Pad21)">
<node ref="U2" pin="21"/>
</net>
<net code="30" name="Net-(U2-Pad14)">
<node ref="U2" pin="14"/>
</net>
<net code="31" name="Net-(U2-Pad41)">
<node ref="U2" pin="41"/>
</net>
<net code="32" name="Net-(U2-Pad40)">
<node ref="U2" pin="40"/>
</net>
<net code="33" name="Net-(U2-Pad45)">
<node ref="U2" pin="45"/>
</net>
<net code="34" name="Net-(Q1-Pad1)">
<node ref="R12" pin="1"/>
<node ref="Q1" pin="1"/>
</net>
<net code="35" name="/5Vusb">
<node ref="D4" pin="2"/>
<node ref="D3" pin="1"/>
<node ref="Q1" pin="3"/>
<node ref="SW3" pin="2"/>
<node ref="C8" pin="1"/>
<node ref="U3" pin="3"/>
</net>
<net code="36" name="Net-(P2-Pad2)">
<node ref="P2" pin="2"/>
<node ref="U2" pin="31"/>
</net>
<net code="37" name="Net-(P1-Pad2)">
<node ref="P1" pin="2"/>
<node ref="U1" pin="4"/>
</net>
<net code="38" name="/U5V">
<node ref="D3" pin="2"/>
<node ref="U1" pin="5"/>
<node ref="R3" pin="2"/>
<node ref="P1" pin="1"/>
</net>
<net code="39" name="Net-(R2-Pad1)">
<node ref="R2" pin="1"/>
<node ref="U1" pin="3"/>
</net>
<net code="40" name="Net-(R1-Pad1)">
<node ref="U1" pin="1"/>
<node ref="R1" pin="1"/>
</net>
<net code="41" name="Net-(P1-Pad3)">
<node ref="U1" pin="6"/>
<node ref="P1" pin="3"/>
</net>
<net code="42" name="/CS">
<node ref="J4" pin="7"/>
<node ref="U2" pin="20"/>
</net>
<net code="43" name="/POWERON">
<node ref="U2" pin="2"/>
<node ref="R12" pin="2"/>
<node ref="R11" pin="2"/>
</net>
<net code="44" name="/USBON">
<node ref="U2" pin="11"/>
<node ref="R3" pin="1"/>
<node ref="R4" pin="2"/>
</net>
<net code="45" name="Net-(U2-Pad1)">
<node ref="U2" pin="1"/>
</net>
<net code="46" name="/3V3Sensors">
<node ref="R8" pin="1"/>
<node ref="R7" pin="1"/>
<node ref="R9" pin="2"/>
<node ref="J2" pin="2"/>
<node ref="J1" pin="3"/>
</net>
<net code="47" name="/BOOT0">
<node ref="R10" pin="1"/>
<node ref="U2" pin="44"/>
<node ref="SW2" pin="1"/>
<node ref="C2" pin="1"/>
</net>
<net code="48" name="Net-(P3-Pad1)">
<node ref="P3" pin="1"/>
</net>
<net code="49" name="Net-(P6-Pad1)">
<node ref="P6" pin="1"/>
</net>
<net code="50" name="Net-(P5-Pad1)">
<node ref="P5" pin="1"/>
</net>
<net code="51" name="Net-(P4-Pad1)">
<node ref="P4" pin="1"/>
</net>
<net code="52" name="Net-(U2-Pad5)">
<node ref="U2" pin="5"/>
</net>
<net code="53" name="Net-(U2-Pad6)">
<node ref="U2" pin="6"/>
</net>
<net code="54" name="Net-(U2-Pad3)">
<node ref="U2" pin="3"/>
</net>
<net code="55" name="Net-(U2-Pad4)">
<node ref="U2" pin="4"/>
</net>
<net code="56" name="Net-(U2-Pad27)">
<node ref="U2" pin="27"/>
</net>
<net code="57" name="/NRST">
<node ref="U2" pin="7"/>
<node ref="C1" pin="1"/>
<node ref="SW1" pin="1"/>
</net>
</nets>
</export>

View File

@ -0,0 +1,3 @@
(sym_lib_table
(lib (name stm32f042-rescue)(type Legacy)(uri ${KIPRJMOD}/stm32f042-rescue.lib)(options "")(descr ""))
)