mirror of
https://github.com/eddyem/stm32samples.git
synced 2025-12-06 10:45:11 +03:00
Add pre-alpha version of Socket_fans code
This commit is contained in:
parent
3eb48d381d
commit
325898bc52
147
F0-nolib/Socket_fans/Makefile
Normal file
147
F0-nolib/Socket_fans/Makefile
Normal file
@ -0,0 +1,147 @@
|
||||
BINARY = sockfans
|
||||
BOOTPORT ?= /dev/ttyUSB0
|
||||
BOOTSPEED ?= 57600
|
||||
# MCU FAMILY
|
||||
FAMILY = F0
|
||||
# MCU code
|
||||
MCU = F072xB
|
||||
# hardware definitions
|
||||
#DEFS += -DEBUG
|
||||
# change this linking script depending on particular MCU model,
|
||||
# for example, if you have STM32F103VBT6, you should write:
|
||||
LDSCRIPT = stm32f0728.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)/Fx -I$(INC_DIR)/cm
|
||||
LIB_DIR := $(INC_DIR)/ld
|
||||
|
||||
###############################################################################
|
||||
# C flags
|
||||
CFLAGS += -O2 -g -MD -D__thumb2__=1
|
||||
CFLAGS += -Wall -Werror -Wextra -Wshadow -Wimplicit-function-declaration
|
||||
CFLAGS += -Wredundant-decls $(INCLUDE)
|
||||
# -Wmissing-prototypes -Wstrict-prototypes
|
||||
CFLAGS += -fno-common -ffunction-sections -fdata-sections
|
||||
|
||||
###############################################################################
|
||||
# Linker flags
|
||||
LDFLAGS += --static -nostartfiles
|
||||
#--specs=nano.specs
|
||||
LDFLAGS += -L$(LIB_DIR)
|
||||
LDFLAGS += -T$(LDSCRIPT)
|
||||
LDFLAGS += -Wl,-Map=$(OBJDIR)/$(BINARY).map
|
||||
LDFLAGS += -Wl,--gc-sections
|
||||
|
||||
###############################################################################
|
||||
# Used libraries
|
||||
LDLIBS += -Wl,--start-group -lc -lgcc -Wl,--end-group
|
||||
LDLIBS += $(shell $(CC) $(CFLAGS) -print-libgcc-file-name)
|
||||
|
||||
DEFS += -DSTM32$(FAMILY) -DSTM32$(MCU)
|
||||
|
||||
#.SUFFIXES: .elf .bin .hex .srec .list .map .images
|
||||
#.SECONDEXPANSION:
|
||||
#.SECONDARY:
|
||||
|
||||
ELF := $(OBJDIR)/$(BINARY).elf
|
||||
LIST := $(OBJDIR)/$(BINARY).list
|
||||
BIN := $(BINARY).bin
|
||||
HEX := $(BINARY).hex
|
||||
|
||||
all: bin list
|
||||
|
||||
elf: $(ELF)
|
||||
bin: $(BIN)
|
||||
hex: $(HEX)
|
||||
list: $(LIST)
|
||||
|
||||
ifneq ($(MAKECMDGOALS),clean)
|
||||
-include $(DEPS)
|
||||
endif
|
||||
|
||||
$(OBJDIR):
|
||||
mkdir $(OBJDIR)
|
||||
|
||||
$(STARTUP): $(INC_DIR)/startup/vector.c
|
||||
$(CC) $(CFLAGS) $(DEFS) $(INCLUDE) $(ARCH_FLAGS) -o $@ -c $<
|
||||
|
||||
$(OBJDIR)/%.o: %.c
|
||||
@echo " CC $<"
|
||||
$(CC) $(CFLAGS) $(DEFS) $(INCLUDE) $(ARCH_FLAGS) -o $@ -c $<
|
||||
|
||||
#$(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 *.d
|
||||
@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 gentags
|
||||
@ -1,5 +1,5 @@
|
||||
# PWM fan control
|
||||
|
||||
Control of 2 4-pin & 1 2-pin 12V fans according to 4 thermal sensors.
|
||||
Turn on/off two ~220V channels (normally opened).
|
||||
Turn on/off one ~220V channels (normally opened).
|
||||
Buzzer signal.
|
||||
|
||||
138
F0-nolib/Socket_fans/adc.c
Normal file
138
F0-nolib/Socket_fans/adc.c
Normal file
@ -0,0 +1,138 @@
|
||||
/*
|
||||
* This file is part of the Chiller project.
|
||||
* Copyright 2018 Edward V. Emelianov <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 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include "adc.h"
|
||||
|
||||
/**
|
||||
* @brief ADC_array - array for ADC channels with median filtering:
|
||||
* 0..3 - external NTC
|
||||
* 4 - ext 12V
|
||||
* 5 - ext 5V
|
||||
* 6 - internal Tsens
|
||||
* 7 - Vref
|
||||
*/
|
||||
uint16_t ADC_array[NUMBER_OF_ADC_CHANNELS*9];
|
||||
|
||||
/**
|
||||
* @brief getADCval - calculate median value for `nch` channel
|
||||
* @param nch - number of channel
|
||||
* @return
|
||||
*/
|
||||
uint16_t getADCval(int nch){
|
||||
int i, addr = nch;
|
||||
register uint16_t temp;
|
||||
#define PIX_SORT(a,b) { if ((a)>(b)) PIX_SWAP((a),(b)); }
|
||||
#define PIX_SWAP(a,b) { temp=(a);(a)=(b);(b)=temp; }
|
||||
uint16_t p[9];
|
||||
for(i = 0; i < 9; ++i, addr += NUMBER_OF_ADC_CHANNELS) // first we should prepare array for optmed
|
||||
p[i] = ADC_array[addr];
|
||||
PIX_SORT(p[1], p[2]) ; PIX_SORT(p[4], p[5]) ; PIX_SORT(p[7], p[8]) ;
|
||||
PIX_SORT(p[0], p[1]) ; PIX_SORT(p[3], p[4]) ; PIX_SORT(p[6], p[7]) ;
|
||||
PIX_SORT(p[1], p[2]) ; PIX_SORT(p[4], p[5]) ; PIX_SORT(p[7], p[8]) ;
|
||||
PIX_SORT(p[0], p[3]) ; PIX_SORT(p[5], p[8]) ; PIX_SORT(p[4], p[7]) ;
|
||||
PIX_SORT(p[3], p[6]) ; PIX_SORT(p[1], p[4]) ; PIX_SORT(p[2], p[5]) ;
|
||||
PIX_SORT(p[4], p[7]) ; PIX_SORT(p[4], p[2]) ; PIX_SORT(p[6], p[4]) ;
|
||||
PIX_SORT(p[4], p[2]) ;
|
||||
return p[4];
|
||||
#undef PIX_SORT
|
||||
#undef PIX_SWAP
|
||||
}
|
||||
|
||||
// return MCU temperature (degrees of celsius * 10)
|
||||
int32_t getMCUtemp(){
|
||||
// getVdd();
|
||||
// make correction on Vdd value
|
||||
// int32_t temperature = (int32_t)ADC_array[4] * VddValue / 330;
|
||||
int32_t ADval = getADCval(6);
|
||||
int32_t temperature = (int32_t) *TEMP30_CAL_ADDR - ADval;
|
||||
temperature *= (int32_t)(1100 - 300);
|
||||
temperature /= (int32_t)(*TEMP30_CAL_ADDR - *TEMP110_CAL_ADDR);
|
||||
temperature += 300;
|
||||
return(temperature);
|
||||
}
|
||||
|
||||
// return Vdd * 100 (V)
|
||||
uint32_t getVdd(){
|
||||
uint32_t vdd = ((uint32_t) *VREFINT_CAL_ADDR) * (uint32_t)330; // 3.3V
|
||||
vdd /= getADCval(7);
|
||||
return vdd;
|
||||
}
|
||||
|
||||
// convert ADU into Volts (*100)
|
||||
static inline uint32_t Ufromadu(uint8_t nch){
|
||||
uint32_t ADU = getADCval(nch);
|
||||
ADU *= getVdd();
|
||||
ADU >>= 12; // /4096
|
||||
return ADU;
|
||||
}
|
||||
|
||||
// get 12V (*100)
|
||||
uint32_t getU12(){
|
||||
uint32_t V = Ufromadu(4) * 493;
|
||||
return V / 100;
|
||||
}
|
||||
|
||||
// get 5V (*100)
|
||||
uint32_t getU5(){
|
||||
return Ufromadu(5) * 2;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief getNTC - return temperature of NTC (*10 degrC)
|
||||
* @param nch - NTC channel number (0..3)
|
||||
* @return
|
||||
*/
|
||||
int16_t getNTC(int nch){
|
||||
#define NKNOTS (9)
|
||||
const int16_t ADU[NKNOTS] = {427, 468, 514, 623, 754, 910, 1087, 1295, 1538};
|
||||
const int16_t T[NKNOTS] = {-200, -180, -159, -116, -72, -26, 23, 75, 132};
|
||||
/*
|
||||
* coefficients: 0.050477 0.045107 0.039150 0.033639 0.029785 0.027017 0.024996 0.023522 0.022514
|
||||
* use
|
||||
* [N D] = rat(K*10); printf("%d, ", N); printf("%d, ", D);
|
||||
*/
|
||||
const int16_t N[NKNOTS] = {1377, 295, 258, 110, 291, 77, 1657, 191, 120};
|
||||
const int16_t D[NKNOTS] = {2728, 654, 659, 327, 977, 285, 6629, 812, 533};
|
||||
|
||||
if(nch < 0 || nch > 3) return -30000;
|
||||
uint16_t val = getADCval(nch);
|
||||
// find interval
|
||||
int idx = (NKNOTS+1)/2; // middle
|
||||
while(idx > 0 && idx < NKNOTS){
|
||||
int16_t left = ADU[idx];
|
||||
int half = idx / 2;
|
||||
if(val < left){
|
||||
if(idx == 0) break;
|
||||
if(val > ADU[idx-1]){ // found
|
||||
--idx;
|
||||
break;
|
||||
}
|
||||
idx = half;
|
||||
}else{
|
||||
if(idx == NKNOTS - 1) break; // more than max value
|
||||
if(val < ADU[idx+1]) break; // found
|
||||
idx += half;
|
||||
}
|
||||
}
|
||||
if(idx < 0) idx = 0;
|
||||
else if(idx > NKNOTS-1) idx = NKNOTS - 1;
|
||||
// T = Y0(idx) + K(idx) * (ADU - X0(idx));
|
||||
int16_t valT = T[idx] + (N[idx]*(val - ADU[idx]))/D[idx];
|
||||
#undef NKNOTS
|
||||
return valT;
|
||||
}
|
||||
33
F0-nolib/Socket_fans/adc.h
Normal file
33
F0-nolib/Socket_fans/adc.h
Normal file
@ -0,0 +1,33 @@
|
||||
/*
|
||||
* This file is part of the Chiller project.
|
||||
* Copyright 2018 Edward V. Emelianov <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 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
#ifndef ADC_H
|
||||
#define ADC_H
|
||||
#include "stm32f0.h"
|
||||
|
||||
// 6 channels + vref + Tmcu
|
||||
#define NUMBER_OF_ADC_CHANNELS (8)
|
||||
|
||||
extern uint16_t ADC_array[];
|
||||
int32_t getMCUtemp();
|
||||
uint32_t getVdd();
|
||||
uint16_t getADCval(int nch);
|
||||
int16_t getNTC(int nch);
|
||||
uint32_t getU12();
|
||||
uint32_t getU5();
|
||||
|
||||
#endif // ADC_H
|
||||
194
F0-nolib/Socket_fans/hardware.c
Normal file
194
F0-nolib/Socket_fans/hardware.c
Normal file
@ -0,0 +1,194 @@
|
||||
/*
|
||||
* 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 "adc.h"
|
||||
#include "hardware.h"
|
||||
|
||||
uint8_t ledsON = 0;
|
||||
|
||||
void adc_setup(){
|
||||
uint16_t ctr = 0; // 0xfff0 - more than 1.3ms
|
||||
ADC1->CR &= ~ADC_CR_ADEN;
|
||||
DMA1_Channel1->CCR &= ~DMA_CCR_EN;
|
||||
RCC->APB2ENR |= RCC_APB2ENR_ADC1EN; // Enable the peripheral clock of the ADC
|
||||
RCC->CR2 |= RCC_CR2_HSI14ON; // Start HSI14 RC oscillator
|
||||
while ((RCC->CR2 & RCC_CR2_HSI14RDY) == 0 && ++ctr < 0xfff0){}; // Wait HSI14 is ready
|
||||
// calibration
|
||||
if(ADC1->CR & ADC_CR_ADEN){ // Ensure that ADEN = 0
|
||||
ADC1->CR &= (uint32_t)(~ADC_CR_ADEN); // Clear ADEN
|
||||
}
|
||||
ADC1->CR |= ADC_CR_ADCAL; // Launch the calibration by setting ADCAL
|
||||
ctr = 0; // ADC calibration time is 5.9us
|
||||
while(ADC1->CR & ADC_CR_ADCAL && ++ctr < 0xfff0); // Wait until ADCAL=0
|
||||
// enable ADC
|
||||
ctr = 0;
|
||||
do{
|
||||
ADC1->CR |= ADC_CR_ADEN;
|
||||
}while((ADC1->ISR & ADC_ISR_ADRDY) == 0 && ++ctr < 0xfff0);
|
||||
// configure ADC
|
||||
ADC1->CFGR1 |= ADC_CFGR1_CONT; // Select the continuous mode
|
||||
ADC1->CHSELR = ADC_CHSELR_CHSEL0 | ADC_CHSELR_CHSEL1 | ADC_CHSELR_CHSEL2 |
|
||||
ADC_CHSELR_CHSEL3 | ADC_CHSELR_CHSEL4 | ADC_CHSELR_CHSEL5 |
|
||||
ADC_CHSELR_CHSEL16 | ADC_CHSELR_CHSEL17; // Select CHSEL0..5 - ADC inputs, 16,17 - t. sensor and vref
|
||||
ADC1->SMPR |= ADC_SMPR_SMP; // Select a sampling mode of 111 i.e. 239.5 ADC clk to be greater than 17.1us
|
||||
ADC->CCR |= ADC_CCR_TSEN | ADC_CCR_VREFEN; // Wake-up the VREFINT and Temperature sensor
|
||||
// configure DMA for ADC
|
||||
RCC->AHBENR |= RCC_AHBENR_DMA1EN; // Enable the peripheral clock on DMA
|
||||
ADC1->CFGR1 |= ADC_CFGR1_DMAEN | ADC_CFGR1_DMACFG; // Enable DMA transfer on ADC and circular mode
|
||||
DMA1_Channel1->CPAR = (uint32_t) (&(ADC1->DR)); // Configure the peripheral data register address
|
||||
DMA1_Channel1->CMAR = (uint32_t)(ADC_array); // Configure the memory address
|
||||
DMA1_Channel1->CNDTR = NUMBER_OF_ADC_CHANNELS * 9; // Configure the number of DMA tranfer to be performs on DMA channel 1
|
||||
DMA1_Channel1->CCR |= DMA_CCR_MINC | DMA_CCR_MSIZE_0 | DMA_CCR_PSIZE_0 | DMA_CCR_CIRC; // Configure increment, size, interrupts and circular mode
|
||||
DMA1_Channel1->CCR |= DMA_CCR_EN; // Enable DMA Channel 1
|
||||
ADC1->CR |= ADC_CR_ADSTART; // start the ADC conversions
|
||||
}
|
||||
|
||||
|
||||
static inline void gpio_setup(void){
|
||||
RCC->AHBENR |= RCC_AHBENR_GPIOAEN | RCC_AHBENR_GPIOBEN | RCC_AHBENR_GPIOCEN;
|
||||
OFF(BUZZER); OFF(RELAY); OFF(COOLER0); OFF(COOLER1);
|
||||
// All outputs are pullups
|
||||
// PA0..5 - ADC, PA6, PA8..10 - timers (PA6, PA7 - pullup, PA7 - exti), PA14 - buzzer
|
||||
GPIOA->MODER = GPIO_MODER_MODER0_AI | GPIO_MODER_MODER1_AI |
|
||||
GPIO_MODER_MODER2_AI | GPIO_MODER_MODER3_AI |
|
||||
GPIO_MODER_MODER4_AI | GPIO_MODER_MODER5_AI |
|
||||
GPIO_MODER_MODER6_AF | GPIO_MODER_MODER8_AF |
|
||||
GPIO_MODER_MODER9_AF | GPIO_MODER_MODER10_AF|
|
||||
GPIO_MODER_MODER14_O;
|
||||
GPIOA->PUPDR = GPIO_PUPDR6_PU | GPIO_PUPDR7_PU;
|
||||
// EXTI @ PA7
|
||||
SYSCFG->EXTICR[1] = SYSCFG_EXTICR2_EXTI7_PA; // PORTA for EXTI
|
||||
EXTI->IMR = EXTI_IMR_MR7; // select pin 7
|
||||
EXTI->RTSR = EXTI_RTSR_TR7; // rising edge @ pin 7
|
||||
NVIC_EnableIRQ(EXTI4_15_IRQn); // enable interrupt
|
||||
NVIC_SetPriority(EXTI4_15_IRQn, 4); // set low priority
|
||||
// PB4/5 - cooler, PB14/15 - buttons (pullup)
|
||||
GPIOB->MODER = GPIO_MODER_MODER4_O | GPIO_MODER_MODER5_O;
|
||||
GPIOB->PUPDR = GPIO_PUPDR14_PU | GPIO_PUPDR15_PU;
|
||||
// PC13 - relay
|
||||
GPIOC->MODER = GPIO_MODER_MODER13_O;
|
||||
/* Alternate functions:
|
||||
* PA6 - TIM3_CH1 AF1
|
||||
* PA8 - TIM1_CH1 AF2
|
||||
* PA9 - TIM1_CH2 AF2
|
||||
* PA10 - TIM1_CH3 AF2
|
||||
*/
|
||||
GPIOA->AFR[0] = (1 << (6*4));
|
||||
GPIOA->AFR[1] = (2 << (0*4)) | (2 << (1*4)) | (2 << (2*4));
|
||||
}
|
||||
|
||||
static inline void timers_setup(){
|
||||
// TIM1 channels 1..3 - PWM output
|
||||
RCC->APB2ENR |= RCC_APB2ENR_TIM1EN; // enable clocking
|
||||
TIM1->PSC = 19; // F=48/20 = 2.4MHz
|
||||
TIM1->ARR = 100; // PWM frequency = 2.4/101 = 23.76kHz
|
||||
TIM1->CCR1 = 20; // near 20% PWM duty cycle
|
||||
TIM1->CCR2 = 20; // near 20% PWM duty cycle
|
||||
//TIM1->CCR3 = 20; // CCR3 is zero - should be activated on cooler3 settings
|
||||
// PWM mode 1 (OCxM = 110), preload enable
|
||||
TIM1->CCMR1 = TIM_CCMR1_OC1M_2 | TIM_CCMR1_OC1M_1 | TIM_CCMR1_OC1PE |
|
||||
TIM_CCMR1_OC2M_2 | TIM_CCMR1_OC2M_1 | TIM_CCMR1_OC2PE;
|
||||
TIM1->CCMR2 = TIM_CCMR2_OC3M_2 | TIM_CCMR2_OC3M_1 | TIM_CCMR2_OC3PE;
|
||||
TIM1->CCER = TIM_CCER_CC1E | TIM_CCER_CC2E | TIM_CCER_CC3E; // active high (CC1P=0), enable outputs
|
||||
TIM1->BDTR |= TIM_BDTR_MOE; // enable main output
|
||||
TIM1->CR1 |= TIM_CR1_CEN; // enable timer
|
||||
TIM1->EGR |= TIM_EGR_UG; // force update generation
|
||||
// TIM3 channel 1 - external counter on channel1
|
||||
RCC->APB1ENR |= RCC_APB1ENR_TIM3EN;
|
||||
TIM3->SMCR = TIM_SMCR_TS_2 | TIM_SMCR_TS_0 | TIM_SMCR_SMS; // TS=101, SMS=111 - external trigger on input1
|
||||
TIM3->CCMR1 = TIM_CCMR1_CC1S_0; // CC1 is input mapped on channel TI1
|
||||
TIM3->CR1 = TIM_CR1_CEN;
|
||||
}
|
||||
|
||||
void HW_setup(){
|
||||
gpio_setup();
|
||||
adc_setup();
|
||||
timers_setup();
|
||||
}
|
||||
|
||||
void iwdg_setup(){
|
||||
uint32_t tmout = 16000000;
|
||||
/* Enable the peripheral clock RTC */
|
||||
/* (1) Enable the LSI (40kHz) */
|
||||
/* (2) Wait while it is not ready */
|
||||
RCC->CSR |= RCC_CSR_LSION; /* (1) */
|
||||
while((RCC->CSR & RCC_CSR_LSIRDY) != RCC_CSR_LSIRDY){if(--tmout == 0) break;} /* (2) */
|
||||
/* Configure IWDG */
|
||||
/* (1) Activate IWDG (not needed if done in option bytes) */
|
||||
/* (2) Enable write access to IWDG registers */
|
||||
/* (3) Set prescaler by 64 (1.6ms for each tick) */
|
||||
/* (4) Set reload value to have a rollover each 2s */
|
||||
/* (5) Check if flags are reset */
|
||||
/* (6) Refresh counter */
|
||||
IWDG->KR = IWDG_START; /* (1) */
|
||||
IWDG->KR = IWDG_WRITE_ACCESS; /* (2) */
|
||||
IWDG->PR = IWDG_PR_PR_1; /* (3) */
|
||||
IWDG->RLR = 1250; /* (4) */
|
||||
tmout = 16000000;
|
||||
while(IWDG->SR){if(--tmout == 0) break;} /* (5) */
|
||||
IWDG->KR = IWDG_REFRESH; /* (6) */
|
||||
}
|
||||
|
||||
// pause in milliseconds for some purposes
|
||||
void pause_ms(uint32_t pause){
|
||||
uint32_t Tnxt = Tms + pause;
|
||||
while(Tms < Tnxt) nop();
|
||||
}
|
||||
|
||||
void Jump2Boot(){
|
||||
void (*SysMemBootJump)(void);
|
||||
volatile uint32_t addr = SystemMem;
|
||||
// reset systick
|
||||
SysTick->CTRL = 0;
|
||||
// reset clocks
|
||||
|
||||
RCC->APB1RSTR = RCC_APB1RSTR_CECRST | RCC_APB1RSTR_DACRST | RCC_APB1RSTR_PWRRST | RCC_APB1RSTR_CRSRST |
|
||||
RCC_APB1RSTR_CANRST | RCC_APB1RSTR_USBRST | RCC_APB1RSTR_I2C2RST | RCC_APB1RSTR_I2C1RST |
|
||||
RCC_APB1RSTR_USART4RST | RCC_APB1RSTR_USART3RST | RCC_APB1RSTR_USART2RST | RCC_APB1RSTR_SPI2RST |
|
||||
RCC_APB1RSTR_WWDGRST | RCC_APB1RSTR_TIM14RST |
|
||||
#ifdef STM32F072xB
|
||||
RCC_APB1RSTR_TIM7RST | RCC_APB1RSTR_TIM6RST |
|
||||
#endif
|
||||
RCC_APB1RSTR_TIM3RST | RCC_APB1RSTR_TIM2RST;
|
||||
RCC->APB2RSTR = RCC_APB2RSTR_DBGMCURST | RCC_APB2RSTR_TIM17RST | RCC_APB2RSTR_TIM16RST |
|
||||
#ifdef STM32F072xB
|
||||
RCC_APB2RSTR_TIM15RST |
|
||||
#endif
|
||||
RCC_APB2RSTR_USART1RST | RCC_APB2RSTR_SPI1RST | RCC_APB2RSTR_TIM1RST | RCC_APB2RSTR_ADCRST | RCC_APB2RSTR_SYSCFGRST;
|
||||
RCC->AHBRSTR = 0;
|
||||
RCC->APB1RSTR = 0;
|
||||
RCC->APB2RSTR = 0;
|
||||
// remap memory to 0 (only for STM32F0)
|
||||
SYSCFG->CFGR1 = 0x01; __DSB(); __ISB();
|
||||
SysMemBootJump = (void (*)(void)) (*((uint32_t *)(addr + 4)));
|
||||
// set main stack pointer
|
||||
__set_MSP(*((uint32_t *)addr));
|
||||
// jump to bootloader
|
||||
SysMemBootJump();
|
||||
}
|
||||
|
||||
|
||||
void exti4_15_isr(){
|
||||
EXTI->PR |= EXTI_PR_PR7; // clear pending bit
|
||||
++Cooler1RPM;
|
||||
}
|
||||
76
F0-nolib/Socket_fans/hardware.h
Normal file
76
F0-nolib/Socket_fans/hardware.h
Normal file
@ -0,0 +1,76 @@
|
||||
/*
|
||||
* 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>
|
||||
|
||||
#define SYSMEM03x 0x1FFFEC00
|
||||
#define SYSMEM04x 0x1FFFC400
|
||||
#define SYSMEM05x 0x1FFFEC00
|
||||
#define SYSMEM07x 0x1FFFC800
|
||||
#define SYSMEM09x 0x1FFFD800
|
||||
|
||||
#define SystemMem SYSMEM07x
|
||||
|
||||
|
||||
#define CONCAT(a,b) a ## b
|
||||
#define STR_HELPER(s) #s
|
||||
#define STR(s) STR_HELPER(s)
|
||||
|
||||
// Buzzer: PA14
|
||||
#define BUZZER_port GPIOA
|
||||
#define BUZZER_pin (1<<14)
|
||||
// Cooler0/1 power on/off: PB4, PB5
|
||||
#define COOLER0_port GPIOB
|
||||
#define COOLER0_pin (1<<4)
|
||||
#define COOLER1_port GPIOB
|
||||
#define COOLER1_pin (1<<5)
|
||||
// Relay: PC13
|
||||
#define RELAY_port GPIOC
|
||||
#define RELAY_pin (1<<13)
|
||||
// Buttons: PB14/15
|
||||
#define BUTTON0_port GPIOB
|
||||
#define BUTTON0_pin (1<<14)
|
||||
#define BUTTON1_port GPIOB
|
||||
#define BUTTON1_pin (1<<15)
|
||||
// common macro for getting status
|
||||
#define CHK(x) ((x ## _port->IDR & (x ## _pin)) ? 1 : 0)
|
||||
|
||||
#define ON(x) do{pin_set(x ## _port, x ## _pin);}while(0)
|
||||
#define OFF(x) do{pin_clear(x ## _port, x ## _pin);}while(0)
|
||||
|
||||
extern volatile uint32_t Tms;
|
||||
extern volatile uint32_t Cooler0speed;
|
||||
extern volatile uint32_t Cooler1speed;
|
||||
extern volatile uint32_t Cooler1RPM;
|
||||
extern uint8_t ledsON;
|
||||
|
||||
void HW_setup(void);
|
||||
void adc_setup();
|
||||
void iwdg_setup();
|
||||
void pause_ms(uint32_t pause);
|
||||
void Jump2Boot();
|
||||
|
||||
#endif // __HARDWARE_H__
|
||||
File diff suppressed because it is too large
Load Diff
4051
F0-nolib/Socket_fans/kicad/pcb/stm32-B_Cu.gbr
Normal file
4051
F0-nolib/Socket_fans/kicad/pcb/stm32-B_Cu.gbr
Normal file
File diff suppressed because it is too large
Load Diff
169
F0-nolib/Socket_fans/kicad/pcb/stm32-B_Mask.gbr
Normal file
169
F0-nolib/Socket_fans/kicad/pcb/stm32-B_Mask.gbr
Normal file
@ -0,0 +1,169 @@
|
||||
G04 #@! TF.GenerationSoftware,KiCad,Pcbnew,5.1.6*
|
||||
G04 #@! TF.CreationDate,2020-10-24T20:22:56+03:00*
|
||||
G04 #@! TF.ProjectId,stm32,73746d33-322e-46b6-9963-61645f706362,rev?*
|
||||
G04 #@! TF.SameCoordinates,Original*
|
||||
G04 #@! TF.FileFunction,Soldermask,Bot*
|
||||
G04 #@! TF.FilePolarity,Negative*
|
||||
%FSLAX46Y46*%
|
||||
G04 Gerber Fmt 4.6, Leading zero omitted, Abs format (unit mm)*
|
||||
G04 Created by KiCad (PCBNEW 5.1.6) date 2020-10-24 20:22:56*
|
||||
%MOMM*%
|
||||
%LPD*%
|
||||
G01*
|
||||
G04 APERTURE LIST*
|
||||
G04 #@! TA.AperFunction,Profile*
|
||||
%ADD10C,0.150000*%
|
||||
G04 #@! TD*
|
||||
%ADD11R,2.130000X2.430000*%
|
||||
%ADD12O,2.130000X2.430000*%
|
||||
%ADD13R,3.000000X3.000000*%
|
||||
%ADD14C,3.000000*%
|
||||
%ADD15R,2.100000X2.100000*%
|
||||
%ADD16O,2.100000X2.100000*%
|
||||
%ADD17O,2.100000X2.400000*%
|
||||
%ADD18C,3.400000*%
|
||||
%ADD19C,2.900000*%
|
||||
%ADD20C,2.100000*%
|
||||
%ADD21C,3.900000*%
|
||||
%ADD22C,3.600000*%
|
||||
%ADD23R,2.400000X2.305000*%
|
||||
%ADD24O,2.400000X2.305000*%
|
||||
%ADD25R,2.000000X2.000000*%
|
||||
%ADD26C,2.000000*%
|
||||
G04 APERTURE END LIST*
|
||||
D10*
|
||||
X38000000Y-104500000D02*
|
||||
X38000000Y-52000000D01*
|
||||
X113500000Y-104500000D02*
|
||||
X38000000Y-104500000D01*
|
||||
X113500000Y-52000000D02*
|
||||
X113500000Y-104500000D01*
|
||||
X38000000Y-52000000D02*
|
||||
X113500000Y-52000000D01*
|
||||
D11*
|
||||
X94500000Y-56000000D03*
|
||||
D12*
|
||||
X97040000Y-56000000D03*
|
||||
X99580000Y-56000000D03*
|
||||
X102120000Y-56000000D03*
|
||||
X86620000Y-56000000D03*
|
||||
X84080000Y-56000000D03*
|
||||
X81540000Y-56000000D03*
|
||||
D11*
|
||||
X79000000Y-56000000D03*
|
||||
D13*
|
||||
X52000000Y-98500000D03*
|
||||
D14*
|
||||
X57000000Y-98500000D03*
|
||||
D15*
|
||||
X74602000Y-98255500D03*
|
||||
D16*
|
||||
X74602000Y-100795500D03*
|
||||
X72062000Y-98255500D03*
|
||||
X72062000Y-100795500D03*
|
||||
X69522000Y-98255500D03*
|
||||
X69522000Y-100795500D03*
|
||||
X66982000Y-98255500D03*
|
||||
X66982000Y-100795500D03*
|
||||
D17*
|
||||
X109000000Y-68500000D03*
|
||||
G36*
|
||||
G01*
|
||||
X105450000Y-69391177D02*
|
||||
X105450000Y-67608823D01*
|
||||
G75*
|
||||
G02*
|
||||
X105758823Y-67300000I308823J0D01*
|
||||
G01*
|
||||
X107241177Y-67300000D01*
|
||||
G75*
|
||||
G02*
|
||||
X107550000Y-67608823I0J-308823D01*
|
||||
G01*
|
||||
X107550000Y-69391177D01*
|
||||
G75*
|
||||
G02*
|
||||
X107241177Y-69700000I-308823J0D01*
|
||||
G01*
|
||||
X105758823Y-69700000D01*
|
||||
G75*
|
||||
G02*
|
||||
X105450000Y-69391177I0J308823D01*
|
||||
G01*
|
||||
G37*
|
||||
G36*
|
||||
G01*
|
||||
X65950000Y-55891177D02*
|
||||
X65950000Y-54108823D01*
|
||||
G75*
|
||||
G02*
|
||||
X66258823Y-53800000I308823J0D01*
|
||||
G01*
|
||||
X67741177Y-53800000D01*
|
||||
G75*
|
||||
G02*
|
||||
X68050000Y-54108823I0J-308823D01*
|
||||
G01*
|
||||
X68050000Y-55891177D01*
|
||||
G75*
|
||||
G02*
|
||||
X67741177Y-56200000I-308823J0D01*
|
||||
G01*
|
||||
X66258823Y-56200000D01*
|
||||
G75*
|
||||
G02*
|
||||
X65950000Y-55891177I0J308823D01*
|
||||
G01*
|
||||
G37*
|
||||
X69500000Y-55000000D03*
|
||||
D13*
|
||||
X56885500Y-58000000D03*
|
||||
D14*
|
||||
X51885500Y-58000000D03*
|
||||
D18*
|
||||
X57025200Y-74107720D03*
|
||||
D19*
|
||||
X55075200Y-68157720D03*
|
||||
D18*
|
||||
X42825200Y-68107720D03*
|
||||
X42875200Y-80157720D03*
|
||||
D19*
|
||||
X55075200Y-80157720D03*
|
||||
D15*
|
||||
X105463000Y-82063000D03*
|
||||
D20*
|
||||
X105463000Y-79563000D03*
|
||||
X107463000Y-79563000D03*
|
||||
X107463000Y-82063000D03*
|
||||
D21*
|
||||
X110173000Y-86833000D03*
|
||||
X110173000Y-74793000D03*
|
||||
D22*
|
||||
X44500000Y-100500000D03*
|
||||
X107500000Y-61000000D03*
|
||||
X44500000Y-61000000D03*
|
||||
X107500000Y-100500000D03*
|
||||
D16*
|
||||
X89588000Y-94001000D03*
|
||||
D15*
|
||||
X89588000Y-96541000D03*
|
||||
X93334500Y-96541000D03*
|
||||
D16*
|
||||
X93334500Y-94001000D03*
|
||||
D23*
|
||||
X42153500Y-88349500D03*
|
||||
D24*
|
||||
X42153500Y-90889500D03*
|
||||
X42153500Y-93429500D03*
|
||||
D15*
|
||||
X79682000Y-70950500D03*
|
||||
D16*
|
||||
X82222000Y-70950500D03*
|
||||
X71460000Y-77872000D03*
|
||||
D15*
|
||||
X74000000Y-77872000D03*
|
||||
D25*
|
||||
X63844500Y-82734000D03*
|
||||
D26*
|
||||
X63844500Y-86234000D03*
|
||||
M02*
|
||||
1604
F0-nolib/Socket_fans/kicad/pcb/stm32-B_SilkS.gbr
Normal file
1604
F0-nolib/Socket_fans/kicad/pcb/stm32-B_SilkS.gbr
Normal file
File diff suppressed because it is too large
Load Diff
14162
F0-nolib/Socket_fans/kicad/pcb/stm32-F_Cu.gbr
Normal file
14162
F0-nolib/Socket_fans/kicad/pcb/stm32-F_Cu.gbr
Normal file
File diff suppressed because it is too large
Load Diff
3919
F0-nolib/Socket_fans/kicad/pcb/stm32-F_Mask.gbr
Normal file
3919
F0-nolib/Socket_fans/kicad/pcb/stm32-F_Mask.gbr
Normal file
File diff suppressed because it is too large
Load Diff
2592
F0-nolib/Socket_fans/kicad/pcb/stm32-F_SilkS.gbr
Normal file
2592
F0-nolib/Socket_fans/kicad/pcb/stm32-F_SilkS.gbr
Normal file
File diff suppressed because it is too large
Load Diff
498
F0-nolib/Socket_fans/kicad/pcb/stm32-NPTH-drl_map.gbr
Normal file
498
F0-nolib/Socket_fans/kicad/pcb/stm32-NPTH-drl_map.gbr
Normal file
@ -0,0 +1,498 @@
|
||||
%FSLAX45Y45*%
|
||||
G04 Gerber Fmt 4.5, Leading zero omitted, Abs format (unit mm)*
|
||||
G04 Created by KiCad (PCBNEW 5.1.6) date 2020-10-24 20:22:54*
|
||||
%MOMM*%
|
||||
%LPD*%
|
||||
G01*
|
||||
G04 APERTURE LIST*
|
||||
%TA.AperFunction,Profile*%
|
||||
%ADD10C,0.150000*%
|
||||
%TD*%
|
||||
%ADD11C,0.200000*%
|
||||
%ADD12C,0.300000*%
|
||||
G04 APERTURE END LIST*
|
||||
D10*
|
||||
X3800000Y-10450000D02*
|
||||
X3800000Y-5200000D01*
|
||||
X11350000Y-10450000D02*
|
||||
X3800000Y-10450000D01*
|
||||
X11350000Y-5200000D02*
|
||||
X11350000Y-10450000D01*
|
||||
X3800000Y-5200000D02*
|
||||
X11350000Y-5200000D01*
|
||||
D11*
|
||||
X10590000Y-9890000D02*
|
||||
X10910000Y-10210000D01*
|
||||
X10910000Y-9890000D02*
|
||||
X10590000Y-10210000D01*
|
||||
X4290000Y-5940000D02*
|
||||
X4610000Y-6260000D01*
|
||||
X4610000Y-5940000D02*
|
||||
X4290000Y-6260000D01*
|
||||
X10590000Y-5940000D02*
|
||||
X10910000Y-6260000D01*
|
||||
X10910000Y-5940000D02*
|
||||
X10590000Y-6260000D01*
|
||||
X4290000Y-9890000D02*
|
||||
X4610000Y-10210000D01*
|
||||
X4610000Y-9890000D02*
|
||||
X4290000Y-10210000D01*
|
||||
D12*
|
||||
X4078928Y-10923214D02*
|
||||
X4078928Y-10623214D01*
|
||||
X4150357Y-10623214D01*
|
||||
X4193214Y-10637500D01*
|
||||
X4221786Y-10666072D01*
|
||||
X4236071Y-10694643D01*
|
||||
X4250357Y-10751786D01*
|
||||
X4250357Y-10794643D01*
|
||||
X4236071Y-10851786D01*
|
||||
X4221786Y-10880357D01*
|
||||
X4193214Y-10908929D01*
|
||||
X4150357Y-10923214D01*
|
||||
X4078928Y-10923214D01*
|
||||
X4378928Y-10923214D02*
|
||||
X4378928Y-10723214D01*
|
||||
X4378928Y-10780357D02*
|
||||
X4393214Y-10751786D01*
|
||||
X4407500Y-10737500D01*
|
||||
X4436071Y-10723214D01*
|
||||
X4464643Y-10723214D01*
|
||||
X4564643Y-10923214D02*
|
||||
X4564643Y-10723214D01*
|
||||
X4564643Y-10623214D02*
|
||||
X4550357Y-10637500D01*
|
||||
X4564643Y-10651786D01*
|
||||
X4578928Y-10637500D01*
|
||||
X4564643Y-10623214D01*
|
||||
X4564643Y-10651786D01*
|
||||
X4750357Y-10923214D02*
|
||||
X4721786Y-10908929D01*
|
||||
X4707500Y-10880357D01*
|
||||
X4707500Y-10623214D01*
|
||||
X4907500Y-10923214D02*
|
||||
X4878928Y-10908929D01*
|
||||
X4864643Y-10880357D01*
|
||||
X4864643Y-10623214D01*
|
||||
X5250357Y-10923214D02*
|
||||
X5250357Y-10623214D01*
|
||||
X5350357Y-10837500D01*
|
||||
X5450357Y-10623214D01*
|
||||
X5450357Y-10923214D01*
|
||||
X5721786Y-10923214D02*
|
||||
X5721786Y-10766072D01*
|
||||
X5707500Y-10737500D01*
|
||||
X5678928Y-10723214D01*
|
||||
X5621786Y-10723214D01*
|
||||
X5593214Y-10737500D01*
|
||||
X5721786Y-10908929D02*
|
||||
X5693214Y-10923214D01*
|
||||
X5621786Y-10923214D01*
|
||||
X5593214Y-10908929D01*
|
||||
X5578928Y-10880357D01*
|
||||
X5578928Y-10851786D01*
|
||||
X5593214Y-10823214D01*
|
||||
X5621786Y-10808929D01*
|
||||
X5693214Y-10808929D01*
|
||||
X5721786Y-10794643D01*
|
||||
X5864643Y-10723214D02*
|
||||
X5864643Y-11023214D01*
|
||||
X5864643Y-10737500D02*
|
||||
X5893214Y-10723214D01*
|
||||
X5950357Y-10723214D01*
|
||||
X5978928Y-10737500D01*
|
||||
X5993214Y-10751786D01*
|
||||
X6007500Y-10780357D01*
|
||||
X6007500Y-10866072D01*
|
||||
X5993214Y-10894643D01*
|
||||
X5978928Y-10908929D01*
|
||||
X5950357Y-10923214D01*
|
||||
X5893214Y-10923214D01*
|
||||
X5864643Y-10908929D01*
|
||||
X6136071Y-10894643D02*
|
||||
X6150357Y-10908929D01*
|
||||
X6136071Y-10923214D01*
|
||||
X6121786Y-10908929D01*
|
||||
X6136071Y-10894643D01*
|
||||
X6136071Y-10923214D01*
|
||||
X6136071Y-10737500D02*
|
||||
X6150357Y-10751786D01*
|
||||
X6136071Y-10766072D01*
|
||||
X6121786Y-10751786D01*
|
||||
X6136071Y-10737500D01*
|
||||
X6136071Y-10766072D01*
|
||||
X3472500Y-11257500D02*
|
||||
X3792500Y-11577500D01*
|
||||
X3792500Y-11257500D02*
|
||||
X3472500Y-11577500D01*
|
||||
X4050357Y-11253214D02*
|
||||
X4236071Y-11253214D01*
|
||||
X4136071Y-11367500D01*
|
||||
X4178928Y-11367500D01*
|
||||
X4207500Y-11381786D01*
|
||||
X4221786Y-11396071D01*
|
||||
X4236071Y-11424643D01*
|
||||
X4236071Y-11496071D01*
|
||||
X4221786Y-11524643D01*
|
||||
X4207500Y-11538929D01*
|
||||
X4178928Y-11553214D01*
|
||||
X4093214Y-11553214D01*
|
||||
X4064643Y-11538929D01*
|
||||
X4050357Y-11524643D01*
|
||||
X4364643Y-11524643D02*
|
||||
X4378928Y-11538929D01*
|
||||
X4364643Y-11553214D01*
|
||||
X4350357Y-11538929D01*
|
||||
X4364643Y-11524643D01*
|
||||
X4364643Y-11553214D01*
|
||||
X4493214Y-11281786D02*
|
||||
X4507500Y-11267500D01*
|
||||
X4536071Y-11253214D01*
|
||||
X4607500Y-11253214D01*
|
||||
X4636071Y-11267500D01*
|
||||
X4650357Y-11281786D01*
|
||||
X4664643Y-11310357D01*
|
||||
X4664643Y-11338929D01*
|
||||
X4650357Y-11381786D01*
|
||||
X4478928Y-11553214D01*
|
||||
X4664643Y-11553214D01*
|
||||
X4850357Y-11253214D02*
|
||||
X4878928Y-11253214D01*
|
||||
X4907500Y-11267500D01*
|
||||
X4921786Y-11281786D01*
|
||||
X4936071Y-11310357D01*
|
||||
X4950357Y-11367500D01*
|
||||
X4950357Y-11438929D01*
|
||||
X4936071Y-11496071D01*
|
||||
X4921786Y-11524643D01*
|
||||
X4907500Y-11538929D01*
|
||||
X4878928Y-11553214D01*
|
||||
X4850357Y-11553214D01*
|
||||
X4821786Y-11538929D01*
|
||||
X4807500Y-11524643D01*
|
||||
X4793214Y-11496071D01*
|
||||
X4778928Y-11438929D01*
|
||||
X4778928Y-11367500D01*
|
||||
X4793214Y-11310357D01*
|
||||
X4807500Y-11281786D01*
|
||||
X4821786Y-11267500D01*
|
||||
X4850357Y-11253214D01*
|
||||
X5078928Y-11553214D02*
|
||||
X5078928Y-11353214D01*
|
||||
X5078928Y-11381786D02*
|
||||
X5093214Y-11367500D01*
|
||||
X5121786Y-11353214D01*
|
||||
X5164643Y-11353214D01*
|
||||
X5193214Y-11367500D01*
|
||||
X5207500Y-11396071D01*
|
||||
X5207500Y-11553214D01*
|
||||
X5207500Y-11396071D02*
|
||||
X5221786Y-11367500D01*
|
||||
X5250357Y-11353214D01*
|
||||
X5293214Y-11353214D01*
|
||||
X5321786Y-11367500D01*
|
||||
X5336071Y-11396071D01*
|
||||
X5336071Y-11553214D01*
|
||||
X5478928Y-11553214D02*
|
||||
X5478928Y-11353214D01*
|
||||
X5478928Y-11381786D02*
|
||||
X5493214Y-11367500D01*
|
||||
X5521786Y-11353214D01*
|
||||
X5564643Y-11353214D01*
|
||||
X5593214Y-11367500D01*
|
||||
X5607500Y-11396071D01*
|
||||
X5607500Y-11553214D01*
|
||||
X5607500Y-11396071D02*
|
||||
X5621786Y-11367500D01*
|
||||
X5650357Y-11353214D01*
|
||||
X5693214Y-11353214D01*
|
||||
X5721786Y-11367500D01*
|
||||
X5736071Y-11396071D01*
|
||||
X5736071Y-11553214D01*
|
||||
X6321786Y-11238929D02*
|
||||
X6064643Y-11624643D01*
|
||||
X6707500Y-11253214D02*
|
||||
X6736071Y-11253214D01*
|
||||
X6764643Y-11267500D01*
|
||||
X6778928Y-11281786D01*
|
||||
X6793214Y-11310357D01*
|
||||
X6807500Y-11367500D01*
|
||||
X6807500Y-11438929D01*
|
||||
X6793214Y-11496071D01*
|
||||
X6778928Y-11524643D01*
|
||||
X6764643Y-11538929D01*
|
||||
X6736071Y-11553214D01*
|
||||
X6707500Y-11553214D01*
|
||||
X6678928Y-11538929D01*
|
||||
X6664643Y-11524643D01*
|
||||
X6650357Y-11496071D01*
|
||||
X6636071Y-11438929D01*
|
||||
X6636071Y-11367500D01*
|
||||
X6650357Y-11310357D01*
|
||||
X6664643Y-11281786D01*
|
||||
X6678928Y-11267500D01*
|
||||
X6707500Y-11253214D01*
|
||||
X6936071Y-11524643D02*
|
||||
X6950357Y-11538929D01*
|
||||
X6936071Y-11553214D01*
|
||||
X6921786Y-11538929D01*
|
||||
X6936071Y-11524643D01*
|
||||
X6936071Y-11553214D01*
|
||||
X7236071Y-11553214D02*
|
||||
X7064643Y-11553214D01*
|
||||
X7150357Y-11553214D02*
|
||||
X7150357Y-11253214D01*
|
||||
X7121786Y-11296071D01*
|
||||
X7093214Y-11324643D01*
|
||||
X7064643Y-11338929D01*
|
||||
X7350357Y-11281786D02*
|
||||
X7364643Y-11267500D01*
|
||||
X7393214Y-11253214D01*
|
||||
X7464643Y-11253214D01*
|
||||
X7493214Y-11267500D01*
|
||||
X7507500Y-11281786D01*
|
||||
X7521786Y-11310357D01*
|
||||
X7521786Y-11338929D01*
|
||||
X7507500Y-11381786D01*
|
||||
X7336071Y-11553214D01*
|
||||
X7521786Y-11553214D01*
|
||||
X7778928Y-11253214D02*
|
||||
X7721786Y-11253214D01*
|
||||
X7693214Y-11267500D01*
|
||||
X7678928Y-11281786D01*
|
||||
X7650357Y-11324643D01*
|
||||
X7636071Y-11381786D01*
|
||||
X7636071Y-11496071D01*
|
||||
X7650357Y-11524643D01*
|
||||
X7664643Y-11538929D01*
|
||||
X7693214Y-11553214D01*
|
||||
X7750357Y-11553214D01*
|
||||
X7778928Y-11538929D01*
|
||||
X7793214Y-11524643D01*
|
||||
X7807500Y-11496071D01*
|
||||
X7807500Y-11424643D01*
|
||||
X7793214Y-11396071D01*
|
||||
X7778928Y-11381786D01*
|
||||
X7750357Y-11367500D01*
|
||||
X7693214Y-11367500D01*
|
||||
X7664643Y-11381786D01*
|
||||
X7650357Y-11396071D01*
|
||||
X7636071Y-11424643D01*
|
||||
X7921786Y-11253214D02*
|
||||
X7921786Y-11310357D01*
|
||||
X8036071Y-11253214D02*
|
||||
X8036071Y-11310357D01*
|
||||
X8478928Y-11667500D02*
|
||||
X8464643Y-11653214D01*
|
||||
X8436071Y-11610357D01*
|
||||
X8421786Y-11581786D01*
|
||||
X8407500Y-11538929D01*
|
||||
X8393214Y-11467500D01*
|
||||
X8393214Y-11410357D01*
|
||||
X8407500Y-11338929D01*
|
||||
X8421786Y-11296071D01*
|
||||
X8436071Y-11267500D01*
|
||||
X8464643Y-11224643D01*
|
||||
X8478928Y-11210357D01*
|
||||
X8721786Y-11353214D02*
|
||||
X8721786Y-11553214D01*
|
||||
X8650357Y-11238929D02*
|
||||
X8578928Y-11453214D01*
|
||||
X8764643Y-11453214D01*
|
||||
X9107500Y-11553214D02*
|
||||
X9107500Y-11253214D01*
|
||||
X9236071Y-11553214D02*
|
||||
X9236071Y-11396071D01*
|
||||
X9221786Y-11367500D01*
|
||||
X9193214Y-11353214D01*
|
||||
X9150357Y-11353214D01*
|
||||
X9121786Y-11367500D01*
|
||||
X9107500Y-11381786D01*
|
||||
X9421786Y-11553214D02*
|
||||
X9393214Y-11538929D01*
|
||||
X9378928Y-11524643D01*
|
||||
X9364643Y-11496071D01*
|
||||
X9364643Y-11410357D01*
|
||||
X9378928Y-11381786D01*
|
||||
X9393214Y-11367500D01*
|
||||
X9421786Y-11353214D01*
|
||||
X9464643Y-11353214D01*
|
||||
X9493214Y-11367500D01*
|
||||
X9507500Y-11381786D01*
|
||||
X9521786Y-11410357D01*
|
||||
X9521786Y-11496071D01*
|
||||
X9507500Y-11524643D01*
|
||||
X9493214Y-11538929D01*
|
||||
X9464643Y-11553214D01*
|
||||
X9421786Y-11553214D01*
|
||||
X9693214Y-11553214D02*
|
||||
X9664643Y-11538929D01*
|
||||
X9650357Y-11510357D01*
|
||||
X9650357Y-11253214D01*
|
||||
X9921786Y-11538929D02*
|
||||
X9893214Y-11553214D01*
|
||||
X9836071Y-11553214D01*
|
||||
X9807500Y-11538929D01*
|
||||
X9793214Y-11510357D01*
|
||||
X9793214Y-11396071D01*
|
||||
X9807500Y-11367500D01*
|
||||
X9836071Y-11353214D01*
|
||||
X9893214Y-11353214D01*
|
||||
X9921786Y-11367500D01*
|
||||
X9936071Y-11396071D01*
|
||||
X9936071Y-11424643D01*
|
||||
X9793214Y-11453214D01*
|
||||
X10050357Y-11538929D02*
|
||||
X10078928Y-11553214D01*
|
||||
X10136071Y-11553214D01*
|
||||
X10164643Y-11538929D01*
|
||||
X10178928Y-11510357D01*
|
||||
X10178928Y-11496071D01*
|
||||
X10164643Y-11467500D01*
|
||||
X10136071Y-11453214D01*
|
||||
X10093214Y-11453214D01*
|
||||
X10064643Y-11438929D01*
|
||||
X10050357Y-11410357D01*
|
||||
X10050357Y-11396071D01*
|
||||
X10064643Y-11367500D01*
|
||||
X10093214Y-11353214D01*
|
||||
X10136071Y-11353214D01*
|
||||
X10164643Y-11367500D01*
|
||||
X10278928Y-11667500D02*
|
||||
X10293214Y-11653214D01*
|
||||
X10321786Y-11610357D01*
|
||||
X10336071Y-11581786D01*
|
||||
X10350357Y-11538929D01*
|
||||
X10364643Y-11467500D01*
|
||||
X10364643Y-11410357D01*
|
||||
X10350357Y-11338929D01*
|
||||
X10336071Y-11296071D01*
|
||||
X10321786Y-11267500D01*
|
||||
X10293214Y-11224643D01*
|
||||
X10278928Y-11210357D01*
|
||||
X10821786Y-11667500D02*
|
||||
X10807500Y-11653214D01*
|
||||
X10778928Y-11610357D01*
|
||||
X10764643Y-11581786D01*
|
||||
X10750357Y-11538929D01*
|
||||
X10736071Y-11467500D01*
|
||||
X10736071Y-11410357D01*
|
||||
X10750357Y-11338929D01*
|
||||
X10764643Y-11296071D01*
|
||||
X10778928Y-11267500D01*
|
||||
X10807500Y-11224643D01*
|
||||
X10821786Y-11210357D01*
|
||||
X10936071Y-11353214D02*
|
||||
X10936071Y-11553214D01*
|
||||
X10936071Y-11381786D02*
|
||||
X10950357Y-11367500D01*
|
||||
X10978928Y-11353214D01*
|
||||
X11021786Y-11353214D01*
|
||||
X11050357Y-11367500D01*
|
||||
X11064643Y-11396071D01*
|
||||
X11064643Y-11553214D01*
|
||||
X11250357Y-11553214D02*
|
||||
X11221786Y-11538929D01*
|
||||
X11207500Y-11524643D01*
|
||||
X11193214Y-11496071D01*
|
||||
X11193214Y-11410357D01*
|
||||
X11207500Y-11381786D01*
|
||||
X11221786Y-11367500D01*
|
||||
X11250357Y-11353214D01*
|
||||
X11293214Y-11353214D01*
|
||||
X11321786Y-11367500D01*
|
||||
X11336071Y-11381786D01*
|
||||
X11350357Y-11410357D01*
|
||||
X11350357Y-11496071D01*
|
||||
X11336071Y-11524643D01*
|
||||
X11321786Y-11538929D01*
|
||||
X11293214Y-11553214D01*
|
||||
X11250357Y-11553214D01*
|
||||
X11436071Y-11353214D02*
|
||||
X11550357Y-11353214D01*
|
||||
X11478928Y-11253214D02*
|
||||
X11478928Y-11510357D01*
|
||||
X11493214Y-11538929D01*
|
||||
X11521786Y-11553214D01*
|
||||
X11550357Y-11553214D01*
|
||||
X11878928Y-11353214D02*
|
||||
X11878928Y-11653214D01*
|
||||
X11878928Y-11367500D02*
|
||||
X11907500Y-11353214D01*
|
||||
X11964643Y-11353214D01*
|
||||
X11993214Y-11367500D01*
|
||||
X12007500Y-11381786D01*
|
||||
X12021786Y-11410357D01*
|
||||
X12021786Y-11496071D01*
|
||||
X12007500Y-11524643D01*
|
||||
X11993214Y-11538929D01*
|
||||
X11964643Y-11553214D01*
|
||||
X11907500Y-11553214D01*
|
||||
X11878928Y-11538929D01*
|
||||
X12193214Y-11553214D02*
|
||||
X12164643Y-11538929D01*
|
||||
X12150357Y-11510357D01*
|
||||
X12150357Y-11253214D01*
|
||||
X12436071Y-11553214D02*
|
||||
X12436071Y-11396071D01*
|
||||
X12421786Y-11367500D01*
|
||||
X12393214Y-11353214D01*
|
||||
X12336071Y-11353214D01*
|
||||
X12307500Y-11367500D01*
|
||||
X12436071Y-11538929D02*
|
||||
X12407500Y-11553214D01*
|
||||
X12336071Y-11553214D01*
|
||||
X12307500Y-11538929D01*
|
||||
X12293214Y-11510357D01*
|
||||
X12293214Y-11481786D01*
|
||||
X12307500Y-11453214D01*
|
||||
X12336071Y-11438929D01*
|
||||
X12407500Y-11438929D01*
|
||||
X12436071Y-11424643D01*
|
||||
X12536071Y-11353214D02*
|
||||
X12650357Y-11353214D01*
|
||||
X12578928Y-11253214D02*
|
||||
X12578928Y-11510357D01*
|
||||
X12593214Y-11538929D01*
|
||||
X12621786Y-11553214D01*
|
||||
X12650357Y-11553214D01*
|
||||
X12864643Y-11538929D02*
|
||||
X12836071Y-11553214D01*
|
||||
X12778928Y-11553214D01*
|
||||
X12750357Y-11538929D01*
|
||||
X12736071Y-11510357D01*
|
||||
X12736071Y-11396071D01*
|
||||
X12750357Y-11367500D01*
|
||||
X12778928Y-11353214D01*
|
||||
X12836071Y-11353214D01*
|
||||
X12864643Y-11367500D01*
|
||||
X12878928Y-11396071D01*
|
||||
X12878928Y-11424643D01*
|
||||
X12736071Y-11453214D01*
|
||||
X13136071Y-11553214D02*
|
||||
X13136071Y-11253214D01*
|
||||
X13136071Y-11538929D02*
|
||||
X13107500Y-11553214D01*
|
||||
X13050357Y-11553214D01*
|
||||
X13021786Y-11538929D01*
|
||||
X13007500Y-11524643D01*
|
||||
X12993214Y-11496071D01*
|
||||
X12993214Y-11410357D01*
|
||||
X13007500Y-11381786D01*
|
||||
X13021786Y-11367500D01*
|
||||
X13050357Y-11353214D01*
|
||||
X13107500Y-11353214D01*
|
||||
X13136071Y-11367500D01*
|
||||
X13250357Y-11667500D02*
|
||||
X13264643Y-11653214D01*
|
||||
X13293214Y-11610357D01*
|
||||
X13307500Y-11581786D01*
|
||||
X13321786Y-11538929D01*
|
||||
X13336071Y-11467500D01*
|
||||
X13336071Y-11410357D01*
|
||||
X13321786Y-11338929D01*
|
||||
X13307500Y-11296071D01*
|
||||
X13293214Y-11267500D01*
|
||||
X13264643Y-11224643D01*
|
||||
X13250357Y-11210357D01*
|
||||
M02*
|
||||
2693
F0-nolib/Socket_fans/kicad/pcb/stm32-PTH-drl_map.gbr
Normal file
2693
F0-nolib/Socket_fans/kicad/pcb/stm32-PTH-drl_map.gbr
Normal file
File diff suppressed because it is too large
Load Diff
@ -1,122 +1,138 @@
|
||||
"Source:","/home/eddy/Yandex.Disk/Projects/stm32samples/F0-nolib/CANbus_stepper/kicad/stm32.sch"
|
||||
"Date:","÷Ô 10 ÍÁÒ 2020 09:31:14"
|
||||
"Source:","/tmp/1/kicad/stm32.sch"
|
||||
"Date:","óÒ 09 ÓÅÎ 2020 12:08:32"
|
||||
"Tool:","Eeschema 5.1.4"
|
||||
"Generator:","/usr/local/share/kicad/plugins/bom_csv_grouped_by_value.py"
|
||||
"Component Count:","66"
|
||||
"Component Count:","87"
|
||||
|
||||
"Individual Components:"
|
||||
|
||||
"Item","Qty","Reference(s)","Value","LibPart","Footprint","Datasheet"
|
||||
"","","C1","0.1","Device:C","Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder",""
|
||||
"","","C2","100uF","Device:CP","Capacitor_THT:CP_Radial_D8.0mm_P3.50mm","~"
|
||||
"","","C1","0.1","stm32-rescue:C-Chiller_control-rescue","Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder",""
|
||||
"","","C2","0.1","stm32-rescue:C-Chiller_control-rescue","Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder",""
|
||||
"","","C3","0.1","Device:C","Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder",""
|
||||
"","","C4","47uF, 10V","Device:CP","Capacitor_Tantalum_SMD:CP_EIA-6032-28_Kemet-C_Pad2.25x2.35mm_HandSolder","~"
|
||||
"","","C5","0.1","Device:C","Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder",""
|
||||
"","","C6","47uF, 10V","Device:CP","Capacitor_Tantalum_SMD:CP_EIA-6032-28_Kemet-C_Pad2.25x2.35mm_HandSolder","~"
|
||||
"","","C7","0.1","Device:C","Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder",""
|
||||
"","","C4","0.1","stm32-rescue:C-Chiller_control-rescue","Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder",""
|
||||
"","","C5","0.1","stm32-rescue:C-Chiller_control-rescue","Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder",""
|
||||
"","","C6","0.1","Device:C","Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder",""
|
||||
"","","C7","47uF, 10V","Device:CP","Capacitor_Tantalum_SMD:CP_EIA-6032-28_Kemet-C_Pad2.25x2.35mm_HandSolder","~"
|
||||
"","","C8","0.1","Device:C","Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder",""
|
||||
"","","C9","0.1","Device:C","Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder",""
|
||||
"","","C10","0.1","Device:C","Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder",""
|
||||
"","","C11","0.1","Device:C","Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder",""
|
||||
"","","C12","0.1","Device:C","Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder",""
|
||||
"","","D1","MBRS130L","Device:D_Schottky","Diode_SMD:D_SMB_Handsoldering",""
|
||||
"","","D2","MBRS130L","Device:D_Schottky","Diode_SMD:D_SMB_Handsoldering",""
|
||||
"","","D3","PESD3V3L4UG","Power_Protection:PESD3V3L4UG","TO_SOT_Packages_SMD:SOT-363_SC-70-6_Handsoldering","https://assets.nexperia.com/documents/data-sheet/PESDXL4UF_G_W.pdf"
|
||||
"","","D4","PESD1CAN","elements:PESD1CAN","TO_SOT_Packages_SMD:SOT-23_Handsoldering",""
|
||||
"","","D5","MM3Z7V5","Device:D_Zener","Diode_SMD:D_0805_2012Metric_Pad1.15x1.40mm_HandSolder","~"
|
||||
"","","D6","USB6B1","Power_Protection:USB6B1","Package_SO:SOIC-8_3.9x4.9mm_P1.27mm",""
|
||||
"","","D7","MM3Z3V9","Device:D_Zener","Diode_SMD:D_0805_2012Metric_Pad1.15x1.40mm_HandSolder",""
|
||||
"","","D8","MM3Z3V9","Device:D_Zener","Diode_SMD:D_0805_2012Metric_Pad1.15x1.40mm_HandSolder",""
|
||||
"","","F1","1A","Device:Fuse","MyFootprints:FuseHolder","~"
|
||||
"","","J1","A","Connector:Screw_Terminal_01x02","TerminalBlock_Phoenix:TerminalBlock_Phoenix_MKDS-1,5-2_1x02_P5.00mm_Horizontal",""
|
||||
"","","J2","B","Connector:Screw_Terminal_01x02","TerminalBlock_Phoenix:TerminalBlock_Phoenix_MKDS-1,5-2_1x02_P5.00mm_Horizontal",""
|
||||
"","","J3","Conn_01x08_Female","Connector:Conn_01x08_Female","Connector_PinSocket_2.54mm:PinSocket_1x08_P2.54mm_Vertical","~"
|
||||
"","","J4","Conn_01x08_Female","Connector:Conn_01x08_Female","Connector_PinSocket_2.54mm:PinSocket_1x08_P2.54mm_Vertical","~"
|
||||
"","","J5","+/-","Connector:Screw_Terminal_01x02","TerminalBlock_Phoenix:TerminalBlock_Phoenix_MKDS-1,5-2_1x02_P5.00mm_Horizontal",""
|
||||
"","","J6","CONN_02X03","Switch:SW_DIP_x04","Button_Switch_THT:SW_DIP_SPSTx04_Slide_9.78x12.34mm_W7.62mm_P2.54mm",""
|
||||
"","","J7","0/1","Connector:Screw_Terminal_01x02","TerminalBlock_Phoenix:TerminalBlock_Phoenix_MKDS-1,5-2_1x02_P5.00mm_Horizontal",""
|
||||
"","","J8","2/3","Connector:Screw_Terminal_01x02","TerminalBlock_Phoenix:TerminalBlock_Phoenix_MKDS-1,5-2_1x02_P5.00mm_Horizontal",""
|
||||
"","","J9","DB9_Female","Connector:DB9_Female","Connector_Dsub:DSUB-9_Female_Horizontal_P2.77x2.84mm_EdgePinOffset4.94mm_Housed_MountingHolesOffset7.48mm",""
|
||||
"","","J10","12v","Connector:Screw_Terminal_01x02","TerminalBlock_Phoenix:TerminalBlock_Phoenix_MKDS-1,5-2_1x02_P5.00mm_Horizontal",""
|
||||
"","","J11","DB9_Male","Connector:DB9_Male","Connector_Dsub:DSUB-9_Male_Horizontal_P2.77x2.84mm_EdgePinOffset4.94mm_Housed_MountingHolesOffset7.48mm",""
|
||||
"","","J12","RS-485","Connector:Screw_Terminal_01x02","TerminalBlock_Phoenix:TerminalBlock_Phoenix_MKDS-1,5-2_1x02_P5.00mm_Horizontal",""
|
||||
"","","J13","Conn_01x06","Connector_Generic:Conn_01x06","Connector_PinSocket_2.54mm:PinSocket_1x06_P2.54mm_Vertical","~"
|
||||
"","","P1","USB_A","Connector:USB_B","Connectors_USB:USB_B_OST_USB-B1HSxx_Horizontal",""
|
||||
"","","C9","10uF, 10V","Device:C","Capacitor_SMD:C_1206_3216Metric_Pad1.42x1.75mm_HandSolder","~"
|
||||
"","","C13","0.1","Device:C","Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder",""
|
||||
"","","C14","0.1","Device:C","Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder",""
|
||||
"","","C15","0.1","Device:C","Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder",""
|
||||
"","","C16","0.1","Device:C","Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder",""
|
||||
"","","C17","0.1","Device:C","Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder",""
|
||||
"","","C18","0.1","Device:C","Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder",""
|
||||
"","","C19","0.1","Device:C","Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder",""
|
||||
"","","C20","0.1","Device:C","Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder",""
|
||||
"","","D1","1N5819","Device:D_Schottky","Diode_SMD:D_SOD-323_HandSoldering",""
|
||||
"","","D2","1N5819","Device:D_Schottky","Diode_SMD:D_SOD-323_HandSoldering",""
|
||||
"","","D3","MM3Z7V5","Device:D_Zener","Diode_SMD:D_0805_2012Metric_Pad1.15x1.40mm_HandSolder","~"
|
||||
"","","D4","1N5819","Device:D_Schottky","Diode_SMD:D_SOD-323_HandSoldering",""
|
||||
"","","D5","1N5819","Device:D_Schottky","Diode_SMD:D_SOD-323_HandSoldering",""
|
||||
"","","D6","1N5819","Device:D_Schottky","Diode_SMD:D_SOD-323_HandSoldering",""
|
||||
"","","D7","MM3Z4V7","Device:D_Zener","Diode_SMD:D_0805_2012Metric_Pad1.15x1.40mm_HandSolder",""
|
||||
"","","D8","MM3Z4V7","Device:D_Zener","Diode_SMD:D_0805_2012Metric_Pad1.15x1.40mm_HandSolder",""
|
||||
"","","D9","1N5819","Device:D_Schottky","Diode_SMD:D_SOD-323_HandSoldering",""
|
||||
"","","J1","12VIN","stm32-rescue:Conn_01x02-Chiller_control-rescue","TerminalBlock_Phoenix:TerminalBlock_Phoenix_MKDS-1,5-2_1x02_P5.00mm_Horizontal",""
|
||||
"","","J2","thermal","Connector_Generic:Conn_02x04_Odd_Even","Connector_PinSocket_2.54mm:PinSocket_2x04_P2.54mm_Vertical","~"
|
||||
"","","J3","Buzzer","Connector:Conn_01x02_Male","Connector_JST:JST_EH_B2B-EH-A_1x02_P2.50mm_Vertical","~"
|
||||
"","","J4","cooler3","Connector:Conn_01x02_Male","Connector_JST:JST_EH_B2B-EH-A_1x02_P2.50mm_Vertical","~"
|
||||
"","","J5","FAN","Connector:Conn_01x04_Male","Connector:FanPinHeader_1x04_P2.54mm_Vertical","~"
|
||||
"","","J6","FAN","Connector:Conn_01x04_Male","Connector:FanPinHeader_1x04_P2.54mm_Vertical","~"
|
||||
"","","J7","Conn_01x02_Female","Connector:Conn_01x02_Female","Connector_PinSocket_2.54mm:PinSocket_1x02_P2.54mm_Vertical","~"
|
||||
"","","J8","MKDS","Connector:Conn_01x02_Female","TerminalBlock_Phoenix:TerminalBlock_Phoenix_MKDS-1,5-2_1x02_P5.00mm_Horizontal","~"
|
||||
"","","J10","Conn_01x02_Female","Connector:Conn_01x02_Female","Connector_PinSocket_2.54mm:PinSocket_1x02_P2.54mm_Vertical","~"
|
||||
"","","K1","SRD-12VDC","stm32-rescue:G5LE-1-socket-rescue","Relay_THT:Relay_SPDT_SANYOU_SRD_Series_Form_C",""
|
||||
"","","L1","BMBA 0.1mH","stm32-rescue:L-Chiller_control-rescue","Inductor_SMD:L_0805_2012Metric_Pad1.15x1.40mm_HandSolder",""
|
||||
"","","P1","USB_A","Connector:USB_B","Connector_USB:USB_B_OST_USB-B1HSxx_Horizontal",""
|
||||
"","","P2","Hole","Connector_Generic:Conn_01x01","MountingHole:MountingHole_3.2mm_M3",""
|
||||
"","","P3","Hole","Connector_Generic:Conn_01x01","MountingHole:MountingHole_3.2mm_M3",""
|
||||
"","","P4","Hole","Connector_Generic:Conn_01x01","MountingHole:MountingHole_3.2mm_M3",""
|
||||
"","","P5","Hole","Connector_Generic:Conn_01x01","MountingHole:MountingHole_3.2mm_M3",""
|
||||
"","","Q1","SI2305","Device:Q_PMOS_GSD","TO_SOT_Packages_SMD:SOT-23_Handsoldering","~"
|
||||
"","","Q2","AO3407","Device:Q_PMOS_GSD","TO_SOT_Packages_SMD:SOT-23_Handsoldering",""
|
||||
"","","R1","330","Device:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder","~"
|
||||
"","","R2","10k","Device:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder","~"
|
||||
"","","R3","120","Device:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder","~"
|
||||
"","","R4","15k","Device:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder",""
|
||||
"","","R5","330","Device:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder","~"
|
||||
"","","R6","330","Device:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder","~"
|
||||
"","","R7","330","Device:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder","~"
|
||||
"","","R8","330","Device:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder","~"
|
||||
"","","R9","120","Device:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder",""
|
||||
"","","R10","10k","Device:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder","~"
|
||||
"","","R11","22","Device:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder",""
|
||||
"","","R12","22","Device:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder",""
|
||||
"","","R13","220k","Device:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder",""
|
||||
"","","R14","56k","Device:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder",""
|
||||
"","","R15","47k","Device:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder",""
|
||||
"","","R16","47k","Device:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder",""
|
||||
"","","R17","47k","Device:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder",""
|
||||
"","","R18","22","Device:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder","~"
|
||||
"","","SW1","SW_DIP_x01","Switch:SW_DIP_x01","Button_Switch_THT:SW_DIP_SPSTx01_Slide_6.7x4.1mm_W7.62mm_P2.54mm_LowProfile","~"
|
||||
"","","U1","ISO1050DUB","Interface_CAN_LIN:ISO1050DUB","Package_SO:SOP-8_6.62x9.15mm_P2.54mm","http://www.ti.com/lit/ds/symlink/iso1050.pdf"
|
||||
"","","U2","LM1117-5.0","Regulator_Linear:LM1117-3.3","TO_SOT_Packages_SMD:SOT-223-3_TabPin2",""
|
||||
"","","U3","LM1117-3.3","Regulator_Linear:LM1117-3.3","TO_SOT_Packages_SMD:SOT-223-3_TabPin2",""
|
||||
"","","U4","MCP2551-I/SN","Interface_CAN_LIN:MCP2551-I-SN","Package_SO:SOIC-8_3.9x4.9mm_P1.27mm",""
|
||||
"","","U5","STM32F072CBTx","MCU_ST_STM32F0:STM32F072CBTx","Package_QFP:LQFP-48_7x7mm_P0.5mm","http://www.st.com/st-web-ui/static/active/en/resource/technical/document/datasheet/DM00090510.pdf"
|
||||
"","","U6","MAX3485","Interface_UART:MAX3485","Package_SO:SO-8_3.9x4.9mm_P1.27mm","https://datasheets.maximintegrated.com/en/ds/MAX3483-MAX3491.pdf"
|
||||
"","","Q1","AO3401","Device:Q_PMOS_GSD","Package_TO_SOT_SMD:SOT-23_Handsoldering",""
|
||||
"","","Q2","IRLML2502","stm32-rescue:Q_NMOS_GSD-Chiller_control-rescue","Package_TO_SOT_SMD:SOT-23_Handsoldering",""
|
||||
"","","Q3","IRLML2502","stm32-rescue:Q_NMOS_GSD-Chiller_control-rescue","Package_TO_SOT_SMD:SOT-23_Handsoldering",""
|
||||
"","","Q4","IRLML2502","stm32-rescue:Q_NMOS_GSD-Chiller_control-rescue","Package_TO_SOT_SMD:SOT-23_Handsoldering",""
|
||||
"","","Q5","IRLML2502","stm32-rescue:Q_NMOS_GSD-Chiller_control-rescue","Package_TO_SOT_SMD:SOT-23_Handsoldering",""
|
||||
"","","Q6","IRLML2502","stm32-rescue:Q_NMOS_GSD-socket-rescue","Package_TO_SOT_SMD:SOT-23_Handsoldering",""
|
||||
"","","R1","10k","Device:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder","~"
|
||||
"","","R2","10k","stm32-rescue:R-Chiller_control-rescue","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder",""
|
||||
"","","R3","4k7, 1%","stm32-rescue:R-Chiller_control-rescue","Resistor_SMD:R_0805_2012Metric_Pad1.15x1.40mm_HandSolder",""
|
||||
"","","R4","10k","stm32-rescue:R-Chiller_control-rescue","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder",""
|
||||
"","","R5","4k7, 1%","stm32-rescue:R-Chiller_control-rescue","Resistor_SMD:R_0805_2012Metric_Pad1.15x1.40mm_HandSolder",""
|
||||
"","","R6","10k","stm32-rescue:R-Chiller_control-rescue","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder",""
|
||||
"","","R7","4k7, 1%","stm32-rescue:R-Chiller_control-rescue","Resistor_SMD:R_0805_2012Metric_Pad1.15x1.40mm_HandSolder",""
|
||||
"","","R8","10k","stm32-rescue:R-Chiller_control-rescue","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder",""
|
||||
"","","R9","4k7, 1%","stm32-rescue:R-Chiller_control-rescue","Resistor_SMD:R_0805_2012Metric_Pad1.15x1.40mm_HandSolder",""
|
||||
"","","R10","510","stm32-rescue:R-Chiller_control-rescue","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder",""
|
||||
"","","R11","510","stm32-rescue:R-Chiller_control-rescue","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder",""
|
||||
"","","R12","510","stm32-rescue:R-Chiller_control-rescue","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder",""
|
||||
"","","R13","10k","stm32-rescue:R-Chiller_control-rescue","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder",""
|
||||
"","","R14","10k","stm32-rescue:R-Chiller_control-rescue","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder",""
|
||||
"","","R15","510","stm32-rescue:R-Chiller_control-rescue","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder",""
|
||||
"","","R16","10k","stm32-rescue:R-Chiller_control-rescue","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder",""
|
||||
"","","R17","10k","stm32-rescue:R-Chiller_control-rescue","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder",""
|
||||
"","","R18","510","stm32-rescue:R-Chiller_control-rescue","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder",""
|
||||
"","","R19","510","stm32-rescue:R-Chiller_control-rescue","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder",""
|
||||
"","","R20","510","stm32-rescue:R-Chiller_control-rescue","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder",""
|
||||
"","","R21","510","stm32-rescue:R-Chiller_control-rescue","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder",""
|
||||
"","","R22","47k","Device:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder",""
|
||||
"","","R23","22","Device:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder","~"
|
||||
"","","R24","510","stm32-rescue:R-Chiller_control-rescue","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder",""
|
||||
"","","R25","510","stm32-rescue:R-Chiller_control-rescue","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder",""
|
||||
"","","R26","220k","Device:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder",""
|
||||
"","","R27","56k","Device:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder",""
|
||||
"","","R28","47k","Device:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder",""
|
||||
"","","R29","47k","Device:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder",""
|
||||
"","","R30","22","Device:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder",""
|
||||
"","","R31","22","Device:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder",""
|
||||
"","","R32","510","stm32-rescue:R-socket-rescue","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder",""
|
||||
"","","R34","10k","stm32-rescue:R-socket-rescue","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder",""
|
||||
"","","SW1","SW_Push","Switch:SW_Push","Connector_PinSocket_2.54mm:PinSocket_1x02_P2.54mm_Vertical","~"
|
||||
"","","SW2","SW_Push","Switch:SW_Push","Connector_PinSocket_2.54mm:PinSocket_1x02_P2.54mm_Vertical","~"
|
||||
"","","U1","LM1117-3.3","Regulator_Linear:LM1117-3.3","Package_TO_SOT_SMD:SOT-223-3_TabPin2",""
|
||||
"","","U2","L7805","Regulator_Linear:L7805","Package_TO_SOT_THT:TO-220-3_Vertical","http://www.st.com/content/ccc/resource/technical/document/datasheet/41/4f/b3/b0/12/d4/47/88/CD00000444.pdf/files/CD00000444.pdf/jcr:content/translations/en.CD00000444.pdf"
|
||||
"","","U3","STM32F072CBTx","MCU_ST_STM32F0:STM32F072CBTx","Package_QFP:LQFP-48_7x7mm_P0.5mm","http://www.st.com/st-web-ui/static/active/en/resource/technical/document/datasheet/DM00090510.pdf"
|
||||
"","","U4","USBLC6-2SC6","Power_Protection:USBLC6-2SC6","Package_TO_SOT_SMD:SOT-23-6","http://www2.st.com/resource/en/datasheet/CD00050750.pdf"
|
||||
|
||||
|
||||
|
||||
"Collated Components:"
|
||||
|
||||
"Item","Qty","Reference(s)","Value","LibPart","Footprint","Datasheet"
|
||||
"1","9","C1, C3, C5, C7, C8, C9, C10, C11, C12","0.1","Device:C","Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder",""
|
||||
"2","1","C2","100uF","Device:CP","Capacitor_THT:CP_Radial_D8.0mm_P3.50mm","~"
|
||||
"3","2","C4, C6","47uF, 10V","Device:CP","Capacitor_Tantalum_SMD:CP_EIA-6032-28_Kemet-C_Pad2.25x2.35mm_HandSolder","~"
|
||||
"4","2","D1, D2","MBRS130L","Device:D_Schottky","Diode_SMD:D_SMB_Handsoldering",""
|
||||
"5","1","D3","PESD3V3L4UG","Power_Protection:PESD3V3L4UG","TO_SOT_Packages_SMD:SOT-363_SC-70-6_Handsoldering","https://assets.nexperia.com/documents/data-sheet/PESDXL4UF_G_W.pdf"
|
||||
"6","1","D4","PESD1CAN","elements:PESD1CAN","TO_SOT_Packages_SMD:SOT-23_Handsoldering",""
|
||||
"7","1","D5","MM3Z7V5","Device:D_Zener","Diode_SMD:D_0805_2012Metric_Pad1.15x1.40mm_HandSolder","~"
|
||||
"8","1","D6","USB6B1","Power_Protection:USB6B1","Package_SO:SOIC-8_3.9x4.9mm_P1.27mm",""
|
||||
"9","2","D7, D8","MM3Z3V9","Device:D_Zener","Diode_SMD:D_0805_2012Metric_Pad1.15x1.40mm_HandSolder",""
|
||||
"10","1","F1","1A","Device:Fuse","MyFootprints:FuseHolder","~"
|
||||
"11","1","J1","A","Connector:Screw_Terminal_01x02","TerminalBlock_Phoenix:TerminalBlock_Phoenix_MKDS-1,5-2_1x02_P5.00mm_Horizontal",""
|
||||
"12","1","J2","B","Connector:Screw_Terminal_01x02","TerminalBlock_Phoenix:TerminalBlock_Phoenix_MKDS-1,5-2_1x02_P5.00mm_Horizontal",""
|
||||
"13","2","J3, J4","Conn_01x08_Female","Connector:Conn_01x08_Female","Connector_PinSocket_2.54mm:PinSocket_1x08_P2.54mm_Vertical","~"
|
||||
"14","1","J5","+/-","Connector:Screw_Terminal_01x02","TerminalBlock_Phoenix:TerminalBlock_Phoenix_MKDS-1,5-2_1x02_P5.00mm_Horizontal",""
|
||||
"15","1","J6","CONN_02X03","Switch:SW_DIP_x04","Button_Switch_THT:SW_DIP_SPSTx04_Slide_9.78x12.34mm_W7.62mm_P2.54mm",""
|
||||
"16","1","J7","0/1","Connector:Screw_Terminal_01x02","TerminalBlock_Phoenix:TerminalBlock_Phoenix_MKDS-1,5-2_1x02_P5.00mm_Horizontal",""
|
||||
"17","1","J8","2/3","Connector:Screw_Terminal_01x02","TerminalBlock_Phoenix:TerminalBlock_Phoenix_MKDS-1,5-2_1x02_P5.00mm_Horizontal",""
|
||||
"18","1","J9","DB9_Female","Connector:DB9_Female","Connector_Dsub:DSUB-9_Female_Horizontal_P2.77x2.84mm_EdgePinOffset4.94mm_Housed_MountingHolesOffset7.48mm",""
|
||||
"19","1","J10","12v","Connector:Screw_Terminal_01x02","TerminalBlock_Phoenix:TerminalBlock_Phoenix_MKDS-1,5-2_1x02_P5.00mm_Horizontal",""
|
||||
"20","1","J11","DB9_Male","Connector:DB9_Male","Connector_Dsub:DSUB-9_Male_Horizontal_P2.77x2.84mm_EdgePinOffset4.94mm_Housed_MountingHolesOffset7.48mm",""
|
||||
"21","1","J12","RS-485","Connector:Screw_Terminal_01x02","TerminalBlock_Phoenix:TerminalBlock_Phoenix_MKDS-1,5-2_1x02_P5.00mm_Horizontal",""
|
||||
"22","1","J13","Conn_01x06","Connector_Generic:Conn_01x06","Connector_PinSocket_2.54mm:PinSocket_1x06_P2.54mm_Vertical","~"
|
||||
"23","1","P1","USB_A","Connector:USB_B","Connectors_USB:USB_B_OST_USB-B1HSxx_Horizontal",""
|
||||
"24","4","P2, P3, P4, P5","Hole","Connector_Generic:Conn_01x01","MountingHole:MountingHole_3.2mm_M3",""
|
||||
"25","1","Q1","SI2305","Device:Q_PMOS_GSD","TO_SOT_Packages_SMD:SOT-23_Handsoldering","~"
|
||||
"26","1","Q2","AO3407","Device:Q_PMOS_GSD","TO_SOT_Packages_SMD:SOT-23_Handsoldering",""
|
||||
"27","5","R1, R5, R6, R7, R8","330","Device:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder","~"
|
||||
"28","2","R2, R10","10k","Device:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder","~"
|
||||
"29","2","R3, R9","120","Device:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder","~"
|
||||
"30","1","R4","15k","Device:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder",""
|
||||
"31","3","R11, R12, R18","22","Device:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder","~"
|
||||
"32","1","R13","220k","Device:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder",""
|
||||
"33","1","R14","56k","Device:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder",""
|
||||
"34","3","R15, R16, R17","47k","Device:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder",""
|
||||
"35","1","SW1","SW_DIP_x01","Switch:SW_DIP_x01","Button_Switch_THT:SW_DIP_SPSTx01_Slide_6.7x4.1mm_W7.62mm_P2.54mm_LowProfile","~"
|
||||
"36","1","U1","ISO1050DUB","Interface_CAN_LIN:ISO1050DUB","Package_SO:SOP-8_6.62x9.15mm_P2.54mm","http://www.ti.com/lit/ds/symlink/iso1050.pdf"
|
||||
"37","1","U2","LM1117-5.0","Regulator_Linear:LM1117-3.3","TO_SOT_Packages_SMD:SOT-223-3_TabPin2",""
|
||||
"38","1","U3","LM1117-3.3","Regulator_Linear:LM1117-3.3","TO_SOT_Packages_SMD:SOT-223-3_TabPin2",""
|
||||
"39","1","U4","MCP2551-I/SN","Interface_CAN_LIN:MCP2551-I-SN","Package_SO:SOIC-8_3.9x4.9mm_P1.27mm",""
|
||||
"40","1","U5","STM32F072CBTx","MCU_ST_STM32F0:STM32F072CBTx","Package_QFP:LQFP-48_7x7mm_P0.5mm","http://www.st.com/st-web-ui/static/active/en/resource/technical/document/datasheet/DM00090510.pdf"
|
||||
"41","1","U6","MAX3485","Interface_UART:MAX3485","Package_SO:SO-8_3.9x4.9mm_P1.27mm","https://datasheets.maximintegrated.com/en/ds/MAX3483-MAX3491.pdf"
|
||||
"1","4","C1, C2, C4, C5","0.1","stm32-rescue:C-Chiller_control-rescue","Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder",""
|
||||
"2","11","C3, C6, C8, C13, C14, C15, C16, C17, C18, C19, C20","0.1","Device:C","Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder",""
|
||||
"3","1","C7","47uF, 10V","Device:CP","Capacitor_Tantalum_SMD:CP_EIA-6032-28_Kemet-C_Pad2.25x2.35mm_HandSolder","~"
|
||||
"4","1","C9","10uF, 10V","Device:C","Capacitor_SMD:C_1206_3216Metric_Pad1.42x1.75mm_HandSolder","~"
|
||||
"5","6","D1, D2, D4, D5, D6, D9","1N5819","Device:D_Schottky","Diode_SMD:D_SOD-323_HandSoldering",""
|
||||
"6","1","D3","MM3Z7V5","Device:D_Zener","Diode_SMD:D_0805_2012Metric_Pad1.15x1.40mm_HandSolder","~"
|
||||
"7","2","D7, D8","MM3Z4V7","Device:D_Zener","Diode_SMD:D_0805_2012Metric_Pad1.15x1.40mm_HandSolder",""
|
||||
"8","1","J1","12VIN","stm32-rescue:Conn_01x02-Chiller_control-rescue","TerminalBlock_Phoenix:TerminalBlock_Phoenix_MKDS-1,5-2_1x02_P5.00mm_Horizontal",""
|
||||
"9","1","J2","thermal","Connector_Generic:Conn_02x04_Odd_Even","Connector_PinSocket_2.54mm:PinSocket_2x04_P2.54mm_Vertical","~"
|
||||
"10","1","J3","Buzzer","Connector:Conn_01x02_Male","Connector_JST:JST_EH_B2B-EH-A_1x02_P2.50mm_Vertical","~"
|
||||
"11","1","J4","cooler3","Connector:Conn_01x02_Male","Connector_JST:JST_EH_B2B-EH-A_1x02_P2.50mm_Vertical","~"
|
||||
"12","2","J5, J6","FAN","Connector:Conn_01x04_Male","Connector:FanPinHeader_1x04_P2.54mm_Vertical","~"
|
||||
"13","2","J7, J10","Conn_01x02_Female","Connector:Conn_01x02_Female","Connector_PinSocket_2.54mm:PinSocket_1x02_P2.54mm_Vertical","~"
|
||||
"14","1","J8","MKDS","Connector:Conn_01x02_Female","TerminalBlock_Phoenix:TerminalBlock_Phoenix_MKDS-1,5-2_1x02_P5.00mm_Horizontal","~"
|
||||
"15","1","K1","SRD-12VDC","stm32-rescue:G5LE-1-socket-rescue","Relay_THT:Relay_SPDT_SANYOU_SRD_Series_Form_C",""
|
||||
"16","1","L1","BMBA 0.1mH","stm32-rescue:L-Chiller_control-rescue","Inductor_SMD:L_0805_2012Metric_Pad1.15x1.40mm_HandSolder",""
|
||||
"17","1","P1","USB_A","Connector:USB_B","Connector_USB:USB_B_OST_USB-B1HSxx_Horizontal",""
|
||||
"18","4","P2, P3, P4, P5","Hole","Connector_Generic:Conn_01x01","MountingHole:MountingHole_3.2mm_M3",""
|
||||
"19","1","Q1","AO3401","Device:Q_PMOS_GSD","Package_TO_SOT_SMD:SOT-23_Handsoldering",""
|
||||
"20","4","Q2, Q3, Q4, Q5","IRLML2502","stm32-rescue:Q_NMOS_GSD-Chiller_control-rescue","Package_TO_SOT_SMD:SOT-23_Handsoldering",""
|
||||
"21","1","Q6","IRLML2502","stm32-rescue:Q_NMOS_GSD-socket-rescue","Package_TO_SOT_SMD:SOT-23_Handsoldering",""
|
||||
"22","1","R1","10k","Device:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder","~"
|
||||
"23","8","R2, R4, R6, R8, R13, R14, R16, R17","10k","stm32-rescue:R-Chiller_control-rescue","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder",""
|
||||
"24","4","R3, R5, R7, R9","4k7, 1%","stm32-rescue:R-Chiller_control-rescue","Resistor_SMD:R_0805_2012Metric_Pad1.15x1.40mm_HandSolder",""
|
||||
"25","10","R10, R11, R12, R15, R18, R19, R20, R21, R24, R25","510","stm32-rescue:R-Chiller_control-rescue","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder",""
|
||||
"26","3","R22, R28, R29","47k","Device:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder",""
|
||||
"27","3","R23, R30, R31","22","Device:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder","~"
|
||||
"28","1","R26","220k","Device:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder",""
|
||||
"29","1","R27","56k","Device:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder",""
|
||||
"30","1","R32","510","stm32-rescue:R-socket-rescue","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder",""
|
||||
"31","1","R34","10k","stm32-rescue:R-socket-rescue","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder",""
|
||||
"32","2","SW1, SW2","SW_Push","Switch:SW_Push","Connector_PinSocket_2.54mm:PinSocket_1x02_P2.54mm_Vertical","~"
|
||||
"33","1","U1","LM1117-3.3","Regulator_Linear:LM1117-3.3","Package_TO_SOT_SMD:SOT-223-3_TabPin2",""
|
||||
"34","1","U2","L7805","Regulator_Linear:L7805","Package_TO_SOT_THT:TO-220-3_Vertical","http://www.st.com/content/ccc/resource/technical/document/datasheet/41/4f/b3/b0/12/d4/47/88/CD00000444.pdf/files/CD00000444.pdf/jcr:content/translations/en.CD00000444.pdf"
|
||||
"35","1","U3","STM32F072CBTx","MCU_ST_STM32F0:STM32F072CBTx","Package_QFP:LQFP-48_7x7mm_P0.5mm","http://www.st.com/st-web-ui/static/active/en/resource/technical/document/datasheet/DM00090510.pdf"
|
||||
"36","1","U4","USBLC6-2SC6","Power_Protection:USBLC6-2SC6","Package_TO_SOT_SMD:SOT-23-6","http://www2.st.com/resource/en/datasheet/CD00050750.pdf"
|
||||
|
||||
|
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
@ -1,8 +1,8 @@
|
||||
(export (version D)
|
||||
(design
|
||||
(source /Big/Data/00__Electronics/STM32/F0-nolib/00_Socket_fans/kicad/stm32.sch)
|
||||
(date "Пн 24 авг 2020 00:36:38")
|
||||
(tool "Eeschema 5.1.5")
|
||||
(source /home/eddy/Yandex.Disk/Projects/stm32samples/F0-nolib/Socket_fans/kicad/stm32.sch)
|
||||
(date "Сб 24 окт 2020 20:15:31")
|
||||
(tool "Eeschema 5.1.6")
|
||||
(sheet (number 1) (name /) (tstamps /)
|
||||
(title_block
|
||||
(title)
|
||||
@ -40,19 +40,19 @@
|
||||
(sheetpath (names /) (tstamps /))
|
||||
(tstamp 59093675))
|
||||
(comp (ref R27)
|
||||
(value 56k)
|
||||
(value 1k)
|
||||
(footprint Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder)
|
||||
(libsource (lib Device) (part R) (description Resistor))
|
||||
(sheetpath (names /) (tstamps /))
|
||||
(tstamp 590A6DDA))
|
||||
(comp (ref R28)
|
||||
(value 47k)
|
||||
(value 4.7k)
|
||||
(footprint Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder)
|
||||
(libsource (lib Device) (part R) (description Resistor))
|
||||
(sheetpath (names /) (tstamps /))
|
||||
(tstamp 590A6F68))
|
||||
(comp (ref R29)
|
||||
(value 47k)
|
||||
(value 4.7k)
|
||||
(footprint Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder)
|
||||
(libsource (lib Device) (part R) (description Resistor))
|
||||
(sheetpath (names /) (tstamps /))
|
||||
@ -82,7 +82,7 @@
|
||||
(sheetpath (names /) (tstamps /))
|
||||
(tstamp 591446F9))
|
||||
(comp (ref D7)
|
||||
(value MM3Z4V7)
|
||||
(value MM3Z4V3)
|
||||
(footprint Diode_SMD:D_0805_2012Metric_Pad1.15x1.40mm_HandSolder)
|
||||
(libsource (lib Device) (part D_Zener) (description "Zener diode"))
|
||||
(sheetpath (names /) (tstamps /))
|
||||
@ -118,12 +118,6 @@
|
||||
(libsource (lib Device) (part CP) (description "Polarized capacitor"))
|
||||
(sheetpath (names /) (tstamps /))
|
||||
(tstamp 5E794E88))
|
||||
(comp (ref D8)
|
||||
(value MM3Z4V7)
|
||||
(footprint Diode_SMD:D_0805_2012Metric_Pad1.15x1.40mm_HandSolder)
|
||||
(libsource (lib Device) (part D_Zener) (description "Zener diode"))
|
||||
(sheetpath (names /) (tstamps /))
|
||||
(tstamp 5E7D7999))
|
||||
(comp (ref R22)
|
||||
(value 47k)
|
||||
(footprint Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder)
|
||||
@ -322,7 +316,7 @@
|
||||
(sheetpath (names /) (tstamps /))
|
||||
(tstamp 5C5D51AF))
|
||||
(comp (ref R26)
|
||||
(value 220k)
|
||||
(value 3.3k)
|
||||
(footprint Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder)
|
||||
(libsource (lib Device) (part R) (description Resistor))
|
||||
(sheetpath (names /) (tstamps /))
|
||||
@ -554,7 +548,14 @@
|
||||
(footprint Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder)
|
||||
(libsource (lib stm32-rescue) (part R-socket-rescue) (description ""))
|
||||
(sheetpath (names /) (tstamps /))
|
||||
(tstamp 5F458865)))
|
||||
(tstamp 5F458865))
|
||||
(comp (ref C10)
|
||||
(value 47u)
|
||||
(footprint Capacitor_THT:CP_Radial_D8.0mm_P3.50mm)
|
||||
(datasheet ~)
|
||||
(libsource (lib Device) (part CP) (description "Polarized capacitor"))
|
||||
(sheetpath (names /) (tstamps /))
|
||||
(tstamp 5F97B2AC)))
|
||||
(libparts
|
||||
(libpart (lib Connector) (part Conn_01x02_Female)
|
||||
(description "Generic connector, single row, 01x02, script generated (kicad-library-utils/schlib/autogen/connector/)")
|
||||
@ -935,329 +936,329 @@
|
||||
(library (logical Switch)
|
||||
(uri /usr/share/kicad/library/Switch.lib))
|
||||
(library (logical stm32-rescue)
|
||||
(uri /Big/Data/00__Electronics/STM32/F0-nolib/00_Socket_fans/kicad/stm32-rescue.lib)))
|
||||
(uri /home/eddy/Yandex.Disk/Projects/stm32samples/F0-nolib/Socket_fans/kicad/stm32-rescue.lib)))
|
||||
(nets
|
||||
(net (code 1) (name "Net-(J5-Pad3)")
|
||||
(net (code 1) (name "Net-(U3-Pad25)")
|
||||
(node (ref U3) (pin 25)))
|
||||
(net (code 2) (name "Net-(U3-Pad5)")
|
||||
(node (ref U3) (pin 5)))
|
||||
(net (code 3) (name "Net-(U3-Pad6)")
|
||||
(node (ref U3) (pin 6)))
|
||||
(net (code 4) (name "Net-(U3-Pad4)")
|
||||
(node (ref U3) (pin 4)))
|
||||
(net (code 5) (name "Net-(U3-Pad34)")
|
||||
(node (ref U3) (pin 34)))
|
||||
(net (code 6) (name "Net-(U3-Pad38)")
|
||||
(node (ref U3) (pin 38)))
|
||||
(net (code 7) (name "Net-(U3-Pad42)")
|
||||
(node (ref U3) (pin 42)))
|
||||
(net (code 8) (name "Net-(U3-Pad43)")
|
||||
(node (ref U3) (pin 43)))
|
||||
(net (code 9) (name "Net-(U3-Pad45)")
|
||||
(node (ref U3) (pin 45)))
|
||||
(net (code 10) (name "Net-(U3-Pad46)")
|
||||
(node (ref U3) (pin 46)))
|
||||
(net (code 11) (name "Net-(U3-Pad26)")
|
||||
(node (ref U3) (pin 26)))
|
||||
(net (code 12) (name "Net-(P5-Pad1)")
|
||||
(node (ref P5) (pin 1)))
|
||||
(net (code 13) (name "Net-(P4-Pad1)")
|
||||
(node (ref P4) (pin 1)))
|
||||
(net (code 14) (name "Net-(P2-Pad1)")
|
||||
(node (ref P2) (pin 1)))
|
||||
(net (code 15) (name "Net-(P3-Pad1)")
|
||||
(node (ref P3) (pin 1)))
|
||||
(net (code 16) (name "Net-(J5-Pad3)")
|
||||
(node (ref J5) (pin 3))
|
||||
(node (ref R18) (pin 2)))
|
||||
(net (code 2) (name +12V)
|
||||
(node (ref J6) (pin 2))
|
||||
(node (ref J3) (pin 2))
|
||||
(node (ref D6) (pin 1))
|
||||
(node (ref D5) (pin 1))
|
||||
(node (ref J5) (pin 2))
|
||||
(node (ref U2) (pin 1))
|
||||
(node (ref Q1) (pin 2))
|
||||
(node (ref C3) (pin 1))
|
||||
(node (ref R26) (pin 1))
|
||||
(node (ref J4) (pin 1))
|
||||
(node (ref D4) (pin 1))
|
||||
(node (ref D9) (pin 2))
|
||||
(node (ref K1) (pin 2))
|
||||
(node (ref D3) (pin 1)))
|
||||
(net (code 3) (name /TIM14_CH1)
|
||||
(net (code 17) (name /TIM14_CH1)
|
||||
(node (ref U3) (pin 17))
|
||||
(node (ref R18) (pin 1)))
|
||||
(net (code 4) (name /TIM1_CH2)
|
||||
(net (code 18) (name /TIM1_CH2)
|
||||
(node (ref R20) (pin 1))
|
||||
(node (ref U3) (pin 30)))
|
||||
(net (code 5) (name "Net-(J5-Pad4)")
|
||||
(node (ref R20) (pin 2))
|
||||
(node (ref J5) (pin 4)))
|
||||
(net (code 6) (name "Net-(Q2-Pad1)")
|
||||
(node (ref Q2) (pin 1))
|
||||
(node (ref R10) (pin 1)))
|
||||
(net (code 7) (name "Net-(D4-Pad2)")
|
||||
(node (ref D4) (pin 2))
|
||||
(node (ref J5) (pin 1))
|
||||
(node (ref Q2) (pin 3)))
|
||||
(net (code 8) (name GND)
|
||||
(net (code 19) (name "Net-(J5-Pad4)")
|
||||
(node (ref J5) (pin 4))
|
||||
(node (ref R20) (pin 2)))
|
||||
(net (code 20) (name "Net-(R30-Pad1)")
|
||||
(node (ref U4) (pin 3))
|
||||
(node (ref R30) (pin 1)))
|
||||
(net (code 21) (name "Net-(R31-Pad1)")
|
||||
(node (ref U4) (pin 1))
|
||||
(node (ref R31) (pin 1)))
|
||||
(net (code 22) (name /5Vusb)
|
||||
(node (ref U4) (pin 5))
|
||||
(node (ref D2) (pin 2))
|
||||
(node (ref P1) (pin 1)))
|
||||
(net (code 23) (name "Net-(P1-Pad2)")
|
||||
(node (ref U4) (pin 4))
|
||||
(node (ref P1) (pin 2)))
|
||||
(net (code 24) (name "Net-(P1-Pad3)")
|
||||
(node (ref P1) (pin 3))
|
||||
(node (ref U4) (pin 6)))
|
||||
(net (code 25) (name /Btn1)
|
||||
(node (ref U3) (pin 28))
|
||||
(node (ref R25) (pin 1)))
|
||||
(net (code 26) (name GND)
|
||||
(node (ref R14) (pin 1))
|
||||
(node (ref R34) (pin 2))
|
||||
(node (ref R1) (pin 2))
|
||||
(node (ref Q3) (pin 2))
|
||||
(node (ref R27) (pin 2))
|
||||
(node (ref C20) (pin 2))
|
||||
(node (ref R29) (pin 2))
|
||||
(node (ref J10) (pin 2))
|
||||
(node (ref Q2) (pin 2))
|
||||
(node (ref C10) (pin 2))
|
||||
(node (ref R34) (pin 2))
|
||||
(node (ref C7) (pin 2))
|
||||
(node (ref J1) (pin 2))
|
||||
(node (ref C6) (pin 2))
|
||||
(node (ref C16) (pin 2))
|
||||
(node (ref C18) (pin 2))
|
||||
(node (ref R22) (pin 2))
|
||||
(node (ref R16) (pin 1))
|
||||
(node (ref Q4) (pin 2))
|
||||
(node (ref R5) (pin 1))
|
||||
(node (ref C8) (pin 2))
|
||||
(node (ref C3) (pin 2))
|
||||
(node (ref C15) (pin 1))
|
||||
(node (ref U2) (pin 2))
|
||||
(node (ref Q5) (pin 2))
|
||||
(node (ref R7) (pin 1))
|
||||
(node (ref R9) (pin 1))
|
||||
(node (ref C5) (pin 1))
|
||||
(node (ref C9) (pin 2))
|
||||
(node (ref D7) (pin 2))
|
||||
(node (ref C19) (pin 1))
|
||||
(node (ref C17) (pin 1))
|
||||
(node (ref U1) (pin 1))
|
||||
(node (ref R17) (pin 1))
|
||||
(node (ref R3) (pin 1))
|
||||
(node (ref C1) (pin 1))
|
||||
(node (ref C2) (pin 1))
|
||||
(node (ref C4) (pin 1))
|
||||
(node (ref Q6) (pin 2))
|
||||
(node (ref U3) (pin 23))
|
||||
(node (ref U3) (pin 35))
|
||||
(node (ref U3) (pin 47))
|
||||
(node (ref U3) (pin 8))
|
||||
(node (ref D8) (pin 2))
|
||||
(node (ref Q3) (pin 2))
|
||||
(node (ref D7) (pin 2))
|
||||
(node (ref C9) (pin 2))
|
||||
(node (ref C5) (pin 1))
|
||||
(node (ref P1) (pin 4))
|
||||
(node (ref P1) (pin 5))
|
||||
(node (ref R3) (pin 1))
|
||||
(node (ref J1) (pin 2))
|
||||
(node (ref R5) (pin 1))
|
||||
(node (ref R7) (pin 1))
|
||||
(node (ref R9) (pin 1))
|
||||
(node (ref R27) (pin 2))
|
||||
(node (ref C8) (pin 2))
|
||||
(node (ref R17) (pin 1))
|
||||
(node (ref C7) (pin 2))
|
||||
(node (ref R29) (pin 2))
|
||||
(node (ref C6) (pin 2))
|
||||
(node (ref Q5) (pin 2))
|
||||
(node (ref C3) (pin 2))
|
||||
(node (ref C18) (pin 2))
|
||||
(node (ref R1) (pin 2))
|
||||
(node (ref C15) (pin 1))
|
||||
(node (ref C16) (pin 2))
|
||||
(node (ref C20) (pin 2))
|
||||
(node (ref U4) (pin 2))
|
||||
(node (ref U1) (pin 1))
|
||||
(node (ref Q4) (pin 2))
|
||||
(node (ref SW1) (pin 1))
|
||||
(node (ref SW2) (pin 1))
|
||||
(node (ref U2) (pin 2))
|
||||
(node (ref C17) (pin 1))
|
||||
(node (ref U3) (pin 47))
|
||||
(node (ref U3) (pin 23))
|
||||
(node (ref C13) (pin 2))
|
||||
(node (ref C14) (pin 2))
|
||||
(node (ref R13) (pin 1))
|
||||
(node (ref R22) (pin 2))
|
||||
(node (ref C19) (pin 1))
|
||||
(node (ref C13) (pin 2)))
|
||||
(net (code 9) (name /Cooler1)
|
||||
(node (ref R10) (pin 2))
|
||||
(node (ref U3) (pin 41))
|
||||
(node (ref R13) (pin 2)))
|
||||
(net (code 10) (name /Btn0)
|
||||
(node (ref R24) (pin 1))
|
||||
(node (ref U3) (pin 27)))
|
||||
(net (code 11) (name "Net-(C13-Pad1)")
|
||||
(node (ref SW1) (pin 2))
|
||||
(node (ref U4) (pin 2))
|
||||
(node (ref Q6) (pin 2))
|
||||
(node (ref U3) (pin 8))
|
||||
(node (ref SW1) (pin 1))
|
||||
(node (ref Q2) (pin 2))
|
||||
(node (ref R13) (pin 1)))
|
||||
(net (code 27) (name /Btn0)
|
||||
(node (ref U3) (pin 27))
|
||||
(node (ref R24) (pin 1)))
|
||||
(net (code 28) (name "Net-(C13-Pad1)")
|
||||
(node (ref C13) (pin 1))
|
||||
(node (ref R24) (pin 2))
|
||||
(node (ref C13) (pin 1)))
|
||||
(net (code 12) (name "Net-(C14-Pad1)")
|
||||
(node (ref SW1) (pin 2)))
|
||||
(net (code 29) (name "Net-(C14-Pad1)")
|
||||
(node (ref C14) (pin 1))
|
||||
(node (ref R25) (pin 2))
|
||||
(node (ref SW2) (pin 2)))
|
||||
(net (code 13) (name /Btn1)
|
||||
(node (ref U3) (pin 28))
|
||||
(node (ref R25) (pin 1)))
|
||||
(net (code 14) (name "Net-(U3-Pad25)")
|
||||
(node (ref U3) (pin 25)))
|
||||
(net (code 15) (name "Net-(U3-Pad5)")
|
||||
(node (ref U3) (pin 5)))
|
||||
(net (code 16) (name "Net-(U3-Pad6)")
|
||||
(node (ref U3) (pin 6)))
|
||||
(net (code 17) (name "Net-(U3-Pad4)")
|
||||
(node (ref U3) (pin 4)))
|
||||
(net (code 18) (name "Net-(U3-Pad34)")
|
||||
(node (ref U3) (pin 34)))
|
||||
(net (code 19) (name "Net-(U3-Pad38)")
|
||||
(node (ref U3) (pin 38)))
|
||||
(net (code 20) (name "Net-(U3-Pad42)")
|
||||
(node (ref U3) (pin 42)))
|
||||
(net (code 21) (name "Net-(U3-Pad43)")
|
||||
(node (ref U3) (pin 43)))
|
||||
(net (code 22) (name "Net-(U3-Pad45)")
|
||||
(node (ref U3) (pin 45)))
|
||||
(net (code 23) (name "Net-(U3-Pad46)")
|
||||
(node (ref U3) (pin 46)))
|
||||
(net (code 24) (name "Net-(U3-Pad26)")
|
||||
(node (ref U3) (pin 26)))
|
||||
(net (code 25) (name "Net-(P5-Pad1)")
|
||||
(node (ref P5) (pin 1)))
|
||||
(net (code 26) (name "Net-(P4-Pad1)")
|
||||
(node (ref P4) (pin 1)))
|
||||
(net (code 27) (name "Net-(P2-Pad1)")
|
||||
(node (ref P2) (pin 1)))
|
||||
(net (code 28) (name "Net-(P3-Pad1)")
|
||||
(node (ref P3) (pin 1)))
|
||||
(net (code 29) (name /TIM1_CH3)
|
||||
(node (ref R15) (pin 2))
|
||||
(node (ref R17) (pin 2))
|
||||
(node (ref U3) (pin 31)))
|
||||
(net (code 30) (name "Net-(D6-Pad2)")
|
||||
(node (ref J4) (pin 2))
|
||||
(node (ref Q5) (pin 3))
|
||||
(node (ref D6) (pin 2)))
|
||||
(net (code 31) (name "Net-(R30-Pad1)")
|
||||
(node (ref R30) (pin 1))
|
||||
(node (ref U4) (pin 3)))
|
||||
(net (code 32) (name "Net-(Q5-Pad1)")
|
||||
(node (ref Q5) (pin 1))
|
||||
(node (ref R15) (pin 1)))
|
||||
(net (code 33) (name /TIM3_CH1)
|
||||
(node (ref R19) (pin 1))
|
||||
(node (ref U3) (pin 16)))
|
||||
(net (code 34) (name "Net-(J6-Pad3)")
|
||||
(node (ref R19) (pin 2))
|
||||
(node (ref J6) (pin 3)))
|
||||
(net (code 35) (name "Net-(J6-Pad4)")
|
||||
(node (ref J6) (pin 4))
|
||||
(node (ref R21) (pin 2)))
|
||||
(net (code 36) (name "Net-(J3-Pad1)")
|
||||
(net (code 30) (name "Net-(J6-Pad4)")
|
||||
(node (ref R21) (pin 2))
|
||||
(node (ref J6) (pin 4)))
|
||||
(net (code 31) (name "Net-(J3-Pad1)")
|
||||
(node (ref J3) (pin 1))
|
||||
(node (ref Q4) (pin 3)))
|
||||
(net (code 37) (name /Cooler0)
|
||||
(node (ref R14) (pin 2))
|
||||
(node (ref R11) (pin 2))
|
||||
(node (ref U3) (pin 40)))
|
||||
(net (code 38) (name /Relay)
|
||||
(net (code 32) (name +12V)
|
||||
(node (ref J4) (pin 1))
|
||||
(node (ref D9) (pin 1))
|
||||
(node (ref D5) (pin 1))
|
||||
(node (ref J5) (pin 2))
|
||||
(node (ref D6) (pin 1))
|
||||
(node (ref D3) (pin 1))
|
||||
(node (ref Q1) (pin 2))
|
||||
(node (ref C10) (pin 1))
|
||||
(node (ref J6) (pin 2))
|
||||
(node (ref U2) (pin 1))
|
||||
(node (ref K1) (pin 2))
|
||||
(node (ref C3) (pin 1))
|
||||
(node (ref D4) (pin 1))
|
||||
(node (ref R26) (pin 1))
|
||||
(node (ref J3) (pin 2)))
|
||||
(net (code 33) (name /TIM1_CH3)
|
||||
(node (ref U3) (pin 31))
|
||||
(node (ref R17) (pin 2))
|
||||
(node (ref R15) (pin 2)))
|
||||
(net (code 34) (name "Net-(D6-Pad2)")
|
||||
(node (ref Q5) (pin 3))
|
||||
(node (ref J4) (pin 2))
|
||||
(node (ref D6) (pin 2)))
|
||||
(net (code 35) (name "Net-(Q2-Pad1)")
|
||||
(node (ref R10) (pin 1))
|
||||
(node (ref Q2) (pin 1)))
|
||||
(net (code 36) (name "Net-(D4-Pad2)")
|
||||
(node (ref J5) (pin 1))
|
||||
(node (ref D4) (pin 2))
|
||||
(node (ref Q2) (pin 3)))
|
||||
(net (code 37) (name /TIM3_CH1)
|
||||
(node (ref R19) (pin 1))
|
||||
(node (ref U3) (pin 16)))
|
||||
(net (code 38) (name "Net-(J6-Pad3)")
|
||||
(node (ref R19) (pin 2))
|
||||
(node (ref J6) (pin 3)))
|
||||
(net (code 39) (name "Net-(U3-Pad3)")
|
||||
(node (ref U3) (pin 3)))
|
||||
(net (code 40) (name "Net-(K1-Pad4)")
|
||||
(node (ref K1) (pin 4)))
|
||||
(net (code 41) (name "Net-(J8-Pad2)")
|
||||
(node (ref J8) (pin 2))
|
||||
(node (ref K1) (pin 3)))
|
||||
(net (code 42) (name "Net-(J8-Pad1)")
|
||||
(node (ref J8) (pin 1))
|
||||
(node (ref K1) (pin 1)))
|
||||
(net (code 43) (name "Net-(D9-Pad2)")
|
||||
(node (ref Q6) (pin 3))
|
||||
(node (ref K1) (pin 5))
|
||||
(node (ref D9) (pin 2)))
|
||||
(net (code 44) (name "Net-(Q6-Pad1)")
|
||||
(node (ref Q6) (pin 1))
|
||||
(node (ref R32) (pin 1)))
|
||||
(net (code 45) (name /Cooler1)
|
||||
(node (ref R10) (pin 2))
|
||||
(node (ref R13) (pin 2))
|
||||
(node (ref U3) (pin 41)))
|
||||
(net (code 46) (name /Relay)
|
||||
(node (ref R34) (pin 1))
|
||||
(node (ref U3) (pin 2))
|
||||
(node (ref R32) (pin 2)))
|
||||
(net (code 39) (name "Net-(U3-Pad3)")
|
||||
(node (ref U3) (pin 3)))
|
||||
(net (code 40) (name "Net-(U3-Pad18)")
|
||||
(net (code 47) (name "Net-(D3-Pad2)")
|
||||
(node (ref R1) (pin 1))
|
||||
(node (ref D3) (pin 2))
|
||||
(node (ref Q1) (pin 1)))
|
||||
(net (code 48) (name "Net-(J1-Pad1)")
|
||||
(node (ref J1) (pin 1))
|
||||
(node (ref Q1) (pin 3)))
|
||||
(net (code 49) (name "Net-(U3-Pad18)")
|
||||
(node (ref U3) (pin 18)))
|
||||
(net (code 41) (name /ADC2)
|
||||
(node (ref C4) (pin 2))
|
||||
(node (ref R6) (pin 2))
|
||||
(node (ref U3) (pin 12)))
|
||||
(net (code 42) (name /ADC3)
|
||||
(node (ref C5) (pin 2))
|
||||
(node (ref U3) (pin 13))
|
||||
(node (ref R8) (pin 2)))
|
||||
(net (code 43) (name /AIN0)
|
||||
(node (ref C16) (pin 1))
|
||||
(node (ref D7) (pin 1))
|
||||
(node (ref R27) (pin 1))
|
||||
(node (ref R26) (pin 2))
|
||||
(node (ref U3) (pin 14)))
|
||||
(net (code 44) (name /AIN1)
|
||||
(node (ref U3) (pin 15))
|
||||
(node (ref R28) (pin 2))
|
||||
(node (ref R29) (pin 1))
|
||||
(node (ref C18) (pin 1))
|
||||
(node (ref D8) (pin 1)))
|
||||
(net (code 45) (name /TIM1_CH1)
|
||||
(node (ref R21) (pin 1))
|
||||
(node (ref U3) (pin 29)))
|
||||
(net (code 46) (name "Net-(U3-Pad19)")
|
||||
(node (ref U3) (pin 19)))
|
||||
(net (code 47) (name "Net-(U3-Pad21)")
|
||||
(node (ref U3) (pin 21)))
|
||||
(net (code 48) (name "Net-(U3-Pad22)")
|
||||
(node (ref U3) (pin 22)))
|
||||
(net (code 49) (name "Net-(U3-Pad20)")
|
||||
(node (ref U3) (pin 20)))
|
||||
(net (code 50) (name "Net-(U3-Pad39)")
|
||||
(node (ref U3) (pin 39)))
|
||||
(net (code 51) (name "Net-(J8-Pad1)")
|
||||
(node (ref J8) (pin 1))
|
||||
(node (ref K1) (pin 1)))
|
||||
(net (code 52) (name "Net-(J8-Pad2)")
|
||||
(node (ref K1) (pin 3))
|
||||
(node (ref J8) (pin 2)))
|
||||
(net (code 53) (name "Net-(K1-Pad4)")
|
||||
(node (ref K1) (pin 4)))
|
||||
(net (code 54) (name "Net-(Q6-Pad1)")
|
||||
(node (ref Q6) (pin 1))
|
||||
(node (ref R32) (pin 1)))
|
||||
(net (code 55) (name /Buzzer)
|
||||
(node (ref U3) (pin 37))
|
||||
(node (ref R16) (pin 2))
|
||||
(node (ref R12) (pin 2)))
|
||||
(net (code 56) (name "Net-(D9-Pad1)")
|
||||
(node (ref Q6) (pin 3))
|
||||
(node (ref D9) (pin 1))
|
||||
(node (ref K1) (pin 5)))
|
||||
(net (code 57) (name "Net-(J2-Pad1)")
|
||||
(node (ref J2) (pin 1))
|
||||
(node (ref R8) (pin 1))
|
||||
(node (ref R9) (pin 2)))
|
||||
(net (code 58) (name "Net-(P1-Pad3)")
|
||||
(node (ref U4) (pin 6))
|
||||
(node (ref P1) (pin 3)))
|
||||
(net (code 59) (name "Net-(R31-Pad1)")
|
||||
(node (ref R31) (pin 1))
|
||||
(node (ref U4) (pin 1)))
|
||||
(net (code 60) (name /5Vusb)
|
||||
(node (ref P1) (pin 1))
|
||||
(node (ref U4) (pin 5))
|
||||
(node (ref D2) (pin 2)))
|
||||
(net (code 61) (name "Net-(P1-Pad2)")
|
||||
(node (ref U4) (pin 4))
|
||||
(node (ref P1) (pin 2)))
|
||||
(net (code 62) (name /BOOT0)
|
||||
(node (ref U3) (pin 44))
|
||||
(node (ref J7) (pin 2))
|
||||
(node (ref R22) (pin 1)))
|
||||
(net (code 63) (name /ADC0)
|
||||
(node (ref R2) (pin 2))
|
||||
(node (ref U3) (pin 10))
|
||||
(node (ref C1) (pin 2)))
|
||||
(net (code 64) (name /ADC1)
|
||||
(node (ref R4) (pin 2))
|
||||
(node (ref U3) (pin 11))
|
||||
(node (ref C2) (pin 2)))
|
||||
(net (code 65) (name /NRST)
|
||||
(net (code 51) (name "Net-(U3-Pad19)")
|
||||
(node (ref U3) (pin 19)))
|
||||
(net (code 52) (name "Net-(U3-Pad20)")
|
||||
(node (ref U3) (pin 20)))
|
||||
(net (code 53) (name "Net-(U3-Pad21)")
|
||||
(node (ref U3) (pin 21)))
|
||||
(net (code 54) (name "Net-(U3-Pad22)")
|
||||
(node (ref U3) (pin 22)))
|
||||
(net (code 55) (name /NRST)
|
||||
(node (ref U3) (pin 7))
|
||||
(node (ref J10) (pin 1)))
|
||||
(net (code 66) (name +3V3)
|
||||
(node (ref C17) (pin 2))
|
||||
(node (ref R23) (pin 2))
|
||||
(node (ref C15) (pin 2))
|
||||
(node (ref U3) (pin 24))
|
||||
(node (ref J2) (pin 2))
|
||||
(node (ref U1) (pin 2))
|
||||
(node (ref U3) (pin 48))
|
||||
(node (ref J2) (pin 4))
|
||||
(node (ref U3) (pin 1))
|
||||
(node (ref C6) (pin 1))
|
||||
(node (ref C7) (pin 1))
|
||||
(node (ref L1) (pin 1))
|
||||
(node (ref U3) (pin 36))
|
||||
(node (ref C19) (pin 2))
|
||||
(node (ref J2) (pin 8))
|
||||
(node (ref J2) (pin 6)))
|
||||
(net (code 67) (name "Net-(J7-Pad1)")
|
||||
(node (ref R23) (pin 1))
|
||||
(node (ref J7) (pin 1)))
|
||||
(net (code 68) (name /5Vin)
|
||||
(net (code 56) (name /ADC2)
|
||||
(node (ref U3) (pin 12))
|
||||
(node (ref C4) (pin 2))
|
||||
(node (ref R6) (pin 2)))
|
||||
(net (code 57) (name /ADC3)
|
||||
(node (ref U3) (pin 13))
|
||||
(node (ref R8) (pin 2))
|
||||
(node (ref C5) (pin 2)))
|
||||
(net (code 58) (name /AIN0)
|
||||
(node (ref R26) (pin 2))
|
||||
(node (ref R27) (pin 1))
|
||||
(node (ref U3) (pin 14))
|
||||
(node (ref D7) (pin 1))
|
||||
(node (ref C16) (pin 1)))
|
||||
(net (code 59) (name /AIN1)
|
||||
(node (ref U3) (pin 15))
|
||||
(node (ref C18) (pin 1))
|
||||
(node (ref R29) (pin 1))
|
||||
(node (ref R28) (pin 2)))
|
||||
(net (code 60) (name /TIM1_CH1)
|
||||
(node (ref R21) (pin 1))
|
||||
(node (ref U3) (pin 29)))
|
||||
(net (code 61) (name /Buzzer)
|
||||
(node (ref R16) (pin 2))
|
||||
(node (ref U3) (pin 37))
|
||||
(node (ref R12) (pin 2)))
|
||||
(net (code 62) (name /BOOT0)
|
||||
(node (ref U3) (pin 44))
|
||||
(node (ref R22) (pin 1))
|
||||
(node (ref J7) (pin 2)))
|
||||
(net (code 63) (name /ADC0)
|
||||
(node (ref R2) (pin 2))
|
||||
(node (ref C1) (pin 2))
|
||||
(node (ref U3) (pin 10)))
|
||||
(net (code 64) (name /ADC1)
|
||||
(node (ref U3) (pin 11))
|
||||
(node (ref R4) (pin 2))
|
||||
(node (ref C2) (pin 2)))
|
||||
(net (code 65) (name /5Vin)
|
||||
(node (ref C8) (pin 1))
|
||||
(node (ref D1) (pin 2))
|
||||
(node (ref U2) (pin 3))
|
||||
(node (ref C9) (pin 1))
|
||||
(node (ref D1) (pin 2)))
|
||||
(net (code 69) (name "Net-(D3-Pad2)")
|
||||
(node (ref R1) (pin 1))
|
||||
(node (ref Q1) (pin 1))
|
||||
(node (ref D3) (pin 2)))
|
||||
(net (code 70) (name +5V)
|
||||
(node (ref C9) (pin 1)))
|
||||
(net (code 66) (name +3V3)
|
||||
(node (ref U3) (pin 1))
|
||||
(node (ref R23) (pin 2))
|
||||
(node (ref U3) (pin 36))
|
||||
(node (ref U3) (pin 48))
|
||||
(node (ref U3) (pin 24))
|
||||
(node (ref C19) (pin 2))
|
||||
(node (ref J2) (pin 2))
|
||||
(node (ref J2) (pin 4))
|
||||
(node (ref J2) (pin 6))
|
||||
(node (ref J2) (pin 8))
|
||||
(node (ref C15) (pin 2))
|
||||
(node (ref C17) (pin 2))
|
||||
(node (ref U1) (pin 2))
|
||||
(node (ref C6) (pin 1))
|
||||
(node (ref L1) (pin 1))
|
||||
(node (ref C7) (pin 1)))
|
||||
(net (code 67) (name "Net-(J7-Pad1)")
|
||||
(node (ref J7) (pin 1))
|
||||
(node (ref R23) (pin 1)))
|
||||
(net (code 68) (name "Net-(Q3-Pad1)")
|
||||
(node (ref R11) (pin 1))
|
||||
(node (ref Q3) (pin 1)))
|
||||
(net (code 69) (name /Cooler0)
|
||||
(node (ref U3) (pin 40))
|
||||
(node (ref R14) (pin 2))
|
||||
(node (ref R11) (pin 2)))
|
||||
(net (code 70) (name "Net-(D5-Pad2)")
|
||||
(node (ref Q3) (pin 3))
|
||||
(node (ref J6) (pin 1))
|
||||
(node (ref D5) (pin 2)))
|
||||
(net (code 71) (name +5V)
|
||||
(node (ref D1) (pin 1))
|
||||
(node (ref R28) (pin 1))
|
||||
(node (ref D2) (pin 1))
|
||||
(node (ref U1) (pin 3))
|
||||
(node (ref D1) (pin 1)))
|
||||
(net (code 71) (name "Net-(C20-Pad1)")
|
||||
(node (ref D2) (pin 1)))
|
||||
(net (code 72) (name "Net-(C20-Pad1)")
|
||||
(node (ref C20) (pin 1))
|
||||
(node (ref U3) (pin 9))
|
||||
(node (ref L1) (pin 2))
|
||||
(node (ref C20) (pin 1)))
|
||||
(net (code 72) (name "Net-(J1-Pad1)")
|
||||
(node (ref Q1) (pin 3))
|
||||
(node (ref J1) (pin 1)))
|
||||
(node (ref L1) (pin 2)))
|
||||
(net (code 73) (name "Net-(R30-Pad2)")
|
||||
(node (ref R30) (pin 2))
|
||||
(node (ref U3) (pin 32)))
|
||||
(net (code 74) (name "Net-(R31-Pad2)")
|
||||
(node (ref R31) (pin 2))
|
||||
(node (ref U3) (pin 33)))
|
||||
(net (code 75) (name "Net-(J2-Pad5)")
|
||||
(node (ref R4) (pin 1))
|
||||
(node (ref J2) (pin 5))
|
||||
(node (ref R5) (pin 2)))
|
||||
(net (code 76) (name "Net-(J2-Pad3)")
|
||||
(node (ref J2) (pin 3))
|
||||
(node (ref U3) (pin 33))
|
||||
(node (ref R31) (pin 2)))
|
||||
(net (code 75) (name "Net-(J2-Pad3)")
|
||||
(node (ref R6) (pin 1))
|
||||
(node (ref R7) (pin 2))
|
||||
(node (ref R6) (pin 1)))
|
||||
(net (code 77) (name "Net-(J2-Pad7)")
|
||||
(node (ref J2) (pin 3)))
|
||||
(net (code 76) (name "Net-(J2-Pad1)")
|
||||
(node (ref J2) (pin 1))
|
||||
(node (ref R9) (pin 2))
|
||||
(node (ref R8) (pin 1)))
|
||||
(net (code 77) (name "Net-(J2-Pad5)")
|
||||
(node (ref R4) (pin 1))
|
||||
(node (ref R5) (pin 2))
|
||||
(node (ref J2) (pin 5)))
|
||||
(net (code 78) (name "Net-(J2-Pad7)")
|
||||
(node (ref R3) (pin 2))
|
||||
(node (ref J2) (pin 7))
|
||||
(node (ref R2) (pin 1))
|
||||
(node (ref R3) (pin 2)))
|
||||
(net (code 78) (name "Net-(Q4-Pad1)")
|
||||
(node (ref R2) (pin 1)))
|
||||
(net (code 79) (name "Net-(Q5-Pad1)")
|
||||
(node (ref Q5) (pin 1))
|
||||
(node (ref R15) (pin 1)))
|
||||
(net (code 80) (name "Net-(Q4-Pad1)")
|
||||
(node (ref R12) (pin 1))
|
||||
(node (ref Q4) (pin 1)))
|
||||
(net (code 79) (name "Net-(Q3-Pad1)")
|
||||
(node (ref Q3) (pin 1))
|
||||
(node (ref R11) (pin 1)))
|
||||
(net (code 80) (name "Net-(D5-Pad2)")
|
||||
(node (ref J6) (pin 1))
|
||||
(node (ref D5) (pin 2))
|
||||
(node (ref Q3) (pin 3)))))
|
||||
(node (ref Q4) (pin 1)))))
|
||||
@ -1,7 +1,7 @@
|
||||
EESchema Schematic File Version 4
|
||||
EELAYER 30 0
|
||||
EELAYER END
|
||||
$Descr A3 16535 11693
|
||||
$Descr A4 11693 8268
|
||||
encoding utf-8
|
||||
Sheet 1 1
|
||||
Title ""
|
||||
@ -16,12 +16,12 @@ $EndDescr
|
||||
$Comp
|
||||
L Device:C C15
|
||||
U 1 1 58C42D39
|
||||
P 6845 7340
|
||||
F 0 "C15" H 6870 7440 50 0000 L CNN
|
||||
F 1 "0.1" H 6870 7240 50 0000 L CNN
|
||||
F 2 "Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder" H 6883 7190 50 0001 C CNN
|
||||
F 3 "" H 6845 7340 50 0000 C CNN
|
||||
1 6845 7340
|
||||
P 6825 5980
|
||||
F 0 "C15" H 6850 6080 50 0000 L CNN
|
||||
F 1 "0.1" H 6850 5880 50 0000 L CNN
|
||||
F 2 "Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder" H 6863 5830 50 0001 C CNN
|
||||
F 3 "" H 6825 5980 50 0000 C CNN
|
||||
1 6825 5980
|
||||
1 0 0 -1
|
||||
$EndComp
|
||||
$Comp
|
||||
@ -60,23 +60,23 @@ $EndComp
|
||||
$Comp
|
||||
L Device:C C17
|
||||
U 1 1 590935EA
|
||||
P 7145 7340
|
||||
F 0 "C17" H 7170 7440 50 0000 L CNN
|
||||
F 1 "0.1" H 7170 7240 50 0000 L CNN
|
||||
F 2 "Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder" H 7183 7190 50 0001 C CNN
|
||||
F 3 "" H 7145 7340 50 0000 C CNN
|
||||
1 7145 7340
|
||||
P 7125 5980
|
||||
F 0 "C17" H 7150 6080 50 0000 L CNN
|
||||
F 1 "0.1" H 7150 5880 50 0000 L CNN
|
||||
F 2 "Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder" H 7163 5830 50 0001 C CNN
|
||||
F 3 "" H 7125 5980 50 0000 C CNN
|
||||
1 7125 5980
|
||||
1 0 0 -1
|
||||
$EndComp
|
||||
$Comp
|
||||
L Device:C C19
|
||||
U 1 1 59093675
|
||||
P 7445 7340
|
||||
F 0 "C19" H 7470 7440 50 0000 L CNN
|
||||
F 1 "0.1" H 7470 7240 50 0000 L CNN
|
||||
F 2 "Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder" H 7483 7190 50 0001 C CNN
|
||||
F 3 "" H 7445 7340 50 0000 C CNN
|
||||
1 7445 7340
|
||||
P 7425 5980
|
||||
F 0 "C19" H 7450 6080 50 0000 L CNN
|
||||
F 1 "0.1" H 7450 5880 50 0000 L CNN
|
||||
F 2 "Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder" H 7463 5830 50 0001 C CNN
|
||||
F 3 "" H 7425 5980 50 0000 C CNN
|
||||
1 7425 5980
|
||||
1 0 0 -1
|
||||
$EndComp
|
||||
Text Notes 660 1940 0 60 ~ 0
|
||||
@ -84,34 +84,34 @@ Text Notes 660 1940 0 60 ~ 0
|
||||
$Comp
|
||||
L power:+3.3V #PWR029
|
||||
U 1 1 590A0C2D
|
||||
P 7445 7490
|
||||
F 0 "#PWR029" H 7445 7340 50 0001 C CNN
|
||||
F 1 "+3.3V" H 7445 7630 50 0000 C CNN
|
||||
F 2 "" H 7445 7490 50 0000 C CNN
|
||||
F 3 "" H 7445 7490 50 0000 C CNN
|
||||
1 7445 7490
|
||||
P 7425 6130
|
||||
F 0 "#PWR029" H 7425 5980 50 0001 C CNN
|
||||
F 1 "+3.3V" H 7425 6270 50 0000 C CNN
|
||||
F 2 "" H 7425 6130 50 0000 C CNN
|
||||
F 3 "" H 7425 6130 50 0000 C CNN
|
||||
1 7425 6130
|
||||
-1 0 0 1
|
||||
$EndComp
|
||||
$Comp
|
||||
L power:GND #PWR025
|
||||
U 1 1 590A1958
|
||||
P 6495 7190
|
||||
F 0 "#PWR025" H 6495 6940 50 0001 C CNN
|
||||
F 1 "GND" H 6495 7040 50 0001 C CNN
|
||||
F 2 "" H 6495 7190 50 0000 C CNN
|
||||
F 3 "" H 6495 7190 50 0000 C CNN
|
||||
1 6495 7190
|
||||
P 6475 5830
|
||||
F 0 "#PWR025" H 6475 5580 50 0001 C CNN
|
||||
F 1 "GND" H 6475 5680 50 0001 C CNN
|
||||
F 2 "" H 6475 5830 50 0000 C CNN
|
||||
F 3 "" H 6475 5830 50 0000 C CNN
|
||||
1 6475 5830
|
||||
1 0 0 -1
|
||||
$EndComp
|
||||
$Comp
|
||||
L power:GND #PWR031
|
||||
U 1 1 590A6FD0
|
||||
P 8655 6505
|
||||
F 0 "#PWR031" H 8655 6255 50 0001 C CNN
|
||||
F 1 "GND" H 8655 6355 50 0001 C CNN
|
||||
F 2 "" H 8655 6505 50 0000 C CNN
|
||||
F 3 "" H 8655 6505 50 0000 C CNN
|
||||
1 8655 6505
|
||||
P 8635 5145
|
||||
F 0 "#PWR031" H 8635 4895 50 0001 C CNN
|
||||
F 1 "GND" H 8635 4995 50 0001 C CNN
|
||||
F 2 "" H 8635 5145 50 0000 C CNN
|
||||
F 3 "" H 8635 5145 50 0000 C CNN
|
||||
1 8635 5145
|
||||
1 0 0 -1
|
||||
$EndComp
|
||||
$Comp
|
||||
@ -119,7 +119,7 @@ L Device:R R27
|
||||
U 1 1 590A6DDA
|
||||
P 6465 1395
|
||||
F 0 "R27" V 6545 1395 50 0000 C CNN
|
||||
F 1 "56k" V 6465 1395 50 0000 C CNN
|
||||
F 1 "1k" V 6465 1395 50 0000 C CNN
|
||||
F 2 "Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder" V 6395 1395 50 0001 C CNN
|
||||
F 3 "" H 6465 1395 50 0000 C CNN
|
||||
1 6465 1395
|
||||
@ -130,7 +130,7 @@ L Device:R R28
|
||||
U 1 1 590A6F68
|
||||
P 7405 985
|
||||
F 0 "R28" V 7485 985 50 0000 C CNN
|
||||
F 1 "47k" V 7405 985 50 0000 C CNN
|
||||
F 1 "4.7k" V 7405 985 50 0000 C CNN
|
||||
F 2 "Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder" V 7335 985 50 0001 C CNN
|
||||
F 3 "" H 7405 985 50 0000 C CNN
|
||||
1 7405 985
|
||||
@ -141,7 +141,7 @@ L Device:R R29
|
||||
U 1 1 590A6F6E
|
||||
P 7405 1385
|
||||
F 0 "R29" V 7485 1385 50 0000 C CNN
|
||||
F 1 "47k" V 7405 1385 50 0000 C CNN
|
||||
F 1 "4.7k" V 7405 1385 50 0000 C CNN
|
||||
F 2 "Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder" V 7335 1385 50 0001 C CNN
|
||||
F 3 "" H 7405 1385 50 0000 C CNN
|
||||
1 7405 1385
|
||||
@ -174,28 +174,28 @@ AIN0
|
||||
Text Label 7755 1185 0 60 ~ 0
|
||||
AIN1
|
||||
Text Notes 6425 1935 0 60 ~ 0
|
||||
V12 = 12Vin/4.93
|
||||
V12 = 12Vin/4.3
|
||||
Text Notes 7425 1935 0 60 ~ 0
|
||||
V5 = U5/2
|
||||
Text Notes 6175 635 0 60 ~ 0
|
||||
ADC block (voltage)
|
||||
Text Notes 4905 645 0 60 ~ 0
|
||||
Boot, reset
|
||||
Text Label 6585 4260 2 60 ~ 0
|
||||
Text Label 6565 2900 2 60 ~ 0
|
||||
NRST
|
||||
Text Label 6585 4460 2 60 ~ 0
|
||||
Text Label 6565 3100 2 60 ~ 0
|
||||
BOOT0
|
||||
Text Label 5365 1255 2 60 ~ 0
|
||||
BOOT0
|
||||
$Comp
|
||||
L power:GND #PWR036
|
||||
U 1 1 590CF25B
|
||||
P 10290 6140
|
||||
F 0 "#PWR036" H 10290 5890 50 0001 C CNN
|
||||
F 1 "GND" H 10290 5990 50 0000 C CNN
|
||||
F 2 "" H 10290 6140 50 0000 C CNN
|
||||
F 3 "" H 10290 6140 50 0000 C CNN
|
||||
1 10290 6140
|
||||
P 10270 4780
|
||||
F 0 "#PWR036" H 10270 4530 50 0001 C CNN
|
||||
F 1 "GND" H 10270 4630 50 0000 C CNN
|
||||
F 2 "" H 10270 4780 50 0000 C CNN
|
||||
F 3 "" H 10270 4780 50 0000 C CNN
|
||||
1 10270 4780
|
||||
1 0 0 -1
|
||||
$EndComp
|
||||
$Comp
|
||||
@ -247,7 +247,7 @@ L Device:D_Zener D7
|
||||
U 1 1 59684468
|
||||
P 6715 1395
|
||||
F 0 "D7" H 6715 1495 50 0000 C CNN
|
||||
F 1 "MM3Z4V7" H 6715 1295 50 0000 C CNN
|
||||
F 1 "MM3Z4V3" H 6715 1295 50 0000 C CNN
|
||||
F 2 "Diode_SMD:D_0805_2012Metric_Pad1.15x1.40mm_HandSolder" H 6715 1395 50 0001 C CNN
|
||||
F 3 "" H 6715 1395 50 0000 C CNN
|
||||
1 6715 1395
|
||||
@ -256,23 +256,23 @@ $EndComp
|
||||
$Comp
|
||||
L Device:R R30
|
||||
U 1 1 5968E385
|
||||
P 8435 6410
|
||||
F 0 "R30" V 8515 6410 50 0000 C CNN
|
||||
F 1 "22" V 8435 6410 50 0000 C CNN
|
||||
F 2 "Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder" V 8365 6410 50 0001 C CNN
|
||||
F 3 "" H 8435 6410 50 0001 C CNN
|
||||
1 8435 6410
|
||||
P 8415 5050
|
||||
F 0 "R30" V 8495 5050 50 0000 C CNN
|
||||
F 1 "22" V 8415 5050 50 0000 C CNN
|
||||
F 2 "Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder" V 8345 5050 50 0001 C CNN
|
||||
F 3 "" H 8415 5050 50 0001 C CNN
|
||||
1 8415 5050
|
||||
0 1 1 0
|
||||
$EndComp
|
||||
$Comp
|
||||
L Device:R R31
|
||||
U 1 1 5968E83B
|
||||
P 8435 6610
|
||||
F 0 "R31" V 8515 6610 50 0000 C CNN
|
||||
F 1 "22" V 8435 6610 50 0000 C CNN
|
||||
F 2 "Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder" V 8365 6610 50 0001 C CNN
|
||||
F 3 "" H 8435 6610 50 0001 C CNN
|
||||
1 8435 6610
|
||||
P 8415 5250
|
||||
F 0 "R31" V 8495 5250 50 0000 C CNN
|
||||
F 1 "22" V 8415 5250 50 0000 C CNN
|
||||
F 2 "Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder" V 8345 5250 50 0001 C CNN
|
||||
F 3 "" H 8415 5250 50 0001 C CNN
|
||||
1 8415 5250
|
||||
0 1 1 0
|
||||
$EndComp
|
||||
Text Label 960 2490 2 60 ~ 0
|
||||
@ -280,14 +280,14 @@ Text Label 960 2490 2 60 ~ 0
|
||||
Wire Wire Line
|
||||
2010 2590 2010 2540
|
||||
Wire Wire Line
|
||||
7885 6460 8235 6460
|
||||
7865 5100 8215 5100
|
||||
Wire Wire Line
|
||||
8235 6460 8235 6410
|
||||
8215 5100 8215 5050
|
||||
Wire Wire Line
|
||||
8235 6610 8235 6560
|
||||
8215 5250 8215 5200
|
||||
Wire Wire Line
|
||||
8235 6560 7885 6560
|
||||
Connection ~ 7145 7190
|
||||
8215 5200 7865 5200
|
||||
Connection ~ 7125 5830
|
||||
Wire Wire Line
|
||||
7405 1135 7405 1185
|
||||
Wire Wire Line
|
||||
@ -299,18 +299,9 @@ Wire Wire Line
|
||||
Wire Wire Line
|
||||
6465 1195 6715 1195
|
||||
Connection ~ 6465 1195
|
||||
Wire Wire Line
|
||||
7405 1185 7655 1185
|
||||
Connection ~ 7405 1185
|
||||
Wire Notes Line
|
||||
6025 1985 6025 535
|
||||
Wire Wire Line
|
||||
7655 1235 7655 1185
|
||||
Connection ~ 7655 1185
|
||||
Wire Wire Line
|
||||
7405 1585 7655 1585
|
||||
Wire Wire Line
|
||||
7655 1585 7655 1535
|
||||
Wire Wire Line
|
||||
6465 1595 6715 1595
|
||||
Wire Wire Line
|
||||
@ -319,9 +310,9 @@ Wire Wire Line
|
||||
6715 1245 6715 1195
|
||||
Connection ~ 6715 1195
|
||||
Wire Wire Line
|
||||
8235 6410 8285 6410
|
||||
8215 5050 8265 5050
|
||||
Wire Wire Line
|
||||
8285 6610 8235 6610
|
||||
8265 5250 8215 5250
|
||||
Wire Wire Line
|
||||
1460 2490 1460 2240
|
||||
Wire Wire Line
|
||||
@ -333,28 +324,26 @@ Wire Wire Line
|
||||
Wire Wire Line
|
||||
7405 1185 7405 1235
|
||||
Wire Wire Line
|
||||
7655 1185 7755 1185
|
||||
6475 5830 6825 5830
|
||||
Wire Wire Line
|
||||
6495 7190 6845 7190
|
||||
7125 5830 7215 5830
|
||||
Wire Wire Line
|
||||
7145 7190 7235 7190
|
||||
Wire Wire Line
|
||||
6845 7490 7145 7490
|
||||
Text Label 9655 6505 1 60 ~ 0
|
||||
6825 6130 7125 6130
|
||||
Text Label 9635 5145 1 60 ~ 0
|
||||
5Vusb
|
||||
Connection ~ 7445 7490
|
||||
Connection ~ 6845 7190
|
||||
Connection ~ 7425 6130
|
||||
Connection ~ 6825 5830
|
||||
Wire Wire Line
|
||||
6845 7190 7145 7190
|
||||
Connection ~ 7145 7490
|
||||
6825 5830 7125 5830
|
||||
Connection ~ 7125 6130
|
||||
Wire Wire Line
|
||||
7145 7490 7445 7490
|
||||
7125 6130 7425 6130
|
||||
Wire Wire Line
|
||||
7235 7060 7235 7190
|
||||
Connection ~ 7235 7060
|
||||
Connection ~ 7235 7190
|
||||
7215 5700 7215 5830
|
||||
Connection ~ 7215 5700
|
||||
Connection ~ 7215 5830
|
||||
Wire Wire Line
|
||||
7235 7190 7445 7190
|
||||
7215 5830 7425 5830
|
||||
Connection ~ 6465 1595
|
||||
$Comp
|
||||
L Device:D_Schottky D1
|
||||
@ -405,30 +394,19 @@ Wire Wire Line
|
||||
2010 2540 2350 2540
|
||||
Connection ~ 2010 2540
|
||||
Connection ~ 2350 2540
|
||||
$Comp
|
||||
L Device:D_Zener D8
|
||||
U 1 1 5E7D7999
|
||||
P 7655 1385
|
||||
F 0 "D8" H 7655 1485 50 0000 C CNN
|
||||
F 1 "MM3Z4V7" H 7655 1285 50 0000 C CNN
|
||||
F 2 "Diode_SMD:D_0805_2012Metric_Pad1.15x1.40mm_HandSolder" H 7655 1385 50 0001 C CNN
|
||||
F 3 "" H 7655 1385 50 0000 C CNN
|
||||
1 7655 1385
|
||||
0 1 1 0
|
||||
$EndComp
|
||||
Wire Notes Line
|
||||
6025 535 7985 535
|
||||
Wire Notes Line
|
||||
7985 535 7985 1985
|
||||
Wire Notes Line
|
||||
7985 1985 6025 1985
|
||||
Text Notes 8145 5860 0 60 ~ 0
|
||||
Text Notes 8125 4500 0 60 ~ 0
|
||||
External 5V voltage control
|
||||
Text Notes 8145 5765 0 60 ~ 0
|
||||
Text Notes 8125 4405 0 60 ~ 0
|
||||
External 12V voltage control
|
||||
Text Label 7885 5860 0 60 ~ 0
|
||||
Text Label 7865 4500 0 60 ~ 0
|
||||
AIN1
|
||||
Text Label 7885 5760 0 60 ~ 0
|
||||
Text Label 7865 4400 0 60 ~ 0
|
||||
AIN0
|
||||
Text Notes 5595 1485 0 59 ~ 0
|
||||
VCC\nBOOT0\nNRST\nGND
|
||||
@ -567,63 +545,47 @@ Wire Notes Line
|
||||
$Comp
|
||||
L Device:C C20
|
||||
U 1 1 590A8102
|
||||
P 7895 4140
|
||||
F 0 "C20" H 7920 4240 50 0000 L CNN
|
||||
F 1 "0.1" H 7920 4040 50 0000 L CNN
|
||||
F 2 "Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder" H 7933 3990 50 0001 C CNN
|
||||
F 3 "" H 7895 4140 50 0000 C CNN
|
||||
1 7895 4140
|
||||
P 7875 2780
|
||||
F 0 "C20" H 7900 2880 50 0000 L CNN
|
||||
F 1 "0.1" H 7900 2680 50 0000 L CNN
|
||||
F 2 "Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder" H 7913 2630 50 0001 C CNN
|
||||
F 3 "" H 7875 2780 50 0000 C CNN
|
||||
1 7875 2780
|
||||
1 0 0 -1
|
||||
$EndComp
|
||||
Text Notes 1670 695 0 60 ~ 0
|
||||
Text Notes 1430 700 0 60 ~ 0
|
||||
5V power source
|
||||
Wire Wire Line
|
||||
1485 1045 1485 1155
|
||||
Connection ~ 1485 1045
|
||||
Wire Wire Line
|
||||
1485 955 1485 1045
|
||||
$Comp
|
||||
L Device:R R1
|
||||
U 1 1 5ED7FE5E
|
||||
P 1335 1045
|
||||
F 0 "R1" V 1255 1045 50 0000 C CNN
|
||||
F 1 "10k" V 1335 1045 50 0000 C CNN
|
||||
F 2 "Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder" V 1265 1045 50 0001 C CNN
|
||||
F 3 "~" H 1335 1045 50 0001 C CNN
|
||||
1 1335 1045
|
||||
P 1095 1155
|
||||
F 0 "R1" V 1015 1155 50 0000 C CNN
|
||||
F 1 "10k" V 1095 1155 50 0000 C CNN
|
||||
F 2 "Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder" V 1025 1155 50 0001 C CNN
|
||||
F 3 "~" H 1095 1155 50 0001 C CNN
|
||||
1 1095 1155
|
||||
0 1 1 0
|
||||
$EndComp
|
||||
$Comp
|
||||
L Device:D_Zener D3
|
||||
U 1 1 5ED78D2C
|
||||
P 1635 1155
|
||||
F 0 "D3" H 1705 1075 50 0000 C CNN
|
||||
F 1 "MM3Z7V5" H 1725 1255 50 0000 C CNN
|
||||
F 2 "Diode_SMD:D_0805_2012Metric_Pad1.15x1.40mm_HandSolder" H 1635 1155 50 0001 C CNN
|
||||
F 3 "~" H 1635 1155 50 0001 C CNN
|
||||
1 1635 1155
|
||||
P 1395 1155
|
||||
F 0 "D3" H 1465 1075 50 0000 C CNN
|
||||
F 1 "MM3Z7V5" H 1515 1265 50 0000 C CNN
|
||||
F 2 "Diode_SMD:D_0805_2012Metric_Pad1.15x1.40mm_HandSolder" H 1395 1155 50 0001 C CNN
|
||||
F 3 "~" H 1395 1155 50 0001 C CNN
|
||||
1 1395 1155
|
||||
-1 0 0 1
|
||||
$EndComp
|
||||
$Comp
|
||||
L power:GND #PWR03
|
||||
U 1 1 5A598436
|
||||
P 1185 1045
|
||||
F 0 "#PWR03" H 1185 795 50 0001 C CNN
|
||||
F 1 "GND" H 1185 895 50 0001 C CNN
|
||||
F 2 "" H 1185 1045 50 0000 C CNN
|
||||
F 3 "" H 1185 1045 50 0000 C CNN
|
||||
1 1185 1045
|
||||
1 0 0 -1
|
||||
$EndComp
|
||||
$Comp
|
||||
L Device:Q_PMOS_GSD Q1
|
||||
U 1 1 5910E2F2
|
||||
P 1685 955
|
||||
F 0 "Q1" H 1525 1010 50 0000 L CNN
|
||||
F 1 "AO3401" H 1400 1085 50 0000 L CNN
|
||||
F 2 "Package_TO_SOT_SMD:SOT-23_Handsoldering" H 1885 1055 50 0001 C CNN
|
||||
F 3 "" H 1685 955 50 0000 C CNN
|
||||
1 1685 955
|
||||
P 1445 955
|
||||
F 0 "Q1" H 1285 1010 50 0000 L CNN
|
||||
F 1 "AO3401" V 1665 810 50 0000 L CNN
|
||||
F 2 "Package_TO_SOT_SMD:SOT-23_Handsoldering" H 1645 1055 50 0001 C CNN
|
||||
F 3 "" H 1445 955 50 0000 C CNN
|
||||
1 1445 955
|
||||
1 0 0 -1
|
||||
$EndComp
|
||||
$Comp
|
||||
@ -773,55 +735,55 @@ ADC0
|
||||
$Comp
|
||||
L stm32-rescue:L-Chiller_control-rescue L1
|
||||
U 1 1 5F7F79F1
|
||||
P 7230 3965
|
||||
F 0 "L1" V 7180 3965 50 0000 C CNN
|
||||
F 1 "BMBA 0.1mH" V 7305 3965 50 0000 C CNN
|
||||
F 2 "Inductor_SMD:L_0805_2012Metric_Pad1.15x1.40mm_HandSolder" H 7230 3965 50 0001 C CNN
|
||||
F 3 "" H 7230 3965 50 0001 C CNN
|
||||
1 7230 3965
|
||||
P 7210 2605
|
||||
F 0 "L1" V 7160 2605 50 0000 C CNN
|
||||
F 1 "BMBA 0.1mH" V 7285 2605 50 0000 C CNN
|
||||
F 2 "Inductor_SMD:L_0805_2012Metric_Pad1.15x1.40mm_HandSolder" H 7210 2605 50 0001 C CNN
|
||||
F 3 "" H 7210 2605 50 0001 C CNN
|
||||
1 7210 2605
|
||||
0 -1 -1 0
|
||||
$EndComp
|
||||
Wire Wire Line
|
||||
7285 4060 7285 4030
|
||||
7265 2700 7265 2670
|
||||
Wire Wire Line
|
||||
7285 4030 7485 4030
|
||||
7265 2670 7465 2670
|
||||
Wire Wire Line
|
||||
7485 4030 7485 4060
|
||||
7465 2670 7465 2700
|
||||
$Comp
|
||||
L power:+3.3V #PWR026
|
||||
U 1 1 5E441E44
|
||||
P 6900 3955
|
||||
F 0 "#PWR026" H 6900 3805 50 0001 C CNN
|
||||
F 1 "+3.3V" H 6900 4095 50 0000 C CNN
|
||||
F 2 "" H 6900 3955 50 0000 C CNN
|
||||
F 3 "" H 6900 3955 50 0000 C CNN
|
||||
1 6900 3955
|
||||
P 6880 2595
|
||||
F 0 "#PWR026" H 6880 2445 50 0001 C CNN
|
||||
F 1 "+3.3V" H 6880 2735 50 0000 C CNN
|
||||
F 2 "" H 6880 2595 50 0000 C CNN
|
||||
F 3 "" H 6880 2595 50 0000 C CNN
|
||||
1 6880 2595
|
||||
1 0 0 -1
|
||||
$EndComp
|
||||
$Comp
|
||||
L power:GND #PWR030
|
||||
U 1 1 5F84BD3A
|
||||
P 7895 4290
|
||||
F 0 "#PWR030" H 7895 4040 50 0001 C CNN
|
||||
F 1 "GND" H 7895 4140 50 0001 C CNN
|
||||
F 2 "" H 7895 4290 50 0000 C CNN
|
||||
F 3 "" H 7895 4290 50 0000 C CNN
|
||||
1 7895 4290
|
||||
P 7875 2930
|
||||
F 0 "#PWR030" H 7875 2680 50 0001 C CNN
|
||||
F 1 "GND" H 7875 2780 50 0001 C CNN
|
||||
F 2 "" H 7875 2930 50 0000 C CNN
|
||||
F 3 "" H 7875 2930 50 0000 C CNN
|
||||
1 7875 2930
|
||||
1 0 0 -1
|
||||
$EndComp
|
||||
Wire Wire Line
|
||||
7380 4060 7385 4060
|
||||
7360 2700 7365 2700
|
||||
Wire Wire Line
|
||||
6900 3955 7080 3955
|
||||
6880 2595 7060 2595
|
||||
Wire Wire Line
|
||||
7080 3955 7080 3965
|
||||
7060 2595 7060 2605
|
||||
Wire Wire Line
|
||||
7080 3965 7080 4060
|
||||
Connection ~ 7080 3965
|
||||
7060 2605 7060 2700
|
||||
Connection ~ 7060 2605
|
||||
Wire Wire Line
|
||||
7380 3965 7605 3965
|
||||
7360 2605 7585 2605
|
||||
Wire Wire Line
|
||||
7895 3965 7895 3990
|
||||
7875 2605 7875 2630
|
||||
Wire Wire Line
|
||||
5320 1155 5365 1155
|
||||
Wire Wire Line
|
||||
@ -867,25 +829,14 @@ $EndComp
|
||||
Wire Wire Line
|
||||
2295 1455 2295 1505
|
||||
$Comp
|
||||
L power:GND #PWR08
|
||||
U 1 1 58C43B9F
|
||||
P 2035 1505
|
||||
F 0 "#PWR08" H 2035 1255 50 0001 C CNN
|
||||
F 1 "GND" H 2035 1355 50 0001 C CNN
|
||||
F 2 "" H 2035 1505 50 0000 C CNN
|
||||
F 3 "" H 2035 1505 50 0000 C CNN
|
||||
1 2035 1505
|
||||
1 0 0 -1
|
||||
$EndComp
|
||||
$Comp
|
||||
L Device:C C3
|
||||
U 1 1 596772D4
|
||||
P 1785 1355
|
||||
F 0 "C3" H 1810 1455 50 0000 L CNN
|
||||
F 1 "0.1" H 1810 1255 50 0000 L CNN
|
||||
F 2 "Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder" H 1823 1205 50 0001 C CNN
|
||||
F 3 "" H 1785 1355 50 0000 C CNN
|
||||
1 1785 1355
|
||||
P 1545 1305
|
||||
F 0 "C3" H 1570 1405 50 0000 L CNN
|
||||
F 1 "0.1" H 1570 1205 50 0000 L CNN
|
||||
F 2 "Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder" H 1583 1155 50 0001 C CNN
|
||||
F 3 "" H 1545 1305 50 0000 C CNN
|
||||
1 1545 1305
|
||||
1 0 0 -1
|
||||
$EndComp
|
||||
$Comp
|
||||
@ -910,18 +861,12 @@ F 3 "" H 2695 1305 50 0000 C CNN
|
||||
1 2695 1305
|
||||
1 0 0 -1
|
||||
$EndComp
|
||||
Wire Wire Line
|
||||
1785 1205 1785 1155
|
||||
Wire Wire Line
|
||||
1785 1505 2035 1505
|
||||
Connection ~ 2295 1505
|
||||
Wire Wire Line
|
||||
2295 1505 2695 1505
|
||||
Connection ~ 2695 1505
|
||||
Wire Wire Line
|
||||
2695 1505 2695 1455
|
||||
Wire Wire Line
|
||||
1785 1155 1990 1155
|
||||
Wire Wire Line
|
||||
2295 1505 2295 1555
|
||||
$Comp
|
||||
@ -941,7 +886,7 @@ Wire Wire Line
|
||||
2945 1505 2945 1455
|
||||
Wire Wire Line
|
||||
2595 1155 2695 1155
|
||||
Connection ~ 1785 1155
|
||||
Connection ~ 1545 1155
|
||||
$Comp
|
||||
L stm32-rescue:+3.3V-Chiller_control-rescue #PWR01
|
||||
U 1 1 5F9F5571
|
||||
@ -1171,19 +1116,14 @@ Wire Notes Line
|
||||
2425 4675 650 4675
|
||||
Wire Notes Line
|
||||
650 4675 650 2900
|
||||
Text Label 7885 5360 0 60 ~ 0
|
||||
Text Label 7865 4000 0 60 ~ 0
|
||||
ADC0
|
||||
Text Label 7885 5460 0 60 ~ 0
|
||||
Text Label 7865 4100 0 60 ~ 0
|
||||
ADC1
|
||||
Text Label 7885 5560 0 60 ~ 0
|
||||
Text Label 7865 4200 0 60 ~ 0
|
||||
ADC2
|
||||
Text Label 7885 5660 0 60 ~ 0
|
||||
Text Label 7865 4300 0 60 ~ 0
|
||||
ADC3
|
||||
Wire Wire Line
|
||||
1785 755 1185 755
|
||||
Wire Wire Line
|
||||
1185 855 1185 1045
|
||||
Connection ~ 1185 1045
|
||||
Wire Notes Line
|
||||
650 525 3150 525
|
||||
Wire Notes Line
|
||||
@ -1192,7 +1132,7 @@ Wire Notes Line
|
||||
3150 1775 650 1775
|
||||
Wire Notes Line
|
||||
650 1775 650 525
|
||||
Text Label 7885 6760 0 60 ~ 0
|
||||
Text Label 7865 5400 0 60 ~ 0
|
||||
Buzzer
|
||||
$Comp
|
||||
L stm32-rescue:+12V-Chiller_control-rescue #PWR06
|
||||
@ -1208,15 +1148,15 @@ $EndComp
|
||||
Connection ~ 1990 1155
|
||||
Wire Wire Line
|
||||
1990 1155 1995 1155
|
||||
Text Label 7885 6160 0 50 ~ 0
|
||||
Text Label 7865 4800 0 50 ~ 0
|
||||
TIM1_CH1
|
||||
Text Label 7885 6260 0 50 ~ 0
|
||||
Text Label 7865 4900 0 50 ~ 0
|
||||
TIM1_CH2
|
||||
Text Label 7885 6360 0 50 ~ 0
|
||||
Text Label 7865 5000 0 50 ~ 0
|
||||
TIM1_CH3
|
||||
Text Label 4865 2985 0 50 ~ 0
|
||||
TIM1_CH1
|
||||
Text Label 7885 6060 0 50 ~ 0
|
||||
Text Label 7865 4700 0 50 ~ 0
|
||||
TIM14_CH1
|
||||
$Comp
|
||||
L stm32-rescue:+12V-Chiller_control-rescue #PWR023
|
||||
@ -1234,7 +1174,7 @@ L Device:R R26
|
||||
U 1 1 590A6DD4
|
||||
P 6465 995
|
||||
F 0 "R26" V 6545 995 50 0000 C CNN
|
||||
F 1 "220k" V 6465 995 50 0000 C CNN
|
||||
F 1 "3.3k" V 6465 995 50 0000 C CNN
|
||||
F 2 "Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder" V 6395 995 50 0001 C CNN
|
||||
F 3 "" H 6465 995 50 0000 C CNN
|
||||
1 6465 995
|
||||
@ -1307,12 +1247,12 @@ TIM1_CH3
|
||||
$Comp
|
||||
L Power_Protection:USBLC6-2SC6 U4
|
||||
U 1 1 5F40EDD5
|
||||
P 9155 6505
|
||||
F 0 "U4" V 8795 6740 50 0000 C CNN
|
||||
F 1 "USBLC6-2SC6" V 8980 6470 50 0000 C CNN
|
||||
F 2 "Package_TO_SOT_SMD:SOT-23-6" H 8405 6905 50 0001 C CNN
|
||||
F 3 "http://www2.st.com/resource/en/datasheet/CD00050750.pdf" H 9355 6855 50 0001 C CNN
|
||||
1 9155 6505
|
||||
P 9135 5145
|
||||
F 0 "U4" V 8775 5380 50 0000 C CNN
|
||||
F 1 "USBLC6-2SC6" V 8960 5110 50 0000 C CNN
|
||||
F 2 "Package_TO_SOT_SMD:SOT-23-6" H 8385 5545 50 0001 C CNN
|
||||
F 3 "http://www2.st.com/resource/en/datasheet/CD00050750.pdf" H 9335 5495 50 0001 C CNN
|
||||
1 9135 5145
|
||||
0 1 -1 0
|
||||
$EndComp
|
||||
$Comp
|
||||
@ -1380,17 +1320,17 @@ Wire Notes Line
|
||||
4725 1500 3250 1500
|
||||
Wire Notes Line
|
||||
3250 1500 3250 525
|
||||
Text Label 7885 5960 0 50 ~ 0
|
||||
Text Label 7865 4600 0 50 ~ 0
|
||||
TIM3_CH1
|
||||
Text Label 4615 2970 2 50 ~ 0
|
||||
TIM3_CH1
|
||||
Text Label 6585 4960 2 60 ~ 0
|
||||
Text Label 6565 3600 2 60 ~ 0
|
||||
Relay
|
||||
Text Label 3495 2545 2 50 ~ 0
|
||||
Cooler0
|
||||
Text Label 6585 5760 2 50 ~ 0
|
||||
Text Label 6565 4400 2 50 ~ 0
|
||||
Cooler0
|
||||
Text Label 6585 5860 2 50 ~ 0
|
||||
Text Label 6565 4500 2 50 ~ 0
|
||||
Cooler1
|
||||
$Comp
|
||||
L Device:D_Schottky D5
|
||||
@ -1608,17 +1548,17 @@ Wire Notes Line
|
||||
5275 5400 3175 5400
|
||||
Wire Notes Line
|
||||
3175 5400 3175 1825
|
||||
NoConn ~ 6585 4660
|
||||
NoConn ~ 6585 4760
|
||||
NoConn ~ 6585 5160
|
||||
NoConn ~ 7885 6660
|
||||
NoConn ~ 7885 6860
|
||||
NoConn ~ 6585 5960
|
||||
NoConn ~ 6585 6060
|
||||
NoConn ~ 6585 6160
|
||||
NoConn ~ 6585 6260
|
||||
NoConn ~ 6585 6560
|
||||
NoConn ~ 6585 6660
|
||||
NoConn ~ 6565 3300
|
||||
NoConn ~ 6565 3400
|
||||
NoConn ~ 6565 3800
|
||||
NoConn ~ 7865 5300
|
||||
NoConn ~ 7865 5500
|
||||
NoConn ~ 6565 4600
|
||||
NoConn ~ 6565 4700
|
||||
NoConn ~ 6565 4800
|
||||
NoConn ~ 6565 4900
|
||||
NoConn ~ 6565 5200
|
||||
NoConn ~ 6565 5300
|
||||
Wire Notes Line
|
||||
8175 550 10250 550
|
||||
NoConn ~ 10775 8925
|
||||
@ -1628,17 +1568,17 @@ NoConn ~ 10650 9800
|
||||
$Comp
|
||||
L power:PWR_FLAG #FLG03
|
||||
U 1 1 5F6E5259
|
||||
P 7605 3965
|
||||
F 0 "#FLG03" H 7605 4040 50 0001 C CNN
|
||||
F 1 "PWR_FLAG" H 7605 4138 50 0001 C CNN
|
||||
F 2 "" H 7605 3965 50 0001 C CNN
|
||||
F 3 "~" H 7605 3965 50 0001 C CNN
|
||||
1 7605 3965
|
||||
P 7585 2605
|
||||
F 0 "#FLG03" H 7585 2680 50 0001 C CNN
|
||||
F 1 "PWR_FLAG" H 7585 2778 50 0001 C CNN
|
||||
F 2 "" H 7585 2605 50 0001 C CNN
|
||||
F 3 "~" H 7585 2605 50 0001 C CNN
|
||||
1 7585 2605
|
||||
1 0 0 -1
|
||||
$EndComp
|
||||
Connection ~ 7605 3965
|
||||
Connection ~ 7585 2605
|
||||
Wire Wire Line
|
||||
7605 3965 7895 3965
|
||||
7585 2605 7875 2605
|
||||
$Comp
|
||||
L power:PWR_FLAG #FLG02
|
||||
U 1 1 5F6E57E8
|
||||
@ -1747,45 +1687,45 @@ Wire Wire Line
|
||||
5135 6005 5135 6185
|
||||
Connection ~ 5235 6185
|
||||
Wire Wire Line
|
||||
8585 6610 8585 7005
|
||||
8565 5250 8565 5645
|
||||
Wire Wire Line
|
||||
8585 7005 9055 7005
|
||||
8565 5645 9035 5645
|
||||
Wire Wire Line
|
||||
8585 6410 8585 6005
|
||||
8565 5050 8565 4645
|
||||
Wire Wire Line
|
||||
8585 6005 9055 6005
|
||||
8565 4645 9035 4645
|
||||
$Comp
|
||||
L Connector:USB_B P1
|
||||
U 1 1 58C433D0
|
||||
P 10020 6540
|
||||
F 0 "P1" H 10180 6200 50 0000 C CNN
|
||||
F 1 "USB_A" H 10020 6890 50 0000 C CNN
|
||||
F 2 "Connector_USB:USB_B_OST_USB-B1HSxx_Horizontal" V 9970 6440 50 0001 C CNN
|
||||
F 3 "" V 9970 6440 50 0000 C CNN
|
||||
1 10020 6540
|
||||
P 10000 5180
|
||||
F 0 "P1" H 10160 4840 50 0000 C CNN
|
||||
F 1 "USB_A" H 10000 5530 50 0000 C CNN
|
||||
F 2 "Connector_USB:USB_B_OST_USB-B1HSxx_Horizontal" V 9950 5080 50 0001 C CNN
|
||||
F 3 "" V 9950 5080 50 0000 C CNN
|
||||
1 10000 5180
|
||||
-1 0 0 1
|
||||
$EndComp
|
||||
Wire Wire Line
|
||||
9720 6440 9720 6005
|
||||
9700 5080 9700 4645
|
||||
Wire Wire Line
|
||||
9720 6005 9255 6005
|
||||
Text Label 9720 6740 3 60 ~ 0
|
||||
9700 4645 9235 4645
|
||||
Text Label 9700 5380 3 60 ~ 0
|
||||
5Vusb
|
||||
Wire Wire Line
|
||||
9720 6540 9680 6540
|
||||
9700 5180 9660 5180
|
||||
Wire Wire Line
|
||||
9680 6540 9680 6700
|
||||
9660 5180 9660 5340
|
||||
Wire Wire Line
|
||||
9680 6700 9505 6700
|
||||
9660 5340 9485 5340
|
||||
Wire Wire Line
|
||||
9505 6700 9505 7005
|
||||
9485 5340 9485 5645
|
||||
Wire Wire Line
|
||||
9505 7005 9255 7005
|
||||
9485 5645 9235 5645
|
||||
Wire Wire Line
|
||||
10020 6140 10120 6140
|
||||
10000 4780 10100 4780
|
||||
Wire Wire Line
|
||||
10120 6140 10290 6140
|
||||
Connection ~ 10120 6140
|
||||
10100 4780 10270 4780
|
||||
Connection ~ 10100 4780
|
||||
Wire Wire Line
|
||||
1335 3940 1625 3940
|
||||
Wire Wire Line
|
||||
@ -1816,16 +1756,16 @@ Text Label 5835 6185 0 50 ~ 0
|
||||
Btn0
|
||||
Text Label 5835 6380 0 50 ~ 0
|
||||
Btn1
|
||||
Text Label 6585 6760 2 50 ~ 0
|
||||
Text Label 6565 5400 2 50 ~ 0
|
||||
Btn0
|
||||
Text Label 6585 6860 2 50 ~ 0
|
||||
Text Label 6565 5500 2 50 ~ 0
|
||||
Btn1
|
||||
NoConn ~ 6585 5660
|
||||
NoConn ~ 6585 5360
|
||||
NoConn ~ 6585 5460
|
||||
NoConn ~ 6585 5560
|
||||
NoConn ~ 6585 6360
|
||||
NoConn ~ 6585 6460
|
||||
NoConn ~ 6565 4300
|
||||
NoConn ~ 6565 4000
|
||||
NoConn ~ 6565 4100
|
||||
NoConn ~ 6565 4200
|
||||
NoConn ~ 6565 5000
|
||||
NoConn ~ 6565 5100
|
||||
$Comp
|
||||
L Connector:Conn_01x02_Female J7
|
||||
U 1 1 5F670F02
|
||||
@ -1849,39 +1789,39 @@ F 3 "~" H 5565 1355 50 0001 C CNN
|
||||
1 0 0 -1
|
||||
$EndComp
|
||||
Wire Wire Line
|
||||
7235 7060 7285 7060
|
||||
7215 5700 7265 5700
|
||||
Wire Wire Line
|
||||
7385 7060 7285 7060
|
||||
Connection ~ 7285 7060
|
||||
7365 5700 7265 5700
|
||||
Connection ~ 7265 5700
|
||||
Wire Wire Line
|
||||
7185 7060 7235 7060
|
||||
7165 5700 7215 5700
|
||||
Wire Wire Line
|
||||
7085 7060 7185 7060
|
||||
Connection ~ 7185 7060
|
||||
Connection ~ 7285 4060
|
||||
7065 5700 7165 5700
|
||||
Connection ~ 7165 5700
|
||||
Connection ~ 7265 2700
|
||||
Wire Wire Line
|
||||
7185 4060 7285 4060
|
||||
Connection ~ 7185 4060
|
||||
7165 2700 7265 2700
|
||||
Connection ~ 7165 2700
|
||||
Wire Wire Line
|
||||
7085 4060 7185 4060
|
||||
7065 2700 7165 2700
|
||||
Wire Wire Line
|
||||
7080 4060 7085 4060
|
||||
Connection ~ 7085 4060
|
||||
7060 2700 7065 2700
|
||||
Connection ~ 7065 2700
|
||||
$Comp
|
||||
L MCU_ST_STM32F0:STM32F072CBTx U3
|
||||
U 1 1 5E89EA8D
|
||||
P 7285 5560
|
||||
F 0 "U3" H 7325 6400 50 0000 C CNN
|
||||
F 1 "STM32F072CBTx" H 7335 6260 50 0000 C CNN
|
||||
F 2 "Package_QFP:LQFP-48_7x7mm_P0.5mm" H 6685 4160 50 0001 R CNN
|
||||
F 3 "http://www.st.com/st-web-ui/static/active/en/resource/technical/document/datasheet/DM00090510.pdf" H 7285 5560 50 0001 C CNN
|
||||
1 7285 5560
|
||||
P 7265 4200
|
||||
F 0 "U3" H 7305 5040 50 0000 C CNN
|
||||
F 1 "STM32F072CBTx" H 7315 4900 50 0000 C CNN
|
||||
F 2 "Package_QFP:LQFP-48_7x7mm_P0.5mm" H 6665 2800 50 0001 R CNN
|
||||
F 3 "http://www.st.com/st-web-ui/static/active/en/resource/technical/document/datasheet/DM00090510.pdf" H 7265 4200 50 0001 C CNN
|
||||
1 7265 4200
|
||||
1 0 0 -1
|
||||
$EndComp
|
||||
Connection ~ 7380 3965
|
||||
Connection ~ 7360 2605
|
||||
Wire Wire Line
|
||||
7380 3965 7380 4060
|
||||
NoConn ~ 6585 5060
|
||||
7360 2605 7360 2700
|
||||
NoConn ~ 6565 3700
|
||||
Wire Wire Line
|
||||
8510 1955 9110 1955
|
||||
NoConn ~ 9410 1405
|
||||
@ -1908,12 +1848,12 @@ $Comp
|
||||
L Device:D_Schottky D9
|
||||
U 1 1 5F45888F
|
||||
P 8815 1105
|
||||
F 0 "D9" V 8800 1275 50 0000 C CNN
|
||||
F 1 "1N5819" H 8815 1195 50 0000 C CNN
|
||||
F 0 "D9" V 8810 925 50 0000 C CNN
|
||||
F 1 "1N5819" H 8820 1015 50 0000 C CNN
|
||||
F 2 "Diode_SMD:D_SOD-323_HandSoldering" H 8815 1105 50 0001 C CNN
|
||||
F 3 "" H 8815 1105 50 0001 C CNN
|
||||
1 8815 1105
|
||||
0 -1 -1 0
|
||||
0 1 1 0
|
||||
$EndComp
|
||||
Wire Wire Line
|
||||
9110 1955 9110 1855
|
||||
@ -2004,4 +1944,59 @@ Wire Notes Line
|
||||
8175 2180 10250 2180
|
||||
Wire Notes Line
|
||||
10250 2180 10250 550
|
||||
Wire Wire Line
|
||||
7405 1185 7755 1185
|
||||
$Comp
|
||||
L power:GND #PWR03
|
||||
U 1 1 5A598436
|
||||
P 945 1155
|
||||
F 0 "#PWR03" H 945 905 50 0001 C CNN
|
||||
F 1 "GND" H 945 1005 50 0001 C CNN
|
||||
F 2 "" H 945 1155 50 0000 C CNN
|
||||
F 3 "" H 945 1155 50 0000 C CNN
|
||||
1 945 1155
|
||||
1 0 0 -1
|
||||
$EndComp
|
||||
Wire Wire Line
|
||||
1245 955 1245 1155
|
||||
Wire Wire Line
|
||||
1185 755 1545 755
|
||||
Connection ~ 1245 1155
|
||||
Wire Wire Line
|
||||
945 1155 945 955
|
||||
Wire Wire Line
|
||||
945 955 1185 955
|
||||
Wire Wire Line
|
||||
1185 955 1185 855
|
||||
Connection ~ 945 1155
|
||||
$Comp
|
||||
L Device:CP C10
|
||||
U 1 1 5F97B2AC
|
||||
P 1800 1305
|
||||
F 0 "C10" H 1820 1395 50 0000 L CNN
|
||||
F 1 "47u" H 1918 1260 50 0000 L CNN
|
||||
F 2 "Capacitor_THT:CP_Radial_D8.0mm_P3.50mm" H 1838 1155 50 0001 C CNN
|
||||
F 3 "~" H 1800 1305 50 0001 C CNN
|
||||
1 1800 1305
|
||||
1 0 0 -1
|
||||
$EndComp
|
||||
Wire Wire Line
|
||||
1545 1155 1800 1155
|
||||
Connection ~ 1800 1155
|
||||
Wire Wire Line
|
||||
1800 1155 1990 1155
|
||||
$Comp
|
||||
L power:GND #PWR08
|
||||
U 1 1 58C43B9F
|
||||
P 1800 1455
|
||||
F 0 "#PWR08" H 1800 1205 50 0001 C CNN
|
||||
F 1 "GND" H 1800 1305 50 0001 C CNN
|
||||
F 2 "" H 1800 1455 50 0000 C CNN
|
||||
F 3 "" H 1800 1455 50 0000 C CNN
|
||||
1 1800 1455
|
||||
1 0 0 -1
|
||||
$EndComp
|
||||
Wire Wire Line
|
||||
1545 1455 1800 1455
|
||||
Connection ~ 1800 1455
|
||||
$EndSCHEMATC
|
||||
|
||||
98
F0-nolib/Socket_fans/main.c
Normal file
98
F0-nolib/Socket_fans/main.c
Normal file
@ -0,0 +1,98 @@
|
||||
/*
|
||||
* 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 "proto.h"
|
||||
#include "usb.h"
|
||||
#include "usb_lib.h"
|
||||
|
||||
volatile uint32_t Tms = 0;
|
||||
|
||||
/* Called when systick fires */
|
||||
void sys_tick_handler(void){
|
||||
static uint32_t actr = 0;
|
||||
++Tms;
|
||||
if(++actr == 1000){ // RPM counter
|
||||
Cooler0speed = TIM3->CNT/2;
|
||||
TIM3->CNT = 0;
|
||||
Cooler1speed = Cooler1RPM/2;
|
||||
Cooler1RPM = 0;
|
||||
actr = 0;
|
||||
}
|
||||
}
|
||||
|
||||
#define USBBUF 63
|
||||
// usb getline
|
||||
static char *get_USB(){
|
||||
static char tmpbuf[USBBUF+1], *curptr = tmpbuf;
|
||||
static int rest = USBBUF;
|
||||
uint8_t x = USB_receive((uint8_t*)curptr);
|
||||
if(!x) return NULL;
|
||||
curptr[x] = 0;
|
||||
if(x == 1 && *curptr == 0x7f){ // backspace
|
||||
if(curptr > tmpbuf){
|
||||
--curptr;
|
||||
USND("\b \b");
|
||||
}
|
||||
return NULL;
|
||||
}
|
||||
USB_sendstr(curptr); // echo
|
||||
if(curptr[x-1] == '\n'){ // || curptr[x-1] == '\r'){
|
||||
curptr = tmpbuf;
|
||||
rest = USBBUF;
|
||||
// omit empty lines
|
||||
if(tmpbuf[0] == '\n') return NULL;
|
||||
// and wrong empty lines
|
||||
if(tmpbuf[0] == '\r' && tmpbuf[1] == '\n') return NULL;
|
||||
return tmpbuf;
|
||||
}
|
||||
curptr += x; rest -= x;
|
||||
if(rest <= 0){ // buffer overflow
|
||||
curptr = tmpbuf;
|
||||
rest = USBBUF;
|
||||
}
|
||||
return NULL;
|
||||
}
|
||||
|
||||
int main(void){
|
||||
//uint32_t lastT = 0;
|
||||
char *txt;
|
||||
sysreset();
|
||||
SysTick_Config(6000, 1);
|
||||
HW_setup();
|
||||
USB_setup();
|
||||
RCC->CSR |= RCC_CSR_RMVF; // remove reset flags
|
||||
iwdg_setup();
|
||||
|
||||
while (1){
|
||||
IWDG->KR = IWDG_REFRESH; // refresh watchdog
|
||||
/*if(lastT && (Tms - lastT > 199)){
|
||||
LED_off(LED0);
|
||||
lastT = 0;
|
||||
}*/
|
||||
usb_proc();
|
||||
if((txt = get_USB())){
|
||||
IWDG->KR = IWDG_REFRESH;
|
||||
cmd_parser(txt);
|
||||
}
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
343
F0-nolib/Socket_fans/proto.c
Normal file
343
F0-nolib/Socket_fans/proto.c
Normal file
@ -0,0 +1,343 @@
|
||||
/*
|
||||
* 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 "adc.h"
|
||||
#include "hardware.h"
|
||||
#include "proto.h"
|
||||
#include "usb.h"
|
||||
|
||||
#include <string.h> // strlen
|
||||
|
||||
static char buff[BUFSZ+1], *bptr = buff;
|
||||
static uint8_t blen = 0;
|
||||
volatile uint32_t Cooler0speed; // RPM of cooler0
|
||||
volatile uint32_t Cooler1RPM; // Cooler1 RPM counter by EXTI @PA7
|
||||
volatile uint32_t Cooler1speed; // RPM of cooler0
|
||||
|
||||
void sendbuf(){
|
||||
IWDG->KR = IWDG_REFRESH;
|
||||
if(blen == 0) return;
|
||||
*bptr = 0;
|
||||
USB_sendstr(buff);
|
||||
bptr = buff;
|
||||
blen = 0;
|
||||
}
|
||||
|
||||
void bufputchar(char ch){
|
||||
if(blen > BUFSZ-1){
|
||||
sendbuf();
|
||||
}
|
||||
*bptr++ = ch;
|
||||
++blen;
|
||||
}
|
||||
|
||||
void addtobuf(const char *txt){
|
||||
IWDG->KR = IWDG_REFRESH;
|
||||
while(*txt) bufputchar(*txt++);
|
||||
}
|
||||
|
||||
char *omit_spaces(char *buf){
|
||||
while(*buf){
|
||||
if(*buf > ' ') break;
|
||||
++buf;
|
||||
}
|
||||
return buf;
|
||||
}
|
||||
|
||||
// THERE'S NO OVERFLOW PROTECTION IN NUMBER READ PROCEDURES!
|
||||
// read decimal number
|
||||
static char *getdec(char *buf, uint32_t *N){
|
||||
uint32_t num = 0;
|
||||
while(*buf){
|
||||
char c = *buf;
|
||||
if(c < '0' || c > '9'){
|
||||
break;
|
||||
}
|
||||
num *= 10;
|
||||
num += c - '0';
|
||||
++buf;
|
||||
}
|
||||
*N = num;
|
||||
return buf;
|
||||
}
|
||||
// read hexadecimal number (without 0x prefix!)
|
||||
static char *gethex(char *buf, uint32_t *N){
|
||||
uint32_t num = 0;
|
||||
while(*buf){
|
||||
char c = *buf;
|
||||
uint8_t M = 0;
|
||||
if(c >= '0' && c <= '9'){
|
||||
M = '0';
|
||||
}else if(c >= 'A' && c <= 'F'){
|
||||
M = 'A' - 10;
|
||||
}else if(c >= 'a' && c <= 'f'){
|
||||
M = 'a' - 10;
|
||||
}
|
||||
if(M){
|
||||
num <<= 4;
|
||||
num += c - M;
|
||||
}else{
|
||||
break;
|
||||
}
|
||||
++buf;
|
||||
}
|
||||
*N = num;
|
||||
return buf;
|
||||
}
|
||||
// read binary number (without 0b prefix!)
|
||||
static char *getbin(char *buf, uint32_t *N){
|
||||
uint32_t num = 0;
|
||||
while(*buf){
|
||||
char c = *buf;
|
||||
if(c < '0' || c > '1'){
|
||||
break;
|
||||
}
|
||||
num <<= 1;
|
||||
if(c == '1') num |= 1;
|
||||
++buf;
|
||||
}
|
||||
*N = num;
|
||||
return buf;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief getnum - read uint32_t from string (dec, hex or bin: 127, 0x7f, 0b1111111)
|
||||
* @param buf - buffer with number and so on
|
||||
* @param N - the number read
|
||||
* @return pointer to first non-number symbol in buf (if it is == buf, there's no number)
|
||||
*/
|
||||
char *getnum(char *txt, uint32_t *N){
|
||||
if(*txt == '0'){
|
||||
if(txt[1] == 'x' || txt[1] == 'X') return gethex(txt+2, N);
|
||||
if(txt[1] == 'b' || txt[1] == 'B') return getbin(txt+2, N);
|
||||
}
|
||||
return getdec(txt, N);
|
||||
}
|
||||
|
||||
static void onoff(char state, GPIO_TypeDef *port, uint32_t pin, char *text){
|
||||
switch(state){
|
||||
case '0': // off
|
||||
pin_clear(port, pin);
|
||||
break;
|
||||
case '1': // on
|
||||
pin_set(port, pin);
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
SEND(text);
|
||||
bufputchar('=');
|
||||
bufputchar('0' + pin_read(port, pin));
|
||||
}
|
||||
|
||||
// get raw ADC value of channel chno + '0'
|
||||
static inline void ADCget(char chno){
|
||||
if(chno < '0' || chno > '7'){
|
||||
SEND("Channel number shoul be from 0 to 7");
|
||||
return;
|
||||
}
|
||||
int nch = chno - '0';
|
||||
SEND("ADCval");
|
||||
bufputchar(chno);
|
||||
bufputchar('=');
|
||||
printu(getADCval(nch));
|
||||
}
|
||||
|
||||
// get coolerx RPM
|
||||
static inline void coolerRPM(char n){
|
||||
if(n < '0' || n > '1'){
|
||||
SEND("Cooler number should be 0 or 1\n");
|
||||
return;
|
||||
}
|
||||
SEND("RPM");
|
||||
bufputchar(n);
|
||||
bufputchar('=');
|
||||
if(n == '0'){ // cooler0
|
||||
printu(Cooler0speed);
|
||||
}else{ // cooler1
|
||||
printu(Cooler1speed);
|
||||
}
|
||||
}
|
||||
|
||||
// change Coolerx RPM
|
||||
static inline void changeRPM(char *str){
|
||||
char channel = *str++;
|
||||
str = omit_spaces(str);
|
||||
uint32_t rpm;
|
||||
getnum(str, &rpm);
|
||||
if(rpm > 100){
|
||||
SEND("RPM should be from 0 to 100%\n");
|
||||
return;
|
||||
}
|
||||
switch(channel){
|
||||
case '0':
|
||||
TIM1->CCR1 = rpm;
|
||||
break;
|
||||
case '1':
|
||||
TIM1->CCR2 = rpm;
|
||||
break;
|
||||
case '2':
|
||||
TIM1->CCR3 = rpm;
|
||||
break;
|
||||
default:
|
||||
SEND("Cooler number should be from 0 to 2\n");
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief cmd_parser - command parsing
|
||||
* @param txt - buffer with commands & data
|
||||
* @param isUSB - == 1 if data got from USB
|
||||
*/
|
||||
void cmd_parser(char *txt){
|
||||
char _1st = txt[0];
|
||||
/*
|
||||
* parse long commands here
|
||||
*/
|
||||
switch(_1st){
|
||||
case '0': // cooler0: set/clear/check
|
||||
onoff(txt[1], COOLER0_port, COOLER0_pin, "Cooler0");
|
||||
goto eof;
|
||||
break;
|
||||
case '1': // cooler0: set/clear/check
|
||||
onoff(txt[1], COOLER1_port, COOLER1_pin, "Cooler1");
|
||||
goto eof;
|
||||
break;
|
||||
case 'A': // ADC raw values
|
||||
ADCget(txt[1]);
|
||||
goto eof;
|
||||
break;
|
||||
case 'C': // Cooler RPM
|
||||
coolerRPM(txt[1]);
|
||||
goto eof;
|
||||
break;
|
||||
case 'r': // relay: set/clear/check
|
||||
onoff(txt[1], RELAY_port, RELAY_pin, "Relay");
|
||||
goto eof;
|
||||
break;
|
||||
case 'S': // set RPM
|
||||
changeRPM(txt+1);
|
||||
goto eof;
|
||||
break;
|
||||
}
|
||||
if(txt[1] != '\n') *txt = '?'; // help for wrong message length
|
||||
switch(_1st){
|
||||
case 'a':
|
||||
SEND("ADC1->DR=");
|
||||
printu(ADC1->DR);
|
||||
break;
|
||||
case 'B':
|
||||
SEND("Button0=");
|
||||
bufputchar('1' - CHK(BUTTON0)); // buttons are inverted
|
||||
SEND("\nButton1=");
|
||||
bufputchar('1' - CHK(BUTTON1));
|
||||
break;
|
||||
case 'D':
|
||||
SEND("Go into DFU mode\n");
|
||||
sendbuf();
|
||||
Jump2Boot();
|
||||
break;
|
||||
case 'M': // MCU temperature
|
||||
SEND("MCUtemp=");
|
||||
printu(getMCUtemp());
|
||||
break;
|
||||
case 'R':
|
||||
SEND("Soft reset\n");
|
||||
sendbuf();
|
||||
pause_ms(5); // a little pause to transmit data
|
||||
NVIC_SystemReset();
|
||||
break;
|
||||
case 'T':
|
||||
SEND("Time (ms): ");
|
||||
printu(Tms);
|
||||
newline();
|
||||
break;
|
||||
case 'V':
|
||||
SEND("V3_3=");
|
||||
printu(getVdd());
|
||||
SEND("\nV5=");
|
||||
printu(getU5());
|
||||
SEND("\nV12=");
|
||||
printu(getU12());
|
||||
break;
|
||||
case 'Z':
|
||||
adc_setup();
|
||||
SEND("ADC restarted\n");
|
||||
break;
|
||||
default: // help
|
||||
SEND(
|
||||
"'0x' - turn cooler0 on/off (x=1/0) or get status (x - any other)\n"
|
||||
"'1x' - turn cooler1 on/off (x=1/0) or get status (x - any other)\n"
|
||||
"'Ax' - get ADC raw value (x=0..7)\n"
|
||||
"'a' - show current value of ADC1->DR\n"
|
||||
"'B' - buttons' state\n"
|
||||
"'Cx' - get cooler x (0/1) RPM\n"
|
||||
"'D' - activate DFU mode\n"
|
||||
"'M' - get MCU temperature\n"
|
||||
"'R' - software reset\n"
|
||||
"'rx' - relay on/off (x=1/0) or get status\n"
|
||||
"'Sx y' - set coolerx RPM to y\n"
|
||||
"'T' - get time from start (ms)\n"
|
||||
"'V' - get voltage\n"
|
||||
"'Z' - reinit ADC\n"
|
||||
);
|
||||
break;
|
||||
}
|
||||
eof:
|
||||
newline();
|
||||
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;
|
||||
int8_t i, j, z=1;
|
||||
for(i = 0; i < 4; ++i, --ptr){
|
||||
if(*ptr == 0){ // omit leading zeros
|
||||
if(i == 3) z = 0;
|
||||
if(z) continue;
|
||||
}
|
||||
else z = 0;
|
||||
for(j = 1; j > -1; --j){
|
||||
uint8_t half = (*ptr >> (4*j)) & 0x0f;
|
||||
if(half < 10) bufputchar(half + '0');
|
||||
else bufputchar(half - 10 + 'a');
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
55
F0-nolib/Socket_fans/proto.h
Normal file
55
F0-nolib/Socket_fans/proto.h
Normal file
@ -0,0 +1,55 @@
|
||||
/*
|
||||
* 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"
|
||||
#include "hardware.h"
|
||||
|
||||
#define BUFSZ (64)
|
||||
|
||||
// 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)
|
||||
// newline with buffer sending
|
||||
#define NL() do{bufputchar('\n'); sendbuf();}while(0)
|
||||
|
||||
void cmd_parser(char *buf);
|
||||
void addtobuf(const char *txt);
|
||||
void bufputchar(char ch);
|
||||
void printu(uint32_t val);
|
||||
void printuhex(uint32_t val);
|
||||
void sendbuf();
|
||||
|
||||
char *omit_spaces(char *buf);
|
||||
char *getnum(char *buf, uint32_t *N);
|
||||
|
||||
#endif // __PROTO_H__
|
||||
BIN
F0-nolib/Socket_fans/sockfans.bin
Executable file
BIN
F0-nolib/Socket_fans/sockfans.bin
Executable file
Binary file not shown.
180
F0-nolib/Socket_fans/usb.c
Normal file
180
F0-nolib/Socket_fans/usb.c
Normal file
@ -0,0 +1,180 @@
|
||||
/*
|
||||
* 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"
|
||||
|
||||
static volatile uint8_t tx_succesfull = 1;
|
||||
static volatile uint8_t rxNE = 0;
|
||||
|
||||
// interrupt IN handler (never used?)
|
||||
static void EP1_Handler(){
|
||||
uint16_t epstatus = KEEP_DTOG(USB->EPnR[1]);
|
||||
if(RX_FLAG(epstatus)) epstatus = (epstatus & ~USB_EPnR_STAT_TX) ^ USB_EPnR_STAT_RX; // set valid RX
|
||||
else epstatus = epstatus & ~(USB_EPnR_STAT_TX|USB_EPnR_STAT_RX);
|
||||
// clear CTR
|
||||
epstatus = (epstatus & ~(USB_EPnR_CTR_RX|USB_EPnR_CTR_TX));
|
||||
USB->EPnR[1] = epstatus;
|
||||
}
|
||||
|
||||
// data IN/OUT handlers
|
||||
static void transmit_Handler(){ // EP3IN
|
||||
tx_succesfull = 1;
|
||||
uint16_t epstatus = KEEP_DTOG_STAT(USB->EPnR[3]);
|
||||
// clear CTR keep DTOGs & STATs
|
||||
USB->EPnR[3] = (epstatus & ~(USB_EPnR_CTR_TX)); // clear TX ctr
|
||||
}
|
||||
|
||||
static void receive_Handler(){ // EP2OUT
|
||||
rxNE = 1;
|
||||
uint16_t epstatus = KEEP_DTOG_STAT(USB->EPnR[2]);
|
||||
USB->EPnR[2] = (epstatus & ~(USB_EPnR_CTR_RX)); // clear RX ctr
|
||||
}
|
||||
|
||||
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_WKUPM;
|
||||
// clear flags
|
||||
USB->ISTR = 0;
|
||||
// and activate pullup
|
||||
USB->BCDR |= USB_BCDR_DPPU;
|
||||
NVIC_EnableIRQ(USB_IRQn);
|
||||
}
|
||||
|
||||
|
||||
static int usbwr(const uint8_t *buf, uint16_t l){
|
||||
uint32_t ctra = 1000000;
|
||||
while(--ctra && tx_succesfull == 0){
|
||||
IWDG->KR = IWDG_REFRESH;
|
||||
}
|
||||
tx_succesfull = 0;
|
||||
EP_Write(3, buf, l);
|
||||
ctra = 1000000;
|
||||
while(--ctra && tx_succesfull == 0){
|
||||
IWDG->KR = IWDG_REFRESH;
|
||||
}
|
||||
if(tx_succesfull == 0){usbON = 0; return 1;} // usb is OFF?
|
||||
return 0;
|
||||
}
|
||||
|
||||
static uint8_t usbbuff[USB_TXBUFSZ-1]; // temporary buffer (63 - to prevent need of ZLP)
|
||||
static uint8_t buflen = 0; // amount of symbols in usbbuff
|
||||
|
||||
// send next up to 63 bytes of data in usbbuff
|
||||
static void send_next(){
|
||||
if(!buflen || !tx_succesfull) return;
|
||||
tx_succesfull = 0;
|
||||
EP_Write(3, usbbuff, buflen);
|
||||
buflen = 0;
|
||||
}
|
||||
|
||||
// unblocking sending - just fill a buffer
|
||||
void USB_send(const uint8_t *buf, uint16_t len){
|
||||
if(!usbON || !len) return;
|
||||
if(len > USB_TXBUFSZ-1 - buflen){
|
||||
usbwr(usbbuff, buflen);
|
||||
buflen = 0;
|
||||
}
|
||||
if(len > USB_TXBUFSZ-1){
|
||||
USB_send_blk(buf, len);
|
||||
return;
|
||||
}
|
||||
while(len--) usbbuff[buflen++] = *buf++;
|
||||
}
|
||||
|
||||
// send zero-terminated string
|
||||
void USB_sendstr(const char *str){
|
||||
uint16_t l = 0;
|
||||
const char *ptr = str;
|
||||
while(*ptr++) ++l;
|
||||
USB_send((uint8_t*)str, l);
|
||||
}
|
||||
|
||||
// blocking sending
|
||||
void USB_send_blk(const uint8_t *buf, uint16_t len){
|
||||
if(!usbON || !len) return; // USB disconnected
|
||||
if(buflen){
|
||||
usbwr(usbbuff, buflen);
|
||||
buflen = 0;
|
||||
}
|
||||
int needzlp = 0;
|
||||
while(len){
|
||||
if(len == USB_TXBUFSZ) needzlp = 1;
|
||||
uint16_t s = (len > USB_TXBUFSZ) ? USB_TXBUFSZ : len;
|
||||
if(usbwr(buf, s)) return;
|
||||
len -= s;
|
||||
buf += s;
|
||||
}
|
||||
if(needzlp){
|
||||
usbwr(NULL, 0);
|
||||
}
|
||||
}
|
||||
|
||||
void usb_proc(){
|
||||
switch(USB_Dev.USB_Status){
|
||||
case USB_STATE_CONFIGURED:
|
||||
// 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, USB_EP1BUFSZ, 0, EP1_Handler); // IN1 - transmit
|
||||
EP_Init(2, EP_TYPE_BULK, 0, USB_RXBUFSZ, receive_Handler); // OUT2 - receive data
|
||||
EP_Init(3, EP_TYPE_BULK, USB_TXBUFSZ, 0, transmit_Handler); // IN3 - transmit data
|
||||
USB_Dev.USB_Status = USB_STATE_CONNECTED;
|
||||
break;
|
||||
case USB_STATE_DEFAULT:
|
||||
case USB_STATE_ADDRESSED:
|
||||
if(usbON){
|
||||
usbON = 0;
|
||||
}
|
||||
break;
|
||||
default: // USB_STATE_CONNECTED - send next data portion
|
||||
if(!usbON) return;
|
||||
send_next();
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief USB_receive
|
||||
* @param buf (i) - buffer[64] for received data
|
||||
* @return amount of received bytes
|
||||
*/
|
||||
uint8_t USB_receive(uint8_t *buf){
|
||||
if(!usbON || !rxNE) return 0;
|
||||
uint8_t sz = EP_Read(2, buf);
|
||||
uint16_t epstatus = KEEP_DTOG(USB->EPnR[2]);
|
||||
// keep stat_tx & set ACK rx
|
||||
USB->EPnR[2] = (epstatus & ~(USB_EPnR_STAT_TX)) ^ USB_EPnR_STAT_RX;
|
||||
rxNE = 0;
|
||||
return sz;
|
||||
}
|
||||
|
||||
41
F0-nolib/Socket_fans/usb.h
Normal file
41
F0-nolib/Socket_fans/usb.h
Normal file
@ -0,0 +1,41 @@
|
||||
/*
|
||||
* 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)
|
||||
|
||||
// send string with constant length
|
||||
#define USND(str) do{USB_send((uint8_t*)str, sizeof(str)-1);}while(0)
|
||||
|
||||
void USB_setup();
|
||||
void usb_proc();
|
||||
void USB_send(const uint8_t *buf, uint16_t len);
|
||||
void USB_sendstr(const char *str);
|
||||
void USB_send_blk(const uint8_t *buf, uint16_t len);
|
||||
uint8_t USB_receive(uint8_t *buf);
|
||||
|
||||
#endif // __USB_H__
|
||||
104
F0-nolib/Socket_fans/usb_defs.h
Normal file
104
F0-nolib/Socket_fans/usb_defs.h
Normal file
@ -0,0 +1,104 @@
|
||||
/*
|
||||
* 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 <stm32f0.h>
|
||||
|
||||
// max endpoints number
|
||||
#define STM32ENDPOINTS 8
|
||||
/**
|
||||
* Buffers size definition
|
||||
**/
|
||||
// !!! when working with CAN bus change USB_BTABLE_SIZE to 768 !!!
|
||||
#define USB_BTABLE_SIZE 768
|
||||
// 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
|
||||
// EP1 - interrupt - buffer size
|
||||
#define USB_EP1BUFSZ 8
|
||||
|
||||
#define USB_BTABLE_BASE 0x40006000
|
||||
|
||||
#ifdef USB_BTABLE
|
||||
#undef USB_BTABLE
|
||||
#endif
|
||||
#define USB_BTABLE ((USB_BtableDef *)(USB_BTABLE_BASE))
|
||||
#define USB_ISTR_EPID 0x0000000F
|
||||
#define USB_FNR_LSOF_0 0x00000800
|
||||
#define USB_FNR_lSOF_1 0x00001000
|
||||
#define USB_LPMCSR_BESL_0 0x00000010
|
||||
#define USB_LPMCSR_BESL_1 0x00000020
|
||||
#define USB_LPMCSR_BESL_2 0x00000040
|
||||
#define USB_LPMCSR_BESL_3 0x00000080
|
||||
#define USB_EPnR_CTR_RX 0x00008000
|
||||
#define USB_EPnR_DTOG_RX 0x00004000
|
||||
#define USB_EPnR_STAT_RX 0x00003000
|
||||
#define USB_EPnR_STAT_RX_0 0x00001000
|
||||
#define USB_EPnR_STAT_RX_1 0x00002000
|
||||
#define USB_EPnR_SETUP 0x00000800
|
||||
#define USB_EPnR_EP_TYPE 0x00000600
|
||||
#define USB_EPnR_EP_TYPE_0 0x00000200
|
||||
#define USB_EPnR_EP_TYPE_1 0x00000400
|
||||
#define USB_EPnR_EP_KIND 0x00000100
|
||||
#define USB_EPnR_CTR_TX 0x00000080
|
||||
#define USB_EPnR_DTOG_TX 0x00000040
|
||||
#define USB_EPnR_STAT_TX 0x00000030
|
||||
#define USB_EPnR_STAT_TX_0 0x00000010
|
||||
#define USB_EPnR_STAT_TX_1 0x00000020
|
||||
#define USB_EPnR_EA 0x0000000F
|
||||
#define USB_COUNTn_RX_BLSIZE 0x00008000
|
||||
#define USB_COUNTn_NUM_BLOCK 0x00007C00
|
||||
#define USB_COUNTn_RX 0x0000003F
|
||||
|
||||
#define USB_TypeDef USB_TypeDef_custom
|
||||
|
||||
typedef struct{
|
||||
__IO uint32_t EPnR[STM32ENDPOINTS];
|
||||
__IO uint32_t RESERVED[STM32ENDPOINTS];
|
||||
__IO uint32_t CNTR;
|
||||
__IO uint32_t ISTR;
|
||||
__IO uint32_t FNR;
|
||||
__IO uint32_t DADDR;
|
||||
__IO uint32_t BTABLE;
|
||||
__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[STM32ENDPOINTS];
|
||||
} USB_BtableDef;
|
||||
|
||||
#endif // __USB_DEFS_H__
|
||||
473
F0-nolib/Socket_fans/usb_lib.c
Normal file
473
F0-nolib/Socket_fans/usb_lib.c
Normal file
@ -0,0 +1,473 @@
|
||||
/*
|
||||
* 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"
|
||||
|
||||
ep_t endpoints[STM32ENDPOINTS];
|
||||
|
||||
usb_dev_t USB_Dev;
|
||||
uint8_t usbON = 0;
|
||||
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){
|
||||
}
|
||||
|
||||
// SET_CONTROL_LINE_STATE
|
||||
void WEAK clstate_handler(uint16_t __attribute__((unused)) val){
|
||||
}
|
||||
|
||||
// SEND_BREAK
|
||||
void WEAK break_handler(){
|
||||
}
|
||||
|
||||
// handler of vendor requests
|
||||
void WEAK vendor_handler(config_pack_t *packet){
|
||||
if(packet->bmRequestType & 0x80){ // read
|
||||
uint8_t c;
|
||||
switch(packet->wValue){
|
||||
case 0x8484:
|
||||
c = 2;
|
||||
break;
|
||||
case 0x0080:
|
||||
c = 1;
|
||||
break;
|
||||
case 0x8686:
|
||||
c = 0xaa;
|
||||
break;
|
||||
default:
|
||||
c = 0;
|
||||
}
|
||||
EP_WriteIRQ(0, &c, 1);
|
||||
}else{ // write ZLP
|
||||
EP_WriteIRQ(0, (uint8_t *)0, 0);
|
||||
}
|
||||
}
|
||||
|
||||
static void wr0(const uint8_t *buf, uint16_t size){
|
||||
if(setup_packet.wLength < size) size = setup_packet.wLength; // shortened request
|
||||
if(size < endpoints[0].txbufsz){
|
||||
EP_WriteIRQ(0, buf, size);
|
||||
return;
|
||||
}
|
||||
while(size){
|
||||
uint16_t l = size;
|
||||
if(l > endpoints[0].txbufsz) l = endpoints[0].txbufsz;
|
||||
EP_WriteIRQ(0, buf, l);
|
||||
buf += l;
|
||||
size -= l;
|
||||
uint8_t needzlp = (l == endpoints[0].txbufsz) ? 1 : 0;
|
||||
if(size || needzlp){ // send last data buffer
|
||||
uint16_t status = KEEP_DTOG(USB->EPnR[0]);
|
||||
// keep DTOGs, clear CTR_RX,TX, set TX VALID, leave stat_Rx
|
||||
USB->EPnR[0] = (status & ~(USB_EPnR_CTR_RX|USB_EPnR_CTR_TX|USB_EPnR_STAT_RX))
|
||||
^ USB_EPnR_STAT_TX;
|
||||
uint32_t ctr = 1000000;
|
||||
while(--ctr && (USB->ISTR & USB_ISTR_CTR) == 0){IWDG->KR = IWDG_REFRESH;};
|
||||
if((USB->ISTR & USB_ISTR_CTR) == 0){
|
||||
return;
|
||||
}
|
||||
if(needzlp) EP_WriteIRQ(0, (uint8_t*)0, 0);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
static inline void get_descriptor(){
|
||||
switch(setup_packet.wValue){
|
||||
case DEVICE_DESCRIPTOR:
|
||||
wr0(USB_DeviceDescriptor, sizeof(USB_DeviceDescriptor));
|
||||
break;
|
||||
case CONFIGURATION_DESCRIPTOR:
|
||||
wr0(USB_ConfigDescriptor, sizeof(USB_ConfigDescriptor));
|
||||
break;
|
||||
case STRING_LANG_DESCRIPTOR:
|
||||
wr0((const uint8_t *)&USB_StringLangDescriptor, STRING_LANG_DESCRIPTOR_SIZE_BYTE);
|
||||
break;
|
||||
case STRING_MAN_DESCRIPTOR:
|
||||
wr0((const uint8_t *)&USB_StringManufacturingDescriptor, USB_StringManufacturingDescriptor.bLength);
|
||||
break;
|
||||
case STRING_PROD_DESCRIPTOR:
|
||||
wr0((const uint8_t *)&USB_StringProdDescriptor, USB_StringProdDescriptor.bLength);
|
||||
break;
|
||||
case STRING_SN_DESCRIPTOR:
|
||||
wr0((const uint8_t *)&USB_StringSerialDescriptor, USB_StringSerialDescriptor.bLength);
|
||||
break;
|
||||
case DEVICE_QUALIFIER_DESCRIPTOR:
|
||||
wr0(USB_DeviceQualifierDescriptor, USB_DeviceQualifierDescriptor[0]);
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
static uint8_t configuration = 0; // reply for GET_CONFIGURATION (==1 if configured)
|
||||
static inline void std_d2h_req(){
|
||||
uint16_t status = 0; // bus powered
|
||||
switch(setup_packet.bRequest){
|
||||
case GET_DESCRIPTOR:
|
||||
get_descriptor();
|
||||
break;
|
||||
case GET_STATUS:
|
||||
EP_WriteIRQ(0, (uint8_t *)&status, 2); // send status: Bus Powered
|
||||
break;
|
||||
case GET_CONFIGURATION:
|
||||
EP_WriteIRQ(0, &configuration, 1);
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
static inline void std_h2d_req(){
|
||||
switch(setup_packet.bRequest){
|
||||
case SET_ADDRESS:
|
||||
// new address will be assigned later - after acknowlegement or request to host
|
||||
USB_Dev.USB_Addr = setup_packet.wValue;
|
||||
break;
|
||||
case SET_CONFIGURATION:
|
||||
// Now device configured
|
||||
USB_Dev.USB_Status = USB_STATE_CONFIGURED;
|
||||
configuration = setup_packet.wValue;
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
bmRequestType: 76543210
|
||||
7 direction: 0 - host->device, 1 - device->host
|
||||
65 type: 0 - standard, 1 - class, 2 - vendor
|
||||
4..0 getter: 0 - device, 1 - interface, 2 - endpoint, 3 - other
|
||||
*/
|
||||
/**
|
||||
* Endpoint0 (control) handler
|
||||
*/
|
||||
static void EP0_Handler(){
|
||||
uint16_t epstatus = USB->EPnR[0]; // EP0R on input -> return this value after modifications
|
||||
uint8_t reqtype = setup_packet.bmRequestType & 0x7f;
|
||||
uint8_t dev2host = (setup_packet.bmRequestType & 0x80) ? 1 : 0;
|
||||
int rxflag = RX_FLAG(epstatus);
|
||||
if(rxflag && SETUP_FLAG(epstatus)){
|
||||
switch(reqtype){
|
||||
case STANDARD_DEVICE_REQUEST_TYPE: // standard device request
|
||||
if(dev2host){
|
||||
std_d2h_req();
|
||||
}else{
|
||||
std_h2d_req();
|
||||
EP_WriteIRQ(0, (uint8_t *)0, 0);
|
||||
}
|
||||
break;
|
||||
case STANDARD_ENDPOINT_REQUEST_TYPE: // standard endpoint request
|
||||
if(setup_packet.bRequest == CLEAR_FEATURE){
|
||||
EP_WriteIRQ(0, (uint8_t *)0, 0);
|
||||
}
|
||||
break;
|
||||
case VENDOR_REQUEST_TYPE:
|
||||
vendor_handler(&setup_packet);
|
||||
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:
|
||||
usbON = 1;
|
||||
clstate_handler(setup_packet.wValue);
|
||||
break;
|
||||
case SEND_BREAK:
|
||||
usbON = 0;
|
||||
break_handler();
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
if(setup_packet.bRequest != GET_LINE_CODING) EP_WriteIRQ(0, (uint8_t *)0, 0); // write acknowledgement
|
||||
break;
|
||||
default:
|
||||
EP_WriteIRQ(0, (uint8_t *)0, 0);
|
||||
}
|
||||
}else if(rxflag){ // got data over EP0 or host acknowlegement
|
||||
if(endpoints[0].rx_cnt){
|
||||
if(setup_packet.bRequest == SET_LINE_CODING){
|
||||
linecoding_handler((usb_LineCoding*)ep0databuf);
|
||||
}
|
||||
}
|
||||
} else if(TX_FLAG(epstatus)){ // 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_STATE_ADDRESSED;
|
||||
}
|
||||
}
|
||||
epstatus = KEEP_DTOG(USB->EPnR[0]);
|
||||
if(rxflag) epstatus ^= USB_EPnR_STAT_TX; // start ZLP/data transmission
|
||||
else epstatus &= ~USB_EPnR_STAT_TX; // or leave unchanged
|
||||
// keep DTOGs, clear CTR_RX,TX, set RX VALID
|
||||
USB->EPnR[0] = (epstatus & ~(USB_EPnR_CTR_RX|USB_EPnR_CTR_TX)) ^ USB_EPnR_STAT_RX;
|
||||
}
|
||||
|
||||
static uint16_t lastaddr = LASTADDR_DEFAULT;
|
||||
/**
|
||||
* 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, void (*func)()){
|
||||
if(number >= STM32ENDPOINTS) return 4; // out of configured amount
|
||||
if(txsz > USB_BTABLE_SIZE || rxsz > USB_BTABLE_SIZE) return 1; // buffer too large
|
||||
if(lastaddr + txsz + rxsz >= USB_BTABLE_SIZE) return 2; // out of btable
|
||||
USB->EPnR[number] = (type << 9) | (number & USB_EPnR_EA);
|
||||
USB->EPnR[number] ^= USB_EPnR_STAT_RX | USB_EPnR_STAT_TX_1;
|
||||
if(rxsz & 1 || rxsz > 512) return 3; // wrong rx buffer size
|
||||
uint16_t countrx = 0;
|
||||
if(rxsz < 64) countrx = rxsz / 2;
|
||||
else{
|
||||
if(rxsz & 0x1f) return 3; // should be multiple of 32
|
||||
countrx = 31 + rxsz / 32;
|
||||
}
|
||||
USB_BTABLE->EP[number].USB_ADDR_TX = lastaddr;
|
||||
endpoints[number].tx_buf = (uint16_t *)(USB_BTABLE_BASE + lastaddr);
|
||||
endpoints[number].txbufsz = txsz;
|
||||
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_CNTR_SUSPM | USB_CNTR_WKUPM;
|
||||
USB->ISTR = 0;
|
||||
// Endpoint 0 - CONTROL
|
||||
// ON USB LS size of EP0 may be 8 bytes, but on FS it should be 64 bytes!
|
||||
lastaddr = LASTADDR_DEFAULT; // 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_STATE_DEFAULT;
|
||||
}
|
||||
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];
|
||||
// copy received bytes amount
|
||||
endpoints[n].rx_cnt = USB_BTABLE->EP[n].USB_COUNT_RX & 0x3FF; // low 10 bits is counter
|
||||
// check direction
|
||||
if(USB->ISTR & USB_ISTR_DIR){ // OUT interrupt - receive data, CTR_RX==1 (if CTR_TX == 1 - two pending transactions: receive following by transmit)
|
||||
if(n == 0){ // control endpoint
|
||||
if(epstatus & USB_EPnR_SETUP){ // setup packet -> copy data to conf_pack
|
||||
EP_Read(0, (uint8_t*)&setup_packet);
|
||||
ep0dbuflen = 0;
|
||||
// interrupt handler will be called later
|
||||
}else if(epstatus & USB_EPnR_CTR_RX){ // data packet -> push received data to ep0databuf
|
||||
ep0dbuflen = endpoints[0].rx_cnt;
|
||||
EP_Read(0, (uint8_t*)&ep0databuf);
|
||||
}
|
||||
}
|
||||
}
|
||||
// call EP handler
|
||||
if(endpoints[n].func) endpoints[n].func(endpoints[n]);
|
||||
}
|
||||
if(USB->ISTR & USB_ISTR_SUSP){ // suspend -> still no connection, may sleep
|
||||
usbON = 0;
|
||||
USB->CNTR |= USB_CNTR_FSUSP | USB_CNTR_LPMODE;
|
||||
USB->ISTR = ~USB_ISTR_SUSP;
|
||||
}
|
||||
if(USB->ISTR & USB_ISTR_WKUP){ // wakeup
|
||||
USB->CNTR &= ~(USB_CNTR_FSUSP | USB_CNTR_LPMODE); // clear suspend flags
|
||||
USB->ISTR = ~USB_ISTR_WKUP;
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* 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){
|
||||
EP_WriteIRQ(number, buf, size);
|
||||
uint16_t status = KEEP_DTOG(USB->EPnR[number]);
|
||||
// keep DTOGs, clear CTR_TX & set TX VALID to start transmission
|
||||
USB->EPnR[number] = (status & ~(USB_EPnR_CTR_TX)) ^ USB_EPnR_STAT_TX;
|
||||
}
|
||||
|
||||
/*
|
||||
* 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;
|
||||
}
|
||||
189
F0-nolib/Socket_fans/usb_lib.h
Normal file
189
F0-nolib/Socket_fans/usb_lib.h
Normal file
@ -0,0 +1,189 @@
|
||||
/*
|
||||
* 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)
|
||||
#define LASTADDR_DEFAULT (STM32ENDPOINTS * 8)
|
||||
|
||||
// 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
|
||||
|
||||
#define RX_FLAG(epstat) (epstat & USB_EPnR_CTR_RX)
|
||||
#define TX_FLAG(epstat) (epstat & USB_EPnR_CTR_TX)
|
||||
#define SETUP_FLAG(epstat) (epstat & USB_EPnR_SETUP)
|
||||
|
||||
// EPnR bits manipulation
|
||||
#define KEEP_DTOG_STAT(EPnR) (EPnR & ~(USB_EPnR_STAT_RX|USB_EPnR_STAT_TX|USB_EPnR_DTOG_RX|USB_EPnR_DTOG_TX))
|
||||
#define KEEP_DTOG(EPnR) (EPnR & ~(USB_EPnR_DTOG_RX|USB_EPnR_DTOG_TX))
|
||||
|
||||
// USB state: uninitialized, addressed, ready for use, client connected
|
||||
typedef enum{
|
||||
USB_STATE_DEFAULT,
|
||||
USB_STATE_ADDRESSED,
|
||||
USB_STATE_CONFIGURED,
|
||||
USB_STATE_CONNECTED
|
||||
} USB_state;
|
||||
|
||||
// EP types
|
||||
#define EP_TYPE_BULK 0x00
|
||||
#define EP_TYPE_CONTROL 0x01
|
||||
#define EP_TYPE_ISO 0x02
|
||||
#define EP_TYPE_INTERRUPT 0x03
|
||||
|
||||
#define LANG_US (uint16_t)0x0409
|
||||
|
||||
#define _USB_STRING_(name, str) \
|
||||
static const struct name \
|
||||
{ \
|
||||
uint8_t bLength; \
|
||||
uint8_t bDescriptorType; \
|
||||
uint16_t bString[(sizeof(str) - 2) / 2]; \
|
||||
\
|
||||
} \
|
||||
name = {sizeof(name), 0x03, str}
|
||||
|
||||
#define _USB_LANG_ID_(name, lng_id) \
|
||||
\
|
||||
static const struct name \
|
||||
{ \
|
||||
uint8_t bLength; \
|
||||
uint8_t bDescriptorType; \
|
||||
uint16_t bString; \
|
||||
\
|
||||
} \
|
||||
name = {0x04, 0x03, lng_id}
|
||||
#define STRING_LANG_DESCRIPTOR_SIZE_BYTE (4)
|
||||
|
||||
// EP0 configuration packet
|
||||
typedef struct {
|
||||
uint8_t bmRequestType;
|
||||
uint8_t bRequest;
|
||||
uint16_t wValue;
|
||||
uint16_t wIndex;
|
||||
uint16_t wLength;
|
||||
} config_pack_t;
|
||||
|
||||
// endpoints state
|
||||
typedef struct __ep_t{
|
||||
uint16_t *tx_buf; // transmission buffer address
|
||||
uint16_t txbufsz; // transmission buffer size
|
||||
uint8_t *rx_buf; // reception buffer address
|
||||
void (*func)(); // endpoint action function
|
||||
uint16_t rx_cnt; // received data counter
|
||||
} 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[];
|
||||
extern usb_dev_t USB_Dev;
|
||||
extern uint8_t usbON;
|
||||
|
||||
void USB_Init();
|
||||
uint8_t USB_GetState();
|
||||
int EP_Init(uint8_t number, uint8_t type, uint16_t txsz, uint16_t rxsz, void (*func)());
|
||||
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 linecoding_handler(usb_LineCoding *lc);
|
||||
void clstate_handler(uint16_t val);
|
||||
void break_handler();
|
||||
void vendor_handler(config_pack_t *packet);
|
||||
|
||||
#endif // __USB_LIB_H__
|
||||
147
F0-nolib/USB_pl2303_snippet/Makefile
Normal file
147
F0-nolib/USB_pl2303_snippet/Makefile
Normal file
@ -0,0 +1,147 @@
|
||||
BINARY = usb
|
||||
BOOTPORT ?= /dev/ttyUSB0
|
||||
BOOTSPEED ?= 57600
|
||||
# MCU FAMILY
|
||||
FAMILY = F0
|
||||
# MCU code
|
||||
MCU = F072xB
|
||||
# hardware definitions
|
||||
#DEFS += -DEBUG
|
||||
# change this linking script depending on particular MCU model,
|
||||
# for example, if you have STM32F103VBT6, you should write:
|
||||
LDSCRIPT = stm32f0728.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)/Fx -I$(INC_DIR)/cm
|
||||
LIB_DIR := $(INC_DIR)/ld
|
||||
|
||||
###############################################################################
|
||||
# C flags
|
||||
CFLAGS += -O2 -g -MD -D__thumb2__=1
|
||||
CFLAGS += -Wall -Werror -Wextra -Wshadow -Wimplicit-function-declaration
|
||||
CFLAGS += -Wredundant-decls $(INCLUDE)
|
||||
# -Wmissing-prototypes -Wstrict-prototypes
|
||||
CFLAGS += -fno-common -ffunction-sections -fdata-sections
|
||||
|
||||
###############################################################################
|
||||
# Linker flags
|
||||
LDFLAGS += --static -nostartfiles
|
||||
#--specs=nano.specs
|
||||
LDFLAGS += -L$(LIB_DIR)
|
||||
LDFLAGS += -T$(LDSCRIPT)
|
||||
LDFLAGS += -Wl,-Map=$(OBJDIR)/$(BINARY).map
|
||||
LDFLAGS += -Wl,--gc-sections
|
||||
|
||||
###############################################################################
|
||||
# Used libraries
|
||||
LDLIBS += -Wl,--start-group -lc -lgcc -Wl,--end-group
|
||||
LDLIBS += $(shell $(CC) $(CFLAGS) -print-libgcc-file-name)
|
||||
|
||||
DEFS += -DSTM32$(FAMILY) -DSTM32$(MCU)
|
||||
|
||||
#.SUFFIXES: .elf .bin .hex .srec .list .map .images
|
||||
#.SECONDEXPANSION:
|
||||
#.SECONDARY:
|
||||
|
||||
ELF := $(OBJDIR)/$(BINARY).elf
|
||||
LIST := $(OBJDIR)/$(BINARY).list
|
||||
BIN := $(BINARY).bin
|
||||
HEX := $(BINARY).hex
|
||||
|
||||
all: bin list
|
||||
|
||||
elf: $(ELF)
|
||||
bin: $(BIN)
|
||||
hex: $(HEX)
|
||||
list: $(LIST)
|
||||
|
||||
ifneq ($(MAKECMDGOALS),clean)
|
||||
-include $(DEPS)
|
||||
endif
|
||||
|
||||
$(OBJDIR):
|
||||
mkdir $(OBJDIR)
|
||||
|
||||
$(STARTUP): $(INC_DIR)/startup/vector.c
|
||||
$(CC) $(CFLAGS) $(DEFS) $(INCLUDE) $(ARCH_FLAGS) -o $@ -c $<
|
||||
|
||||
$(OBJDIR)/%.o: %.c
|
||||
@echo " CC $<"
|
||||
$(CC) $(CFLAGS) $(DEFS) $(INCLUDE) $(ARCH_FLAGS) -o $@ -c $<
|
||||
|
||||
#$(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 *.d
|
||||
@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 gentags
|
||||
1
F0-nolib/USB_pl2303_snippet/Readme
Normal file
1
F0-nolib/USB_pl2303_snippet/Readme
Normal file
@ -0,0 +1 @@
|
||||
For STM32F072B
|
||||
99
F0-nolib/USB_pl2303_snippet/hardware.c
Normal file
99
F0-nolib/USB_pl2303_snippet/hardware.c
Normal file
@ -0,0 +1,99 @@
|
||||
/*
|
||||
* 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"
|
||||
|
||||
uint8_t ledsON = 0;
|
||||
|
||||
void gpio_setup(void){
|
||||
/*
|
||||
RCC->AHBENR |= RCC_AHBENR_GPIOBEN;
|
||||
// Set LEDS (PB0/1) as output
|
||||
pin_set(LED0_port, LED0_pin); // clear LEDs
|
||||
pin_set(LED1_port, LED1_pin);
|
||||
GPIOB->MODER = (GPIOB->MODER & ~(GPIO_MODER_MODER0 | GPIO_MODER_MODER1)
|
||||
) |
|
||||
GPIO_MODER_MODER0_O | GPIO_MODER_MODER1_O;
|
||||
*/
|
||||
}
|
||||
|
||||
void iwdg_setup(){
|
||||
uint32_t tmout = 16000000;
|
||||
/* Enable the peripheral clock RTC */
|
||||
/* (1) Enable the LSI (40kHz) */
|
||||
/* (2) Wait while it is not ready */
|
||||
RCC->CSR |= RCC_CSR_LSION; /* (1) */
|
||||
while((RCC->CSR & RCC_CSR_LSIRDY) != RCC_CSR_LSIRDY){if(--tmout == 0) break;} /* (2) */
|
||||
/* Configure IWDG */
|
||||
/* (1) Activate IWDG (not needed if done in option bytes) */
|
||||
/* (2) Enable write access to IWDG registers */
|
||||
/* (3) Set prescaler by 64 (1.6ms for each tick) */
|
||||
/* (4) Set reload value to have a rollover each 2s */
|
||||
/* (5) Check if flags are reset */
|
||||
/* (6) Refresh counter */
|
||||
IWDG->KR = IWDG_START; /* (1) */
|
||||
IWDG->KR = IWDG_WRITE_ACCESS; /* (2) */
|
||||
IWDG->PR = IWDG_PR_PR_1; /* (3) */
|
||||
IWDG->RLR = 1250; /* (4) */
|
||||
tmout = 16000000;
|
||||
while(IWDG->SR){if(--tmout == 0) break;} /* (5) */
|
||||
IWDG->KR = IWDG_REFRESH; /* (6) */
|
||||
}
|
||||
|
||||
// pause in milliseconds for some purposes
|
||||
void pause_ms(uint32_t pause){
|
||||
uint32_t Tnxt = Tms + pause;
|
||||
while(Tms < Tnxt) nop();
|
||||
}
|
||||
|
||||
void Jump2Boot(){
|
||||
void (*SysMemBootJump)(void);
|
||||
volatile uint32_t addr = SystemMem;
|
||||
// reset systick
|
||||
SysTick->CTRL = 0;
|
||||
// reset clocks
|
||||
|
||||
RCC->APB1RSTR = RCC_APB1RSTR_CECRST | RCC_APB1RSTR_DACRST | RCC_APB1RSTR_PWRRST | RCC_APB1RSTR_CRSRST |
|
||||
RCC_APB1RSTR_CANRST | RCC_APB1RSTR_USBRST | RCC_APB1RSTR_I2C2RST | RCC_APB1RSTR_I2C1RST |
|
||||
RCC_APB1RSTR_USART4RST | RCC_APB1RSTR_USART3RST | RCC_APB1RSTR_USART2RST | RCC_APB1RSTR_SPI2RST |
|
||||
RCC_APB1RSTR_WWDGRST | RCC_APB1RSTR_TIM14RST |
|
||||
#ifdef STM32F072xB
|
||||
RCC_APB1RSTR_TIM7RST | RCC_APB1RSTR_TIM6RST |
|
||||
#endif
|
||||
RCC_APB1RSTR_TIM3RST | RCC_APB1RSTR_TIM2RST;
|
||||
RCC->APB2RSTR = RCC_APB2RSTR_DBGMCURST | RCC_APB2RSTR_TIM17RST | RCC_APB2RSTR_TIM16RST |
|
||||
#ifdef STM32F072xB
|
||||
RCC_APB2RSTR_TIM15RST |
|
||||
#endif
|
||||
RCC_APB2RSTR_USART1RST | RCC_APB2RSTR_SPI1RST | RCC_APB2RSTR_TIM1RST | RCC_APB2RSTR_ADCRST | RCC_APB2RSTR_SYSCFGRST;
|
||||
RCC->AHBRSTR = 0;
|
||||
RCC->APB1RSTR = 0;
|
||||
RCC->APB2RSTR = 0;
|
||||
// remap memory to 0 (only for STM32F0)
|
||||
SYSCFG->CFGR1 = 0x01; __DSB(); __ISB();
|
||||
SysMemBootJump = (void (*)(void)) (*((uint32_t *)(addr + 4)));
|
||||
// set main stack pointer
|
||||
__set_MSP(*((uint32_t *)addr));
|
||||
// jump to bootloader
|
||||
SysMemBootJump();
|
||||
}
|
||||
63
F0-nolib/USB_pl2303_snippet/hardware.h
Normal file
63
F0-nolib/USB_pl2303_snippet/hardware.h
Normal file
@ -0,0 +1,63 @@
|
||||
/*
|
||||
* 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>
|
||||
|
||||
#define SYSMEM03x 0x1FFFEC00
|
||||
#define SYSMEM04x 0x1FFFC400
|
||||
#define SYSMEM05x 0x1FFFEC00
|
||||
#define SYSMEM07x 0x1FFFC800
|
||||
#define SYSMEM09x 0x1FFFD800
|
||||
|
||||
#define SystemMem SYSMEM07x
|
||||
|
||||
|
||||
#define CONCAT(a,b) a ## b
|
||||
#define STR_HELPER(s) #s
|
||||
#define STR(s) STR_HELPER(s)
|
||||
|
||||
// LEDS: 0 - PB0, 1 - PB1
|
||||
// LED0
|
||||
#define LED0_port GPIOB
|
||||
#define LED0_pin (1<<0)
|
||||
// LED1
|
||||
#define LED1_port GPIOB
|
||||
#define LED1_pin (1<<1)
|
||||
|
||||
#define LED_blink(x) do{if(ledsON) pin_toggle(x ## _port, x ## _pin);}while(0)
|
||||
#define LED_on(x) do{if(ledsON) pin_clear(x ## _port, x ## _pin);}while(0)
|
||||
#define LED_off(x) do{pin_set(x ## _port, x ## _pin);}while(0)
|
||||
|
||||
extern volatile uint32_t Tms;
|
||||
|
||||
extern uint8_t ledsON;
|
||||
|
||||
void gpio_setup(void);
|
||||
void iwdg_setup();
|
||||
void pause_ms(uint32_t pause);
|
||||
void Jump2Boot();
|
||||
|
||||
#endif // __HARDWARE_H__
|
||||
90
F0-nolib/USB_pl2303_snippet/main.c
Normal file
90
F0-nolib/USB_pl2303_snippet/main.c
Normal file
@ -0,0 +1,90 @@
|
||||
/*
|
||||
* 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 "proto.h"
|
||||
#include "usb.h"
|
||||
#include "usb_lib.h"
|
||||
|
||||
volatile uint32_t Tms = 0;
|
||||
|
||||
/* Called when systick fires */
|
||||
void sys_tick_handler(void){
|
||||
++Tms;
|
||||
}
|
||||
|
||||
#define USBBUF 63
|
||||
// usb getline
|
||||
static char *get_USB(){
|
||||
static char tmpbuf[USBBUF+1], *curptr = tmpbuf;
|
||||
static int rest = USBBUF;
|
||||
uint8_t x = USB_receive((uint8_t*)curptr);
|
||||
if(!x) return NULL;
|
||||
curptr[x] = 0;
|
||||
if(x == 1 && *curptr == 0x7f){ // backspace
|
||||
if(curptr > tmpbuf){
|
||||
--curptr;
|
||||
USND("\b \b");
|
||||
}
|
||||
return NULL;
|
||||
}
|
||||
USB_sendstr(curptr); // echo
|
||||
if(curptr[x-1] == '\n'){ // || curptr[x-1] == '\r'){
|
||||
curptr = tmpbuf;
|
||||
rest = USBBUF;
|
||||
// omit empty lines
|
||||
if(tmpbuf[0] == '\n') return NULL;
|
||||
// and wrong empty lines
|
||||
if(tmpbuf[0] == '\r' && tmpbuf[1] == '\n') return NULL;
|
||||
return tmpbuf;
|
||||
}
|
||||
curptr += x; rest -= x;
|
||||
if(rest <= 0){ // buffer overflow
|
||||
curptr = tmpbuf;
|
||||
rest = USBBUF;
|
||||
}
|
||||
return NULL;
|
||||
}
|
||||
|
||||
int main(void){
|
||||
//uint32_t lastT = 0;
|
||||
char *txt;
|
||||
sysreset();
|
||||
SysTick_Config(6000, 1);
|
||||
gpio_setup();
|
||||
USB_setup();
|
||||
RCC->CSR |= RCC_CSR_RMVF; // remove reset flags
|
||||
iwdg_setup();
|
||||
|
||||
while (1){
|
||||
IWDG->KR = IWDG_REFRESH; // refresh watchdog
|
||||
/*if(lastT && (Tms - lastT > 199)){
|
||||
LED_off(LED0);
|
||||
lastT = 0;
|
||||
}*/
|
||||
usb_proc();
|
||||
if((txt = get_USB())){
|
||||
IWDG->KR = IWDG_REFRESH;
|
||||
cmd_parser(txt);
|
||||
}
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
212
F0-nolib/USB_pl2303_snippet/proto.c
Normal file
212
F0-nolib/USB_pl2303_snippet/proto.c
Normal file
@ -0,0 +1,212 @@
|
||||
/*
|
||||
* 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 "proto.h"
|
||||
#include "usb.h"
|
||||
|
||||
#include <string.h> // strlen
|
||||
|
||||
static char buff[BUFSZ+1], *bptr = buff;
|
||||
static uint8_t blen = 0;
|
||||
|
||||
void sendbuf(){
|
||||
IWDG->KR = IWDG_REFRESH;
|
||||
if(blen == 0) return;
|
||||
*bptr = 0;
|
||||
USB_sendstr(buff);
|
||||
bptr = buff;
|
||||
blen = 0;
|
||||
}
|
||||
|
||||
void bufputchar(char ch){
|
||||
if(blen > BUFSZ-1){
|
||||
sendbuf();
|
||||
}
|
||||
*bptr++ = ch;
|
||||
++blen;
|
||||
}
|
||||
|
||||
void addtobuf(const char *txt){
|
||||
IWDG->KR = IWDG_REFRESH;
|
||||
while(*txt) bufputchar(*txt++);
|
||||
}
|
||||
|
||||
char *omit_spaces(char *buf){
|
||||
while(*buf){
|
||||
if(*buf > ' ') break;
|
||||
++buf;
|
||||
}
|
||||
return buf;
|
||||
}
|
||||
|
||||
// THERE'S NO OVERFLOW PROTECTION IN NUMBER READ PROCEDURES!
|
||||
// read decimal number
|
||||
static char *getdec(char *buf, uint32_t *N){
|
||||
uint32_t num = 0;
|
||||
while(*buf){
|
||||
char c = *buf;
|
||||
if(c < '0' || c > '9'){
|
||||
break;
|
||||
}
|
||||
num *= 10;
|
||||
num += c - '0';
|
||||
++buf;
|
||||
}
|
||||
*N = num;
|
||||
return buf;
|
||||
}
|
||||
// read hexadecimal number (without 0x prefix!)
|
||||
static char *gethex(char *buf, uint32_t *N){
|
||||
uint32_t num = 0;
|
||||
while(*buf){
|
||||
char c = *buf;
|
||||
uint8_t M = 0;
|
||||
if(c >= '0' && c <= '9'){
|
||||
M = '0';
|
||||
}else if(c >= 'A' && c <= 'F'){
|
||||
M = 'A' - 10;
|
||||
}else if(c >= 'a' && c <= 'f'){
|
||||
M = 'a' - 10;
|
||||
}
|
||||
if(M){
|
||||
num <<= 4;
|
||||
num += c - M;
|
||||
}else{
|
||||
break;
|
||||
}
|
||||
++buf;
|
||||
}
|
||||
*N = num;
|
||||
return buf;
|
||||
}
|
||||
// read binary number (without 0b prefix!)
|
||||
static char *getbin(char *buf, uint32_t *N){
|
||||
uint32_t num = 0;
|
||||
while(*buf){
|
||||
char c = *buf;
|
||||
if(c < '0' || c > '1'){
|
||||
break;
|
||||
}
|
||||
num <<= 1;
|
||||
if(c == '1') num |= 1;
|
||||
++buf;
|
||||
}
|
||||
*N = num;
|
||||
return buf;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief getnum - read uint32_t from string (dec, hex or bin: 127, 0x7f, 0b1111111)
|
||||
* @param buf - buffer with number and so on
|
||||
* @param N - the number read
|
||||
* @return pointer to first non-number symbol in buf (if it is == buf, there's no number)
|
||||
*/
|
||||
char *getnum(char *txt, uint32_t *N){
|
||||
if(*txt == '0'){
|
||||
if(txt[1] == 'x' || txt[1] == 'X') return gethex(txt+2, N);
|
||||
if(txt[1] == 'b' || txt[1] == 'B') return getbin(txt+2, N);
|
||||
}
|
||||
return getdec(txt, N);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief cmd_parser - command parsing
|
||||
* @param txt - buffer with commands & data
|
||||
* @param isUSB - == 1 if data got from USB
|
||||
*/
|
||||
void cmd_parser(char *txt){
|
||||
char _1st = txt[0];
|
||||
/*
|
||||
* parse long commands here
|
||||
*/
|
||||
/*switch(_1st){
|
||||
case 'a':
|
||||
addIGN(txt + 1);
|
||||
goto eof;
|
||||
break;
|
||||
}*/
|
||||
if(txt[1] != '\n') *txt = '?'; // help for wrong message length
|
||||
switch(_1st){
|
||||
case 'D':
|
||||
SEND("Go into DFU mode\n");
|
||||
sendbuf();
|
||||
Jump2Boot();
|
||||
break;
|
||||
case 'R':
|
||||
SEND("Soft reset\n");
|
||||
sendbuf();
|
||||
pause_ms(5); // a little pause to transmit data
|
||||
NVIC_SystemReset();
|
||||
break;
|
||||
case 'T':
|
||||
SEND("Time (ms): ");
|
||||
printu(Tms);
|
||||
newline();
|
||||
break;
|
||||
default: // help
|
||||
SEND(
|
||||
"'D' - activate DFU mode\n"
|
||||
"'R' - software reset\n"
|
||||
"'T' - get time from start (ms)\n"
|
||||
);
|
||||
break;
|
||||
}
|
||||
//eof:
|
||||
newline();
|
||||
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;
|
||||
int8_t i, j, z=1;
|
||||
for(i = 0; i < 4; ++i, --ptr){
|
||||
if(*ptr == 0){ // omit leading zeros
|
||||
if(i == 3) z = 0;
|
||||
if(z) continue;
|
||||
}
|
||||
else z = 0;
|
||||
for(j = 1; j > -1; --j){
|
||||
uint8_t half = (*ptr >> (4*j)) & 0x0f;
|
||||
if(half < 10) bufputchar(half + '0');
|
||||
else bufputchar(half - 10 + 'a');
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
55
F0-nolib/USB_pl2303_snippet/proto.h
Normal file
55
F0-nolib/USB_pl2303_snippet/proto.h
Normal file
@ -0,0 +1,55 @@
|
||||
/*
|
||||
* 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"
|
||||
#include "hardware.h"
|
||||
|
||||
#define BUFSZ (64)
|
||||
|
||||
// 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)
|
||||
// newline with buffer sending over USART
|
||||
#define NL() do{bufputchar('\n'); sendbuf();}while(0)
|
||||
|
||||
void cmd_parser(char *buf);
|
||||
void addtobuf(const char *txt);
|
||||
void bufputchar(char ch);
|
||||
void printu(uint32_t val);
|
||||
void printuhex(uint32_t val);
|
||||
void sendbuf();
|
||||
|
||||
char *omit_spaces(char *buf);
|
||||
char *getnum(char *buf, uint32_t *N);
|
||||
|
||||
#endif // __PROTO_H__
|
||||
BIN
F0-nolib/USB_pl2303_snippet/usb.bin
Executable file
BIN
F0-nolib/USB_pl2303_snippet/usb.bin
Executable file
Binary file not shown.
180
F0-nolib/USB_pl2303_snippet/usb.c
Normal file
180
F0-nolib/USB_pl2303_snippet/usb.c
Normal file
@ -0,0 +1,180 @@
|
||||
/*
|
||||
* 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"
|
||||
|
||||
static volatile uint8_t tx_succesfull = 1;
|
||||
static volatile uint8_t rxNE = 0;
|
||||
|
||||
// interrupt IN handler (never used?)
|
||||
static void EP1_Handler(){
|
||||
uint16_t epstatus = KEEP_DTOG(USB->EPnR[1]);
|
||||
if(RX_FLAG(epstatus)) epstatus = (epstatus & ~USB_EPnR_STAT_TX) ^ USB_EPnR_STAT_RX; // set valid RX
|
||||
else epstatus = epstatus & ~(USB_EPnR_STAT_TX|USB_EPnR_STAT_RX);
|
||||
// clear CTR
|
||||
epstatus = (epstatus & ~(USB_EPnR_CTR_RX|USB_EPnR_CTR_TX));
|
||||
USB->EPnR[1] = epstatus;
|
||||
}
|
||||
|
||||
// data IN/OUT handlers
|
||||
static void transmit_Handler(){ // EP3IN
|
||||
tx_succesfull = 1;
|
||||
uint16_t epstatus = KEEP_DTOG_STAT(USB->EPnR[3]);
|
||||
// clear CTR keep DTOGs & STATs
|
||||
USB->EPnR[3] = (epstatus & ~(USB_EPnR_CTR_TX)); // clear TX ctr
|
||||
}
|
||||
|
||||
static void receive_Handler(){ // EP2OUT
|
||||
rxNE = 1;
|
||||
uint16_t epstatus = KEEP_DTOG_STAT(USB->EPnR[2]);
|
||||
USB->EPnR[2] = (epstatus & ~(USB_EPnR_CTR_RX)); // clear RX ctr
|
||||
}
|
||||
|
||||
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_WKUPM;
|
||||
// clear flags
|
||||
USB->ISTR = 0;
|
||||
// and activate pullup
|
||||
USB->BCDR |= USB_BCDR_DPPU;
|
||||
NVIC_EnableIRQ(USB_IRQn);
|
||||
}
|
||||
|
||||
|
||||
static int usbwr(const uint8_t *buf, uint16_t l){
|
||||
uint32_t ctra = 1000000;
|
||||
while(--ctra && tx_succesfull == 0){
|
||||
IWDG->KR = IWDG_REFRESH;
|
||||
}
|
||||
tx_succesfull = 0;
|
||||
EP_Write(3, buf, l);
|
||||
ctra = 1000000;
|
||||
while(--ctra && tx_succesfull == 0){
|
||||
IWDG->KR = IWDG_REFRESH;
|
||||
}
|
||||
if(tx_succesfull == 0){usbON = 0; return 1;} // usb is OFF?
|
||||
return 0;
|
||||
}
|
||||
|
||||
static uint8_t usbbuff[USB_TXBUFSZ-1]; // temporary buffer (63 - to prevent need of ZLP)
|
||||
static uint8_t buflen = 0; // amount of symbols in usbbuff
|
||||
|
||||
// send next up to 63 bytes of data in usbbuff
|
||||
static void send_next(){
|
||||
if(!buflen || !tx_succesfull) return;
|
||||
tx_succesfull = 0;
|
||||
EP_Write(3, usbbuff, buflen);
|
||||
buflen = 0;
|
||||
}
|
||||
|
||||
// unblocking sending - just fill a buffer
|
||||
void USB_send(const uint8_t *buf, uint16_t len){
|
||||
if(!usbON || !len) return;
|
||||
if(len > USB_TXBUFSZ-1 - buflen){
|
||||
usbwr(usbbuff, buflen);
|
||||
buflen = 0;
|
||||
}
|
||||
if(len > USB_TXBUFSZ-1){
|
||||
USB_send_blk(buf, len);
|
||||
return;
|
||||
}
|
||||
while(len--) usbbuff[buflen++] = *buf++;
|
||||
}
|
||||
|
||||
// send zero-terminated string
|
||||
void USB_sendstr(const char *str){
|
||||
uint16_t l = 0;
|
||||
const char *ptr = str;
|
||||
while(*ptr++) ++l;
|
||||
USB_send((uint8_t*)str, l);
|
||||
}
|
||||
|
||||
// blocking sending
|
||||
void USB_send_blk(const uint8_t *buf, uint16_t len){
|
||||
if(!usbON || !len) return; // USB disconnected
|
||||
if(buflen){
|
||||
usbwr(usbbuff, buflen);
|
||||
buflen = 0;
|
||||
}
|
||||
int needzlp = 0;
|
||||
while(len){
|
||||
if(len == USB_TXBUFSZ) needzlp = 1;
|
||||
uint16_t s = (len > USB_TXBUFSZ) ? USB_TXBUFSZ : len;
|
||||
if(usbwr(buf, s)) return;
|
||||
len -= s;
|
||||
buf += s;
|
||||
}
|
||||
if(needzlp){
|
||||
usbwr(NULL, 0);
|
||||
}
|
||||
}
|
||||
|
||||
void usb_proc(){
|
||||
switch(USB_Dev.USB_Status){
|
||||
case USB_STATE_CONFIGURED:
|
||||
// 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, USB_EP1BUFSZ, 0, EP1_Handler); // IN1 - transmit
|
||||
EP_Init(2, EP_TYPE_BULK, 0, USB_RXBUFSZ, receive_Handler); // OUT2 - receive data
|
||||
EP_Init(3, EP_TYPE_BULK, USB_TXBUFSZ, 0, transmit_Handler); // IN3 - transmit data
|
||||
USB_Dev.USB_Status = USB_STATE_CONNECTED;
|
||||
break;
|
||||
case USB_STATE_DEFAULT:
|
||||
case USB_STATE_ADDRESSED:
|
||||
if(usbON){
|
||||
usbON = 0;
|
||||
}
|
||||
break;
|
||||
default: // USB_STATE_CONNECTED - send next data portion
|
||||
if(!usbON) return;
|
||||
send_next();
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief USB_receive
|
||||
* @param buf (i) - buffer[64] for received data
|
||||
* @return amount of received bytes
|
||||
*/
|
||||
uint8_t USB_receive(uint8_t *buf){
|
||||
if(!usbON || !rxNE) return 0;
|
||||
uint8_t sz = EP_Read(2, buf);
|
||||
uint16_t epstatus = KEEP_DTOG(USB->EPnR[2]);
|
||||
// keep stat_tx & set ACK rx
|
||||
USB->EPnR[2] = (epstatus & ~(USB_EPnR_STAT_TX)) ^ USB_EPnR_STAT_RX;
|
||||
rxNE = 0;
|
||||
return sz;
|
||||
}
|
||||
|
||||
41
F0-nolib/USB_pl2303_snippet/usb.h
Normal file
41
F0-nolib/USB_pl2303_snippet/usb.h
Normal file
@ -0,0 +1,41 @@
|
||||
/*
|
||||
* 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)
|
||||
|
||||
// send string with constant length
|
||||
#define USND(str) do{USB_send((uint8_t*)str, sizeof(str)-1);}while(0)
|
||||
|
||||
void USB_setup();
|
||||
void usb_proc();
|
||||
void USB_send(const uint8_t *buf, uint16_t len);
|
||||
void USB_sendstr(const char *str);
|
||||
void USB_send_blk(const uint8_t *buf, uint16_t len);
|
||||
uint8_t USB_receive(uint8_t *buf);
|
||||
|
||||
#endif // __USB_H__
|
||||
104
F0-nolib/USB_pl2303_snippet/usb_defs.h
Normal file
104
F0-nolib/USB_pl2303_snippet/usb_defs.h
Normal file
@ -0,0 +1,104 @@
|
||||
/*
|
||||
* 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 <stm32f0.h>
|
||||
|
||||
// max endpoints number
|
||||
#define STM32ENDPOINTS 8
|
||||
/**
|
||||
* Buffers size definition
|
||||
**/
|
||||
// !!! when working with CAN bus change USB_BTABLE_SIZE to 768 !!!
|
||||
#define USB_BTABLE_SIZE 768
|
||||
// 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
|
||||
// EP1 - interrupt - buffer size
|
||||
#define USB_EP1BUFSZ 8
|
||||
|
||||
#define USB_BTABLE_BASE 0x40006000
|
||||
|
||||
#ifdef USB_BTABLE
|
||||
#undef USB_BTABLE
|
||||
#endif
|
||||
#define USB_BTABLE ((USB_BtableDef *)(USB_BTABLE_BASE))
|
||||
#define USB_ISTR_EPID 0x0000000F
|
||||
#define USB_FNR_LSOF_0 0x00000800
|
||||
#define USB_FNR_lSOF_1 0x00001000
|
||||
#define USB_LPMCSR_BESL_0 0x00000010
|
||||
#define USB_LPMCSR_BESL_1 0x00000020
|
||||
#define USB_LPMCSR_BESL_2 0x00000040
|
||||
#define USB_LPMCSR_BESL_3 0x00000080
|
||||
#define USB_EPnR_CTR_RX 0x00008000
|
||||
#define USB_EPnR_DTOG_RX 0x00004000
|
||||
#define USB_EPnR_STAT_RX 0x00003000
|
||||
#define USB_EPnR_STAT_RX_0 0x00001000
|
||||
#define USB_EPnR_STAT_RX_1 0x00002000
|
||||
#define USB_EPnR_SETUP 0x00000800
|
||||
#define USB_EPnR_EP_TYPE 0x00000600
|
||||
#define USB_EPnR_EP_TYPE_0 0x00000200
|
||||
#define USB_EPnR_EP_TYPE_1 0x00000400
|
||||
#define USB_EPnR_EP_KIND 0x00000100
|
||||
#define USB_EPnR_CTR_TX 0x00000080
|
||||
#define USB_EPnR_DTOG_TX 0x00000040
|
||||
#define USB_EPnR_STAT_TX 0x00000030
|
||||
#define USB_EPnR_STAT_TX_0 0x00000010
|
||||
#define USB_EPnR_STAT_TX_1 0x00000020
|
||||
#define USB_EPnR_EA 0x0000000F
|
||||
#define USB_COUNTn_RX_BLSIZE 0x00008000
|
||||
#define USB_COUNTn_NUM_BLOCK 0x00007C00
|
||||
#define USB_COUNTn_RX 0x0000003F
|
||||
|
||||
#define USB_TypeDef USB_TypeDef_custom
|
||||
|
||||
typedef struct{
|
||||
__IO uint32_t EPnR[STM32ENDPOINTS];
|
||||
__IO uint32_t RESERVED[STM32ENDPOINTS];
|
||||
__IO uint32_t CNTR;
|
||||
__IO uint32_t ISTR;
|
||||
__IO uint32_t FNR;
|
||||
__IO uint32_t DADDR;
|
||||
__IO uint32_t BTABLE;
|
||||
__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[STM32ENDPOINTS];
|
||||
} USB_BtableDef;
|
||||
|
||||
#endif // __USB_DEFS_H__
|
||||
473
F0-nolib/USB_pl2303_snippet/usb_lib.c
Normal file
473
F0-nolib/USB_pl2303_snippet/usb_lib.c
Normal file
@ -0,0 +1,473 @@
|
||||
/*
|
||||
* 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"
|
||||
|
||||
ep_t endpoints[STM32ENDPOINTS];
|
||||
|
||||
usb_dev_t USB_Dev;
|
||||
uint8_t usbON = 0;
|
||||
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){
|
||||
}
|
||||
|
||||
// SET_CONTROL_LINE_STATE
|
||||
void WEAK clstate_handler(uint16_t __attribute__((unused)) val){
|
||||
}
|
||||
|
||||
// SEND_BREAK
|
||||
void WEAK break_handler(){
|
||||
}
|
||||
|
||||
// handler of vendor requests
|
||||
void WEAK vendor_handler(config_pack_t *packet){
|
||||
if(packet->bmRequestType & 0x80){ // read
|
||||
uint8_t c;
|
||||
switch(packet->wValue){
|
||||
case 0x8484:
|
||||
c = 2;
|
||||
break;
|
||||
case 0x0080:
|
||||
c = 1;
|
||||
break;
|
||||
case 0x8686:
|
||||
c = 0xaa;
|
||||
break;
|
||||
default:
|
||||
c = 0;
|
||||
}
|
||||
EP_WriteIRQ(0, &c, 1);
|
||||
}else{ // write ZLP
|
||||
EP_WriteIRQ(0, (uint8_t *)0, 0);
|
||||
}
|
||||
}
|
||||
|
||||
static void wr0(const uint8_t *buf, uint16_t size){
|
||||
if(setup_packet.wLength < size) size = setup_packet.wLength; // shortened request
|
||||
if(size < endpoints[0].txbufsz){
|
||||
EP_WriteIRQ(0, buf, size);
|
||||
return;
|
||||
}
|
||||
while(size){
|
||||
uint16_t l = size;
|
||||
if(l > endpoints[0].txbufsz) l = endpoints[0].txbufsz;
|
||||
EP_WriteIRQ(0, buf, l);
|
||||
buf += l;
|
||||
size -= l;
|
||||
uint8_t needzlp = (l == endpoints[0].txbufsz) ? 1 : 0;
|
||||
if(size || needzlp){ // send last data buffer
|
||||
uint16_t status = KEEP_DTOG(USB->EPnR[0]);
|
||||
// keep DTOGs, clear CTR_RX,TX, set TX VALID, leave stat_Rx
|
||||
USB->EPnR[0] = (status & ~(USB_EPnR_CTR_RX|USB_EPnR_CTR_TX|USB_EPnR_STAT_RX))
|
||||
^ USB_EPnR_STAT_TX;
|
||||
uint32_t ctr = 1000000;
|
||||
while(--ctr && (USB->ISTR & USB_ISTR_CTR) == 0){IWDG->KR = IWDG_REFRESH;};
|
||||
if((USB->ISTR & USB_ISTR_CTR) == 0){
|
||||
return;
|
||||
}
|
||||
if(needzlp) EP_WriteIRQ(0, (uint8_t*)0, 0);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
static inline void get_descriptor(){
|
||||
switch(setup_packet.wValue){
|
||||
case DEVICE_DESCRIPTOR:
|
||||
wr0(USB_DeviceDescriptor, sizeof(USB_DeviceDescriptor));
|
||||
break;
|
||||
case CONFIGURATION_DESCRIPTOR:
|
||||
wr0(USB_ConfigDescriptor, sizeof(USB_ConfigDescriptor));
|
||||
break;
|
||||
case STRING_LANG_DESCRIPTOR:
|
||||
wr0((const uint8_t *)&USB_StringLangDescriptor, STRING_LANG_DESCRIPTOR_SIZE_BYTE);
|
||||
break;
|
||||
case STRING_MAN_DESCRIPTOR:
|
||||
wr0((const uint8_t *)&USB_StringManufacturingDescriptor, USB_StringManufacturingDescriptor.bLength);
|
||||
break;
|
||||
case STRING_PROD_DESCRIPTOR:
|
||||
wr0((const uint8_t *)&USB_StringProdDescriptor, USB_StringProdDescriptor.bLength);
|
||||
break;
|
||||
case STRING_SN_DESCRIPTOR:
|
||||
wr0((const uint8_t *)&USB_StringSerialDescriptor, USB_StringSerialDescriptor.bLength);
|
||||
break;
|
||||
case DEVICE_QUALIFIER_DESCRIPTOR:
|
||||
wr0(USB_DeviceQualifierDescriptor, USB_DeviceQualifierDescriptor[0]);
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
static uint8_t configuration = 0; // reply for GET_CONFIGURATION (==1 if configured)
|
||||
static inline void std_d2h_req(){
|
||||
uint16_t status = 0; // bus powered
|
||||
switch(setup_packet.bRequest){
|
||||
case GET_DESCRIPTOR:
|
||||
get_descriptor();
|
||||
break;
|
||||
case GET_STATUS:
|
||||
EP_WriteIRQ(0, (uint8_t *)&status, 2); // send status: Bus Powered
|
||||
break;
|
||||
case GET_CONFIGURATION:
|
||||
EP_WriteIRQ(0, &configuration, 1);
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
static inline void std_h2d_req(){
|
||||
switch(setup_packet.bRequest){
|
||||
case SET_ADDRESS:
|
||||
// new address will be assigned later - after acknowlegement or request to host
|
||||
USB_Dev.USB_Addr = setup_packet.wValue;
|
||||
break;
|
||||
case SET_CONFIGURATION:
|
||||
// Now device configured
|
||||
USB_Dev.USB_Status = USB_STATE_CONFIGURED;
|
||||
configuration = setup_packet.wValue;
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
bmRequestType: 76543210
|
||||
7 direction: 0 - host->device, 1 - device->host
|
||||
65 type: 0 - standard, 1 - class, 2 - vendor
|
||||
4..0 getter: 0 - device, 1 - interface, 2 - endpoint, 3 - other
|
||||
*/
|
||||
/**
|
||||
* Endpoint0 (control) handler
|
||||
*/
|
||||
static void EP0_Handler(){
|
||||
uint16_t epstatus = USB->EPnR[0]; // EP0R on input -> return this value after modifications
|
||||
uint8_t reqtype = setup_packet.bmRequestType & 0x7f;
|
||||
uint8_t dev2host = (setup_packet.bmRequestType & 0x80) ? 1 : 0;
|
||||
int rxflag = RX_FLAG(epstatus);
|
||||
if(rxflag && SETUP_FLAG(epstatus)){
|
||||
switch(reqtype){
|
||||
case STANDARD_DEVICE_REQUEST_TYPE: // standard device request
|
||||
if(dev2host){
|
||||
std_d2h_req();
|
||||
}else{
|
||||
std_h2d_req();
|
||||
EP_WriteIRQ(0, (uint8_t *)0, 0);
|
||||
}
|
||||
break;
|
||||
case STANDARD_ENDPOINT_REQUEST_TYPE: // standard endpoint request
|
||||
if(setup_packet.bRequest == CLEAR_FEATURE){
|
||||
EP_WriteIRQ(0, (uint8_t *)0, 0);
|
||||
}
|
||||
break;
|
||||
case VENDOR_REQUEST_TYPE:
|
||||
vendor_handler(&setup_packet);
|
||||
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:
|
||||
usbON = 1;
|
||||
clstate_handler(setup_packet.wValue);
|
||||
break;
|
||||
case SEND_BREAK:
|
||||
usbON = 0;
|
||||
break_handler();
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
if(setup_packet.bRequest != GET_LINE_CODING) EP_WriteIRQ(0, (uint8_t *)0, 0); // write acknowledgement
|
||||
break;
|
||||
default:
|
||||
EP_WriteIRQ(0, (uint8_t *)0, 0);
|
||||
}
|
||||
}else if(rxflag){ // got data over EP0 or host acknowlegement
|
||||
if(endpoints[0].rx_cnt){
|
||||
if(setup_packet.bRequest == SET_LINE_CODING){
|
||||
linecoding_handler((usb_LineCoding*)ep0databuf);
|
||||
}
|
||||
}
|
||||
} else if(TX_FLAG(epstatus)){ // 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_STATE_ADDRESSED;
|
||||
}
|
||||
}
|
||||
epstatus = KEEP_DTOG(USB->EPnR[0]);
|
||||
if(rxflag) epstatus ^= USB_EPnR_STAT_TX; // start ZLP/data transmission
|
||||
else epstatus &= ~USB_EPnR_STAT_TX; // or leave unchanged
|
||||
// keep DTOGs, clear CTR_RX,TX, set RX VALID
|
||||
USB->EPnR[0] = (epstatus & ~(USB_EPnR_CTR_RX|USB_EPnR_CTR_TX)) ^ USB_EPnR_STAT_RX;
|
||||
}
|
||||
|
||||
static uint16_t lastaddr = LASTADDR_DEFAULT;
|
||||
/**
|
||||
* 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, void (*func)()){
|
||||
if(number >= STM32ENDPOINTS) return 4; // out of configured amount
|
||||
if(txsz > USB_BTABLE_SIZE || rxsz > USB_BTABLE_SIZE) return 1; // buffer too large
|
||||
if(lastaddr + txsz + rxsz >= USB_BTABLE_SIZE) return 2; // out of btable
|
||||
USB->EPnR[number] = (type << 9) | (number & USB_EPnR_EA);
|
||||
USB->EPnR[number] ^= USB_EPnR_STAT_RX | USB_EPnR_STAT_TX_1;
|
||||
if(rxsz & 1 || rxsz > 512) return 3; // wrong rx buffer size
|
||||
uint16_t countrx = 0;
|
||||
if(rxsz < 64) countrx = rxsz / 2;
|
||||
else{
|
||||
if(rxsz & 0x1f) return 3; // should be multiple of 32
|
||||
countrx = 31 + rxsz / 32;
|
||||
}
|
||||
USB_BTABLE->EP[number].USB_ADDR_TX = lastaddr;
|
||||
endpoints[number].tx_buf = (uint16_t *)(USB_BTABLE_BASE + lastaddr);
|
||||
endpoints[number].txbufsz = txsz;
|
||||
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_CNTR_SUSPM | USB_CNTR_WKUPM;
|
||||
USB->ISTR = 0;
|
||||
// Endpoint 0 - CONTROL
|
||||
// ON USB LS size of EP0 may be 8 bytes, but on FS it should be 64 bytes!
|
||||
lastaddr = LASTADDR_DEFAULT; // 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_STATE_DEFAULT;
|
||||
}
|
||||
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];
|
||||
// copy received bytes amount
|
||||
endpoints[n].rx_cnt = USB_BTABLE->EP[n].USB_COUNT_RX & 0x3FF; // low 10 bits is counter
|
||||
// check direction
|
||||
if(USB->ISTR & USB_ISTR_DIR){ // OUT interrupt - receive data, CTR_RX==1 (if CTR_TX == 1 - two pending transactions: receive following by transmit)
|
||||
if(n == 0){ // control endpoint
|
||||
if(epstatus & USB_EPnR_SETUP){ // setup packet -> copy data to conf_pack
|
||||
EP_Read(0, (uint8_t*)&setup_packet);
|
||||
ep0dbuflen = 0;
|
||||
// interrupt handler will be called later
|
||||
}else if(epstatus & USB_EPnR_CTR_RX){ // data packet -> push received data to ep0databuf
|
||||
ep0dbuflen = endpoints[0].rx_cnt;
|
||||
EP_Read(0, (uint8_t*)&ep0databuf);
|
||||
}
|
||||
}
|
||||
}
|
||||
// call EP handler
|
||||
if(endpoints[n].func) endpoints[n].func(endpoints[n]);
|
||||
}
|
||||
if(USB->ISTR & USB_ISTR_SUSP){ // suspend -> still no connection, may sleep
|
||||
usbON = 0;
|
||||
USB->CNTR |= USB_CNTR_FSUSP | USB_CNTR_LPMODE;
|
||||
USB->ISTR = ~USB_ISTR_SUSP;
|
||||
}
|
||||
if(USB->ISTR & USB_ISTR_WKUP){ // wakeup
|
||||
USB->CNTR &= ~(USB_CNTR_FSUSP | USB_CNTR_LPMODE); // clear suspend flags
|
||||
USB->ISTR = ~USB_ISTR_WKUP;
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* 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){
|
||||
EP_WriteIRQ(number, buf, size);
|
||||
uint16_t status = KEEP_DTOG(USB->EPnR[number]);
|
||||
// keep DTOGs, clear CTR_TX & set TX VALID to start transmission
|
||||
USB->EPnR[number] = (status & ~(USB_EPnR_CTR_TX)) ^ USB_EPnR_STAT_TX;
|
||||
}
|
||||
|
||||
/*
|
||||
* 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;
|
||||
}
|
||||
189
F0-nolib/USB_pl2303_snippet/usb_lib.h
Normal file
189
F0-nolib/USB_pl2303_snippet/usb_lib.h
Normal file
@ -0,0 +1,189 @@
|
||||
/*
|
||||
* 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)
|
||||
#define LASTADDR_DEFAULT (STM32ENDPOINTS * 8)
|
||||
|
||||
// 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
|
||||
|
||||
#define RX_FLAG(epstat) (epstat & USB_EPnR_CTR_RX)
|
||||
#define TX_FLAG(epstat) (epstat & USB_EPnR_CTR_TX)
|
||||
#define SETUP_FLAG(epstat) (epstat & USB_EPnR_SETUP)
|
||||
|
||||
// EPnR bits manipulation
|
||||
#define KEEP_DTOG_STAT(EPnR) (EPnR & ~(USB_EPnR_STAT_RX|USB_EPnR_STAT_TX|USB_EPnR_DTOG_RX|USB_EPnR_DTOG_TX))
|
||||
#define KEEP_DTOG(EPnR) (EPnR & ~(USB_EPnR_DTOG_RX|USB_EPnR_DTOG_TX))
|
||||
|
||||
// USB state: uninitialized, addressed, ready for use, client connected
|
||||
typedef enum{
|
||||
USB_STATE_DEFAULT,
|
||||
USB_STATE_ADDRESSED,
|
||||
USB_STATE_CONFIGURED,
|
||||
USB_STATE_CONNECTED
|
||||
} USB_state;
|
||||
|
||||
// EP types
|
||||
#define EP_TYPE_BULK 0x00
|
||||
#define EP_TYPE_CONTROL 0x01
|
||||
#define EP_TYPE_ISO 0x02
|
||||
#define EP_TYPE_INTERRUPT 0x03
|
||||
|
||||
#define LANG_US (uint16_t)0x0409
|
||||
|
||||
#define _USB_STRING_(name, str) \
|
||||
static const struct name \
|
||||
{ \
|
||||
uint8_t bLength; \
|
||||
uint8_t bDescriptorType; \
|
||||
uint16_t bString[(sizeof(str) - 2) / 2]; \
|
||||
\
|
||||
} \
|
||||
name = {sizeof(name), 0x03, str}
|
||||
|
||||
#define _USB_LANG_ID_(name, lng_id) \
|
||||
\
|
||||
static const struct name \
|
||||
{ \
|
||||
uint8_t bLength; \
|
||||
uint8_t bDescriptorType; \
|
||||
uint16_t bString; \
|
||||
\
|
||||
} \
|
||||
name = {0x04, 0x03, lng_id}
|
||||
#define STRING_LANG_DESCRIPTOR_SIZE_BYTE (4)
|
||||
|
||||
// EP0 configuration packet
|
||||
typedef struct {
|
||||
uint8_t bmRequestType;
|
||||
uint8_t bRequest;
|
||||
uint16_t wValue;
|
||||
uint16_t wIndex;
|
||||
uint16_t wLength;
|
||||
} config_pack_t;
|
||||
|
||||
// endpoints state
|
||||
typedef struct __ep_t{
|
||||
uint16_t *tx_buf; // transmission buffer address
|
||||
uint16_t txbufsz; // transmission buffer size
|
||||
uint8_t *rx_buf; // reception buffer address
|
||||
void (*func)(); // endpoint action function
|
||||
uint16_t rx_cnt; // received data counter
|
||||
} 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[];
|
||||
extern usb_dev_t USB_Dev;
|
||||
extern uint8_t usbON;
|
||||
|
||||
void USB_Init();
|
||||
uint8_t USB_GetState();
|
||||
int EP_Init(uint8_t number, uint8_t type, uint16_t txsz, uint16_t rxsz, void (*func)());
|
||||
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 linecoding_handler(usb_LineCoding *lc);
|
||||
void clstate_handler(uint16_t val);
|
||||
void break_handler();
|
||||
void vendor_handler(config_pack_t *packet);
|
||||
|
||||
#endif // __USB_LIB_H__
|
||||
@ -46,4 +46,4 @@
|
||||
|
||||
|
||||
|
||||
#endif // __COMMON_MACROS_H__
|
||||
#endif // __COMMON_MACROS_H__
|
||||
|
||||
12
F0-nolib/inc/ld/stm32f072B.ld
Normal file
12
F0-nolib/inc/ld/stm32f072B.ld
Normal file
@ -0,0 +1,12 @@
|
||||
/* Linker script for STM32F072xB, 128K flash, 16K RAM. */
|
||||
|
||||
/* Define memory regions. */
|
||||
MEMORY
|
||||
{
|
||||
rom (rx) : ORIGIN = 0x08000000, LENGTH = 128K
|
||||
ram (rwx) : ORIGIN = 0x20000000, LENGTH = 16K
|
||||
}
|
||||
|
||||
/* Include the common ld script. */
|
||||
INCLUDE stm32f01234.ld
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user