check in usb-interface firmware and hardware files

usb-interface
informatic 2020-06-21 23:45:36 +02:00
parent 494f5ef2bc
commit 1cf9ce4211
27 changed files with 78945 additions and 0 deletions

4
.gitignore vendored
View File

@ -2,3 +2,7 @@
*.cfg
*.db
*.sqlite3
**/*-bork
cython-tests/*
.ropeproject
cygpio/*

6
.gitmodules vendored Normal file
View File

@ -0,0 +1,6 @@
[submodule "usb-interface/firmware/libopencm3"]
path = usb-interface/firmware/libopencm3
url = https://github.com/libopencm3/libopencm3
[submodule "usb-interface/hardware/Kicad-STM32"]
path = usb-interface/hardware/Kicad-STM32
url = https://github.com/yet-another-average-joe/Kicad-STM32

4
usb-interface/firmware/.gitignore vendored Normal file
View File

@ -0,0 +1,4 @@
*.d
*.o
*.elf
*.map

View File

@ -0,0 +1,42 @@
##
## This file is part of the libopencm3 project.
##
## Copyright (C) 2009 Uwe Hermann <uwe@hermann-uwe.de>
##
## This library is free software: you can redistribute it and/or modify
## it under the terms of the GNU Lesser General Public License as published by
## the Free Software Foundation, either version 3 of the License, or
## (at your option) any later version.
##
## This library 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 Lesser General Public License for more details.
##
## You should have received a copy of the GNU Lesser General Public License
## along with this library. If not, see <http://www.gnu.org/licenses/>.
##
BINARY = main
OBJS += fifo.o iobuffers.o usb.o stdio.o
CFLAGS += -DSTDIO_USB
LDSCRIPT = stm32-h103.ld
OOCD_TARGET = stm32f1x
LIBNAME = opencm3_stm32f1
DEFS += -DSTM32F1
FP_FLAGS ?= -msoft-float
ARCH_FLAGS = -mthumb -mcpu=cortex-m3 $(FP_FLAGS) -mfix-cortex-m3-ldrd
################################################################################
# OpenOCD specific variables
OOCD ?= openocd
OOCD_TARGET ?= stm32f1x
OOCD_INTERFACE ?= stlink-v2
include libopencm3.rules.mk
cleanall: clean

View File

@ -0,0 +1,50 @@
/* Copyright (c) 2016, Jan Wiśniewski <vuko@hackerspace.pl>
*
* This software is provided 'as-is', without any express or implied
* warranty. In no event will the authors be held liable for any damages
* arising from the use of this software.
*
* Permission is granted to anyone to use this software for any purpose,
* including commercial applications, and to alter it and redistribute it
* freely, subject to the following restrictions:
*
* 1. The origin of this software must not be misrepresented; you must not
* claim that you wrote the original software. If you use this software
* in a product, an acknowledgment in the product documentation would be
* appreciated but is not required.
* 2. Altered source versions must be plainly marked as such, and must not be
* misrepresented as being the original software.
*/
#include"fifo.h"
void fifoInit(fifo *f, uint8_t *addr, uint16_t size){
f->first = 0;
f->last = 0;
f->size = size;
f->data = addr;
};
inline uint8_t fifoEmpty(fifo *f){
return f->first == f->last;
}
inline uint8_t fifoFull(fifo *f){
return f->first == (f->last+1)%f->size;
}
void fifoPush(fifo *f, uint8_t d){
if(!fifoFull(f)){
f->data[f->last] = d;
f->last = (f->last + 1)%f->size;
}
}
uint8_t fifoPop(fifo *f){
uint16_t first = f->first;
if(!fifoEmpty(f)){
f->first = (f->first + 1)%f->size;
return f->data[first];
} else {
return 0x00;
}
}

View File

@ -0,0 +1,37 @@
/* Copyright (c) 2016, Jan Wiśniewski <vuko@hackerspace.pl>
*
* This software is provided 'as-is', without any express or implied
* warranty. In no event will the authors be held liable for any damages
* arising from the use of this software.
*
* Permission is granted to anyone to use this software for any purpose,
* including commercial applications, and to alter it and redistribute it
* freely, subject to the following restrictions:
*
* 1. The origin of this software must not be misrepresented; you must not
* claim that you wrote the original software. If you use this software
* in a product, an acknowledgment in the product documentation would be
* appreciated but is not required.
* 2. Altered source versions must be plainly marked as such, and must not be
* misrepresented as being the original software.
*/
#ifndef MFIFO_H
#define MFIFO_H
#include<stdint.h>
#include<stdio.h>
typedef struct fifo {
uint16_t first;
uint16_t last;
uint8_t *data;
uint16_t size;
} fifo;
void fifoInit(fifo*,uint8_t*,uint16_t);
uint8_t fifoEmpty(fifo*);
uint8_t fifoFull(fifo*);
void fifoPush(fifo*,uint8_t);
uint8_t fifoPop(fifo*);
#endif

View File

@ -0,0 +1,109 @@
/* Copyright (c) 2016, vuko@hackerspace.pl
*
* This software is provided 'as-is', without any express or implied
* warranty. In no event will the authors be held liable for any damages
* arising from the use of this software.
*
* Permission is granted to anyone to use this software for any purpose,
* including commercial applications, and to alter it and redistribute it
* freely, subject to the following restrictions:
*
* 1. The origin of this software must not be misrepresented; you must not
* claim that you wrote the original software. If you use this software
* in a product, an acknowledgment in the product documentation would be
* appreciated but is not required.
* 2. Altered source versions must be plainly marked as such, and must not be
* misrepresented as being the original software.
*/
#include"iobuffers.h"
#include <libopencm3/cm3/nvic.h>
#include<libopencmsis/core_cm3.h>
#include <libopencm3/stm32/usart.h>
#include <libopencm3/usb/usbd.h>
#include "usb.h"
int _write(int file, char *ptr, int len){
(void)file;
int no = 0;
__disable_irq();
while(no<len && !fifoFull(&tx_fifo)){
fifoPush(&tx_fifo, ptr[no]);
++no;
}
#ifdef STDIO_UART
USART_CR1(USART1) |= USART_CR1_TXEIE;
__enable_irq();
#endif
#ifdef STDIO_USB
if(usb_tx_in_progress == 0){
usb_tx_in_progress = 1;
__enable_irq();
cdcacm_data_tx_cb(usbd_dev,0x82);
}
else
__enable_irq();
#endif
return no;
}
int _write_block(int file, char *ptr, int len){
(void)file;
int no = 0;
__disable_irq();
while(no<len){
while(fifoFull(&tx_fifo)){
__WFI();
__enable_irq();
__asm("nop"); // TODO remove
__disable_irq();
}
fifoPush(&tx_fifo, ptr[no]);
++no;
}
#ifdef STDIO_UART
USART_CR1(USART1) |= USART_CR1_TXEIE;
__enable_irq();
return no;
#endif
#ifdef STDIO_USB
if(usb_tx_in_progress == 0){
usb_tx_in_progress = 1;
__enable_irq();
cdcacm_data_tx_cb(usbd_dev,0x82);
}
else
__enable_irq();
return no;
#endif
}
int _read(int file, char *ptr, int len){
(void)file;
int no = 0;
__disable_irq();
while(no<len && !fifoEmpty(&rx_fifo)){
ptr[no] = fifoPop(&rx_fifo);
++no;
}
__enable_irq();
return no;
}
int _read_block(int file, char *ptr, int len){
(void)file;
int no = 0;
__disable_irq();
while(no<len){
while(fifoEmpty(&rx_fifo)){
__WFI();
__enable_irq();
__asm("nop");
__disable_irq();
}
ptr[no] = fifoPop(&rx_fifo);
++no;
}
__enable_irq();
return no;
}

View File

@ -0,0 +1,29 @@
/* Copyright (c) 2016, vuko@hackerspace.pl
*
* This software is provided 'as-is', without any express or implied
* warranty. In no event will the authors be held liable for any damages
* arising from the use of this software.
*
* Permission is granted to anyone to use this software for any purpose,
* including commercial applications, and to alter it and redistribute it
* freely, subject to the following restrictions:
*
* 1. The origin of this software must not be misrepresented; you must not
* claim that you wrote the original software. If you use this software
* in a product, an acknowledgment in the product documentation would be
* appreciated but is not required.
* 2. Altered source versions must be plainly marked as such, and must not be
* misrepresented as being the original software.
*/
#ifndef IOBUFFERS_H
#define IOBUFFERS_H
#include"fifo.h"
extern fifo tx_fifo;
extern fifo rx_fifo;
int _write(int, char*, int);
int _read(int, char*, int);
int _write_block(int, char*, int);
int _read_block(int, char*, int);
#endif

@ -0,0 +1 @@
Subproject commit 755ce402e2366a1b27b07de4de794ca0ac3bc8b2

View File

@ -0,0 +1,268 @@
##
## This file is part of the libopencm3 project.
##
## Copyright (C) 2009 Uwe Hermann <uwe@hermann-uwe.de>
## Copyright (C) 2010 Piotr Esden-Tempski <piotr@esden.net>
## Copyright (C) 2013 Frantisek Burian <BuFran@seznam.cz>
##
## This library is free software: you can redistribute it and/or modify
## it under the terms of the GNU Lesser General Public License as published by
## the Free Software Foundation, either version 3 of the License, or
## (at your option) any later version.
##
## This library 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 Lesser General Public License for more details.
##
## You should have received a copy of the GNU Lesser General Public License
## along with this library. If not, see <http://www.gnu.org/licenses/>.
##
# Be silent per default, but 'make V=1' will show all compiler calls.
ifneq ($(V),1)
Q := @
NULL := 2>/dev/null
endif
###############################################################################
# Executables
PREFIX ?= arm-none-eabi
CC := $(PREFIX)-gcc
CXX := $(PREFIX)-g++
LD := $(PREFIX)-gcc
AR := $(PREFIX)-ar
AS := $(PREFIX)-as
OBJCOPY := $(PREFIX)-objcopy
OBJDUMP := $(PREFIX)-objdump
GDB := $(PREFIX)-gdb
STFLASH = $(shell which st-flash)
STYLECHECK := /checkpatch.pl
STYLECHECKFLAGS := --no-tree -f --terse --mailback
STYLECHECKFILES := $(shell find . -name '*.[ch]')
OPT := -Os
CSTD ?= -std=c99
###############################################################################
# Source files
OBJS += $(BINARY).o
ifeq ($(strip $(OPENCM3_DIR)),)
# user has not specified the library path, so we try to detect it
# where we search for the library
LIBPATHS := ./libopencm3 ../../../../libopencm3 ../../../../../libopencm3
OPENCM3_DIR := $(wildcard $(LIBPATHS:=/locm3.sublime-project))
OPENCM3_DIR := $(firstword $(dir $(OPENCM3_DIR)))
ifeq ($(strip $(OPENCM3_DIR)),)
$(warning Cannot find libopencm3 library in the standard search paths.)
$(error Please specify it through OPENCM3_DIR variable!)
endif
endif
ifeq ($(V),1)
$(info Using $(OPENCM3_DIR) path to library)
endif
define ERR_DEVICE_LDSCRIPT_CONFLICT
You can either specify DEVICE=blah, and have the LDSCRIPT generated,
or you can provide LDSCRIPT, and ensure CPPFLAGS, LDFLAGS and LDLIBS
all contain the correct values for the target you wish to use.
You cannot provide both!
endef
ifeq ($(strip $(DEVICE)),)
# Old style, assume LDSCRIPT exists
DEFS += -I$(OPENCM3_DIR)/include
LDFLAGS += -L$(OPENCM3_DIR)/lib
LDLIBS += -l$(LIBNAME)
LDSCRIPT ?= $(BINARY).ld
else
# New style, assume device is provided, and we're generating the rest.
ifneq ($(strip $(LDSCRIPT)),)
$(error $(ERR_DEVICE_LDSCRIPT_CONFLICT))
endif
include $(OPENCM3_DIR)/mk/genlink-config.mk
endif
SCRIPT_DIR = $(OPENCM3_DIR)/scripts
###############################################################################
# C flags
TGT_CFLAGS += $(OPT) $(CSTD) -g
TGT_CFLAGS += $(ARCH_FLAGS)
TGT_CFLAGS += -Wextra -Wshadow -Wimplicit-function-declaration
TGT_CFLAGS += -Wredundant-decls -Wmissing-prototypes -Wstrict-prototypes
TGT_CFLAGS += -fno-common -ffunction-sections -fdata-sections
###############################################################################
# C++ flags
TGT_CXXFLAGS += $(OPT) $(CXXSTD) -g
TGT_CXXFLAGS += $(ARCH_FLAGS)
TGT_CXXFLAGS += -Wextra -Wshadow -Wredundant-decls -Weffc++
TGT_CXXFLAGS += -fno-common -ffunction-sections -fdata-sections
###############################################################################
# C & C++ preprocessor common flags
TGT_CPPFLAGS += -MD
TGT_CPPFLAGS += -Wall -Wundef
TGT_CPPFLAGS += $(DEFS)
###############################################################################
# Linker flags
TGT_LDFLAGS += --static -nostartfiles
TGT_LDFLAGS += -T$(LDSCRIPT)
TGT_LDFLAGS += $(ARCH_FLAGS)
TGT_LDFLAGS += -Wl,-Map=$(*).map
TGT_LDFLAGS += -Wl,--gc-sections
ifeq ($(V),99)
TGT_LDFLAGS += -Wl,--print-gc-sections
endif
###############################################################################
# Used libraries
LDLIBS += -Wl,--start-group -lc -lgcc -lnosys -Wl,--end-group
###############################################################################
###############################################################################
###############################################################################
.SUFFIXES: .elf .bin .hex .srec .list .map .images
.SECONDEXPANSION:
.SECONDARY:
all: elf
elf: $(BINARY).elf
bin: $(BINARY).bin
hex: $(BINARY).hex
srec: $(BINARY).srec
list: $(BINARY).list
images: $(BINARY).images
flash: $(BINARY).flash
# Either verify the user provided LDSCRIPT exists, or generate it.
ifeq ($(strip $(DEVICE)),)
$(LDSCRIPT):
ifeq (,$(wildcard $(LDSCRIPT)))
$(error Unable to find specified linker script: $(LDSCRIPT))
endif
else
include $(OPENCM3_DIR)/mk/genlink-rules.mk
endif
# Define a helper macro for debugging make errors online
# you can type "make print-OPENCM3_DIR" and it will show you
# how that ended up being resolved by all of the included
# makefiles.
print-%:
@echo $*=$($*)
%.images: %.bin %.hex %.srec %.list %.map
@#printf "*** $* images generated ***\n"
%.bin: %.elf
@#printf " OBJCOPY $(*).bin\n"
$(Q)$(OBJCOPY) -Obinary $(*).elf $(*).bin
%.hex: %.elf
@#printf " OBJCOPY $(*).hex\n"
$(Q)$(OBJCOPY) -Oihex $(*).elf $(*).hex
%.srec: %.elf
@#printf " OBJCOPY $(*).srec\n"
$(Q)$(OBJCOPY) -Osrec $(*).elf $(*).srec
%.list: %.elf
@#printf " OBJDUMP $(*).list\n"
$(Q)$(OBJDUMP) -S $(*).elf > $(*).list
%.elf %.map: $(OBJS) $(LDSCRIPT)
@#printf " LD $(*).elf\n"
$(Q)$(LD) $(TGT_LDFLAGS) $(LDFLAGS) $(OBJS) $(LDLIBS) -o $(*).elf
%.o: %.c
@#printf " CC $(*).c\n"
$(Q)$(CC) $(TGT_CFLAGS) $(CFLAGS) $(TGT_CPPFLAGS) $(CPPFLAGS) -o $(*).o -c $(*).c
%.o: %.cxx
@#printf " CXX $(*).cxx\n"
$(Q)$(CXX) $(TGT_CXXFLAGS) $(CXXFLAGS) $(TGT_CPPFLAGS) $(CPPFLAGS) -o $(*).o -c $(*).cxx
%.o: %.cpp
@#printf " CXX $(*).cpp\n"
$(Q)$(CXX) $(TGT_CXXFLAGS) $(CXXFLAGS) $(TGT_CPPFLAGS) $(CPPFLAGS) -o $(*).o -c $(*).cpp
clean:
@#printf " CLEAN\n"
$(Q)$(RM) *.o *.d *.elf *.bin *.hex *.srec *.list *.map generated.* ${OBJS} ${OBJS:%.o:%.d}
stylecheck: $(STYLECHECKFILES:=.stylecheck)
styleclean: $(STYLECHECKFILES:=.styleclean)
# the cat is due to multithreaded nature - we like to have consistent chunks of text on the output
%.stylecheck: %
$(Q)$(SCRIPT_DIR)$(STYLECHECK) $(STYLECHECKFLAGS) $* > $*.stylecheck; \
if [ -s $*.stylecheck ]; then \
cat $*.stylecheck; \
else \
rm -f $*.stylecheck; \
fi;
%.styleclean:
$(Q)rm -f $*.stylecheck;
%.stlink-flash: %.bin
@printf " FLASH $<\n"
$(STFLASH) write $(*).bin 0x8000000
ifeq ($(STLINK_PORT),)
ifeq ($(BMP_PORT),)
ifeq ($(OOCD_FILE),)
%.flash: %.elf
@printf " FLASH $<\n"
(echo "halt; program $(realpath $(*).elf) verify reset" | nc -4 localhost 4444 2>/dev/null) || \
$(OOCD) -f interface/$(OOCD_INTERFACE).cfg \
-f target/$(OOCD_TARGET).cfg \
-c "program $(*).elf verify reset exit"
else
%.flash: %.elf
@printf " FLASH $<\n"
(echo "halt; program $(realpath $(*).elf) verify reset" | nc -4 localhost 4444 2>/dev/null) || \
$(OOCD) -f $(OOCD_FILE) \
-c "program $(*).elf verify reset exit"
endif
else
%.flash: %.elf
@printf " GDB $(*).elf (flash)\n"
$(GDB) --batch \
-ex 'target extended-remote $(BMP_PORT)' \
-x $(SCRIPT_DIR)/black_magic_probe_flash.scr \
$(*).elf
endif
else
%.flash: %.elf
@printf " GDB $(*).elf (flash)\n"
$(GDB) --batch \
-ex 'target extended-remote $(STLINK_PORT)' \
-x $(SCRIPT_DIR)/stlink_flash.scr \
$(*).elf
endif
.PHONY: images clean stylecheck styleclean elf bin hex srec list
-include $(OBJS:.o=.d)

View File

@ -0,0 +1,19 @@
##
## This file is part of the libopencm3 project.
##
## Copyright (C) 2009 Uwe Hermann <uwe@hermann-uwe.de>
## Copyright (C) 2010 Piotr Esden-Tempski <piotr@esden.net>
##
## This library is free software: you can redistribute it and/or modify
## it under the terms of the GNU Lesser General Public License as published by
## the Free Software Foundation, either version 3 of the License, or
## (at your option) any later version.
##
## This library 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 Lesser General Public License for more details.
##
## You should have received a copy of the GNU Lesser General Public License
## along with this library. If not, see <http://www.gnu.org/licenses/>.
##

View File

@ -0,0 +1,7 @@
#define logt(tag, fmt, ...) do { \
double ___v = rtc_get_counter_val() / 256.; \
printf("\33[33m%7.3f [" __FILE__ ":%d] \33[36m%s: \33[0m" fmt "\r\n", ___v, __LINE__, tag, ##__VA_ARGS__); \
} while(0);
#define log(fmt, ...) logt(__func__, fmt, ##__VA_ARGS__);
//__FILE_S__, __LINE__, message, ##__VA_ARGS__

View File

@ -0,0 +1,134 @@
/* Copyright (c) 2016, Jan Wiśniewski <vuko@hackerspace.pl>
*
* This software is provided 'as-is', without any express or implied
* warranty. In no event will the authors be held liable for any damages
* arising from the use of this software.
*
* Permission is granted to anyone to use this software for any purpose,
* including commercial applications, and to alter it and redistribute it
* freely, subject to the following restrictions:
*
* 1. The origin of this software must not be misrepresented; you must not
* claim that you wrote the original software. If you use this software
* in a product, an acknowledgment in the product documentation would be
* appreciated but is not required.
* 2. Altered source versions must be plainly marked as such, and must not be
* misrepresented as being the original software.
*/
#include <libopencm3/stm32/dbgmcu.h>
#include <libopencm3/stm32/gpio.h>
#include <libopencm3/stm32/rcc.h>
#include <libopencm3/stm32/rtc.h>
#include <libopencm3/stm32/usart.h>
#include <libopencm3/cm3/nvic.h>
#include <libopencmsis/core_cm3.h>
#include <stdint.h>
#include <stdio.h>
#include "log.h"
void stdio_init(void);
int main(void);
void mdb_slave_init() {
nvic_enable_irq(NVIC_USART2_IRQ);
rcc_periph_clock_enable(RCC_GPIOA);
rcc_periph_clock_enable(RCC_USART2);
gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_50_MHZ,
GPIO_CNF_OUTPUT_ALTFN_PUSHPULL, GPIO_USART2_TX);
gpio_set_mode(GPIOA, GPIO_MODE_INPUT,
GPIO_CNF_INPUT_PULL_UPDOWN, GPIO_USART2_RX);
gpio_set(GPIOA, GPIO3);
usart_set_baudrate(USART2, 9600);
usart_set_databits(USART2, 9);
usart_set_stopbits(USART2, USART_STOPBITS_1);
usart_set_parity(USART2, USART_PARITY_NONE);
usart_set_flow_control(USART2, USART_FLOWCONTROL_NONE);
usart_set_mode(USART2, USART_MODE_TX_RX);
usart_enable_rx_interrupt(USART2);
usart_enable(USART2);
}
static void led_init(void) {
gpio_set(GPIOC, GPIO13);
/* Setup GPIO6 and 7 (in GPIO port A) for LED use. */
gpio_set_mode(GPIOC, GPIO_MODE_OUTPUT_50_MHZ,
GPIO_CNF_OUTPUT_PUSHPULL, GPIO13);
}
int main(){
// enable dubbuger during sleep modes
//DBGMCU_CR |= DBGMCU_CR_SLEEP | DBGMCU_CR_STOP | DBGMCU_CR_STANDBY;
stdio_init();
/* clocks init */
rcc_clock_setup_in_hse_8mhz_out_72mhz();
rcc_periph_clock_enable(RCC_GPIOB);
rcc_periph_clock_enable(RCC_GPIOC);
rcc_periph_clock_enable(RCC_AFIO);
rcc_periph_clock_enable(RCC_TIM2);
led_init();
mdb_slave_init();
rtc_auto_awake(RCC_LSE, 0x7fff / 256); // 0x7fff);
gpio_toggle(GPIOC, GPIO13);
while(1){
//log("Testing shit around 1");
/*usart_send_blocking(USART2, 0b100000000);
usart_send_blocking(USART2, 1);
usart_send_blocking(USART2, 2);
usart_send_blocking(USART2, 3);
usart_send_blocking(USART2, 4);*/
uint8_t buf[2];
uint8_t sz = 0;
if ((sz = _read(0, buf, 2)) == 2) {
// log("got bytes %d", sz);
usart_send_blocking(USART2, buf[0] | (buf[1] << 8));
}
// log("tick");
// usart_send_blocking(USART2, 5);
// for (int i = 0; i < 8000000; i++) /* Wait a bit. */
// __asm__("nop");
}
return 0;
}
uint8_t mdb_pos = 0;
uint8_t mdb_buffer[40];
void usart2_isr(void)
{
static uint16_t data = 'A';
/* Check if we were called because of RXNE. */
if (((USART_CR1(USART2) & USART_CR1_RXNEIE) != 0) &&
((USART_SR(USART2) & USART_SR_RXNE) != 0)) {
/* Indicate that we got data. */
gpio_toggle(GPIOC, GPIO13);
/* Retrieve the data from the peripheral. */
data = usart_recv(USART2);
if (data & (1 << 8)) {
mdb_pos = 0;
}
if (mdb_pos >= 40) {
log("ovf");
return;
}
mdb_buffer[mdb_pos++] = data & 0xff;
uint8_t buf[2] = {data & 0xff, data >> 8};
fwrite(buf, 1, 2, stdout);
fflush(stdout);
// log("got byte: %03x [%d]", data, mdb_pos);
}
}

View File

@ -0,0 +1,94 @@
#include <libopencm3/cm3/nvic.h>
#include <libopencm3/stm32/dbgmcu.h>
#include <libopencm3/stm32/gpio.h>
#include <libopencm3/stm32/rcc.h>
#include <libopencm3/stm32/timer.h>
#include <libopencm3/stm32/usart.h>
#include <libopencm3/usb/cdc.h>
#include <libopencm3/usb/usbd.h>
#include <libopencmsis/core_cm3.h>
#include "fifo.h"
#include "iobuffers.h"
#include "usb.h"
uint8_t tx_buffer[1024];
uint8_t rx_buffer[1024];
fifo tx_fifo;
fifo rx_fifo;
void stdio_init(void);
#ifdef STDIO_USB
usbd_device* usbd_dev;
void usb_hp_can_tx_isr(void){
usbd_poll(usbd_dev);
}
void usb_lp_can_rx0_isr(void){
usbd_poll(usbd_dev);
}
#endif
#ifdef STDIO_UART
void usart1_isr(void) {
uint8_t data;
/* RXNE interrupt handling */
if (((USART_CR1(USART1) & USART_CR1_RXNEIE) != 0) &&
((USART_SR(USART1) & USART_SR_RXNE) != 0)) {
data = usart_recv(USART1);
if(!fifoFull(&rx_fifo))
fifoPush(&rx_fifo, data);
}
/* TXE interrupt handling */
if (((USART_CR1(USART1) & USART_CR1_TXEIE) != 0) &&
((USART_SR(USART1) & USART_SR_TXE) != 0)) {
if(!fifoEmpty(&tx_fifo)){
data = fifoPop(&tx_fifo);
usart_send(USART1, data);
} else {
/* disable TXE interrupt if buffer empty */
USART_CR1(USART1) &= ~USART_CR1_TXEIE;
}
}
}
#endif
void stdio_init(void) {
/* init data structures */
fifoInit(&tx_fifo, tx_buffer, 1024);
fifoInit(&rx_fifo, rx_buffer, 1024);
#ifdef STDIO_UART
/* usart configuration */
rcc_periph_clock_enable(RCC_USART1);
gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_50_MHZ,
GPIO_CNF_OUTPUT_ALTFN_PUSHPULL, GPIO_USART1_TX);
gpio_set_mode(GPIOA, GPIO_MODE_INPUT,
GPIO_CNF_INPUT_FLOAT, GPIO_USART1_RX);
usart_set_baudrate(USART1, 115200);
usart_set_databits(USART1, 8);
usart_set_stopbits(USART1, USART_STOPBITS_1);
usart_set_parity(USART1, USART_PARITY_NONE);
usart_set_flow_control(USART1, USART_FLOWCONTROL_NONE);
usart_set_mode(USART1, USART_MODE_TX_RX);
USART_CR1(USART1) |= USART_CR1_RXNEIE; // enable interrupt
usart_enable(USART1);
#endif
#ifdef STDIO_USB
/* usb configuration */
rcc_set_usbpre(RCC_CFGR_USBPRE_PLL_CLK_DIV1_5);
usbd_dev = usb_init();
usbd_poll(usbd_dev);
nvic_enable_irq(NVIC_USB_HP_CAN_TX_IRQ);
nvic_enable_irq(NVIC_USB_LP_CAN_RX0_IRQ);
nvic_set_priority(NVIC_USB_HP_CAN_TX_IRQ, 1);
nvic_set_priority(NVIC_USB_LP_CAN_RX0_IRQ, 1);
#endif
}

View File

@ -0,0 +1,31 @@
/*
* This file is part of the libopencm3 project.
*
* Copyright (C) 2009 Uwe Hermann <uwe@hermann-uwe.de>
*
* This library is free software: you can redistribute it and/or modify
* it under the terms of the GNU Lesser General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This library 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 Lesser General Public License for more details.
*
* You should have received a copy of the GNU Lesser General Public License
* along with this library. If not, see <http://www.gnu.org/licenses/>.
*/
/* Linker script for Olimex STM32-H103 (STM32F103RBT6, 128K flash, 20K RAM). */
/* Define memory regions. */
MEMORY
{
rom (rx) : ORIGIN = 0x08000000, LENGTH = 128K
ram (rwx) : ORIGIN = 0x20000000, LENGTH = 20K
}
/* Include the common ld script. */
INCLUDE stm32/f1/libopencm3_stm32f1.ld

View File

@ -0,0 +1,295 @@
/*
* This file is part of the libopencm3 project.
*
* Copyright (C) 2010 Gareth McMullin <gareth@blacksphere.co.nz>
*
* This library is free software: you can redistribute it and/or modify
* it under the terms of the GNU Lesser General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This library 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 Lesser General Public License for more details.
*
* You should have received a copy of the GNU Lesser General Public License
* along with this library. If not, see <http://www.gnu.org/licenses/>.
*
* Modified by Jan Wiśniewski <vuko@hackerspace.pl>
*/
#include <stdlib.h>
#include <libopencm3/stm32/rcc.h>
#include <libopencm3/stm32/gpio.h>
#include <libopencm3/stm32/spi.h>
#include <libopencm3/usb/usbd.h>
#include <libopencm3/usb/cdc.h>
#include<libopencmsis/core_cm3.h>
#include "usb.h"
#include "fifo.h"
#include "iobuffers.h"
uint8_t usb_tx_in_progress = 0;
uint8_t usb_enabled = 0;
static const struct usb_device_descriptor dev = {
.bLength = USB_DT_DEVICE_SIZE,
.bDescriptorType = USB_DT_DEVICE,
.bcdUSB = 0x0200,
.bDeviceClass = USB_CLASS_CDC,
.bDeviceSubClass = 0,
.bDeviceProtocol = 0,
.bMaxPacketSize0 = 64,
.idVendor = 0x0483,
.idProduct = 0x5740,
.bcdDevice = 0x0200,
.iManufacturer = 1,
.iProduct = 2,
.iSerialNumber = 3,
.bNumConfigurations = 1,
};
/*
* This notification endpoint isn't implemented. According to CDC spec its
* optional, but its absence causes a NULL pointer dereference in Linux
* cdc_acm driver.
*/
static const struct usb_endpoint_descriptor comm_endp[] = {{
.bLength = USB_DT_ENDPOINT_SIZE,
.bDescriptorType = USB_DT_ENDPOINT,
.bEndpointAddress = 0x83,
.bmAttributes = USB_ENDPOINT_ATTR_INTERRUPT,
.wMaxPacketSize = 16,
.bInterval = 128,
}};
static const struct usb_endpoint_descriptor data_endp[] = {{
.bLength = USB_DT_ENDPOINT_SIZE,
.bDescriptorType = USB_DT_ENDPOINT,
.bEndpointAddress = 0x01,
.bmAttributes = USB_ENDPOINT_ATTR_BULK,
.wMaxPacketSize = 64,
.bInterval = 1,
}, {
.bLength = USB_DT_ENDPOINT_SIZE,
.bDescriptorType = USB_DT_ENDPOINT,
.bEndpointAddress = 0x82,
.bmAttributes = USB_ENDPOINT_ATTR_BULK,
.wMaxPacketSize = 64,
.bInterval = 1,
}};
static const struct {
struct usb_cdc_header_descriptor header;
struct usb_cdc_call_management_descriptor call_mgmt;
struct usb_cdc_acm_descriptor acm;
struct usb_cdc_union_descriptor cdc_union;
} __attribute__((packed)) cdcacm_functional_descriptors = {
.header = {
.bFunctionLength = sizeof(struct usb_cdc_header_descriptor),
.bDescriptorType = CS_INTERFACE,
.bDescriptorSubtype = USB_CDC_TYPE_HEADER,
.bcdCDC = 0x0110,
},
.call_mgmt = {
.bFunctionLength =
sizeof(struct usb_cdc_call_management_descriptor),
.bDescriptorType = CS_INTERFACE,
.bDescriptorSubtype = USB_CDC_TYPE_CALL_MANAGEMENT,
.bmCapabilities = 0,
.bDataInterface = 1,
},
.acm = {
.bFunctionLength = sizeof(struct usb_cdc_acm_descriptor),
.bDescriptorType = CS_INTERFACE,
.bDescriptorSubtype = USB_CDC_TYPE_ACM,
.bmCapabilities = 0,
},
.cdc_union = {
.bFunctionLength = sizeof(struct usb_cdc_union_descriptor),
.bDescriptorType = CS_INTERFACE,
.bDescriptorSubtype = USB_CDC_TYPE_UNION,
.bControlInterface = 0,
.bSubordinateInterface0 = 1,
}
};
static const struct usb_interface_descriptor comm_iface[] = {{
.bLength = USB_DT_INTERFACE_SIZE,
.bDescriptorType = USB_DT_INTERFACE,
.bInterfaceNumber = 0,
.bAlternateSetting = 0,
.bNumEndpoints = 1,
.bInterfaceClass = USB_CLASS_CDC,
.bInterfaceSubClass = USB_CDC_SUBCLASS_ACM,
.bInterfaceProtocol = USB_CDC_PROTOCOL_AT,
.iInterface = 0,
.endpoint = comm_endp,
.extra = &cdcacm_functional_descriptors,
.extralen = sizeof(cdcacm_functional_descriptors)
}};
static const struct usb_interface_descriptor data_iface[] = {{
.bLength = USB_DT_INTERFACE_SIZE,
.bDescriptorType = USB_DT_INTERFACE,
.bInterfaceNumber = 1,
.bAlternateSetting = 0,
.bNumEndpoints = 2,
.bInterfaceClass = USB_CLASS_DATA,
.bInterfaceSubClass = 0,
.bInterfaceProtocol = 0,
.iInterface = 0,
.endpoint = data_endp,
}};
static const struct usb_interface ifaces[] = {{
.num_altsetting = 1,
.altsetting = comm_iface,
}, {
.num_altsetting = 1,
.altsetting = data_iface,
}};
static const struct usb_config_descriptor config = {
.bLength = USB_DT_CONFIGURATION_SIZE,
.bDescriptorType = USB_DT_CONFIGURATION,
.wTotalLength = 0,
.bNumInterfaces = 2,
.bConfigurationValue = 1,
.iConfiguration = 0,
.bmAttributes = 0x80,
.bMaxPower = 0x32,
.interface = ifaces,
};
static const char *usb_strings[] = {
"vuko@hackerspace.pl",
"flowMeter",
"00001",
};
/* Buffer to be used for control requests. */
uint8_t usbd_control_buffer[128];
static int cdcacm_control_request(usbd_device *usbd_dev, struct usb_setup_data *req, uint8_t **buf,
uint16_t *len, void (**complete)(usbd_device *usbd_dev, struct usb_setup_data *req))
{
(void)complete;
(void)buf;
(void)usbd_dev;
switch(req->bRequest) {
case USB_CDC_REQ_SET_CONTROL_LINE_STATE: {
/*
* This Linux cdc_acm driver requires this to be implemented
* even though it's optional in the CDC spec, and we don't
* advertise it in the ACM functional descriptor.
*/
char local_buf[10];
struct usb_cdc_notification *notif = (void *)local_buf;
/* We echo signals back to host as notification. */
notif->bmRequestType = 0xA1;
notif->bNotification = USB_CDC_NOTIFY_SERIAL_STATE;
notif->wValue = 0;
notif->wIndex = 0;
notif->wLength = 2;
local_buf[8] = req->wValue & 3;
local_buf[9] = 0;
//usbd_ep_write_packet(usbd_dev, 0x83, local_buf, 10);
return 1;
}
case USB_CDC_REQ_SET_LINE_CODING:
if(*len < sizeof(struct usb_cdc_line_coding))
return 0;
return 1;
}
return 0;
}
static void cdcacm_data_rx_cb(usbd_device *usbd_dev, uint8_t ep)
{
(void)ep;
char buf[64];
int len = usbd_ep_read_packet(usbd_dev, 0x01, buf, 64);
int i;
for(i = 0;i<len;++i){
__disable_irq();
if(!fifoFull(&rx_fifo))
fifoPush(&rx_fifo, buf[i]);
__enable_irq();
}
}
void cdcacm_data_tx_cb(usbd_device *usbd_dev, uint8_t ep)
{
(void)ep;
char buf[64];
uint8_t len = 0;
usb_tx_in_progress = 1;
uint8_t i;
for(i = 0;i<64;++i){
__disable_irq();
if(!fifoEmpty(&tx_fifo)){
buf[i] = fifoPop(&tx_fifo);
++len;
} else {
__enable_irq();
break;
}
__enable_irq();
}
if(len>0){
if(usb_enabled == 1){ // TODO what happens after reset
usbd_ep_write_packet(usbd_dev, 0x82, buf, len);
}
else
usb_tx_in_progress = 0;
}
else {
__disable_irq();
if(fifoEmpty(&tx_fifo)){
usb_tx_in_progress = 0;
__enable_irq();
}
else {
__enable_irq();
cdcacm_data_tx_cb(usbd_dev,ep);
}
}
}
static void cdcacm_set_config(usbd_device *usbd_dev, uint16_t wValue)
{
(void)wValue;
usbd_ep_setup(usbd_dev, 0x01, USB_ENDPOINT_ATTR_BULK, 64, cdcacm_data_rx_cb);
usbd_ep_setup(usbd_dev, 0x82, USB_ENDPOINT_ATTR_BULK, 64, cdcacm_data_tx_cb);
usbd_ep_setup(usbd_dev, 0x83, USB_ENDPOINT_ATTR_INTERRUPT, 16, NULL);
usbd_register_control_callback(
usbd_dev,
USB_REQ_TYPE_CLASS | USB_REQ_TYPE_INTERFACE,
USB_REQ_TYPE_TYPE | USB_REQ_TYPE_RECIPIENT,
cdcacm_control_request);
usb_enabled = 1;
}
usbd_device * usb_init(void){
usbd_device * usbd_dev;
usbd_dev = usbd_init(&st_usbfs_v1_usb_driver, &dev, &config, usb_strings, 3, usbd_control_buffer, sizeof(usbd_control_buffer));
usbd_register_set_config_callback(usbd_dev, cdcacm_set_config);
return usbd_dev;
}

View File

@ -0,0 +1,7 @@
#include <libopencm3/usb/usbd.h>
#include <libopencm3/usb/cdc.h>
usbd_device * usb_init(void);
extern uint8_t usb_tx_in_progress;
extern uint8_t usb_active;
extern usbd_device * usbd_dev;
void cdcacm_data_tx_cb(usbd_device*, uint8_t);

3
usb-interface/hardware/.gitignore vendored Normal file
View File

@ -0,0 +1,3 @@
*.pdf
*-bak
_autosave-*

@ -0,0 +1 @@
Subproject commit 1bab665a85f403d4d41eeb137ea1547de33b344e

View File

@ -0,0 +1,316 @@
EESchema-LIBRARY Version 2.4
#encoding utf-8
#
# Connector_Conn_01x03_Male
#
DEF Connector_Conn_01x03_Male J 0 40 Y N 1 F N
F0 "J" 0 200 50 H V C CNN
F1 "Connector_Conn_01x03_Male" 0 -200 50 H V C CNN
F2 "" 0 0 50 H I C CNN
F3 "" 0 0 50 H I C CNN
$FPLIST
Connector*:*_1x??_*
$ENDFPLIST
DRAW
S 34 -95 0 -105 1 1 6 F
S 34 5 0 -5 1 1 6 F
S 34 105 0 95 1 1 6 F
P 2 1 1 6 50 -100 34 -100 N
P 2 1 1 6 50 0 34 0 N
P 2 1 1 6 50 100 34 100 N
X Pin_1 1 200 100 150 L 50 50 1 1 P
X Pin_2 2 200 0 150 L 50 50 1 1 P
X Pin_3 3 200 -100 150 L 50 50 1 1 P
ENDDRAW
ENDDEF
#
# Connector_Generic_Conn_02x03_Top_Bottom
#
DEF Connector_Generic_Conn_02x03_Top_Bottom J 0 40 Y N 1 F N
F0 "J" 50 200 50 H V C CNN
F1 "Connector_Generic_Conn_02x03_Top_Bottom" 50 -200 50 H V C CNN
F2 "" 0 0 50 H I C CNN
F3 "" 0 0 50 H I C CNN
$FPLIST
Connector*:*_2x??_*
$ENDFPLIST
DRAW
S -50 -95 0 -105 1 1 6 N
S -50 5 0 -5 1 1 6 N
S -50 105 0 95 1 1 6 N
S -50 150 150 -150 1 1 10 f
S 150 -95 100 -105 1 1 6 N
S 150 5 100 -5 1 1 6 N
S 150 105 100 95 1 1 6 N
X Pin_1 1 -200 100 150 R 50 50 1 1 P
X Pin_2 2 -200 0 150 R 50 50 1 1 P
X Pin_3 3 -200 -100 150 R 50 50 1 1 P
X Pin_4 4 300 100 150 L 50 50 1 1 P
X Pin_5 5 300 0 150 L 50 50 1 1 P
X Pin_6 6 300 -100 150 L 50 50 1 1 P
ENDDRAW
ENDDEF
#
# Connector_Screw_Terminal_01x02
#
DEF Connector_Screw_Terminal_01x02 J 0 40 Y N 1 F N
F0 "J" 0 100 50 H V C CNN
F1 "Connector_Screw_Terminal_01x02" 0 -200 50 H V C CNN
F2 "" 0 0 50 H I C CNN
F3 "" 0 0 50 H I C CNN
$FPLIST
TerminalBlock*:*
$ENDFPLIST
DRAW
C 0 -100 25 1 1 6 N
C 0 0 25 1 1 6 N
S -50 50 50 -150 1 1 10 f
P 2 1 1 6 -21 -87 13 -120 N
P 2 1 1 6 -21 13 13 -20 N
P 2 1 1 6 -14 -80 20 -113 N
P 2 1 1 6 -14 20 20 -13 N
X Pin_1 1 -200 0 150 R 50 50 1 1 P
X Pin_2 2 -200 -100 150 R 50 50 1 1 P
ENDDRAW
ENDDEF
#
# Device_R
#
DEF Device_R R 0 0 N Y 1 F N
F0 "R" 80 0 50 V V C CNN
F1 "Device_R" 0 0 50 V V C CNN
F2 "" -70 0 50 V I C CNN
F3 "" 0 0 50 H I C CNN
$FPLIST
R_*
$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
#
# Isolator_PC817
#
DEF Isolator_PC817 U 0 40 Y Y 1 F N
F0 "U" -200 200 50 H V L CNN
F1 "Isolator_PC817" 0 200 50 H V L CNN
F2 "Package_DIP:DIP-4_W7.62mm" -200 -200 50 H I L CIN
F3 "" 0 0 50 H I L CNN
ALIAS EL817
$FPLIST
DIP*W7.62mm*
$ENDFPLIST
DRAW
S -200 150 200 -150 0 1 10 f
P 2 0 1 10 -125 -25 -75 -25 N
P 2 0 1 0 100 25 175 100 N
P 2 0 1 0 175 -100 100 -25 F
P 2 0 1 0 175 -100 200 -100 N
P 2 0 1 0 175 100 200 100 N
P 3 0 1 0 -200 100 -100 100 -100 -25 N
P 3 0 1 0 -100 -25 -100 -100 -200 -100 N
P 3 0 1 20 100 75 100 -75 100 -75 N
P 4 0 1 10 -100 -25 -125 25 -75 25 -100 -25 N
P 5 0 1 0 -20 -20 30 -20 15 -25 15 -15 30 -20 N
P 5 0 1 0 -20 20 30 20 15 15 15 25 30 20 N
P 5 0 1 0 120 -65 140 -45 160 -85 120 -65 120 -65 F
X ~ 1 -300 100 100 R 50 50 1 1 P
X ~ 2 -300 -100 100 R 50 50 1 1 P
X ~ 3 300 -100 100 L 50 50 1 1 P
X ~ 4 300 100 100 L 50 50 1 1 P
ENDDRAW
ENDDEF
#
# YAAJ_STM32_BluePill_1
#
DEF YAAJ_STM32_BluePill_1 BP? 0 40 Y Y 1 F N
F0 "BP?" 650 50 50 H V C CNN
F1 "YAAJ_STM32_BluePill_1" 300 50 50 H V C CNN
F2 "" 1250 -1950 50 H I C CNN
F3 "" 1250 -1950 50 H I C CNN
DRAW
C -20 -1750 14 0 0 0 F
C -20 -1650 14 0 0 0 F
C -20 -1550 14 0 0 0 F
C -20 -1450 14 0 0 0 F
C -20 -1350 14 0 0 0 F
C -20 -1250 14 0 0 0 F
C -20 -1150 14 0 0 0 F
C -20 -1050 14 0 0 0 F
C -20 -950 14 0 0 0 F
C -20 -850 14 0 0 0 F
C -20 -750 14 0 0 0 F
C -20 -650 14 0 0 0 F
C -20 -550 14 0 0 0 F
C -20 -450 14 0 0 0 F
C -20 -350 14 0 0 0 F
C -20 -250 14 0 0 0 F
C -20 -50 14 0 0 0 F
C 305 -1925 5 0 0 0 F
C 305 -1925 10 0 0 0 N
C 305 -1925 14 0 0 0 N
C 1170 -550 10 0 0 0 F
C 1170 -550 14 0 0 0 N
C 1170 -450 10 0 0 0 F
C 1170 -450 14 0 0 0 N
C -20 -150 14 1 1 0 F
T 0 520 -1760 39 0 0 0 "30pF 2MHz" Normal 0 C C
T 0 520 -1925 39 0 0 0 "5V tolerant" Normal 0 C C
T 0 855 -1550 39 0 0 0 ADC0 Normal 0 C C
T 0 855 -1450 39 0 0 0 ADC1 Normal 0 C C
T 0 855 -1350 39 0 0 0 ADC2 Normal 0 C C
T 0 855 -1255 39 0 0 0 ADC3 Normal 0 C C
T 0 855 -1150 39 0 0 0 ADC4 Normal 0 C C
T 0 850 -750 39 0 0 0 ADC8 Normal 0 C C
T 0 850 -650 39 0 0 0 ADC9 Normal 0 C C
T 0 840 -1845 39 0 0 0 LED Normal 0 C C
T 0 845 -950 39 0 0 0 MISO1 Normal 0 C C
T 0 845 -850 39 0 0 0 MOSI1 Normal 0 C C
T 0 330 -945 39 0 0 0 NSS1 Normal 0 C C
T 0 475 -1845 39 0 0 0 "PWM pin" Normal 0 C C
T 0 310 -655 39 0 0 0 RX1 Normal 0 C C
T 0 710 -1255 39 0 0 0 RX2 Normal 0 C C
T 0 830 -450 39 0 0 0 RX3 Normal 0 C C
T 0 855 -1050 39 0 0 0 SCK1 Normal 0 C C
T 0 325 -1345 39 0 0 0 SCL1 Normal 0 C C
T 0 325 -1450 39 0 0 0 SDA1 Normal 0 C C
T 0 485 -1640 39 0 0 0 "sink 3mA" Normal 0 C C
T 0 525 -1695 39 0 0 0 "source 0mA" Normal 0 C C
T 0 305 -550 39 0 0 0 TX1 Normal 0 C C
T 0 705 -1350 39 0 0 0 TX2 Normal 0 C C
T 0 835 -550 39 0 0 0 TX3 Normal 0 C C
T 0 600 -100 50 0 0 0 USB Normal 0 C C
T 0 335 -850 39 0 0 0 USB+ Normal 0 C C
T 0 335 -750 39 0 0 0 USB- Normal 0 C C
T 0 515 -20 20 0 0 0 Y@@J Normal 0 C C
S 0 0 1150 -2000 0 0 0 N
S 750 0 450 -200 0 1 0 N
P 18 0 0 0 280 -1665 305 -1625 330 -1665 280 -1665 305 -1630 325 -1665 285 -1660 305 -1635 320 -1665 290 -1655 310 -1640 315 -1665 295 -1650 315 -1645 310 -1660 300 -1650 310 -1655 305 -1645 N
P 18 0 0 0 1275 -1865 1300 -1825 1325 -1865 1275 -1865 1300 -1830 1320 -1865 1280 -1860 1300 -1835 1315 -1865 1285 -1855 1305 -1840 1310 -1865 1290 -1850 1310 -1845 1305 -1860 1295 -1850 1305 -1855 1300 -1845 N
P 18 0 0 0 1275 -1765 1300 -1725 1325 -1765 1275 -1765 1300 -1730 1320 -1765 1280 -1760 1300 -1735 1315 -1765 1285 -1755 1305 -1740 1310 -1765 1290 -1750 1310 -1745 1305 -1760 1295 -1750 1305 -1755 1300 -1745 N
P 18 0 0 0 1275 -1665 1300 -1625 1325 -1665 1275 -1665 1300 -1630 1320 -1665 1280 -1660 1300 -1635 1315 -1665 1285 -1655 1305 -1640 1310 -1665 1290 -1650 1310 -1645 1305 -1660 1295 -1650 1305 -1655 1300 -1645 N
P 6 0 1 0 -140 -1650 -140 -1670 -160 -1670 -160 -1630 -180 -1630 -180 -1650 N
P 6 0 1 0 -140 -1550 -140 -1570 -160 -1570 -160 -1530 -180 -1530 -180 -1550 N
P 6 0 1 0 -140 -1450 -140 -1470 -160 -1470 -160 -1430 -180 -1430 -180 -1450 N
P 6 0 1 0 -140 -1350 -140 -1370 -160 -1370 -160 -1330 -180 -1330 -180 -1350 N
P 6 0 1 0 -140 -650 -140 -670 -160 -670 -160 -630 -180 -630 -180 -650 N
P 6 0 1 0 -140 -550 -140 -570 -160 -570 -160 -530 -180 -530 -180 -550 N
P 6 0 1 0 -140 -450 -140 -470 -160 -470 -160 -430 -180 -430 -180 -450 N
P 6 0 1 0 320 -1845 320 -1865 300 -1865 300 -1825 280 -1825 280 -1845 N
P 6 0 1 0 1330 -1550 1330 -1570 1310 -1570 1310 -1530 1290 -1530 1290 -1550 N
P 6 0 1 0 1330 -1450 1330 -1470 1310 -1470 1310 -1430 1290 -1430 1290 -1450 N
P 6 0 1 0 1330 -1350 1330 -1370 1310 -1370 1310 -1330 1290 -1330 1290 -1350 N
P 6 0 1 0 1330 -1250 1330 -1270 1310 -1270 1310 -1230 1290 -1230 1290 -1250 N
P 6 0 1 0 1330 -950 1330 -970 1310 -970 1310 -930 1290 -930 1290 -950 N
P 6 0 1 0 1330 -850 1330 -870 1310 -870 1310 -830 1290 -830 1290 -850 N
P 6 0 1 0 1330 -750 1330 -770 1310 -770 1310 -730 1290 -730 1290 -750 N
P 6 0 1 0 1330 -650 1330 -670 1310 -670 1310 -630 1290 -630 1290 -650 N
X PB12 1 -200 -50 200 R 50 50 1 1 B
X PA15 10 -200 -950 200 R 50 50 1 1 B
X PB3 11 -200 -1050 200 R 50 50 1 1 B
X PB4 12 -200 -1150 200 R 50 50 1 1 B
X PB5 13 -200 -1250 200 R 50 50 1 1 B
X PB6 14 -200 -1350 200 R 50 50 1 1 B
X PB7 15 -200 -1450 200 R 50 50 1 1 B
X PB8 16 -200 -1550 200 R 50 50 1 1 B
X PB9 17 -200 -1650 200 R 50 50 1 1 B
X 5V 18 -200 -1750 200 R 50 50 1 1 w
X GND 19 -200 -1850 200 R 50 50 1 1 W
X PB13 2 -200 -150 200 R 50 50 1 1 B
X 3V3 20 -200 -1950 200 R 50 50 1 1 w
X VBat 21 1350 -1950 200 L 50 50 1 1 W
X PC13 22 1350 -1850 200 L 50 50 1 1 B
X PC14 23 1350 -1750 200 L 50 50 1 1 B
X PC15 24 1350 -1650 200 L 50 50 1 1 B
X PA0 25 1350 -1550 200 L 50 50 1 1 B
X PA1 26 1350 -1450 200 L 50 50 1 1 B
X PA2 27 1350 -1350 200 L 50 50 1 1 B
X PA3 28 1350 -1250 200 L 50 50 1 1 B
X PA4 29 1350 -1150 200 L 50 50 1 1 B
X PB14 3 -200 -250 200 R 50 50 1 1 B
X PA5 30 1350 -1050 200 L 50 50 1 1 B
X PA6 31 1350 -950 200 L 50 50 1 1 B
X PA7 32 1350 -850 200 L 50 50 1 1 B
X PB0 33 1350 -750 200 L 50 50 1 1 B
X PB1 34 1350 -650 200 L 50 50 1 1 B
X PB10 35 1350 -550 200 L 50 50 1 1 B
X PB11 36 1350 -450 200 L 50 50 1 1 B
X RST 37 1350 -350 200 L 50 50 1 1 I
X 3V3 38 1350 -250 200 L 50 50 1 1 w
X GND 39 1350 -150 200 L 50 50 1 1 W
X PB15 4 -200 -350 200 R 50 50 1 1 B
X GND 40 1350 -50 200 L 50 50 1 1 W
X PA8 5 -200 -450 200 R 50 50 1 1 B
X PA9 6 -200 -550 200 R 50 50 1 1 B
X PA10 7 -200 -650 200 R 50 50 1 1 B
X PA11 8 -200 -750 200 R 50 50 1 1 B
X PA12 9 -200 -850 200 R 50 50 1 1 B
ENDDRAW
ENDDEF
#
# power_+3V3
#
DEF power_+3V3 #PWR 0 0 Y Y 1 F P
F0 "#PWR" 0 -150 50 H I C CNN
F1 "power_+3V3" 0 140 50 H V C CNN
F2 "" 0 0 50 H I C CNN
F3 "" 0 0 50 H I C CNN
ALIAS +3.3V
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
#
# power_GND
#
DEF power_GND #PWR 0 0 Y Y 1 F P
F0 "#PWR" 0 -250 50 H I C CNN
F1 "power_GND" 0 -150 50 H V C CNN
F2 "" 0 0 50 H I C CNN
F3 "" 0 0 50 H I C CNN
DRAW
P 6 0 1 0 0 0 0 -50 50 -50 0 -100 -50 -50 0 -50 N
X GND 1 0 0 0 D 50 50 1 1 W N
ENDDRAW
ENDDEF
#
# power_GNDPWR
#
DEF power_GNDPWR #PWR 0 0 Y Y 1 F P
F0 "#PWR" 0 -200 50 H I C CNN
F1 "power_GNDPWR" 0 -130 50 H V C CNN
F2 "" 0 -50 50 H I C CNN
F3 "" 0 -50 50 H I C CNN
DRAW
P 2 0 1 0 0 -50 0 0 N
P 3 0 1 8 -40 -50 -50 -80 -50 -80 N
P 3 0 1 8 -20 -50 -30 -80 -30 -80 N
P 3 0 1 8 0 -50 -10 -80 -10 -80 N
P 3 0 1 8 20 -50 10 -80 10 -80 N
P 3 0 1 8 40 -50 -40 -50 -40 -50 N
P 4 0 1 8 40 -50 30 -80 30 -80 30 -80 N
X GNDPWR 1 0 0 0 D 50 50 1 1 W N
ENDDRAW
ENDDEF
#
# power_VBUS
#
DEF power_VBUS #PWR 0 0 Y Y 1 F P
F0 "#PWR" 0 -150 50 H I C CNN
F1 "power_VBUS" 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 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 VBUS 1 0 0 0 U 50 50 1 1 W N
ENDDRAW
ENDDEF
#
#End Library

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,323 @@
(export (version D)
(design
(source /home/informatic/Projects/bitvend-interface/bitvend-interface.sch)
(date "Sun 21 Jun 2020 07:40:24 PM CEST")
(tool "Eeschema 5.1.5")
(sheet (number 1) (name /) (tstamps /)
(title_block
(title)
(company)
(rev)
(date)
(source bitvend-interface.sch)
(comment (number 1) (value ""))
(comment (number 2) (value ""))
(comment (number 3) (value ""))
(comment (number 4) (value "")))))
(components
(comp (ref U1)
(value PC817)
(footprint Package_DIP:DIP-4_W7.62mm)
(datasheet http://www.soselectronic.cz/a_info/resource/d/pc817.pdf)
(libsource (lib Isolator) (part PC817) (description "DC Optocoupler, Vce 35V, CTR 50-300%, DIP-4"))
(sheetpath (names /) (tstamps /))
(tstamp 5EEF4BBD))
(comp (ref R2)
(value 330)
(footprint Resistor_SMD:R_1206_3216Metric_Pad1.42x1.75mm_HandSolder)
(datasheet ~)
(libsource (lib Device) (part R) (description Resistor))
(sheetpath (names /) (tstamps /))
(tstamp 5EEF5E00))
(comp (ref U2)
(value PC817)
(footprint Package_DIP:DIP-4_W7.62mm)
(datasheet http://www.soselectronic.cz/a_info/resource/d/pc817.pdf)
(libsource (lib Isolator) (part PC817) (description "DC Optocoupler, Vce 35V, CTR 50-300%, DIP-4"))
(sheetpath (names /) (tstamps /))
(tstamp 5EEF8932))
(comp (ref R3)
(value 330)
(footprint Resistor_SMD:R_1206_3216Metric_Pad1.42x1.75mm_HandSolder)
(datasheet ~)
(libsource (lib Device) (part R) (description Resistor))
(sheetpath (names /) (tstamps /))
(tstamp 5EEF8B9E))
(comp (ref R1)
(value 470)
(footprint Resistor_SMD:R_1206_3216Metric_Pad1.42x1.75mm_HandSolder)
(datasheet ~)
(libsource (lib Device) (part R) (description Resistor))
(sheetpath (names /) (tstamps /))
(tstamp 5EEFA474))
(comp (ref BP?1)
(value BluePill_1)
(footprint Modules:YAAJ_BluePill)
(libsource (lib YAAJ_STM32) (part BluePill_1) (description "STM32 Blue Pill"))
(sheetpath (names /) (tstamps /))
(tstamp 5EEFB3BF))
(comp (ref J2)
(value Conn_02x03_Top_Bottom)
(footprint Connector_Molex:Molex_Mini-Fit_Jr_5569-06A2_2x03_P4.20mm_Horizontal)
(datasheet ~)
(libsource (lib Connector_Generic) (part Conn_02x03_Top_Bottom) (description "Generic connector, double row, 02x03, top/bottom pin numbering scheme (row 1: 1...pins_per_row, row2: pins_per_row+1 ... num_pins), script generated (kicad-library-utils/schlib/autogen/connector/)"))
(sheetpath (names /) (tstamps /))
(tstamp 5EF0784E))
(comp (ref J1)
(value Screw_Terminal_01x02)
(footprint TerminalBlock:TerminalBlock_bornier-2_P5.08mm)
(datasheet ~)
(libsource (lib Connector) (part Screw_Terminal_01x02) (description "Generic screw terminal, single row, 01x02, script generated (kicad-library-utils/schlib/autogen/connector/)"))
(sheetpath (names /) (tstamps /))
(tstamp 5EF0A49F))
(comp (ref J4)
(value Conn_01x03_Male)
(footprint Connector_PinHeader_2.54mm:PinHeader_1x03_P2.54mm_Vertical)
(datasheet ~)
(libsource (lib Connector) (part Conn_01x03_Male) (description "Generic connector, single row, 01x03, script generated (kicad-library-utils/schlib/autogen/connector/)"))
(sheetpath (names /) (tstamps /))
(tstamp 5EF18300))
(comp (ref J3)
(value Conn_01x03_Male)
(footprint Connector_PinHeader_2.54mm:PinHeader_1x03_P2.54mm_Vertical)
(datasheet ~)
(libsource (lib Connector) (part Conn_01x03_Male) (description "Generic connector, single row, 01x03, script generated (kicad-library-utils/schlib/autogen/connector/)"))
(sheetpath (names /) (tstamps /))
(tstamp 5EF1D31D)))
(libparts
(libpart (lib Connector) (part Conn_01x03_Male)
(description "Generic connector, single row, 01x03, script generated (kicad-library-utils/schlib/autogen/connector/)")
(docs ~)
(footprints
(fp Connector*:*_1x??_*))
(fields
(field (name Reference) J)
(field (name Value) Conn_01x03_Male))
(pins
(pin (num 1) (name Pin_1) (type passive))
(pin (num 2) (name Pin_2) (type passive))
(pin (num 3) (name Pin_3) (type passive))))
(libpart (lib Connector) (part Screw_Terminal_01x02)
(description "Generic screw terminal, single row, 01x02, script generated (kicad-library-utils/schlib/autogen/connector/)")
(docs ~)
(footprints
(fp TerminalBlock*:*))
(fields
(field (name Reference) J)
(field (name Value) Screw_Terminal_01x02))
(pins
(pin (num 1) (name Pin_1) (type passive))
(pin (num 2) (name Pin_2) (type passive))))
(libpart (lib Connector_Generic) (part Conn_02x03_Top_Bottom)
(description "Generic connector, double row, 02x03, top/bottom pin numbering scheme (row 1: 1...pins_per_row, row2: pins_per_row+1 ... num_pins), script generated (kicad-library-utils/schlib/autogen/connector/)")
(docs ~)
(footprints
(fp Connector*:*_2x??_*))
(fields
(field (name Reference) J)
(field (name Value) Conn_02x03_Top_Bottom))
(pins
(pin (num 1) (name Pin_1) (type passive))
(pin (num 2) (name Pin_2) (type passive))
(pin (num 3) (name Pin_3) (type passive))
(pin (num 4) (name Pin_4) (type passive))
(pin (num 5) (name Pin_5) (type passive))
(pin (num 6) (name Pin_6) (type passive))))
(libpart (lib Device) (part R)
(description Resistor)
(docs ~)
(footprints
(fp R_*))
(fields
(field (name Reference) R)
(field (name Value) R))
(pins
(pin (num 1) (name ~) (type passive))
(pin (num 2) (name ~) (type passive))))
(libpart (lib Isolator) (part PC817)
(aliases
(alias EL817))
(description "DC Optocoupler, Vce 35V, CTR 50-300%, DIP-4")
(docs http://www.soselectronic.cz/a_info/resource/d/pc817.pdf)
(footprints
(fp DIP*W7.62mm*))
(fields
(field (name Reference) U)
(field (name Value) PC817)
(field (name Footprint) Package_DIP:DIP-4_W7.62mm))
(pins
(pin (num 1) (name ~) (type passive))
(pin (num 2) (name ~) (type passive))
(pin (num 3) (name ~) (type passive))
(pin (num 4) (name ~) (type passive))))
(libpart (lib YAAJ_STM32) (part BluePill_1)
(description "STM32 Blue Pill")
(fields
(field (name Reference) BP?)
(field (name Value) BluePill_1))
(pins
(pin (num 1) (name PB12) (type BiDi))
(pin (num 2) (name PB13) (type BiDi))
(pin (num 3) (name PB14) (type BiDi))
(pin (num 4) (name PB15) (type BiDi))
(pin (num 5) (name PA8) (type BiDi))
(pin (num 6) (name PA9) (type BiDi))
(pin (num 7) (name PA10) (type BiDi))
(pin (num 8) (name PA11) (type BiDi))
(pin (num 9) (name PA12) (type BiDi))
(pin (num 10) (name PA15) (type BiDi))
(pin (num 11) (name PB3) (type BiDi))
(pin (num 12) (name PB4) (type BiDi))
(pin (num 13) (name PB5) (type BiDi))
(pin (num 14) (name PB6) (type BiDi))
(pin (num 15) (name PB7) (type BiDi))
(pin (num 16) (name PB8) (type BiDi))
(pin (num 17) (name PB9) (type BiDi))
(pin (num 18) (name 5V) (type power_out))
(pin (num 19) (name GND) (type power_in))
(pin (num 20) (name 3V3) (type power_out))
(pin (num 21) (name VBat) (type power_in))
(pin (num 22) (name PC13) (type BiDi))
(pin (num 23) (name PC14) (type BiDi))
(pin (num 24) (name PC15) (type BiDi))
(pin (num 25) (name PA0) (type BiDi))
(pin (num 26) (name PA1) (type BiDi))
(pin (num 27) (name PA2) (type BiDi))
(pin (num 28) (name PA3) (type BiDi))
(pin (num 29) (name PA4) (type BiDi))
(pin (num 30) (name PA5) (type BiDi))
(pin (num 31) (name PA6) (type BiDi))
(pin (num 32) (name PA7) (type BiDi))
(pin (num 33) (name PB0) (type BiDi))
(pin (num 34) (name PB1) (type BiDi))
(pin (num 35) (name PB10) (type BiDi))
(pin (num 36) (name PB11) (type BiDi))
(pin (num 37) (name RST) (type input))
(pin (num 38) (name 3V3) (type power_out))
(pin (num 39) (name GND) (type power_in))
(pin (num 40) (name GND) (type power_in)))))
(libraries
(library (logical Connector)
(uri /nix/store/5zl1s45rc2jzps4hqwg3411qw3k3ylrl-kicad-symbols-5.1.5/share/kicad/library/Connector.lib))
(library (logical Connector_Generic)
(uri /nix/store/5zl1s45rc2jzps4hqwg3411qw3k3ylrl-kicad-symbols-5.1.5/share/kicad/library/Connector_Generic.lib))
(library (logical Device)
(uri /nix/store/5zl1s45rc2jzps4hqwg3411qw3k3ylrl-kicad-symbols-5.1.5/share/kicad/library/Device.lib))
(library (logical Isolator)
(uri /nix/store/5zl1s45rc2jzps4hqwg3411qw3k3ylrl-kicad-symbols-5.1.5/share/kicad/library/Isolator.lib))
(library (logical YAAJ_STM32)
(uri /home/informatic/Projects/bitvend-interface/Kicad-STM32/Symbols/YAAJ_STM32.lib)))
(nets
(net (code 1) (name GND)
(node (ref BP?1) (pin 40))
(node (ref BP?1) (pin 39))
(node (ref U1) (pin 3))
(node (ref BP?1) (pin 19))
(node (ref J4) (pin 1)))
(net (code 2) (name "Net-(J2-Pad3)")
(node (ref J2) (pin 3)))
(net (code 3) (name +3V3)
(node (ref R2) (pin 1))
(node (ref R3) (pin 1))
(node (ref BP?1) (pin 38))
(node (ref BP?1) (pin 20)))
(net (code 4) (name VBUS)
(node (ref J2) (pin 1))
(node (ref J1) (pin 1)))
(net (code 5) (name "Net-(BP?1-Pad9)")
(node (ref BP?1) (pin 9)))
(net (code 6) (name "Net-(BP?1-Pad8)")
(node (ref BP?1) (pin 8)))
(net (code 7) (name "Net-(BP?1-Pad7)")
(node (ref BP?1) (pin 7)))
(net (code 8) (name "Net-(BP?1-Pad6)")
(node (ref BP?1) (pin 6)))
(net (code 9) (name "Net-(BP?1-Pad5)")
(node (ref BP?1) (pin 5)))
(net (code 10) (name "Net-(BP?1-Pad4)")
(node (ref BP?1) (pin 4)))
(net (code 11) (name "Net-(BP?1-Pad37)")
(node (ref BP?1) (pin 37)))
(net (code 12) (name /MDB_RX)
(node (ref J2) (pin 5))
(node (ref U1) (pin 1))
(node (ref J3) (pin 3)))
(net (code 13) (name /MDB_TX)
(node (ref J2) (pin 4))
(node (ref J3) (pin 2))
(node (ref U2) (pin 4)))
(net (code 14) (name "Net-(BP?1-Pad36)")
(node (ref BP?1) (pin 36)))
(net (code 15) (name GNDPWR)
(node (ref J1) (pin 2))
(node (ref J2) (pin 2)))
(net (code 16) (name "Net-(R3-Pad2)")
(node (ref U2) (pin 1))
(node (ref R3) (pin 2)))
(net (code 17) (name "Net-(BP?1-Pad1)")
(node (ref BP?1) (pin 1)))
(net (code 18) (name "Net-(R1-Pad2)")
(node (ref R1) (pin 2))
(node (ref U1) (pin 2)))
(net (code 19) (name /MDB_GND)
(node (ref U2) (pin 3))
(node (ref J2) (pin 6))
(node (ref R1) (pin 1))
(node (ref J3) (pin 1)))
(net (code 20) (name "Net-(BP?1-Pad10)")
(node (ref BP?1) (pin 10)))
(net (code 21) (name "Net-(BP?1-Pad23)")
(node (ref BP?1) (pin 23)))
(net (code 22) (name "Net-(BP?1-Pad35)")
(node (ref BP?1) (pin 35)))
(net (code 23) (name "Net-(BP?1-Pad34)")
(node (ref BP?1) (pin 34)))
(net (code 24) (name "Net-(BP?1-Pad33)")
(node (ref BP?1) (pin 33)))
(net (code 25) (name "Net-(BP?1-Pad32)")
(node (ref BP?1) (pin 32)))
(net (code 26) (name "Net-(BP?1-Pad31)")
(node (ref BP?1) (pin 31)))
(net (code 27) (name "Net-(BP?1-Pad30)")
(node (ref BP?1) (pin 30)))
(net (code 28) (name "Net-(BP?1-Pad3)")
(node (ref BP?1) (pin 3)))
(net (code 29) (name "Net-(BP?1-Pad29)")
(node (ref BP?1) (pin 29)))
(net (code 30) (name /UART2_RX)
(node (ref BP?1) (pin 28))
(node (ref U1) (pin 4))
(node (ref R2) (pin 2))
(node (ref J4) (pin 3)))
(net (code 31) (name /UART2_TX)
(node (ref BP?1) (pin 27))
(node (ref U2) (pin 2))
(node (ref J4) (pin 2)))
(net (code 32) (name "Net-(BP?1-Pad26)")
(node (ref BP?1) (pin 26)))
(net (code 33) (name "Net-(BP?1-Pad25)")
(node (ref BP?1) (pin 25)))
(net (code 34) (name "Net-(BP?1-Pad24)")
(node (ref BP?1) (pin 24)))
(net (code 35) (name "Net-(BP?1-Pad22)")
(node (ref BP?1) (pin 22)))
(net (code 36) (name "Net-(BP?1-Pad21)")
(node (ref BP?1) (pin 21)))
(net (code 37) (name "Net-(BP?1-Pad2)")
(node (ref BP?1) (pin 2)))
(net (code 38) (name "Net-(BP?1-Pad18)")
(node (ref BP?1) (pin 18)))
(net (code 39) (name "Net-(BP?1-Pad17)")
(node (ref BP?1) (pin 17)))
(net (code 40) (name "Net-(BP?1-Pad16)")
(node (ref BP?1) (pin 16)))
(net (code 41) (name "Net-(BP?1-Pad15)")
(node (ref BP?1) (pin 15)))
(net (code 42) (name "Net-(BP?1-Pad14)")
(node (ref BP?1) (pin 14)))
(net (code 43) (name "Net-(BP?1-Pad13)")
(node (ref BP?1) (pin 13)))
(net (code 44) (name "Net-(BP?1-Pad12)")
(node (ref BP?1) (pin 12)))
(net (code 45) (name "Net-(BP?1-Pad11)")
(node (ref BP?1) (pin 11)))))

View File

@ -0,0 +1,241 @@
update=Sun 21 Jun 2020 03:06:57 PM CEST
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=bitvend-interface.net
CopperLayerCount=2
BoardThickness=1.6
AllowMicroVias=0
AllowBlindVias=0
RequireCourtyardDefinitions=0
ProhibitOverlappingCourtyards=1
MinTrackWidth=0.2
MinViaDiameter=0.4
MinViaDrill=0.3
MinMicroViaDiameter=0.2
MinMicroViaDrill=0.09999999999999999
MinHoleToHole=0.25
TrackWidth1=0.25
TrackWidth2=0.25
TrackWidth3=0.5
TrackWidth4=0.75
ViaDiameter1=0.8
ViaDrill1=0.4
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
[pcbnew/Layer.F.Cu]
Name=F.Cu
Type=0
Enabled=1
[pcbnew/Layer.In1.Cu]
Name=In1.Cu
Type=0
Enabled=0
[pcbnew/Layer.In2.Cu]
Name=In2.Cu
Type=0
Enabled=0
[pcbnew/Layer.In3.Cu]
Name=In3.Cu
Type=0
Enabled=0
[pcbnew/Layer.In4.Cu]
Name=In4.Cu
Type=0
Enabled=0
[pcbnew/Layer.In5.Cu]
Name=In5.Cu
Type=0
Enabled=0
[pcbnew/Layer.In6.Cu]
Name=In6.Cu
Type=0
Enabled=0
[pcbnew/Layer.In7.Cu]
Name=In7.Cu
Type=0
Enabled=0
[pcbnew/Layer.In8.Cu]
Name=In8.Cu
Type=0
Enabled=0
[pcbnew/Layer.In9.Cu]
Name=In9.Cu
Type=0
Enabled=0
[pcbnew/Layer.In10.Cu]
Name=In10.Cu
Type=0
Enabled=0
[pcbnew/Layer.In11.Cu]
Name=In11.Cu
Type=0
Enabled=0
[pcbnew/Layer.In12.Cu]
Name=In12.Cu
Type=0
Enabled=0
[pcbnew/Layer.In13.Cu]
Name=In13.Cu
Type=0
Enabled=0
[pcbnew/Layer.In14.Cu]
Name=In14.Cu
Type=0
Enabled=0
[pcbnew/Layer.In15.Cu]
Name=In15.Cu
Type=0
Enabled=0
[pcbnew/Layer.In16.Cu]
Name=In16.Cu
Type=0
Enabled=0
[pcbnew/Layer.In17.Cu]
Name=In17.Cu
Type=0
Enabled=0
[pcbnew/Layer.In18.Cu]
Name=In18.Cu
Type=0
Enabled=0
[pcbnew/Layer.In19.Cu]
Name=In19.Cu
Type=0
Enabled=0
[pcbnew/Layer.In20.Cu]
Name=In20.Cu
Type=0
Enabled=0
[pcbnew/Layer.In21.Cu]
Name=In21.Cu
Type=0
Enabled=0
[pcbnew/Layer.In22.Cu]
Name=In22.Cu
Type=0
Enabled=0
[pcbnew/Layer.In23.Cu]
Name=In23.Cu
Type=0
Enabled=0
[pcbnew/Layer.In24.Cu]
Name=In24.Cu
Type=0
Enabled=0
[pcbnew/Layer.In25.Cu]
Name=In25.Cu
Type=0
Enabled=0
[pcbnew/Layer.In26.Cu]
Name=In26.Cu
Type=0
Enabled=0
[pcbnew/Layer.In27.Cu]
Name=In27.Cu
Type=0
Enabled=0
[pcbnew/Layer.In28.Cu]
Name=In28.Cu
Type=0
Enabled=0
[pcbnew/Layer.In29.Cu]
Name=In29.Cu
Type=0
Enabled=0
[pcbnew/Layer.In30.Cu]
Name=In30.Cu
Type=0
Enabled=0
[pcbnew/Layer.B.Cu]
Name=B.Cu
Type=0
Enabled=1
[pcbnew/Layer.B.Adhes]
Enabled=1
[pcbnew/Layer.F.Adhes]
Enabled=1
[pcbnew/Layer.B.Paste]
Enabled=1
[pcbnew/Layer.F.Paste]
Enabled=1
[pcbnew/Layer.B.SilkS]
Enabled=1
[pcbnew/Layer.F.SilkS]
Enabled=1
[pcbnew/Layer.B.Mask]
Enabled=1
[pcbnew/Layer.F.Mask]
Enabled=1
[pcbnew/Layer.Dwgs.User]
Enabled=1
[pcbnew/Layer.Cmts.User]
Enabled=1
[pcbnew/Layer.Eco1.User]
Enabled=1
[pcbnew/Layer.Eco2.User]
Enabled=1
[pcbnew/Layer.Edge.Cuts]
Enabled=1
[pcbnew/Layer.Margin]
Enabled=1
[pcbnew/Layer.B.CrtYd]
Enabled=1
[pcbnew/Layer.F.CrtYd]
Enabled=1
[pcbnew/Layer.B.Fab]
Enabled=1
[pcbnew/Layer.F.Fab]
Enabled=1
[pcbnew/Layer.Rescue]
Enabled=0
[pcbnew/Netclasses]
[pcbnew/Netclasses/Default]
Name=Default
Clearance=0.2
TrackWidth=0.25
ViaDiameter=0.8
ViaDrill=0.4
uViaDiameter=0.3
uViaDrill=0.1
dPairWidth=0.2
dPairGap=0.25
dPairViaGap=0.25

View File

@ -0,0 +1,309 @@
EESchema Schematic File Version 4
EELAYER 30 0
EELAYER END
$Descr A4 11693 8268
encoding utf-8
Sheet 1 1
Title ""
Date ""
Rev ""
Comp ""
Comment1 ""
Comment2 ""
Comment3 ""
Comment4 ""
$EndDescr
$Comp
L Isolator:PC817 U1
U 1 1 5EEF4BBD
P 1500 1200
F 0 "U1" H 1500 1500 50 0000 C CNN
F 1 "PC817" H 1500 1400 50 0000 C CNN
F 2 "Package_DIP:DIP-4_W7.62mm" H 1300 1000 50 0001 L CIN
F 3 "http://www.soselectronic.cz/a_info/resource/d/pc817.pdf" H 1500 1200 50 0001 L CNN
1 1500 1200
1 0 0 -1
$EndComp
Text Label 2000 1100 0 50 ~ 0
UART2_RX
Wire Wire Line
1800 1100 1850 1100
$Comp
L Device:R R2
U 1 1 5EEF5E00
P 1850 950
F 0 "R2" H 1920 996 50 0000 L CNN
F 1 "330" H 1920 905 50 0000 L CNN
F 2 "Resistor_SMD:R_1206_3216Metric_Pad1.42x1.75mm_HandSolder" V 1780 950 50 0001 C CNN
F 3 "~" H 1850 950 50 0001 C CNN
1 1850 950
1 0 0 -1
$EndComp
Connection ~ 1850 1100
Wire Wire Line
1850 1100 2000 1100
$Comp
L power:+3V3 #PWR0101
U 1 1 5EEF6392
P 1850 800
F 0 "#PWR0101" H 1850 650 50 0001 C CNN
F 1 "+3V3" H 1865 973 50 0000 C CNN
F 2 "" H 1850 800 50 0001 C CNN
F 3 "" H 1850 800 50 0001 C CNN
1 1850 800
1 0 0 -1
$EndComp
$Comp
L power:GND #PWR0102
U 1 1 5EEF698C
P 1800 1300
F 0 "#PWR0102" H 1800 1050 50 0001 C CNN
F 1 "GND" V 1805 1172 50 0000 R CNN
F 2 "" H 1800 1300 50 0001 C CNN
F 3 "" H 1800 1300 50 0001 C CNN
1 1800 1300
0 -1 -1 0
$EndComp
$Comp
L Isolator:PC817 U2
U 1 1 5EEF8932
P 1500 1950
F 0 "U2" H 1500 1633 50 0000 C CNN
F 1 "PC817" H 1500 1724 50 0000 C CNN
F 2 "Package_DIP:DIP-4_W7.62mm" H 1300 1750 50 0001 L CIN
F 3 "http://www.soselectronic.cz/a_info/resource/d/pc817.pdf" H 1500 1950 50 0001 L CNN
1 1500 1950
-1 0 0 1
$EndComp
$Comp
L Device:R R3
U 1 1 5EEF8B9E
P 1950 2050
F 0 "R3" V 1743 2050 50 0000 C CNN
F 1 "330" V 1834 2050 50 0000 C CNN
F 2 "Resistor_SMD:R_1206_3216Metric_Pad1.42x1.75mm_HandSolder" V 1880 2050 50 0001 C CNN
F 3 "~" H 1950 2050 50 0001 C CNN
1 1950 2050
0 1 1 0
$EndComp
$Comp
L power:+3V3 #PWR0103
U 1 1 5EEF92CE
P 2100 2050
F 0 "#PWR0103" H 2100 1900 50 0001 C CNN
F 1 "+3V3" V 2115 2178 50 0000 L CNN
F 2 "" H 2100 2050 50 0001 C CNN
F 3 "" H 2100 2050 50 0001 C CNN
1 2100 2050
0 1 1 0
$EndComp
Text Label 2050 1850 0 50 ~ 0
UART2_TX
Wire Wire Line
1800 1850 2050 1850
Text Label 1200 2050 2 50 ~ 0
MDB_TX
Text Label 1200 1100 2 50 ~ 0
MDB_RX
$Comp
L Device:R R1
U 1 1 5EEFA474
P 1050 1300
F 0 "R1" V 1257 1300 50 0000 C CNN
F 1 "470" V 1166 1300 50 0000 C CNN
F 2 "Resistor_SMD:R_1206_3216Metric_Pad1.42x1.75mm_HandSolder" V 980 1300 50 0001 C CNN
F 3 "~" H 1050 1300 50 0001 C CNN
1 1050 1300
0 -1 -1 0
$EndComp
$Comp
L YAAJ_STM32:BluePill_1 BP?1
U 1 1 5EEFB3BF
P 4150 1500
F 0 "BP?1" H 4725 1675 50 0000 C CNN
F 1 "BluePill_1" H 4725 1584 50 0000 C CNN
F 2 "Modules:YAAJ_BluePill" H 5400 -450 50 0001 C CNN
F 3 "" H 5400 -450 50 0001 C CNN
1 4150 1500
1 0 0 -1
$EndComp
Text Label 5500 2850 0 50 ~ 0
UART2_TX
Text Label 5500 2750 0 50 ~ 0
UART2_RX
$Comp
L power:GND #PWR0104
U 1 1 5EEFF1CD
P 5500 1550
F 0 "#PWR0104" H 5500 1300 50 0001 C CNN
F 1 "GND" V 5505 1422 50 0000 R CNN
F 2 "" H 5500 1550 50 0001 C CNN
F 3 "" H 5500 1550 50 0001 C CNN
1 5500 1550
0 -1 -1 0
$EndComp
$Comp
L power:GND #PWR0105
U 1 1 5EEFF592
P 5500 1650
F 0 "#PWR0105" H 5500 1400 50 0001 C CNN
F 1 "GND" V 5505 1522 50 0000 R CNN
F 2 "" H 5500 1650 50 0001 C CNN
F 3 "" H 5500 1650 50 0001 C CNN
1 5500 1650
0 -1 -1 0
$EndComp
$Comp
L power:+3V3 #PWR0106
U 1 1 5EEFF9C7
P 5500 1750
F 0 "#PWR0106" H 5500 1600 50 0001 C CNN
F 1 "+3V3" V 5515 1878 50 0000 L CNN
F 2 "" H 5500 1750 50 0001 C CNN
F 3 "" H 5500 1750 50 0001 C CNN
1 5500 1750
0 1 1 0
$EndComp
$Comp
L power:+3V3 #PWR0107
U 1 1 5EEFFFB4
P 3950 3450
F 0 "#PWR0107" H 3950 3300 50 0001 C CNN
F 1 "+3V3" V 3965 3578 50 0000 L CNN
F 2 "" H 3950 3450 50 0001 C CNN
F 3 "" H 3950 3450 50 0001 C CNN
1 3950 3450
0 -1 -1 0
$EndComp
$Comp
L power:GND #PWR0108
U 1 1 5EF00B58
P 3950 3350
F 0 "#PWR0108" H 3950 3100 50 0001 C CNN
F 1 "GND" V 3955 3222 50 0000 R CNN
F 2 "" H 3950 3350 50 0001 C CNN
F 3 "" H 3950 3350 50 0001 C CNN
1 3950 3350
0 1 1 0
$EndComp
$Comp
L Connector_Generic:Conn_02x03_Top_Bottom J2
U 1 1 5EF0784E
P 1550 3400
F 0 "J2" H 1600 3075 50 0000 C CNN
F 1 "Conn_02x03_Top_Bottom" H 1600 3166 50 0000 C CNN
F 2 "Connector_Molex:Molex_Mini-Fit_Jr_5569-06A2_2x03_P4.20mm_Horizontal" H 1550 3400 50 0001 C CNN
F 3 "~" H 1550 3400 50 0001 C CNN
1 1550 3400
-1 0 0 1
$EndComp
$Comp
L Connector:Screw_Terminal_01x02 J1
U 1 1 5EF0A49F
P 1500 4100
F 0 "J1" H 1418 3775 50 0000 C CNN
F 1 "Screw_Terminal_01x02" H 1418 3866 50 0000 C CNN
F 2 "TerminalBlock:TerminalBlock_bornier-2_P5.08mm" H 1500 4100 50 0001 C CNN
F 3 "~" H 1500 4100 50 0001 C CNN
1 1500 4100
-1 0 0 1
$EndComp
$Comp
L power:GNDPWR #PWR0109
U 1 1 5EF0B421
P 1750 3400
F 0 "#PWR0109" H 1750 3200 50 0001 C CNN
F 1 "GNDPWR" V 1755 3292 50 0000 R CNN
F 2 "" H 1750 3350 50 0001 C CNN
F 3 "" H 1750 3350 50 0001 C CNN
1 1750 3400
0 -1 -1 0
$EndComp
$Comp
L power:VBUS #PWR0110
U 1 1 5EF0C13C
P 1750 3500
F 0 "#PWR0110" H 1750 3350 50 0001 C CNN
F 1 "VBUS" V 1765 3628 50 0000 L CNN
F 2 "" H 1750 3500 50 0001 C CNN
F 3 "" H 1750 3500 50 0001 C CNN
1 1750 3500
0 1 1 0
$EndComp
NoConn ~ 1750 3300
$Comp
L power:VBUS #PWR0111
U 1 1 5EF0CD85
P 1700 4100
F 0 "#PWR0111" H 1700 3950 50 0001 C CNN
F 1 "VBUS" V 1715 4228 50 0000 L CNN
F 2 "" H 1700 4100 50 0001 C CNN
F 3 "" H 1700 4100 50 0001 C CNN
1 1700 4100
0 1 1 0
$EndComp
$Comp
L power:GNDPWR #PWR0112
U 1 1 5EF0D2D4
P 1700 4000
F 0 "#PWR0112" H 1700 3800 50 0001 C CNN
F 1 "GNDPWR" V 1705 3892 50 0000 R CNN
F 2 "" H 1700 3950 50 0001 C CNN
F 3 "" H 1700 3950 50 0001 C CNN
1 1700 4000
0 -1 -1 0
$EndComp
Text Label 1250 3500 2 50 ~ 0
MDB_TX
Text Label 1250 3400 2 50 ~ 0
MDB_RX
Text Label 1250 3300 2 50 ~ 0
MDB_GND
Text Label 1200 1850 2 50 ~ 0
MDB_GND
Text Label 900 1300 2 50 ~ 0
MDB_GND
$Comp
L Connector:Conn_01x03_Male J4
U 1 1 5EF18300
P 2700 1550
F 0 "J4" H 2672 1482 50 0000 R CNN
F 1 "Conn_01x03_Male" H 2672 1573 50 0000 R CNN
F 2 "Connector_PinHeader_2.54mm:PinHeader_1x03_P2.54mm_Vertical" H 2700 1550 50 0001 C CNN
F 3 "~" H 2700 1550 50 0001 C CNN
1 2700 1550
1 0 0 -1
$EndComp
$Comp
L power:GND #PWR0113
U 1 1 5EF1A6CC
P 2900 1450
F 0 "#PWR0113" H 2900 1200 50 0001 C CNN
F 1 "GND" V 2905 1322 50 0000 R CNN
F 2 "" H 2900 1450 50 0001 C CNN
F 3 "" H 2900 1450 50 0001 C CNN
1 2900 1450
0 -1 -1 0
$EndComp
Text Label 2900 1550 0 50 ~ 0
UART2_TX
$Comp
L Connector:Conn_01x03_Male J3
U 1 1 5EF1D31D
P 2650 3750
F 0 "J3" H 2758 4031 50 0000 C CNN
F 1 "Conn_01x03_Male" H 2758 3940 50 0000 C CNN
F 2 "Connector_PinHeader_2.54mm:PinHeader_1x03_P2.54mm_Vertical" H 2650 3750 50 0001 C CNN
F 3 "~" H 2650 3750 50 0001 C CNN
1 2650 3750
1 0 0 -1
$EndComp
Text Label 2850 3650 0 50 ~ 0
MDB_GND
Text Label 2850 3850 0 50 ~ 0
MDB_RX
Text Label 2850 3750 0 50 ~ 0
MDB_TX
Text Label 2900 1650 0 50 ~ 0
UART2_RX
$EndSCHEMATC

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,3 @@
(fp_lib_table
(lib (name Modules)(type KiCad)(uri ${KIPRJMOD}/Kicad-STM32/Modules)(options "")(descr ""))
)

View File

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