add LIDAR chronometer (pre-alpha)

This commit is contained in:
eddyem 2019-06-27 21:12:42 +03:00
parent a4c08dc741
commit 3a5ef823db
38 changed files with 34574 additions and 1 deletions

1
.gitignore vendored
View File

@ -8,6 +8,7 @@
*.drl
*.pdf
*.svg
*.ods
*.xml
*/mk/*
.hg*

Binary file not shown.

View File

@ -144,7 +144,7 @@ void USB_send(char *buf){
* @param buf (i) - buffer for received data
* @param bufsize - its size
* @return amount of received bytes
*/
*
int USB_receive(char *buf, int bufsize){
if(!bufsize || !idatalen) return 0;
USB->CNTR = 0;
@ -163,6 +163,36 @@ int USB_receive(char *buf, int bufsize){
}
USB->CNTR = USB_CNTR_RESETM | USB_CNTR_CTRM;
return sz;
}*/
int USB_receive(char *buf, int bufsize){
if(bufsize<1 || !idatalen) return 0;
IWDG->KR = IWDG_REFRESH;
int stlen = 0;
for(int i = 0; i < idatalen; ++i){
if(incoming_data[i] == '\n'){
stlen = i+1;
incoming_data[i] = 0;
break;
}
}
if(stlen == 0) return 0;
USB->CNTR = 0;
int sz = (stlen > bufsize) ? bufsize : stlen, rest = idatalen - sz;
memcpy(buf, incoming_data, sz);
if(rest > 0){
memmove(incoming_data, &incoming_data[sz], rest);
idatalen = rest;
}else idatalen = 0;
if(ovfl){
EP23_Handler(endpoints[2]);
uint16_t epstatus = USB->EPnR[2];
epstatus = CLEAR_DTOG_RX(epstatus);
epstatus = SET_VALID_RX(epstatus);
USB->EPnR[2] = epstatus;
}
USB->CNTR = USB_CNTR_RESETM | USB_CNTR_CTRM;
return sz;
}
/**

175
F1-nolib/chronometer/GPS.c Normal file
View File

@ -0,0 +1,175 @@
/*
* GPS.c
*
* Copyright 2015 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 "GPS.h"
#include "hardware.h"
#include "time.h"
#include "usart.h"
#include "str.h"
#include <string.h> // memcpy
#define GPS_endline() do{usart_send(GPS_USART, "\r\n"); transmit_tbuf(GPS_USART); }while(0)
#define GPS_send_string(str) do{usart_send(GPS_USART, str);}while(0)
gps_status GPS_status = GPS_WAIT;
int need2startseq = 1;
static uint8_t hex(uint8_t n){
return ((n < 10) ? (n+'0') : (n+'A'-10));
}
/**
* Check checksum
*/
static int checksum_true(const char *buf){
char *eol;
uint8_t checksum = 0, cs[3];
if(*buf != '$' || !(eol = getchr(buf, '*'))){
return 0;
}
while(++buf != eol)
checksum ^= (uint8_t)*buf;
++buf;
cs[0] = hex(checksum >> 4);
cs[1] = hex(checksum & 0x0f);
if(buf[0] == cs[0] && buf[1] == cs[1])
return 1;
return 0;
}
static void send_chksum(uint8_t chs){
usart_putchar(GPS_USART, hex(chs >> 4));
usart_putchar(1, hex(chs >> 4));
usart_putchar(GPS_USART, hex(chs & 0x0f));
usart_putchar(1, hex(chs & 0x0f));
}
/**
* Calculate checksum & write message to port
* @param buf - command to write (without leading $ and trailing *)
* return 0 if fails
*/
static void write_with_checksum(const char *buf){
char *txt = NULL;
// clear old buffer data
for(int i = 0; i < 10000; ++i){
if(usartrx(GPS_USART)){
usart_getline(GPS_USART, &txt);
DBG("Old data");
GPS_parse_answer(txt);
break;
}
}
DBG("Send:");
uint8_t checksum = 0;
usart_putchar(GPS_USART, '$');
usart_putchar(1, '$');
GPS_send_string(buf);
SEND(buf);
do{
checksum ^= *buf++;
}while(*buf);
usart_putchar(GPS_USART, '*');
usart_putchar(1, '*');
send_chksum(checksum);
newline();
GPS_endline();
}
/*
* MTK fields format:
* $PMTKxxx,yyy,zzz*2E
* P - proprietary, MTK - always this, xxx - packet type, yyy,zzz - packet data
* Packet types:
* 220 - PMTK_SET_POS_FIX, data - position fix interval (msec, > 200)
* 255 - PMTK_SET_SYNC_PPS_NMEA - turn on/off (def - off) PPS, data = 0/1 -> "$PMTK255,1" turn ON
* 285 - PMTK_SET_PPS_CONFIG - set PPS configuration, data fields:
* 1st - 0-disable, 1-after 1st fix, 2-3D only, 3-2D/3D only, 4-always
* 2nd - 2..998 - pulse width
* 314 - PMTK_API_SET_NMEA_OUTPUT - set output messages, N== N fixes per output,
* order of messages: GLL,RMC,VTG,GGA,GSA,GSV,GRS,GST, only RMC per every pos fix:
* $PMTK314,0,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0
* 386 - PMTK_API_SET_STATIC_NAV_THD speed threshold (m/s) for static navigation
* $PMTK386,1.5
* ;
*/
/**
* Send starting sequences (get only RMC messages)
*/
void GPS_send_start_seq(){
DBG("Send start seq");
// turn ON PPS:
write_with_checksum("PMTK255,1");
// set pulse width to 10ms with working after 1st fix
write_with_checksum("PMTK285,1,10");
// set only RMC:
write_with_checksum("PMTK314,0,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0");
// set static speed threshold
write_with_checksum("PMTK386,1.5");
need2startseq = 0;
}
/**
* Parse answer from GPS module
*
* Recommended minimum specific GPS/Transit data
* $GPRMC,hhmmss.sss,status,latitude,N,longitude,E,spd,cog,ddmmyy,mv,mvE,mode*cs
* 1 = UTC of position fix
* 2 = Data status (V=valid, A=invalid)
* 3 = Latitude (ddmm.mmmm)
* 4 = N or S
* 5 = Longitude (dddmm.mmmm)
* 6 = E or W
* 7 = Speed over ground in knots
* 8 = Cource over ground in degrees
* 9 = UT date (ddmmyy)
* 10 = Magnetic variation degrees (Easterly var. subtracts from true course)
* 11 = E or W
* 12 = Mode: N(bad), E(approx), A(auto), D(diff)
* 213457.00,A,4340.59415,N,04127.47560,E,2.494,,290615,,,A*7B
*/
void GPS_parse_answer(const char *buf){
char *ptr;
DBG(buf);
if(buf[1] == 'P') return; // answers to proprietary messages
if(cmpstr(buf+3, "RMC", 3)){ // not RMC message
need2startseq = 1;
return;
}
if(!checksum_true(buf)){
return; // wrong checksum
}
buf += 7; // skip header
if(*buf == ','){ // time unknown
GPS_status = GPS_WAIT;
return;
}
ptr = getchr(buf, ',');
if(!ptr ) return;
*ptr++ = 0;
if(*ptr == 'A'){
GPS_status = GPS_VALID;
set_time(buf);
}else{
GPS_status = GPS_NOT_VALID;
}
}

View File

@ -0,0 +1,41 @@
/*
* GPS.h
*
* Copyright 2015 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 __GPS_H__
#define __GPS_H__
#include "stm32f1.h"
extern int need2startseq;
typedef enum{
GPS_WAIT // wait for satellites
,GPS_NOT_VALID // time known, but not valid
,GPS_VALID
} gps_status;
extern gps_status GPS_status;
void GPS_parse_answer(const char *string);
void GPS_send_start_seq();
#endif // __GPS_H__

View File

@ -0,0 +1,140 @@
BINARY = chrono
BOOTPORT ?= /dev/ttyUSB0
BOOTSPEED ?= 115200
# MCU FAMILY
FAMILY ?= F1
# MCU code
MCU ?= F103x8
# density (stm32f10x.h, lines 70-84)
DENSITY ?= MD
# change this linking script depending on particular MCU model,
LDSCRIPT ?= stm32f103x8.ld
DEFS = -DVERSION=\"0.0.1\"
# debug
DEFS += -DEBUG
INDEPENDENT_HEADERS=
FP_FLAGS ?= -msoft-float -mfloat-abi=soft
ASM_FLAGS ?= -mthumb -mcpu=cortex-m3 -mfix-cortex-m3-ldrd
ARCH_FLAGS = $(ASM_FLAGS) $(FP_FLAGS)
###############################################################################
# Executables
#PREFIX ?= arm-none-eabi
# gcc from arm web site
PREFIX ?= /opt/bin/arm-none-eabi
TOOLCHLIB ?= /opt/arm-none-eabi/lib
RM := rm -f
RMDIR := rmdir
CC := $(PREFIX)-gcc
# don't replace ld with gcc: the binary size would be much greater!!
LD := $(PREFIX)-ld
AR := $(PREFIX)-ar
AS := $(PREFIX)-as
SIZE := $(PREFIX)-size
OBJCOPY := $(PREFIX)-objcopy
OBJDUMP := $(PREFIX)-objdump
GDB := $(PREFIX)-gdb
STFLASH := $(shell which st-flash)
STBOOT := $(shell which stm32flash)
DFUUTIL := $(shell which dfu-util)
###############################################################################
# Source files
OBJDIR = mk
SRC := $(wildcard *.c)
OBJS := $(addprefix $(OBJDIR)/, $(SRC:%.c=%.o))
STARTUP = $(OBJDIR)/startup.o
OBJS += $(STARTUP)
# dependencies: we need them to recompile files if their headers-dependencies changed
DEPS := $(OBJS:.o=.d)
INC_DIR ?= ../inc
INCLUDE := -I$(INC_DIR)/Fx -I$(INC_DIR)/cm
LIB_DIR := $(INC_DIR)/ld
###############################################################################
# C flags
CFLAGS += -O2 -g -D__thumb2__=1 -MD
CFLAGS += -Wall -Werror -Wextra -Wshadow
CFLAGS += -fno-common -ffunction-sections -fdata-sections -fno-stack-protector
CFLAGS += $(ARCH_FLAGS)
###############################################################################
# Linker flags
LDFLAGS += -nostartfiles --static -nostdlibs
LDFLAGS += -L$(LIB_DIR) -L$(TOOLCHLIB)
LDFLAGS += -T$(LDSCRIPT)
###############################################################################
# Used libraries
LDLIBS += -lc $(shell $(CC) $(CFLAGS) -print-libgcc-file-name)
DEFS += -DSTM32$(FAMILY) -DSTM32$(MCU) -DSTM32F10X_$(DENSITY)
ELF := $(OBJDIR)/$(BINARY).elf
LIST := $(OBJDIR)/$(BINARY).list
BIN := $(BINARY).bin
HEX := $(BINARY).hex
all: bin list size
elf: $(ELF)
bin: $(BIN)
hex: $(HEX)
list: $(LIST)
ifneq ($(MAKECMDGOALS),clean)
-include $(DEPS)
endif
$(OBJDIR):
mkdir $(OBJDIR)
$(STARTUP): $(INC_DIR)/startup/vector.c
$(CC) $(CFLAGS) $(DEFS) $(INCLUDE) -o $@ -c $<
$(OBJDIR)/%.o: %.c
@echo " CC $<"
$(CC) $(CFLAGS) $(DEFS) $(INCLUDE) -o $@ -c $<
$(BIN): $(ELF)
@echo " OBJCOPY $(BIN)"
$(OBJCOPY) -Obinary $(ELF) $(BIN)
$(HEX): $(ELF)
@echo " OBJCOPY $(HEX)"
$(OBJCOPY) -Oihex $(ELF) $(HEX)
$(LIST): $(ELF)
@echo " OBJDUMP $(LIST)"
$(OBJDUMP) -S $(ELF) > $(LIST)
$(ELF): $(OBJDIR) $(OBJS)
@echo " LD $(ELF)"
$(LD) $(LDFLAGS) $(OBJS) $(LDLIBS) -o $(ELF)
size: $(ELF)
$(SIZE) $(ELF)
clean:
@echo " CLEAN"
$(RM) $(OBJS) $(DEPS) $(ELF) $(HEX) $(LIST)
@rmdir $(OBJDIR) 2>/dev/null || true
flash: $(BIN)
@echo " FLASH $(BIN)"
$(STFLASH) write $(BIN) 0x8000000
boot: $(BIN)
@echo " LOAD $(BIN) through bootloader"
$(STBOOT) -b$(BOOTSPEED) $(BOOTPORT) -w $(BIN)
dfuboot: $(BIN)
@echo " LOAD $(BIN) THROUGH DFU"
$(DFUUTIL) -a0 -D $(BIN) -s 0x08000000
.PHONY: clean flash boot

View File

@ -0,0 +1,18 @@
Chronometer for downhill competitions
=====================================
## Pinout
- PA9(Tx),PA10 (debug mode) - USART1 - debug console
- PA2(Tx), PA3 - USART2 - GPS
- PB10(Tx), PB11 - USART3 - LIDAR
- PA1 - PPS signal from GPS (EXTI)
- PB8, PB9 - onboard LEDs
- PA4 - TRIG2 - 12V trigger (EXTI)
- PA13 - TRIG0 - button0 (EXTI)
- PA14 - TRIG1 - button1/laser/etc (EXTI)
- PA15 - USB pullup

View File

@ -0,0 +1,70 @@
/*
* This file is part of the chronometer 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 - Rvar
* 1 - internal Tsens
* 2 - Vref
*/
uint16_t ADC_array[NUMBER_OF_ADC_CHANNELS*9];
/**
* @brief getADCval - calculate median value for `nch` channel
* @param nch - number of channel
* @return
*/
uint16_t getADCval(int nch){
int i, addr = nch;
register uint16_t temp;
#define PIX_SORT(a,b) { if ((a)>(b)) PIX_SWAP((a),(b)); }
#define PIX_SWAP(a,b) { temp=(a);(a)=(b);(b)=temp; }
uint16_t p[9];
for(i = 0; i < 9; ++i, addr += NUMBER_OF_ADC_CHANNELS) // first we should prepare array for optmed
p[i] = ADC_array[addr];
PIX_SORT(p[1], p[2]) ; PIX_SORT(p[4], p[5]) ; PIX_SORT(p[7], p[8]) ;
PIX_SORT(p[0], p[1]) ; PIX_SORT(p[3], p[4]) ; PIX_SORT(p[6], p[7]) ;
PIX_SORT(p[1], p[2]) ; PIX_SORT(p[4], p[5]) ; PIX_SORT(p[7], p[8]) ;
PIX_SORT(p[0], p[3]) ; PIX_SORT(p[5], p[8]) ; PIX_SORT(p[4], p[7]) ;
PIX_SORT(p[3], p[6]) ; PIX_SORT(p[1], p[4]) ; PIX_SORT(p[2], p[5]) ;
PIX_SORT(p[4], p[7]) ; PIX_SORT(p[4], p[2]) ; PIX_SORT(p[6], p[4]) ;
PIX_SORT(p[4], p[2]) ;
return p[4];
#undef PIX_SORT
#undef PIX_SWAP
}
// return MCU temperature (degrees of celsius * 10)
int32_t getMCUtemp(){
// Temp = (V25 - Vsense)/Avg_Slope + 25
// V_25 = 1.45V, Slope = 4.3e-3
int32_t Vsense = getVdd() * getADCval(1);
int32_t temperature = 593920 - Vsense; // 593920 == 145*4096
temperature /= 172; // == /(4096*10*4.3e-3), 10 - to convert from *100 to *10
temperature += 250;
return(temperature);
}
// return Vdd * 100 (V)
uint32_t getVdd(){
uint32_t vdd = 120 * 4096; // 1.2V
vdd /= getADCval(2);
return vdd;
}

View File

@ -0,0 +1,29 @@
/*
* This file is part of the chronometer 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 "stm32f1.h"
#define NUMBER_OF_ADC_CHANNELS (3)
extern uint16_t ADC_array[];
int32_t getMCUtemp();
uint32_t getVdd();
uint16_t getADCval(int nch);
#endif // ADC_H

BIN
F1-nolib/chronometer/chrono.bin Executable file

Binary file not shown.

View File

@ -0,0 +1,122 @@
/*
* 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"
#include "usart.h"
static inline void gpio_setup(){
// Enable clocks to the GPIO subsystems (PB for ADC), turn on AFIO clocking to disable SWD/JTAG
RCC->APB2ENR |= RCC_APB2ENR_IOPAEN | RCC_APB2ENR_IOPBEN | RCC_APB2ENR_IOPCEN | RCC_APB2ENR_AFIOEN;
// turn off SWJ/JTAG
AFIO->MAPR = AFIO_MAPR_SWJ_CFG_DISABLE;
// pullups
GPIOA->ODR = (1<<12)|(1<<13)|(1<<14);
// Set led (PB8) as opendrain output
GPIOB->CRH = CRH(8, CNF_ODOUTPUT|MODE_SLOW);
// PPS pin (PA1) - input with weak pullup
GPIOA->CRL = CRL(1, CNF_PUDINPUT|MODE_INPUT);
// Set buttons (PA13/14) as inputs with weak pullups, USB pullup (PA15) - opendrain output
GPIOA->CRH = CRH(13, CNF_PUDINPUT|MODE_INPUT) | CRH(14, CNF_PUDINPUT|MODE_INPUT) |
CRH(15, CNF_ODOUTPUT|MODE_SLOW);
// EXTI: all three EXTI are on PA -> AFIO_EXTICRx = 0
// interrupt on pulse front: buttons - 1->0, PPS - 0->1
EXTI->IMR = EXTI_IMR_MR1 | EXTI_IMR_MR13 | EXTI_IMR_MR14; // unmask
EXTI->RTSR = EXTI_RTSR_TR1; // rising trigger
EXTI->FTSR = EXTI_FTSR_TR13 | EXTI_FTSR_TR14; // falling trigger
NVIC_EnableIRQ(EXTI15_10_IRQn);
NVIC_EnableIRQ(EXTI1_IRQn);
}
static inline void adc_setup(){
GPIOB->CRL |= CRL(0, CNF_ANALOG|MODE_INPUT);
uint32_t ctr = 0;
// Enable clocking
RCC->APB2ENR |= RCC_APB2ENR_ADC1EN;
RCC->CFGR &= ~(RCC_CFGR_ADCPRE);
RCC->CFGR |= RCC_CFGR_ADCPRE_DIV8; // ADC clock = RCC / 8
// sampling time - 239.5 cycles for channels 8, 16 and 17
ADC1->SMPR2 = ADC_SMPR2_SMP8;
ADC1->SMPR1 = ADC_SMPR1_SMP16 | ADC_SMPR1_SMP17;
// we have three conversions in group -> ADC1->SQR1[L] = 2, order: 8->16->17
ADC1->SQR3 = 8 | (16<<5) | (17<<10);
ADC1->SQR1 = ADC_SQR1_L_1;
ADC1->CR1 |= ADC_CR1_SCAN; // scan mode
// DMA configuration
RCC->AHBENR |= RCC_AHBENR_DMA1EN;
DMA1_Channel1->CPAR = (uint32_t) (&(ADC1->DR));
DMA1_Channel1->CMAR = (uint32_t)(ADC_array);
DMA1_Channel1->CNDTR = NUMBER_OF_ADC_CHANNELS * 9;
DMA1_Channel1->CCR |= DMA_CCR_MINC | DMA_CCR_MSIZE_0 | DMA_CCR_PSIZE_0
| DMA_CCR_CIRC | DMA_CCR_PL | DMA_CCR_EN;
// continuous mode & DMA; enable vref & Tsens; wake up ADC
ADC1->CR2 |= ADC_CR2_DMA | ADC_CR2_TSVREFE | ADC_CR2_CONT | ADC_CR2_ADON;
// wait for Tstab - at least 1us
while(++ctr < 0xff) nop();
// calibration
ADC1->CR2 |= ADC_CR2_RSTCAL;
ctr = 0; while((ADC1->CR2 & ADC_CR2_RSTCAL) && ++ctr < 0xfffff);
ADC1->CR2 |= ADC_CR2_CAL;
ctr = 0; while((ADC1->CR2 & ADC_CR2_CAL) && ++ctr < 0xfffff);
// turn ON ADC
ADC1->CR2 |= ADC_CR2_ADON;
}
void hw_setup(){
gpio_setup();
//adc_setup();
}
void exti1_isr(){ // PPS - PA1
/*
if(trigger_ms[2] == DIDNT_TRIGGERED){ // prevent bounce
trigger_ms[2] = Timer;
memcpy(&trigger_time[2], &current_time, sizeof(curtime));
}
*/
DBG("exti1");
EXTI->PR = EXTI_PR_PR1;
}
void exti15_10_isr(){ // PA13 - button0, PA14 - button1
if(EXTI->PR & EXTI_PR_PR13){
/*
if(trigger_ms[0] == DIDNT_TRIGGERED){ // prevent bounce
trigger_ms[0] = Timer;
memcpy(&trigger_time[0], &current_time, sizeof(curtime));
}
*/
DBG("exti13");
EXTI->PR = EXTI_PR_PR13;
}
if(EXTI->PR & EXTI_PR_PR14){
/*
if(trigger_ms[3] == DIDNT_TRIGGERED){ // prevent bounce
trigger_ms[3] = Timer;
memcpy(&trigger_time[3], &current_time, sizeof(curtime));
}
*/
DBG("exti14");
EXTI->PR = EXTI_PR_PR14;
}
}

View File

@ -0,0 +1,68 @@
/*
* 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 "stm32f1.h"
// usb commands
// lower and upper limits to capture
#define CMD_DISTMIN "distmin"
#define CMD_DISTMAX "distmax"
#define CMD_ADC1MIN "adc1min"
#define CMD_ADC2MIN "adc2min"
#define CMD_ADC1MAX "adc1max"
#define CMD_ADC2MAX "adc2max"
#define CMD_PRINTTIME "time"
// onboard LED - PB8
#define LED_port GPIOB
#define LED_pin (1<<8)
// PPS pin - PA1
#define PPS_port GPIOA
#define PPS_pin (1<<1)
// Buttons' state: PA13 (0)/PA14 (1)
#define GET_BTN0() ((GPIOA->IDR & (1<<13)) ? 0 : 1)
#define GET_BTN1() ((GPIOA->IDR & (1<<14)) ? 0 : 1)
#define GET_PPS() ((GPIOA->IDR & (1<<1)) ? 1 : 0)
// USB pullup - PA15
#define USBPU_port GPIOA
#define USBPU_pin (1<<15)
#define USBPU_ON() pin_clear(USBPU_port, USBPU_pin)
#define USBPU_OFF() pin_set(USBPU_port, USBPU_pin)
#define LED_blink() pin_toggle(LED_port, LED_pin)
#define LED_on() pin_clear(LED_port, LED_pin)
#define LED_off() pin_set(LED_port, LED_pin)
// GPS USART == USART2, LIDAR USART == USART3
#define GPS_USART (2)
#define LIDAR_USART (3)
void hw_setup();
#endif // __HARDWARE_H__

View File

@ -0,0 +1,115 @@
"Source:","/home/eddy/Docs/SAO/ELECTRONICS/STM32/F1-srcs/chronometer/kicad/chrono/chrono.sch"
"Date:","þÔ 27 ÉÀÎ 2019 18:58:30"
"Tool:","Eeschema (6.0.0-rc1-dev-1613-ga55d9819b)"
"Generator:","/usr/local/share/kicad/plugins/bom_csv_grouped_by_value.py"
"Component Count:","62"
"Individual Components:"
"Item","Qty","Reference(s)","Value","LibPart","Footprint","Datasheet","Manufacturer"
"","","C1","0.1","stm32-rescue:C","Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder","",""
"","","C2","0.1","stm32-rescue:C","Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder","",""
"","","C3","0.1","stm32-rescue:C","Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder","",""
"","","C4","47u","stm32-rescue:CP","Capacitor_Tantalum_SMD:CP_EIA-3216-18_Kemet-A_Pad1.58x1.35mm_HandSolder","",""
"","","C5","10u","Device:C","Capacitor_SMD:C_1206_3216Metric_Pad1.42x1.75mm_HandSolder","~",""
"","","C6","100u","stm32-rescue:CP","Capacitor_THT:CP_Radial_D8.0mm_P3.50mm","",""
"","","C7","0.1","stm32-rescue:C","Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder","",""
"","","C8","0.1","stm32-rescue:C","Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder","",""
"","","C9","47u","stm32-rescue:CP","Capacitor_Tantalum_SMD:CP_EIA-3216-18_Kemet-A_Pad1.58x1.35mm_HandSolder","",""
"","","C10","12","stm32-rescue:C","Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder","",""
"","","C11","12","stm32-rescue:C","Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder","",""
"","","C12","0.1","stm32-rescue:C","Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder","",""
"","","C13","0.1","stm32-rescue:C","Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder","",""
"","","C14","0.1","stm32-rescue:C","Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder","",""
"","","C15","0.1","stm32-rescue:C","Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder","",""
"","","D1","MM3Z7V5","Device:D_Zener","Diode_SMD:D_0805_2012Metric_Pad1.15x1.40mm_HandSolder","~",""
"","","D2","SS14","Device:D_Schottky","Diode_SMD:D_SMA_Handsoldering","~",""
"","","D3","1n5822","stm32-rescue:D","Diode_THT:D_DO-201_P12.70mm_Horizontal","",""
"","","D4","LED0","stm32-rescue:LED-RESCUE-stm32","LED_THT:LED_D5.0mm","",""
"","","D5","LED1","stm32-rescue:LED-RESCUE-stm32","LED_THT:LED_D5.0mm","",""
"","","J1","Power 12V","Connector_Generic:Conn_01x02","TerminalBlock_Phoenix:TerminalBlock_Phoenix_MKDS-1,5-2-5.08_1x02_P5.08mm_Horizontal","~",""
"","","J2","+5Vout","Connector_Generic:Conn_01x02","TerminalBlock_Phoenix:TerminalBlock_Phoenix_MKDS-1,5-2-5.08_1x02_P5.08mm_Horizontal","~",""
"","","J3","Ext_trig0","Connector_Generic:Conn_01x02","TerminalBlock_Phoenix:TerminalBlock_Phoenix_MKDS-1,5-2-5.08_1x02_P5.08mm_Horizontal","~",""
"","","J4","LIDAR","Connector:Conn_01x04_Female","Connector_PinSocket_2.54mm:PinSocket_1x04_P2.54mm_Vertical","~",""
"","","J5","Ext_trig1","Connector_Generic:Conn_01x02","TerminalBlock_Phoenix:TerminalBlock_Phoenix_MKDS-1,5-2-5.08_1x02_P5.08mm_Horizontal","~",""
"","","J6","Ext_trig2","Connector_Generic:Conn_01x02","TerminalBlock_Phoenix:TerminalBlock_Phoenix_MKDS-1,5-2-5.08_1x02_P5.08mm_Horizontal","~",""
"","","J7","USART1","Connector:Conn_01x03_Female","Connector_PinSocket_2.54mm:PinSocket_1x03_P2.54mm_Vertical","~",""
"","","L1","100u","stm32-rescue:L","Inductor_SMD:L_12x12mm_H4.5mm","",""
"","","P1","USB_B","stm32-rescue:USB_A-RESCUE-stm32","Connectors_USB:USB_B_OST_USB-B1HSxx_Horizontal","",""
"","","Q1","AO3407","stm32-rescue:Q_PMOS_GSD","TO_SOT_Packages_SMD:SOT-23_Handsoldering","",""
"","","Q2","DTA114Y","Transistor_BJT:DTA114Y","TO_SOT_Packages_SMD:SOT-323_SC-70_Handsoldering","",""
"","","R1","10k","stm32-rescue:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder","",""
"","","R2","10k","stm32-rescue:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder","",""
"","","R3","22","stm32-rescue:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder","",""
"","","R4","22","stm32-rescue:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder","",""
"","","R5","10k","stm32-rescue:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder","",""
"","","R6","1k5","stm32-rescue:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder","",""
"","","R7","22","Device:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder","~",""
"","","R8","330","stm32-rescue:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder","",""
"","","R9","330","stm32-rescue:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder","",""
"","","R10","330","Device:R","Resistor_SMD:R_0805_2012Metric_Pad1.15x1.40mm_HandSolder","~",""
"","","R11","4k7","Device:R","Resistor_SMD:R_0805_2012Metric_Pad1.15x1.40mm_HandSolder","~",""
"","","R12","4k7","Device:R","Resistor_SMD:R_0805_2012Metric_Pad1.15x1.40mm_HandSolder","~",""
"","","R13","100k","stm32-rescue:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder","",""
"","","R14","330","Device:R","Resistor_SMD:R_0805_2012Metric_Pad1.15x1.40mm_HandSolder","~",""
"","","R15","4k7","Device:R","Resistor_SMD:R_0805_2012Metric_Pad1.15x1.40mm_HandSolder","~",""
"","","R16","4k7","Device:R","Resistor_SMD:R_0805_2012Metric_Pad1.15x1.40mm_HandSolder","~",""
"","","R17","2k2","Device:R","Resistor_SMD:R_0805_2012Metric_Pad1.15x1.40mm_HandSolder","~",""
"","","R18","100k","stm32-rescue:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder","",""
"","","R19","4k7","Device:R","Resistor_SMD:R_0805_2012Metric_Pad1.15x1.40mm_HandSolder","~",""
"","","R20","4k7","Device:R","Resistor_SMD:R_0805_2012Metric_Pad1.15x1.40mm_HandSolder","~",""
"","","SW1","Reset","Switch:SW_Push","Buttons_Switches_SMD:SW_SPST_FSMSM","",""
"","","SW2","Boot","Switch:SW_Push","Buttons_Switches_SMD:SW_SPST_FSMSM","",""
"","","U1","USBLC6-2SC6","Power_Protection:USBLC6-2SC6","TO_SOT_Packages_SMD:SOT-23-6_Handsoldering","http://www2.st.com/resource/en/datasheet/CD00050750.pdf",""
"","","U2","LM2576HV","stm32-rescue:LM2576HV","TO_SOT_Packages_THT:TO-220-5_P3.4x3.7mm_StaggerEven_Lead3.8mm_Vertical","","Texas Instruments"
"","","U3","L80-R","Chrono:L80-R","chrono:L80-R","",""
"","","U4","LM1117-3.3","stm32-rescue:LM1117-3.3-RESCUE-stm32","TO_SOT_Packages_SMD:SOT-223","",""
"","","U5","PC817","Isolator:PC817","Package_DIP:DIP-4_W7.62mm","http://www.soselectronic.cz/a_info/resource/d/pc817.pdf",""
"","","U6","PC817","Isolator:PC817","Package_DIP:DIP-4_W7.62mm","http://www.soselectronic.cz/a_info/resource/d/pc817.pdf",""
"","","U7","STM32F103C6Tx","MCU_ST_STM32F1:STM32F103C6Tx","Package_QFP:LQFP-48_7x7mm_P0.5mm","http://www.st.com/st-web-ui/static/active/en/resource/technical/document/datasheet/CD00210843.pdf",""
"","","U8","PC817","Isolator:PC817","Package_DIP:DIP-4_W7.62mm","http://www.soselectronic.cz/a_info/resource/d/pc817.pdf",""
"","","Y1","8MHz","Device:Crystal","Crystal:Crystal_HC49-U_Vertical","~",""
"Collated Components:"
"Item","Qty","Reference(s)","Value","LibPart","Footprint","Datasheet","Manufacturer"
"1","9","C1, C2, C3, C7, C8, C12, C13, C14, C15","0.1","stm32-rescue:C","Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder","",""
"2","2","C4, C9","47u","stm32-rescue:CP","Capacitor_Tantalum_SMD:CP_EIA-3216-18_Kemet-A_Pad1.58x1.35mm_HandSolder","",""
"3","1","C5","10u","Device:C","Capacitor_SMD:C_1206_3216Metric_Pad1.42x1.75mm_HandSolder","~",""
"4","1","C6","100u","stm32-rescue:CP","Capacitor_THT:CP_Radial_D8.0mm_P3.50mm","",""
"5","2","C10, C11","12","stm32-rescue:C","Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder","",""
"6","1","D1","MM3Z7V5","Device:D_Zener","Diode_SMD:D_0805_2012Metric_Pad1.15x1.40mm_HandSolder","~",""
"7","1","D2","SS14","Device:D_Schottky","Diode_SMD:D_SMA_Handsoldering","~",""
"8","1","D3","1n5822","stm32-rescue:D","Diode_THT:D_DO-201_P12.70mm_Horizontal","",""
"9","1","D4","LED0","stm32-rescue:LED-RESCUE-stm32","LED_THT:LED_D5.0mm","",""
"10","1","D5","LED1","stm32-rescue:LED-RESCUE-stm32","LED_THT:LED_D5.0mm","",""
"11","1","J1","Power 12V","Connector_Generic:Conn_01x02","TerminalBlock_Phoenix:TerminalBlock_Phoenix_MKDS-1,5-2-5.08_1x02_P5.08mm_Horizontal","~",""
"12","1","J2","+5Vout","Connector_Generic:Conn_01x02","TerminalBlock_Phoenix:TerminalBlock_Phoenix_MKDS-1,5-2-5.08_1x02_P5.08mm_Horizontal","~",""
"13","1","J3","Ext_trig0","Connector_Generic:Conn_01x02","TerminalBlock_Phoenix:TerminalBlock_Phoenix_MKDS-1,5-2-5.08_1x02_P5.08mm_Horizontal","~",""
"14","1","J4","LIDAR","Connector:Conn_01x04_Female","Connector_PinSocket_2.54mm:PinSocket_1x04_P2.54mm_Vertical","~",""
"15","1","J5","Ext_trig1","Connector_Generic:Conn_01x02","TerminalBlock_Phoenix:TerminalBlock_Phoenix_MKDS-1,5-2-5.08_1x02_P5.08mm_Horizontal","~",""
"16","1","J6","Ext_trig2","Connector_Generic:Conn_01x02","TerminalBlock_Phoenix:TerminalBlock_Phoenix_MKDS-1,5-2-5.08_1x02_P5.08mm_Horizontal","~",""
"17","1","J7","USART1","Connector:Conn_01x03_Female","Connector_PinSocket_2.54mm:PinSocket_1x03_P2.54mm_Vertical","~",""
"18","1","L1","100u","stm32-rescue:L","Inductor_SMD:L_12x12mm_H4.5mm","",""
"19","1","P1","USB_B","stm32-rescue:USB_A-RESCUE-stm32","Connectors_USB:USB_B_OST_USB-B1HSxx_Horizontal","",""
"20","1","Q1","AO3407","stm32-rescue:Q_PMOS_GSD","TO_SOT_Packages_SMD:SOT-23_Handsoldering","",""
"21","1","Q2","DTA114Y","Transistor_BJT:DTA114Y","TO_SOT_Packages_SMD:SOT-323_SC-70_Handsoldering","",""
"22","3","R1, R2, R5","10k","stm32-rescue:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder","",""
"23","3","R3, R4, R7","22","Device:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder","~",""
"24","1","R6","1k5","stm32-rescue:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder","",""
"25","2","R8, R9","330","stm32-rescue:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder","",""
"26","2","R10, R14","330","Device:R","Resistor_SMD:R_0805_2012Metric_Pad1.15x1.40mm_HandSolder","~",""
"27","6","R11, R12, R15, R16, R19, R20","4k7","Device:R","Resistor_SMD:R_0805_2012Metric_Pad1.15x1.40mm_HandSolder","~",""
"28","2","R13, R18","100k","stm32-rescue:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder","",""
"29","1","R17","2k2","Device:R","Resistor_SMD:R_0805_2012Metric_Pad1.15x1.40mm_HandSolder","~",""
"30","1","SW1","Reset","Switch:SW_Push","Buttons_Switches_SMD:SW_SPST_FSMSM","",""
"31","1","SW2","Boot","Switch:SW_Push","Buttons_Switches_SMD:SW_SPST_FSMSM","",""
"32","1","U1","USBLC6-2SC6","Power_Protection:USBLC6-2SC6","TO_SOT_Packages_SMD:SOT-23-6_Handsoldering","http://www2.st.com/resource/en/datasheet/CD00050750.pdf",""
"33","1","U2","LM2576HV","stm32-rescue:LM2576HV","TO_SOT_Packages_THT:TO-220-5_P3.4x3.7mm_StaggerEven_Lead3.8mm_Vertical","","Texas Instruments"
"34","1","U3","L80-R","Chrono:L80-R","chrono:L80-R","",""
"35","1","U4","LM1117-3.3","stm32-rescue:LM1117-3.3-RESCUE-stm32","TO_SOT_Packages_SMD:SOT-223","",""
"36","3","U5, U6, U8","PC817","Isolator:PC817","Package_DIP:DIP-4_W7.62mm","http://www.soselectronic.cz/a_info/resource/d/pc817.pdf",""
"37","1","U7","STM32F103C6Tx","MCU_ST_STM32F1:STM32F103C6Tx","Package_QFP:LQFP-48_7x7mm_P0.5mm","http://www.st.com/st-web-ui/static/active/en/resource/technical/document/datasheet/CD00210843.pdf",""
"38","1","Y1","8MHz","Device:Crystal","Crystal:Crystal_HC49-U_Vertical","~",""
Can't render this file because it has a wrong number of fields in line 7.

View File

@ -0,0 +1,31 @@
EESchema-LIBRARY Version 2.4
#encoding utf-8
#
# L80-R
#
DEF L80-R U 0 40 Y Y 1 F N
F0 "U" 0 -375 50 H V C CNN
F1 "L80-R" 0 425 50 H V C CNN
F2 "chrono:L80-R" 0 0 50 H I C CNN
F3 "" -550 -50 50 H I C CNN
$FPLIST
L80-R
$ENDFPLIST
DRAW
S -250 350 250 -325 0 1 0 N
X RXD 1 -450 250 200 R 50 50 1 1 P
X RESET 10 450 50 200 L 50 50 1 1 P
X Res 11 450 150 200 L 50 50 1 1 P
X Gnd 12 450 250 200 L 50 50 1 1 P
X TXD 2 -450 150 200 R 50 50 1 1 P
X Gnd 3 -450 50 200 R 50 50 1 1 P
X Vcc 4 -450 -50 200 R 50 50 1 1 P
X V_BKP 5 -450 -150 200 R 50 50 1 1 P
X PPS 6 -450 -250 200 R 50 50 1 1 P
X Res 7 450 -250 200 L 50 50 1 1 P
X Res 8 450 -150 200 L 50 50 1 1 P
X NC 9 450 -50 200 L 50 50 1 1 P
ENDDRAW
ENDDEF
#
#End Library

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,38 @@
(module L80-R (layer F.Cu) (tedit 5D1478E8)
(fp_text reference REF** (at 0 4) (layer F.SilkS)
(effects (font (size 1 1) (thickness 0.15)))
)
(fp_text value L80-R (at 0 -8) (layer F.Fab)
(effects (font (size 1 1) (thickness 0.15)))
)
(fp_line (start -8 -14) (end -8 3) (layer F.SilkS) (width 0.15))
(fp_line (start -8 3) (end 8 3) (layer F.SilkS) (width 0.15))
(fp_line (start 8 3) (end 8 -14) (layer F.SilkS) (width 0.15))
(fp_line (start 8 -14) (end -8 -14) (layer F.SilkS) (width 0.15))
(fp_text user 1 (at 10 3) (layer F.SilkS)
(effects (font (size 2.5 2.5) (thickness 0.15)))
)
(fp_line (start -4 3) (end -4 1) (layer F.SilkS) (width 0.15))
(fp_line (start -4 1) (end -8 1) (layer F.SilkS) (width 0.15))
(fp_line (start 8 2) (end 7 3) (layer F.SilkS) (width 0.15))
(fp_text user Keepout (at -0.05 -8.65) (layer F.SilkS)
(effects (font (size 1 1) (thickness 0.15)))
)
(fp_text user area (at 0 -4.5) (layer F.SilkS)
(effects (font (size 1 1) (thickness 0.15)))
)
(pad 1 smd rect (at 8 0) (size 4 2) (layers F.Cu F.Paste F.Mask))
(pad 2 smd rect (at 8 -2.54) (size 4 2) (layers F.Cu F.Paste F.Mask))
(pad 3 smd rect (at 8 -5.08) (size 4 2) (layers F.Cu F.Paste F.Mask))
(pad 4 smd rect (at 8 -7.62) (size 4 2) (layers F.Cu F.Paste F.Mask))
(pad 5 smd rect (at 8 -10.16) (size 4 2) (layers F.Cu F.Paste F.Mask))
(pad 6 smd rect (at 8 -12.7) (size 4 2) (layers F.Cu F.Paste F.Mask))
(pad 12 smd rect (at -8 0) (size 4 2) (layers F.Cu F.Paste F.Mask))
(pad 11 smd rect (at -8 -2.54) (size 4 2) (layers F.Cu F.Paste F.Mask))
(pad 10 smd rect (at -8 -5.08) (size 4 2) (layers F.Cu F.Paste F.Mask))
(pad 9 smd rect (at -8 -7.62) (size 4 2) (layers F.Cu F.Paste F.Mask))
(pad 8 smd rect (at -8 -10.16) (size 4 2) (layers F.Cu F.Paste F.Mask))
(pad 7 smd rect (at -8 -12.7) (size 4 2) (layers F.Cu F.Paste F.Mask))
(pad 13 smd circle (at 0 -6.35) (size 2.5 2.5) (layers *.SilkS)
(solder_mask_margin 1.5) (solder_paste_margin 1.5) (clearance 1.3) (zone_connect 0))
)

View File

@ -0,0 +1,65 @@
update=Чт 27 июн 2019 14:51:04
version=1
last_client=kicad
[general]
version=1
RootSch=
BoardNm=
[cvpcb]
version=1
NetIExt=net
[eeschema]
version=1
LibDir=
[eeschema/libraries]
[pcbnew]
version=1
PageLayoutDescrFile=
LastNetListRead=chrono.net
CopperLayerCount=2
BoardThickness=1.6
AllowMicroVias=0
AllowBlindVias=0
RequireCourtyardDefinitions=0
ProhibitOverlappingCourtyards=1
MinTrackWidth=0.2
MinViaDiameter=0.4
MinViaDrill=0.3
MinMicroViaDiameter=0.2
MinMicroViaDrill=0.09999999999999999
MinHoleToHole=0.25
TrackWidth1=0.25
TrackWidth2=0.5
TrackWidth3=1
TrackWidth4=2
ViaDiameter1=1.5
ViaDrill1=0.6
ViaDiameter2=2.5
ViaDrill2=0.8
dPairWidth1=0.2
dPairGap1=0.25
dPairViaGap1=0.25
SilkLineWidth=0.12
SilkTextSizeV=1
SilkTextSizeH=1
SilkTextSizeThickness=0.15
SilkTextItalic=0
SilkTextUpright=1
CopperLineWidth=0.2
CopperTextSizeV=1.5
CopperTextSizeH=1.5
CopperTextThickness=0.3
CopperTextItalic=0
CopperTextUpright=1
EdgeCutLineWidth=0.05
CourtyardLineWidth=0.05
OthersLineWidth=0.15
OthersTextSizeV=1
OthersTextSizeH=1
OthersTextSizeThickness=0.15
OthersTextItalic=0
OthersTextUpright=1
SolderMaskClearance=0.051
SolderMaskMinWidth=0.25
SolderPasteClearance=0
SolderPasteRatio=-0

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,7 @@
(fp_lib_table
(lib (name chrono)(type KiCad)(uri ${KIPRJMOD}/chrono.pretty)(options "")(descr ""))
(lib (name TerminalBlock_Phoenix)(type KiCad)(uri ${KISYSMOD}/TerminalBlock_Phoenix.pretty)(options "")(descr ""))
(lib (name Inductor_SMD)(type KiCad)(uri ${KISYSMOD}/Inductor_SMD.pretty)(options "")(descr ""))
(lib (name LED_THT)(type KiCad)(uri ${KISYSMOD}/LED_THT.pretty)(options "")(descr ""))
(lib (name Crystal)(type KiCad)(uri ${KISYSMOD}/Crystal.pretty)(options "")(descr ""))
)

View File

@ -0,0 +1,694 @@
EESchema-LIBRARY Version 2.4
#encoding utf-8
#
# +3.3V
#
DEF +3.3V #PWR 0 0 Y Y 1 F P
F0 "#PWR" 0 -150 50 H I C CNN
F1 "+3.3V" 0 140 50 H V C CNN
F2 "" 0 0 50 H I C CNN
F3 "" 0 0 50 H I C CNN
DRAW
P 2 0 1 0 -30 50 0 100 N
P 2 0 1 0 0 0 0 100 N
P 2 0 1 0 0 100 30 50 N
X +3V3 1 0 0 0 U 50 50 1 1 W N
ENDDRAW
ENDDEF
#
# +5V
#
DEF +5V #PWR 0 0 Y Y 1 F P
F0 "#PWR" 0 -150 50 H I C CNN
F1 "+5V" 0 140 50 H V C CNN
F2 "" 0 0 50 H I C CNN
F3 "" 0 0 50 H I C CNN
DRAW
P 2 0 1 0 -30 50 0 100 N
P 2 0 1 0 0 0 0 100 N
P 2 0 1 0 0 100 30 50 N
X +5V 1 0 0 0 U 50 50 1 1 W N
ENDDRAW
ENDDEF
#
# 74HC4051
#
DEF 74HC4051 U 0 10 Y Y 1 F N
F0 "U" 0 0 50 H V C CNN
F1 "74HC4051" 0 -150 50 H V C CNN
F2 "" 0 0 50 H V C CNN
F3 "" 0 0 50 H V C CNN
$FPLIST
SO16
TSSOP16
SSOP16
DHVQFN16
$ENDFPLIST
DRAW
S -400 450 400 -450 0 1 0 N
X Y4 1 700 -50 300 L 50 50 1 1 B
X S1 10 -700 250 300 R 50 50 1 1 I
X S0 11 -700 350 300 R 50 50 1 1 I
X Y3 12 700 50 300 L 50 50 1 1 B
X Y0 13 700 350 300 L 50 50 1 1 B
X Y1 14 700 250 300 L 50 50 1 1 B
X Y2 15 700 150 300 L 50 50 1 1 B
X VCC 16 -700 -100 300 R 50 50 1 1 W
X Y6 2 700 -250 300 L 50 50 1 1 B
X Z 3 0 -750 300 U 50 50 1 1 B
X Y7 4 700 -350 300 L 50 50 1 1 B
X Y5 5 700 -150 300 L 50 50 1 1 B
X ~E 6 -700 -350 300 R 50 50 1 1 I I
X VEE 7 -700 0 300 R 50 50 1 1 W
X GND 8 -700 -200 300 R 50 50 1 1 W
X S2 9 -700 150 300 R 50 50 1 1 I
ENDDRAW
ENDDEF
#
# C
#
DEF C C 0 10 N Y 1 F N
F0 "C" 25 100 50 H V L CNN
F1 "C" 25 -100 50 H V L CNN
F2 "" 38 -150 50 H I C CNN
F3 "" 0 0 50 H I C CNN
$FPLIST
C_*
$ENDFPLIST
DRAW
P 2 0 1 20 -80 -30 80 -30 N
P 2 0 1 20 -80 30 80 30 N
X ~ 1 0 150 110 D 50 50 1 1 P
X ~ 2 0 -150 110 U 50 50 1 1 P
ENDDRAW
ENDDEF
#
# CONN_01X01
#
DEF CONN_01X01 J 0 40 Y N 1 F N
F0 "J" 0 100 50 H V C CNN
F1 "CONN_01X01" 100 0 50 V V C CNN
F2 "" 0 0 50 H I C CNN
F3 "" 0 0 50 H I C CNN
$FPLIST
Pin_Header_Straight_1X*
Pin_Header_Angled_1X*
Socket_Strip_Straight_1X*
Socket_Strip_Angled_1X*
$ENDFPLIST
DRAW
S -50 5 10 -5 0 1 0 N
S -50 50 50 -50 0 1 0 N
X P1 1 -200 0 150 R 50 50 1 1 P
ENDDRAW
ENDDEF
#
# CONN_01X03
#
DEF CONN_01X03 J 0 40 Y N 1 F N
F0 "J" 0 200 50 H V C CNN
F1 "CONN_01X03" 100 0 50 V V C CNN
F2 "" 0 0 50 H I C CNN
F3 "" 0 0 50 H I C CNN
$FPLIST
Pin_Header_Straight_1X*
Pin_Header_Angled_1X*
Socket_Strip_Straight_1X*
Socket_Strip_Angled_1X*
$ENDFPLIST
DRAW
S -50 -95 10 -105 0 1 0 N
S -50 5 10 -5 0 1 0 N
S -50 105 10 95 0 1 0 N
S -50 150 50 -150 0 1 0 N
X P1 1 -200 100 150 R 50 50 1 1 P
X P2 2 -200 0 150 R 50 50 1 1 P
X P3 3 -200 -100 150 R 50 50 1 1 P
ENDDRAW
ENDDEF
#
# CONN_01X04
#
DEF CONN_01X04 J 0 40 Y N 1 F N
F0 "J" 0 250 50 H V C CNN
F1 "CONN_01X04" 100 0 50 V V C CNN
F2 "" 0 0 50 H I C CNN
F3 "" 0 0 50 H I C CNN
$FPLIST
Pin_Header_Straight_1X*
Pin_Header_Angled_1X*
Socket_Strip_Straight_1X*
Socket_Strip_Angled_1X*
$ENDFPLIST
DRAW
S -50 -145 10 -155 0 1 0 N
S -50 -45 10 -55 0 1 0 N
S -50 55 10 45 0 1 0 N
S -50 155 10 145 0 1 0 N
S -50 200 50 -200 0 1 0 N
X P1 1 -200 150 150 R 50 50 1 1 P
X P2 2 -200 50 150 R 50 50 1 1 P
X P3 3 -200 -50 150 R 50 50 1 1 P
X P4 4 -200 -150 150 R 50 50 1 1 P
ENDDRAW
ENDDEF
#
# CONN_01X08
#
DEF CONN_01X08 J 0 40 Y N 1 F N
F0 "J" 0 450 50 H V C CNN
F1 "CONN_01X08" 100 0 50 V V C CNN
F2 "" 0 0 50 H I C CNN
F3 "" 0 0 50 H I C CNN
$FPLIST
Pin_Header_Straight_1X*
Pin_Header_Angled_1X*
Socket_Strip_Straight_1X*
Socket_Strip_Angled_1X*
$ENDFPLIST
DRAW
S -50 -400 50 400 0 1 0 N
S -50 -345 10 -355 0 1 0 N
S -50 -245 10 -255 0 1 0 N
S -50 -145 10 -155 0 1 0 N
S -50 -45 10 -55 0 1 0 N
S -50 55 10 45 0 1 0 N
S -50 155 10 145 0 1 0 N
S -50 255 10 245 0 1 0 N
S -50 355 10 345 0 1 0 N
X P1 1 -200 350 150 R 50 50 1 1 P
X P2 2 -200 250 150 R 50 50 1 1 P
X P3 3 -200 150 150 R 50 50 1 1 P
X P4 4 -200 50 150 R 50 50 1 1 P
X P5 5 -200 -50 150 R 50 50 1 1 P
X P6 6 -200 -150 150 R 50 50 1 1 P
X P7 7 -200 -250 150 R 50 50 1 1 P
X P8 8 -200 -350 150 R 50 50 1 1 P
ENDDRAW
ENDDEF
#
# CP
#
DEF CP C 0 10 N Y 1 F N
F0 "C" 25 100 50 H V L CNN
F1 "CP" 25 -100 50 H V L CNN
F2 "" 38 -150 50 H I C CNN
F3 "" 0 0 50 H I C CNN
$FPLIST
CP_*
$ENDFPLIST
DRAW
S -90 20 -90 40 0 1 0 N
S -90 20 90 20 0 1 0 N
S 90 -20 -90 -40 0 1 0 F
S 90 40 -90 40 0 1 0 N
S 90 40 90 20 0 1 0 N
P 2 0 1 0 -70 90 -30 90 N
P 2 0 1 0 -50 110 -50 70 N
X ~ 1 0 150 110 D 50 50 1 1 P
X ~ 2 0 -150 110 U 50 50 1 1 P
ENDDRAW
ENDDEF
#
# D
#
DEF D D 0 40 N N 1 F N
F0 "D" 0 100 50 H V C CNN
F1 "D" 0 -100 50 H V C CNN
F2 "" 0 0 50 H I C CNN
F3 "" 0 0 50 H I C CNN
$FPLIST
TO-???*
*SingleDiode
*_Diode_*
*SingleDiode*
D_*
$ENDFPLIST
DRAW
P 2 0 1 8 -50 50 -50 -50 N
P 2 0 1 0 50 0 -50 0 N
P 4 0 1 8 50 50 50 -50 -50 0 50 50 N
X K 1 -150 0 100 R 50 50 1 1 P
X A 2 150 0 100 L 50 50 1 1 P
ENDDRAW
ENDDEF
#
# D_Schottky
#
DEF D_Schottky D 0 40 N N 1 F N
F0 "D" 0 100 50 H V C CNN
F1 "D_Schottky" 0 -100 50 H V C CNN
F2 "" 0 0 50 H I C CNN
F3 "" 0 0 50 H I C CNN
$FPLIST
TO-???*
*SingleDiode
*_Diode_*
*SingleDiode*
D_*
$ENDFPLIST
DRAW
P 2 0 1 0 50 0 -50 0 N
P 4 0 1 8 50 50 50 -50 -50 0 50 50 N
P 6 0 1 8 -75 25 -75 50 -50 50 -50 -50 -25 -50 -25 -25 N
X K 1 -150 0 100 R 50 50 1 1 P
X A 2 150 0 100 L 50 50 1 1 P
ENDDRAW
ENDDEF
#
# D_Zener
#
DEF D_Zener D 0 40 N N 1 F N
F0 "D" 0 100 50 H V C CNN
F1 "D_Zener" 0 -100 50 H V C CNN
F2 "" 0 0 50 H I C CNN
F3 "" 0 0 50 H I C CNN
$FPLIST
TO-???*
*SingleDiode
*_Diode_*
*SingleDiode*
D_*
$ENDFPLIST
DRAW
P 2 0 1 0 50 0 -50 0 N
P 3 0 1 8 -50 -50 -50 50 -30 50 N
P 4 0 1 8 50 -50 50 50 -50 0 50 -50 N
X K 1 -150 0 100 R 50 50 1 1 P
X A 2 150 0 100 L 50 50 1 1 P
ENDDRAW
ENDDEF
#
# GND
#
DEF GND #PWR 0 0 Y Y 1 F P
F0 "#PWR" 0 -250 50 H I C CNN
F1 "GND" 0 -150 50 H V C CNN
F2 "" 0 0 50 H I C CNN
F3 "" 0 0 50 H I C CNN
DRAW
P 6 0 1 0 0 0 0 -50 50 -50 0 -100 -50 -50 0 -50 N
X GND 1 0 0 0 D 50 50 1 1 W N
ENDDRAW
ENDDEF
#
# Jumper_NO_Small
#
DEF Jumper_NO_Small JP 0 30 N N 1 F N
F0 "JP" 0 80 50 H V C CNN
F1 "Jumper_NO_Small" 10 -60 50 H V C CNN
F2 "" 0 0 50 H I C CNN
F3 "" 0 0 50 H I C CNN
DRAW
C -40 0 20 0 1 0 N
C 40 0 20 0 1 0 N
X 1 1 -100 0 40 R 50 50 0 1 P
X 2 2 100 0 40 L 50 50 0 1 P
ENDDRAW
ENDDEF
#
# L
#
DEF L L 0 40 N N 1 F N
F0 "L" -50 0 50 V V C CNN
F1 "L" 75 0 50 V V C CNN
F2 "" 0 0 50 H I C CNN
F3 "" 0 0 50 H I C CNN
$FPLIST
Choke_*
*Coil*
Inductor_*
L_*
$ENDFPLIST
DRAW
A 0 -75 25 -899 899 0 1 0 N 0 -100 0 -50
A 0 -25 25 -899 899 0 1 0 N 0 -50 0 0
A 0 25 25 -899 899 0 1 0 N 0 0 0 50
A 0 75 25 -899 899 0 1 0 N 0 50 0 100
X 1 1 0 150 50 D 50 50 1 1 P
X 2 2 0 -150 50 U 50 50 1 1 P
ENDDRAW
ENDDEF
#
# LED-RESCUE-stm32
#
DEF LED-RESCUE-stm32 D 0 40 Y N 1 F N
F0 "D" 0 100 50 H V C CNN
F1 "LED-RESCUE-stm32" 0 -100 50 H V C CNN
F2 "" 0 0 50 H V C CNN
F3 "" 0 0 50 H V C CNN
$FPLIST
LED*
$ENDFPLIST
DRAW
P 2 0 1 8 -50 -50 -50 50 N
P 2 0 1 0 -50 0 50 0 N
P 4 0 1 8 50 -50 50 50 -50 0 50 -50 N
P 5 0 1 0 -120 -30 -180 -90 -150 -90 -180 -90 -180 -60 N
P 5 0 1 0 -70 -30 -130 -90 -100 -90 -130 -90 -130 -60 N
X K 1 -150 0 100 R 50 50 1 1 P
X A 2 150 0 100 L 50 50 1 1 P
ENDDRAW
ENDDEF
#
# LM1117-3.3-RESCUE-stm32
#
DEF LM1117-3.3-RESCUE-stm32 U 0 30 Y Y 1 F N
F0 "U" 100 -250 50 H V C CNN
F1 "LM1117-3.3-RESCUE-stm32" 0 250 50 H V C CNN
F2 "" 0 0 50 H I C CNN
F3 "" 0 0 50 H I C CNN
$FPLIST
SOT-223*
TO-263*
TO-252*
$ENDFPLIST
DRAW
S -200 -200 200 200 0 1 10 f
X GND/ADJ 1 0 -300 100 U 50 50 1 1 W
X VO 2 300 50 100 L 50 50 1 1 P
X VI 3 -300 0 100 R 50 50 1 1 W
X VO 4 300 -50 100 L 50 50 1 1 w
ENDDRAW
ENDDEF
#
# LM2576HV
#
DEF LM2576HV U 0 40 Y Y 1 F N
F0 "U" -350 250 60 H V C CNN
F1 "LM2576HV" 250 250 60 H V C CNN
F2 "" 0 0 60 H I C CNN
F3 "" 0 0 60 H I C CNN
F4 "Texas Instruments" 0 350 60 H I C CNN "Manufacturer"
$FPLIST
*DIP8
SOIC8
$ENDFPLIST
DRAW
S -400 200 400 -250 0 1 0 N
X VIN 1 -700 100 300 R 50 50 1 1 W
X VOUT 2 700 -100 300 L 50 50 1 1 w
X GND 3 100 -550 300 U 50 50 1 1 W
X FB 4 700 100 300 L 50 50 1 1 I
X ON/OFF 5 -100 -550 300 U 50 50 1 1 I I
ENDDRAW
ENDDEF
#
# MAX471-RESCUE-stm32
#
DEF MAX471-RESCUE-stm32 U 0 40 Y Y 1 F N
F0 "U" -300 350 50 H V L CNN
F1 "MAX471-RESCUE-stm32" -300 -350 50 H V L CNN
F2 "" 0 0 50 H I C CNN
F3 "" 0 0 50 H I C CNN
DRAW
S -300 300 300 -300 0 1 10 f
X SHDN 1 -400 -100 100 R 50 50 1 1 I
X RS+ 2 -400 200 100 R 50 50 1 1 W
X RS+ 3 -400 100 100 R 50 50 1 1 P
X GND 4 -400 -200 100 R 50 50 1 1 W
X SIGN 5 400 -100 100 L 50 50 1 1 C
X RS- 6 400 200 100 L 50 50 1 1 w
X RS- 7 400 100 100 L 50 50 1 1 P
X OUT 8 400 -200 100 L 50 50 1 1 O
ENDDRAW
ENDDEF
#
# MCP2551-I_SN
#
DEF MCP2551-I_SN U 0 40 Y Y 1 F N
F0 "U" -400 350 50 H V L CNN
F1 "MCP2551-I_SN" 100 350 50 H V L CNN
F2 "Housings_SOIC:SOIC-8_3.9x4.9mm_Pitch1.27mm" 0 -500 50 H I C CIN
F3 "" 0 0 50 H I C CNN
$FPLIST
SOIC*Pitch1.27mm*
$ENDFPLIST
DRAW
S -400 300 400 -300 0 1 10 f
X TXD 1 -500 200 100 R 50 50 1 1 I
X VSS 2 0 -400 100 U 50 50 1 1 W
X VDD 3 0 400 100 D 50 50 1 1 W
X RXD 4 -500 100 100 R 50 50 1 1 O
X Vref 5 -500 -100 100 R 50 50 1 1 w
X CANL 6 500 -100 100 L 50 50 1 1 B
X CANH 7 500 100 100 L 50 50 1 1 B
X Rs 8 -500 -200 100 R 50 50 1 1 I
ENDDRAW
ENDDEF
#
# PESD1CAN
#
DEF PESD1CAN D 0 30 Y N 1 F N
F0 "D" 0 -350 50 H V C CNN
F1 "PESD1CAN" 50 150 50 H V C CNN
F2 "" 0 0 50 H V C CNN
F3 "" 0 0 50 H V C CNN
$FPLIST
SOT23
$ENDFPLIST
DRAW
S -200 100 300 -300 0 1 0 N
P 2 0 1 0 -140 -200 150 -200 N
P 2 0 1 0 -140 0 150 0 N
P 3 0 1 8 -150 -150 -150 -250 -150 -250 N
P 3 0 1 8 -150 50 -150 -50 -150 -50 N
P 3 0 1 8 150 -150 150 -250 150 -250 N
P 3 0 1 8 150 50 150 -50 150 -50 N
P 4 0 1 8 -150 -150 -170 -150 -170 -160 -170 -160 N
P 4 0 1 8 -150 50 -170 50 -170 40 -170 40 N
P 4 0 1 8 150 -250 170 -250 170 -240 170 -240 N
P 4 0 1 8 150 -150 130 -150 130 -160 130 -160 N
P 4 0 1 8 150 -50 170 -50 170 -40 170 -40 N
P 4 0 1 0 150 0 250 0 250 -200 150 -200 N
P 4 0 1 8 150 50 130 50 130 40 130 40 N
P 5 0 1 8 -130 -240 -130 -250 -150 -250 -150 -250 -150 -250 N
P 5 0 1 8 -130 -40 -130 -50 -150 -50 -150 -50 -150 -50 N
P 6 0 1 8 -50 -250 -150 -200 -50 -150 -50 -250 -50 -250 -50 -250 N
P 6 0 1 8 -50 -50 -150 0 -50 50 -50 -50 -50 -50 -50 -50 N
P 6 0 1 8 50 -150 150 -200 50 -250 50 -150 50 -150 50 -150 N
P 6 0 1 8 50 50 150 0 50 -50 50 50 50 50 50 50 N
X K 1 -300 0 150 R 50 50 0 1 P
X K 2 -300 -200 150 R 50 50 0 1 P
X O 3 400 -100 150 L 50 50 0 1 P
ENDDRAW
ENDDEF
#
# PWR_FLAG
#
DEF PWR_FLAG #FLG 0 0 N N 1 F P
F0 "#FLG" 0 75 50 H I C CNN
F1 "PWR_FLAG" 0 150 50 H V C CNN
F2 "" 0 0 50 H I C CNN
F3 "" 0 0 50 H I C CNN
DRAW
P 6 0 1 0 0 0 0 50 -40 75 0 100 40 75 0 50 N
X pwr 1 0 0 0 U 50 50 0 0 w
ENDDRAW
ENDDEF
#
# Q_PMOS_GSD
#
DEF Q_PMOS_GSD Q 0 0 Y N 1 F N
F0 "Q" 200 50 50 H V L CNN
F1 "Q_PMOS_GSD" 200 -50 50 H V L CNN
F2 "" 200 100 50 H I C CNN
F3 "" 0 0 50 H I C CNN
DRAW
C 65 0 111 0 1 10 N
C 100 -70 11 0 1 0 F
C 100 70 11 0 1 0 F
P 2 0 1 0 2 0 10 0 N
P 2 0 1 0 30 -70 100 -70 N
P 2 0 1 10 30 -50 30 -90 N
P 2 0 1 0 30 0 100 0 N
P 2 0 1 10 30 20 30 -20 N
P 2 0 1 0 30 70 100 70 N
P 2 0 1 10 30 90 30 50 N
P 2 0 1 0 100 -70 100 -100 N
P 2 0 1 0 100 -70 100 0 N
P 2 0 1 0 100 100 100 70 N
P 3 0 1 10 10 75 10 -75 10 -75 N
P 4 0 1 0 90 0 50 -15 50 15 90 0 F
P 4 0 1 0 100 -70 130 -70 130 70 100 70 N
P 4 0 1 0 110 -20 115 -15 145 -15 150 -10 N
P 4 0 1 0 130 -15 115 10 145 10 130 -15 N
X G 1 -200 0 200 R 50 50 1 1 I
X S 2 100 -200 100 U 50 50 1 1 P
X D 3 100 200 100 D 50 50 1 1 P
ENDDRAW
ENDDEF
#
# R
#
DEF R R 0 0 N Y 1 F N
F0 "R" 80 0 50 V V C CNN
F1 "R" 0 0 50 V V C CNN
F2 "" -70 0 50 V I C CNN
F3 "" 0 0 50 H I C CNN
$FPLIST
R_*
R_*
$ENDFPLIST
DRAW
S -40 -100 40 100 0 1 10 N
X ~ 1 0 150 50 D 50 50 1 1 P
X ~ 2 0 -150 50 U 50 50 1 1 P
ENDDRAW
ENDDEF
#
# STM32F042C6Tx
#
DEF STM32F042C6Tx U 0 40 Y Y 1 L N
F0 "U" -3000 1725 50 H V L BNN
F1 "STM32F042C6Tx" 3000 1725 50 H V R BNN
F2 "LQFP48" 3000 1675 50 H V R TNN
F3 "" 0 0 50 H V C CNN
DRAW
S -3000 -1700 3000 1700 0 1 10 f
X VBAT 1 -3100 1100 100 R 50 50 1 1 W
X ADC_IN0/RTC_TAMP2/SYS_WKUP1/TIM2_CH1/TIM2_ETR/TSC_G1_IO1/USART2_CTS/PA0 10 3100 100 100 L 50 50 1 1 B
X ADC_IN1/TIM2_CH2/TSC_G1_IO2/USART2_DE/USART2_RTS/PA1 11 3100 0 100 L 50 50 1 1 B
X ADC_IN2/SYS_WKUP4/TIM2_CH3/TSC_G1_IO3/USART2_TX/PA2 12 3100 -100 100 L 50 50 1 1 B
X ADC_IN3/TIM2_CH4/TSC_G1_IO4/USART2_RX/PA3 13 3100 -200 100 L 50 50 1 1 B
X ADC_IN4/I2S1_WS/SPI1_NSS/TIM14_CH1/TSC_G2_IO1/USART2_CK/USB_OE/PA4 14 3100 -300 100 L 50 50 1 1 B
X ADC_IN5/CEC/I2S1_CK/SPI1_SCK/TIM2_CH1/TIM2_ETR/TSC_G2_IO2/PA5 15 3100 -400 100 L 50 50 1 1 B
X ADC_IN6/I2S1_MCK/SPI1_MISO/TIM16_CH1/TIM1_BKIN/TIM3_CH1/TSC_G2_IO3/PA6 16 3100 -500 100 L 50 50 1 1 B
X ADC_IN7/I2S1_SD/SPI1_MOSI/TIM14_CH1/TIM17_CH1/TIM1_CH1N/TIM3_CH2/TSC_G2_IO4/PA7 17 3100 -600 100 L 50 50 1 1 B
X PB0/ADC_IN8/TIM1_CH2N/TIM3_CH3/TSC_G3_IO2 18 -3100 100 100 R 50 50 1 1 B
X PB1/ADC_IN9/TIM14_CH1/TIM1_CH3N/TIM3_CH4/TSC_G3_IO3 19 -3100 0 100 R 50 50 1 1 B
X PC13/RTC_OUT_ALARM/RTC_OUT_CALIB/RTC_TAMP1/RTC_TS/SYS_WKUP2 2 -3100 500 100 R 50 50 1 1 B
X PB2/TSC_G3_IO4 20 -3100 -100 100 R 50 50 1 1 B
X PB10/CEC/I2C1_SCL/SPI2_SCK/TIM2_CH3/TSC_SYNC 21 -3100 -900 100 R 50 50 1 1 B
X PB11/I2C1_SDA/TIM2_CH4 22 -3100 -1000 100 R 50 50 1 1 B
X VSS 23 -200 -1800 100 U 50 50 1 1 W
X VDD 24 -200 1800 100 D 50 50 1 1 W
X PB12/SPI2_NSS/TIM1_BKIN 25 -3100 -1100 100 R 50 50 1 1 B
X PB13/I2C1_SCL/SPI2_SCK/TIM1_CH1N 26 -3100 -1200 100 R 50 50 1 1 B
X PB14/I2C1_SDA/SPI2_MISO/TIM1_CH2N 27 -3100 -1300 100 R 50 50 1 1 B
X PB15/RTC_REFIN/SPI2_MOSI/SYS_WKUP7/TIM1_CH3N 28 -3100 -1400 100 R 50 50 1 1 B
X CRS_SYNC/RCC_MCO/TIM1_CH1/USART1_CK/PA8 29 3100 -700 100 L 50 50 1 1 B
X PC14/RCC_OSC32_IN 3 -3100 400 100 R 50 50 1 1 B
X I2C1_SCL/TIM1_CH2/TSC_G4_IO1/USART1_TX/PA9 30 3100 -800 100 L 50 50 1 1 B
X I2C1_SDA/TIM17_BKIN/TIM1_CH3/TSC_G4_IO2/USART1_RX/PA10 31 3100 -900 100 L 50 50 1 1 B
X CAN_RX/I2C1_SCL/TIM1_CH4/TSC_G4_IO3/USART1_CTS/USB_DM/PA11 32 3100 -1000 100 L 50 50 1 1 B
X CAN_TX/I2C1_SDA/TIM1_ETR/TSC_G4_IO4/USART1_DE/USART1_RTS/USB_DP/PA12 33 3100 -1100 100 L 50 50 1 1 B
X IR_OUT/SYS_SWDIO/USB_OE/PA13 34 3100 -1200 100 L 50 50 1 1 B
X VSS 35 -100 -1800 100 U 50 50 1 1 W
X VDDIO2 36 100 1800 100 D 50 50 1 1 W
X SYS_SWCLK/USART2_TX/PA14 37 3100 -1300 100 L 50 50 1 1 B
X I2S1_WS/SPI1_NSS/TIM2_CH1/TIM2_ETR/USART2_RX/USB_OE/PA15 38 3100 -1400 100 L 50 50 1 1 B
X PB3/I2S1_CK/SPI1_SCK/TIM2_CH2/TSC_G5_IO1 39 -3100 -200 100 R 50 50 1 1 B
X PC15/RCC_OSC32_OUT 4 -3100 300 100 R 50 50 1 1 B
X PB4/I2S1_MCK/SPI1_MISO/TIM17_BKIN/TIM3_CH1/TSC_G5_IO2 40 -3100 -300 100 R 50 50 1 1 B
X PB5/I2C1_SMBA/I2S1_SD/SPI1_MOSI/SYS_WKUP6/TIM16_BKIN/TIM3_CH2 41 -3100 -400 100 R 50 50 1 1 B
X PB6/I2C1_SCL/TIM16_CH1N/TSC_G5_IO3/USART1_TX 42 -3100 -500 100 R 50 50 1 1 B
X PB7/I2C1_SDA/TIM17_CH1N/TSC_G5_IO4/USART1_RX 43 -3100 -600 100 R 50 50 1 1 B
X PF11 44 -3100 700 100 R 50 50 1 1 B
X PB8/CAN_RX/CEC/I2C1_SCL/TIM16_CH1/TSC_SYNC 45 -3100 -700 100 R 50 50 1 1 B
X PB9/CAN_TX/I2C1_SDA/IR_OUT/SPI2_NSS/TIM17_CH1 46 -3100 -800 100 R 50 50 1 1 B
X VSS 47 0 -1800 100 U 50 50 1 1 W
X VDD 48 -100 1800 100 D 50 50 1 1 W
X PF0/CRS_SYNC/I2C1_SDA/RCC_OSC_IN 5 -3100 900 100 R 50 50 1 1 I
X PF1/I2C1_SCL/RCC_OSC_OUT 6 -3100 800 100 R 50 50 1 1 I
X NRST 7 -3100 1300 100 R 50 50 1 1 I
X VSSA 8 100 -1800 100 U 50 50 1 1 W
X VDDA 9 0 1800 100 D 50 50 1 1 W
ENDDRAW
ENDDEF
#
# TPS2051
#
DEF TPS2051 U 0 40 Y Y 1 F N
F0 "U" 0 -300 60 H V C CNN
F1 "TPS2051" 0 300 60 H V C CNN
F2 "" 0 0 60 H I C CNN
F3 "" 0 0 60 H I C CNN
DRAW
S -250 250 250 -250 0 1 0 N
X GND 1 -450 150 200 R 50 50 1 1 W
X IN 2 -450 50 200 R 50 50 1 1 W
X IN 3 -450 -50 200 R 50 50 1 1 P
X EN 4 -450 -150 200 R 50 50 1 1 I
X ~OC 5 450 -150 200 L 50 50 1 1 O
X OUT 6 450 -50 200 L 50 50 1 1 P
X OUT 7 450 50 200 L 50 50 1 1 P
X OUT 8 450 150 200 L 50 50 1 1 w
ENDDRAW
ENDDEF
#
# USB6B1
#
DEF USB6B1 D 0 30 Y N 1 F N
F0 "D" 0 -450 50 H V C CNN
F1 "USB6B1" 0 400 50 H V C CNN
F2 "" 200 -100 50 V V C CNN
F3 "" 200 -100 50 V V C CNN
$FPLIST
SO8
$ENDFPLIST
DRAW
C -150 -300 7 0 1 0 N
C -150 100 7 0 1 0 N
C -150 300 7 0 1 0 N
C 0 -300 7 0 1 0 N
C 0 -100 7 0 1 0 N
C 0 300 7 0 1 0 N
C 200 -300 7 0 1 0 N
C 200 300 7 0 1 0 N
S -300 -100 300 -100 0 1 0 N
S -300 300 300 300 0 1 0 N
S -200 -150 -100 -150 0 1 0 N
S -200 250 -100 250 0 1 0 N
S -150 300 -150 -300 0 1 0 N
S -50 -150 50 -150 0 1 0 N
S -50 250 50 250 0 1 0 N
S 0 300 0 -300 0 1 0 N
S 200 300 200 -300 0 1 0 N
S 300 -300 -300 -300 0 1 0 N
S 300 100 -300 100 0 1 0 N
P 3 0 1 8 150 50 250 50 250 50 N
P 4 0 1 8 150 50 150 30 160 30 160 30 N
P 4 0 1 8 250 50 250 70 240 70 240 70 N
P 5 0 1 0 -250 350 300 350 300 -350 -250 -350 -250 350 N
P 6 0 1 8 -200 -250 -150 -150 -100 -250 -200 -250 -200 -250 -200 -250 N
P 6 0 1 8 -200 150 -150 250 -100 150 -200 150 -200 150 -200 150 N
P 6 0 1 8 -50 -250 0 -150 50 -250 -50 -250 -50 -250 -50 -250 N
P 6 0 1 8 -50 150 0 250 50 150 -50 150 -50 150 -50 150 N
P 6 0 1 8 150 -50 200 50 250 -50 150 -50 150 -50 150 -50 N
X VCC 1 -500 300 200 R 50 50 1 1 P
X I/O1 2 -500 100 200 R 50 50 1 1 P
X I/O2 3 -500 -100 200 R 50 50 1 1 P
X GND 4 -500 -300 200 R 50 50 1 1 P
X GND 5 500 -300 200 L 50 50 1 1 P
X I/O2 6 500 -100 200 L 50 50 1 1 P
X I/O1 7 500 100 200 L 50 50 1 1 P
X VCC 8 500 300 200 L 50 50 1 1 P
ENDDRAW
ENDDEF
#
# USB_A-RESCUE-stm32
#
DEF USB_A-RESCUE-stm32 P 0 40 Y Y 1 F N
F0 "P" 200 -200 50 H V C CNN
F1 "USB_A-RESCUE-stm32" -50 200 50 H V C CNN
F2 "" -50 -100 50 V V C CNN
F3 "" -50 -100 50 V V C CNN
$FPLIST
USB*
$ENDFPLIST
DRAW
S -250 -150 150 150 0 1 0 N
S -205 -150 -195 -120 0 1 0 N
S -105 -150 -95 -120 0 1 0 N
S -5 -150 5 -120 0 1 0 N
S 95 -150 105 -120 0 1 0 N
X VBUS 1 -200 -300 150 U 50 50 1 1 W
X D- 2 -100 -300 150 U 50 50 1 1 P
X D+ 3 0 -300 150 U 50 50 1 1 P
X GND 4 100 -300 150 U 50 50 1 1 W
X shield 5 300 100 150 L 50 50 1 1 P
ENDDRAW
ENDDEF
#
#End Library

View File

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

View File

@ -0,0 +1,61 @@
/*
* This file is part of the chronometer project.
* Copyright 2019 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 "lidar.h"
#include "usart.h"
uint16_t lidar_max_dist = 100;
uint16_t lidar_min_dist = 50;
uint16_t last_lidar_dist = 0;
uint16_t last_lidar_stren = 0;
uint16_t lidar_triggered_dist = 0;
void parse_lidar_data(char *txt){
static int triggered = 0;
last_lidar_dist = txt[2] | (txt[3] << 8);
last_lidar_stren = txt[4] | (txt[5] << 8);
if(last_lidar_stren < LIDAR_LOWER_STREN) return; // weak signal
if(!lidar_triggered_dist){ // first run
lidar_triggered_dist = last_lidar_dist;
return;
}
if(triggered){ // check if body gone
if(last_lidar_dist < lidar_min_dist || last_lidar_dist > lidar_max_dist || last_lidar_dist > lidar_triggered_dist + LIDAR_DIST_THRES){
triggered = 0;
#ifdef EBUG
SEND("Untriggered! distance=");
printu(1, last_lidar_dist);
SEND(" signal=");
printu(1, last_lidar_stren);
newline();
#endif
}
}else{
if(last_lidar_dist > lidar_min_dist && last_lidar_dist < lidar_max_dist){
triggered = 1;
lidar_triggered_dist = last_lidar_dist;
#ifdef EBUG
SEND("Triggered! distance=");
printu(1, last_lidar_dist);
SEND(" signal=");
printu(1, last_lidar_stren);
newline();
#endif
}
}
}

View File

@ -0,0 +1,36 @@
/*
* This file is part of the chronometer project.
* Copyright 2019 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/>.
*/
#pragma once
#ifndef LIDAR_H__
#define LIDAR_H__
#include <stm32f1.h>
#define LIDAR_FRAME_LEN (9)
// frame header
#define LIDAR_FRAME_HEADER (0x59)
// lower strength limit
#define LIDAR_LOWER_STREN (10)
// triggered distance threshold - 1 meter
#define LIDAR_DIST_THRES (100)
extern uint16_t last_lidar_dist;
extern uint16_t lidar_triggered_dist;
extern uint16_t last_lidar_stren;
void parse_lidar_data(char *txt);
#endif // LIDAR_H__

254
F1-nolib/chronometer/main.c Normal file
View File

@ -0,0 +1,254 @@
/*
* main.c
*
* Copyright 2017 Edward V. Emelianoff <eddy@sao.ru, edward.emelianoff@gmail.com>
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; if not, write to the Free Software
* Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston,
* MA 02110-1301, USA.
*/
//#include "adc.h"
#include "GPS.h"
#include "hardware.h"
#include "lidar.h"
#include "str.h"
#include "time.h"
#include "usart.h"
#include "usb.h"
#include "usb_lib.h"
#ifndef VERSION
#define VERSION "0.0.0"
#endif
volatile uint32_t Tms = 0;
/* Called when systick fires */
void sys_tick_handler(void){
++Tms;
}
void iwdg_setup(){
uint32_t tmout = 16000000;
/* Enable the peripheral clock RTC */
/* (1) Enable the LSI (40kHz) */
/* (2) Wait while it is not ready */
RCC->CSR |= RCC_CSR_LSION; /* (1) */
while((RCC->CSR & RCC_CSR_LSIRDY) != RCC_CSR_LSIRDY){if(--tmout == 0) break;} /* (2) */
/* Configure IWDG */
/* (1) Activate IWDG (not needed if done in option bytes) */
/* (2) Enable write access to IWDG registers */
/* (3) Set prescaler by 64 (1.6ms for each tick) */
/* (4) Set reload value to have a rollover each 2s */
/* (5) Check if flags are reset */
/* (6) Refresh counter */
IWDG->KR = IWDG_START; /* (1) */
IWDG->KR = IWDG_WRITE_ACCESS; /* (2) */
IWDG->PR = IWDG_PR_PR_1; /* (3) */
IWDG->RLR = 1250; /* (4) */
tmout = 16000000;
while(IWDG->SR){if(--tmout == 0) break;} /* (5) */
IWDG->KR = IWDG_REFRESH; /* (6) */
}
#ifdef EBUG
char *parse_cmd(char *buf){
static char btns[] = "BTN0=0, BTN1=0, PPS=0\n";
if(buf[1] != '\n') return buf;
switch(*buf){
case '0':
LED_off();
break;
case '1':
LED_on();
break;
case 'b':
btns[5] = GET_BTN0() + '0';
btns[13] = GET_BTN1() + '0';
btns[20] = GET_PPS() + '0';
return btns;
break;
case 'p':
pin_toggle(USBPU_port, USBPU_pin);
SEND("USB pullup is ");
if(pin_read(USBPU_port, USBPU_pin)) SEND("off");
else SEND("on");
newline();
break;
case 'G':
SEND("LIDAR_DIST=");
printu(1, last_lidar_dist);
SEND(", LIDAR_STREN=");
printu(1, last_lidar_stren);
newline();
break;
case 'L':
USB_send("Very long test string for USB (it's length is more than 64 bytes).\n"
"This is another part of the string! Can you see all of this?\n");
return "Long test sent\n";
break;
case 'R':
USB_send("Soft reset\n");
SEND("Soft reset\n");
NVIC_SystemReset();
break;
case 'S':
USB_send("Test string for USB\n");
return "Short test sent\n";
break;
case 'T':
SEND(get_time(&current_time, get_millis()));
break;
case 'W':
USB_send("Wait for reboot\n");
SEND("Wait for reboot\n");
while(1){nop();};
break;
default: // help
return
"0/1 - turn on/off LED1\n"
"'b' - get buttons's state\n"
"'p' - toggle USB pullup\n"
"'G' - get last LIDAR distance\n"
"'L' - send long string over USB\n"
"'R' - software reset\n"
"'S' - send short string over USB\n"
"'T' - show current GPS time\n"
"'W' - test watchdog\n"
;
break;
}
return NULL;
}
#endif
// usb getline
static char *get_USB(){
static char tmpbuf[512], *curptr = tmpbuf;
static int rest = 511;
int x = USB_receive(curptr, rest);
curptr[x] = 0;
if(!x) return NULL;
if(curptr[x-1] == '\n'){
curptr = tmpbuf;
rest = 511;
return tmpbuf;
}
curptr += x; rest -= x;
if(rest <= 0){ // buffer overflow
SEND("USB buffer overflow!\n");
curptr = tmpbuf;
rest = 511;
}
return NULL;
}
#define CMP(a,b) cmpstr(a, b, sizeof(b)-1)
static void parse_USBCMD(char *cmd){
if(!cmd || !*cmd) return;
if(*cmd == '?'){ // help
USB_send("Commands:\n"
CMD_DISTMIN " - min distance threshold (cm)\n"
CMD_DISTMAX " - max distance threshold (cm)\n"
CMD_PRINTTIME " - print time\n"
);
}else if(CMP(cmd, CMD_PRINTTIME) == 0){
USB_send(get_time(&current_time, get_millis()));
}else if(CMP(cmd, CMD_DISTMIN) == 0){ // set low limit
DBG("CMD_DISTMIN");
}else if(CMP(cmd, CMD_DISTMAX) == 0){ // set low limit
DBG("CMD_DISTMAX");
}
}
int main(void){
uint32_t lastT = 0;
sysreset();
StartHSE();
hw_setup();
USBPU_OFF();
usarts_setup();
SysTick_Config(72000);
SEND("Chronometer version " VERSION ".\n");
if(RCC->CSR & RCC_CSR_IWDGRSTF){ // watchdog reset occured
SEND("WDGRESET=1\n");
}
if(RCC->CSR & RCC_CSR_SFTRSTF){ // software reset occured
SEND("SOFTRESET=1\n");
}
RCC->CSR |= RCC_CSR_RMVF; // remove reset flags
USB_setup();
//iwdg_setup();
USBPU_ON();
while (1){
IWDG->KR = IWDG_REFRESH; // refresh watchdog
if(lastT > Tms || Tms - lastT > 499){
if(need2startseq) GPS_send_start_seq();
LED_blink();
lastT = Tms;
if(usartrx(LIDAR_USART)){
char *txt;
if(usart_getline(LIDAR_USART, &txt)){
DBG("LIDAR:");
DBG(txt);
}
}
#ifdef EBUG
transmit_tbuf(1); // non-blocking transmission of data from UART buffer every 0.5s
#endif
transmit_tbuf(GPS_USART);
transmit_tbuf(LIDAR_USART);
}
usb_proc();
int r = 0;
char *txt, *ans;
if((txt = get_USB())){
parse_USBCMD(txt);
DBG("Received data over USB:");
DBG(txt);
USB_send(txt); // echo all back
}
#ifdef EBUG
if(usartrx(1)){ // usart1 received data, store in in buffer
r = usart_getline(1, &txt);
if(r){
txt[r] = 0;
ans = parse_cmd(txt);
if(ans){
usart_send(1, ans);
transmit_tbuf(1);
}
}
}
#endif
if(usartrx(GPS_USART)){
r = usart_getline(GPS_USART, &txt);
if(r){
txt[r] = 0;
GPS_parse_answer(txt);
}
}
if(usartrx(LIDAR_USART)){
r = usart_getline(LIDAR_USART, &txt);
if(r){
parse_lidar_data(txt);
}
}
}
return 0;
}

View File

@ -0,0 +1,46 @@
/*
* This file is part of the chronometer project.
* Copyright 2019 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 "str.h"
#include "usart.h"
/**
* @brief cmpstr - the same as strncmp
* @param s1,s2 - strings to compare
* @param n - max symbols amount
* @return 0 if strings equal or 1/-1
*/
int cmpstr(const char *s1, const char *s2, int n){
int ret = 0;
do{
ret = *s1 - *s2;
}while(*s1++ && *s2++ && --n);
return ret;
}
/**
* @brief getchr - analog of strchr
* @param str - string to search
* @param symbol - searching symbol
* @return pointer to symbol found or NULL
*/
char *getchr(const char *str, char symbol){
do{
if(*str == symbol) return (char*)str;
}while(*(++str));
return NULL;
}

View File

@ -0,0 +1,25 @@
/*
* This file is part of the chronometer project.
* Copyright 2019 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/>.
*/
#pragma once
#ifndef STR_H__
#define STR_H__
int cmpstr(const char *s1, const char *s2, int n);
char *getchr(const char *str, char symbol);
#endif // STR_H__

View File

@ -0,0 +1,92 @@
/*
* This file is part of the chronometer project.
* Copyright 2019 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 "GPS.h"
#include "time.h"
#include "usb.h"
#include <string.h>
curtime current_time = TMNOTINI;
volatile int need_sync = 1;
static inline uint8_t atou(const char *b){
return (b[0]-'0')*10 + b[1]-'0';
}
void set_time(const char *buf){
uint8_t H = atou(buf) + TIMEZONE_GMT_PLUS;
if(H > 23) H -= 24;
current_time.H = H;
current_time.M = atou(&buf[2]);
current_time.S = atou(&buf[4]);
}
/**
* print time: Tm - time structure, T - milliseconds
*/
char *get_time(curtime *Tm, uint32_t T){
static char buf[64];
char *bstart = &buf[5], *bptr = bstart;
/*
void putint(int i){ // put integer from 0 to 99 into buffer with leading zeros
if(i > 9){
*bptr++ = i/10 + '0';
i = i%10;
}else *bptr++ = '0';
*bptr++ = i + '0';
}*/
int S = 0;
if(Tm->S < 60 && Tm->M < 60 && Tm->H < 24)
S = Tm->S + Tm->H*3600 + Tm->M*60; // seconds from day beginning
if(!S) *(--bstart) = '0';
while(S){
*(--bstart) = S%10 + '0';
S /= 10;
}
// now bstart is buffer starting index; bptr points to decimal point
*bptr++ = '.';
if(T > 99){
*bptr++ = T/100 + '0';
T %= 100;
}else *bptr++ = '0';
if(T > 9){
*bptr++ = T/10 + '0';
T %= 10;
}else *bptr++ = '0';
*bptr++ = T + '0';
if(GPS_status == GPS_NOT_VALID){
strcpy(bptr, " (not valid)");
bptr += 12;
}
if(need_sync){
strcpy(bptr, " need synchronisation");
bptr += 21;
}
*bptr++ = '\n';
*bptr = 0;
return bstart;
}
/**
* @brief get_millis - calculate milliseconds due to global fix parameter
* @return milliseconds value
*/
uint32_t get_millis(){
// TODO: calculate right millis
return Tms % 1000; // temporary gag
}

View File

@ -0,0 +1,52 @@
/*
* This file is part of the chronometer project.
* Copyright 2019 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/>.
*/
#pragma once
#ifndef TIME_H__
#define TIME_H__
#include <stm32f1.h>
#define STK_RVR_DEFAULT_VAL (8999)
#define TIMEZONE_GMT_PLUS (3)
#define DIDNT_TRIGGERED (2000)
// debounce delay: .4s
#define TRIGGER_DELAY (400)
#define TMNOTINI {25,61,61}
typedef struct{
uint8_t H;
uint8_t M;
uint8_t S;
} curtime;
extern volatile uint32_t Tms;
extern curtime current_time;
extern curtime trigger_time[];
extern uint32_t trigger_ms[];
extern volatile int need_sync;
char *get_time(curtime *T, uint32_t m);
void set_time(const char *buf);
uint32_t get_millis(); // current milliseconds
#endif // TIME_H__

View File

@ -0,0 +1,334 @@
/*
* This file is part of the chronometer project.
* Copyright 2019 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 "stm32f1.h"
#include "usart.h"
#include "lidar.h"
extern volatile uint32_t Tms;
static volatile int idatalen[4][2] = {0}; // received data line length (including '\n')
static volatile int odatalen[4][2] = {0};
volatile int linerdy[4] = {0}, // received data ready
dlen[4] = {0}, // length of data (including '\n') in current buffer
bufovr[4] = {0}, // input buffer overfull
txrdy[4] = {0,1,1,1} // transmission done
;
int rbufno[4] = {0}, tbufno[4] = {0}; // current rbuf/tbuf numbers
static char rbuf[4][2][UARTBUFSZ], tbuf[4][2][UARTBUFSZ]; // receive & transmit buffers
static char *recvdata[4] = {0};
/**
* return length of received data (without trailing zero)
*/
int usart_getline(int n, char **line){
if(bufovr[n]){
bufovr[n] = 0;
linerdy[n] = 0;
return 0;
}
*line = recvdata[n];
linerdy[n] = 0;
return dlen[n];
}
// transmit current tbuf and swap buffers
void transmit_tbuf(int n){
if(n < 1 || n > 3) return;
uint32_t tmout = 72000;
while(!txrdy[n]){if(--tmout == 0) return;}; // wait for previos buffer transmission
register int l = odatalen[n][tbufno[n]];
if(!l) return;
txrdy[n] = 0;
odatalen[n][tbufno[n]] = 0;
DMA_Channel_TypeDef *DMA;
IWDG->KR = IWDG_REFRESH;
switch(n){
case 1:
DMA = DMA1_Channel4;
break;
case 2:
DMA = DMA1_Channel7;
break;
case 3:
DMA = DMA1_Channel2;
break;
}
DMA->CCR &= ~DMA_CCR_EN;
DMA->CMAR = (uint32_t) tbuf[n][tbufno[n]]; // mem
DMA->CNDTR = l;
DMA->CCR |= DMA_CCR_EN;
tbufno[n] = !tbufno[n];
}
void usart_putchar(int n, char ch){
for(int i = 0; odatalen[n][tbufno[n]] == UARTBUFSZ && i < 1024; ++i) transmit_tbuf(n);
tbuf[n][tbufno[n]][odatalen[n][tbufno[n]]++] = ch;
}
void usart_send(int n, const char *str){
uint32_t x = 512;
while(*str && --x){
if(odatalen[n][tbufno[n]] == UARTBUFSZ){
transmit_tbuf(n);
continue;
}
tbuf[n][tbufno[n]][odatalen[n][tbufno[n]]++] = *str++;
}
}
#ifdef EBUG
// only for USART1
void newline(){
usart_putchar(1, '\n');
transmit_tbuf(1);
}
#endif
/*
* USART speed: baudrate = Fck/(USARTDIV)
* USARTDIV stored in USART->BRR
*
* for 72MHz USARTDIV=72000/f(kboud); so for 115200 USARTDIV=72000/115.2=625 -> BRR=0x271
* 9600: BRR = 7500 (0x1D4C)
*/
static void usart_setup(int n, uint32_t BRR){
DMA_Channel_TypeDef *DMA;
IRQn_Type DMAirqN, USARTirqN;
USART_TypeDef *USART;
switch(n){
case 1:
// USART1 Tx DMA - Channel4 (Rx - channel 5)
DMA = DMA1_Channel4;
DMAirqN = DMA1_Channel4_IRQn;
USARTirqN = USART1_IRQn;
// PA9 - Tx, PA10 - Rx
RCC->APB2ENR |= RCC_APB2ENR_IOPAEN | RCC_APB2ENR_USART1EN;
GPIOA->CRH |= CRH(9, CNF_AFPP|MODE_NORMAL) | CRH(10, CNF_FLINPUT|MODE_INPUT);
USART = USART1;
break;
case 2:
// USART2 Tx DMA - Channel7
DMA = DMA1_Channel7;
DMAirqN = DMA1_Channel7_IRQn;
USARTirqN = USART2_IRQn;
// PA2 - Tx, PA3 - Rx
RCC->APB2ENR |= RCC_APB2ENR_IOPAEN;
RCC->APB1ENR |= RCC_APB1ENR_USART2EN;
GPIOA->CRL |= CRL(2, CNF_AFPP|MODE_NORMAL) | CRL(3, CNF_FLINPUT|MODE_INPUT);
USART = USART2;
break;
case 3:
// USART3 Tx DMA - Channel2
DMA = DMA1_Channel2;
DMAirqN = DMA1_Channel2_IRQn;
USARTirqN = USART3_IRQn;
// PB10 - Tx, PB11 - Rx
RCC->APB2ENR |= RCC_APB2ENR_IOPBEN;
RCC->APB1ENR |= RCC_APB1ENR_USART3EN;
GPIOB->CRH |= CRH(10, CNF_AFPP|MODE_NORMAL) | CRH(11, CNF_FLINPUT|MODE_INPUT);
USART = USART3;
break;
default:
return;
}
DMA->CPAR = (uint32_t) &USART->DR; // periph
DMA->CCR |= DMA_CCR_MINC | DMA_CCR_DIR | DMA_CCR_TCIE; // 8bit, mem++, mem->per, transcompl irq
// setup usart(n)
USART->BRR = BRR;
USART->CR1 = USART_CR1_TE | USART_CR1_RE | USART_CR1_UE; // 1start,8data,nstop; enable Rx,Tx,USART
uint32_t tmout = 16000000;
while(!(USART->SR & USART_SR_TC)){if(--tmout == 0) break;} // polling idle frame Transmission
USART->SR = 0; // clear flags
USART->CR1 |= USART_CR1_RXNEIE; // allow Rx IRQ
USART->CR3 = USART_CR3_DMAT; // enable DMA Tx
// Tx CNDTR set @ each transmission due to data size
NVIC_SetPriority(DMAirqN, n);
NVIC_EnableIRQ(DMAirqN);
NVIC_SetPriority(USARTirqN, n);
NVIC_EnableIRQ(USARTirqN);
}
void usarts_setup(){
RCC->AHBENR |= RCC_AHBENR_DMA1EN;
#ifdef EBUG
usart_setup(1, 72000000 / 115200); // debug console
#endif
usart_setup(2, 36000000 / 9600); // GPS
usart_setup(3, 36000000 / 115200); // LIDAR
}
void usart_isr(int n, USART_TypeDef *USART){
#ifdef CHECK_TMOUT
static uint32_t tmout[n] = 0;
#endif
IWDG->KR = IWDG_REFRESH;
if(USART->SR & USART_SR_RXNE){ // RX not emty - receive next char
#ifdef CHECK_TMOUT
if(tmout[n] && Tms >= tmout[n]){ // set overflow flag
bufovr[n] = 1;
idatalen[n][rbufno[n]] = 0;
}
tmout[n] = Tms + TIMEOUT_MS;
if(!tmout[n]) tmout[n] = 1; // prevent 0
#endif
uint8_t rb = USART->DR;
if(idatalen[n][rbufno[n]] < UARTBUFSZ){ // put next char into buf
rbuf[n][rbufno[n]][idatalen[n][rbufno[n]]++] = rb;
if(rb == '\n'){ // got newline - line ready
linerdy[n] = 1;
dlen[n] = idatalen[n][rbufno[n]];
recvdata[n] = rbuf[n][rbufno[n]];
// prepare other buffer
rbufno[n] = !rbufno[n];
idatalen[n][rbufno[n]] = 0;
#ifdef CHECK_TMOUT
// clear timeout at line end
tmout[n] = 0;
#endif
}
}else{ // buffer overrun
bufovr[n] = 1;
idatalen[n][rbufno[n]] = 0;
#ifdef CHECK_TMOUT
tmout[n] = 0;
#endif
}
}
}
#ifdef EBUG
void usart1_isr(){
usart_isr(1, USART1);
}
#endif
// GPS_USART
void usart2_isr(){
usart_isr(2, USART2);
}
// LIDAR_USART
void usart3_isr(){
IWDG->KR = IWDG_REFRESH;
if(USART3->SR & USART_SR_RXNE){ // RX not emty - receive next char
uint8_t rb = USART3->DR, L = idatalen[3][rbufno[3]];
if(rb != LIDAR_FRAME_HEADER && (L == 0 || L == 1)){ // bad starting sequence
idatalen[3][rbufno[3]] = 0;
return;
}
if(L < LIDAR_FRAME_LEN){ // put next char into buf
rbuf[3][rbufno[3]][idatalen[3][rbufno[3]]++] = rb;
if(L == LIDAR_FRAME_LEN-1){ // got LIDAR_FRAME_LEN bytes - line ready
linerdy[3] = 1;
dlen[3] = idatalen[3][rbufno[3]];
recvdata[3] = rbuf[3][rbufno[3]];
// prepare other buffer
rbufno[3] = !rbufno[3];
idatalen[3][rbufno[3]] = 0;
}
}else{ // buffer overrun
idatalen[3][rbufno[3]] = 0;
}
}
}
// return string buffer with val
char *u2str(uint32_t val){
static char bufa[11];
char bufb[10];
int l = 0, bpos = 0;
IWDG->KR = IWDG_REFRESH;
if(!val){
bufa[0] = '0';
l = 1;
}else{
while(val){
bufb[l++] = val % 10 + '0';
val /= 10;
}
int i;
bpos += l;
for(i = 0; i < l; ++i){
bufa[--bpos] = bufb[i];
}
}
bufa[l + bpos] = 0;
return bufa;
}
// print 32bit unsigned int
void printu(int n, uint32_t val){
usart_send(n, u2str(val));
}
// print 32bit unsigned int as hex
void printuhex(int n, uint32_t val){
usart_send(n, "0x");
uint8_t *ptr = (uint8_t*)&val + 3;
int i, j;
IWDG->KR = IWDG_REFRESH;
for(i = 0; i < 4; ++i, --ptr){
for(j = 1; j > -1; --j){
register uint8_t half = (*ptr >> (4*j)) & 0x0f;
if(half < 10) usart_putchar(n, half + '0');
else usart_putchar(n, half - 10 + 'a');
}
}
}
#ifdef EBUG
// dump memory buffer
void hexdump(uint8_t *arr, uint16_t len){
for(uint16_t l = 0; l < len; ++l, ++arr){
IWDG->KR = IWDG_REFRESH;
for(int16_t j = 1; j > -1; --j){
register uint8_t half = (*arr >> (4*j)) & 0x0f;
if(half < 10) usart_putchar(1, half + '0');
else usart_putchar(1, half - 10 + 'a');
}
if(l % 16 == 15) usart_putchar(1, '\n');
else if((l & 3) == 3) usart_putchar(1, ' ');
}
}
#endif
#ifdef EBUG
void dma1_channel4_isr(){ // USART1
if(DMA1->ISR & DMA_ISR_TCIF4){ // Tx
DMA1->IFCR = DMA_IFCR_CTCIF4; // clear TC flag
txrdy[1] = 1;
}
}
#endif
void dma1_channel7_isr(){ // USART2
if(DMA1->ISR & DMA_ISR_TCIF7){ // Tx
DMA1->IFCR = DMA_IFCR_CTCIF7; // clear TC flag
txrdy[2] = 1;
}
}
void dma1_channel2_isr(){ // USART3
if(DMA1->ISR & DMA_ISR_TCIF2){ // Tx
DMA1->IFCR = DMA_IFCR_CTCIF2; // clear TC flag
txrdy[3] = 1;
}
}

View File

@ -0,0 +1,67 @@
/*
* This file is part of the chronometer project.
* Copyright 2019 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/>.
*/
#pragma once
#ifndef __USART_H__
#define __USART_H__
#include <stm32f1.h>
// input and output buffers size
#define UARTBUFSZ (128)
// timeout between data bytes
#ifndef TIMEOUT_MS
#define TIMEOUT_MS (1500)
#endif
#define STR_HELPER(s) #s
#define STR(s) STR_HELPER(s)
#ifdef EBUG
#define SEND(str) usart_send(1, str)
#define MSG(str) do{SEND(__FILE__ " (L" STR(__LINE__) "): " str);}while(0)
#define DBG(str) do{SEND(str); newline(); }while(0)
#else
#define SEND(str)
#define MSG(str)
#define DBG(str)
#endif
#define usartrx(n) (linerdy[n])
#define usartovr(n) (bufovr[n])
extern volatile int linerdy[4], bufovr[4], txrdy[4];
void transmit_tbuf(int n);
void usarts_setup();
int usart_getline(int n, char **line);
void usart_send(int n, const char *str);
void usart_putchar(int n, char ch);
char *u2str(uint32_t val);
void printu(int n, uint32_t val);
void printuhex(int n, uint32_t val);
#ifdef EBUG
void newline();
void hexdump(uint8_t *arr, uint16_t len);
#endif
/*
void hexdump16(uint16_t *arr, uint16_t len);
void hexdump32(uint32_t *arr, uint16_t len);
*/
#endif // __USART_H__

153
F1-nolib/chronometer/usb.c Normal file
View File

@ -0,0 +1,153 @@
/*
* geany_encoding=koi8-r
* usb.c - base functions for different USB types
*
* Copyright 2018 Edward V. Emelianov <eddy@sao.ru, edward.emelianoff@gmail.com>
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; if not, write to the Free Software
* Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston,
* MA 02110-1301, USA.
*
*/
#include "usb.h"
#include "usb_lib.h"
#include "usart.h"
// incoming buffer size
#define IDATASZ (256)
static uint8_t incoming_data[IDATASZ];
static uint8_t ovfl = 0;
static uint16_t idatalen = 0;
static volatile uint8_t tx_succesfull = 0;
static int8_t usbON = 0; // ==1 when USB fully configured
// interrupt IN handler (never used?)
static uint16_t EP1_Handler(ep_t ep){
if (ep.rx_flag){
ep.status = SET_VALID_TX(ep.status);
ep.status = KEEP_STAT_RX(ep.status);
}else if (ep.tx_flag){
ep.status = SET_VALID_RX(ep.status);
ep.status = SET_STALL_TX(ep.status);
}
return ep.status;
}
// data IN/OUT handler
static uint16_t EP23_Handler(ep_t ep){
if(ep.rx_flag){
int rd = ep.rx_cnt, rest = IDATASZ - idatalen;
if(rd){
if(rd <= rest){
idatalen += EP_Read(2, (uint16_t*)&incoming_data[idatalen]);
ovfl = 0;
}else{
ep.status = SET_NAK_RX(ep.status);
ovfl = 1;
return ep.status;
}
}
// end of transaction: clear DTOGs
ep.status = CLEAR_DTOG_RX(ep.status);
ep.status = CLEAR_DTOG_TX(ep.status);
ep.status = SET_STALL_TX(ep.status);
}else if (ep.tx_flag){
ep.status = KEEP_STAT_TX(ep.status);
tx_succesfull = 1;
}
ep.status = SET_VALID_RX(ep.status);
return ep.status;
}
void USB_setup(){
NVIC_DisableIRQ(USB_LP_CAN1_RX0_IRQn);
NVIC_DisableIRQ(USB_HP_CAN1_TX_IRQn);
RCC->APB1ENR |= RCC_APB1ENR_USBEN;
USB->CNTR = USB_CNTR_FRES; // Force USB Reset
for(uint32_t ctr = 0; ctr < 72000; ++ctr) nop(); // wait >1ms
//uint32_t ctr = 0;
USB->CNTR = 0;
USB->BTABLE = 0;
USB->DADDR = 0;
USB->ISTR = 0;
USB->CNTR = USB_CNTR_RESETM | USB_CNTR_WKUPM; // allow only wakeup & reset interrupts
NVIC_EnableIRQ(USB_LP_CAN1_RX0_IRQn);
NVIC_EnableIRQ(USB_HP_CAN1_TX_IRQn );
}
void usb_proc(){
if(USB_GetState() == USB_CONFIGURE_STATE){ // USB configured - activate other endpoints
if(!usbON){ // endpoints not activated
// make new BULK endpoint
// Buffer have 1024 bytes, but last 256 we use for CAN bus (30.2 of RM: USB main features)
EP_Init(1, EP_TYPE_INTERRUPT, 10, 0, EP1_Handler); // IN1 - transmit
EP_Init(2, EP_TYPE_BULK, 0, USB_RXBUFSZ, EP23_Handler); // OUT2 - receive data
EP_Init(3, EP_TYPE_BULK, USB_TXBUFSZ, 0, EP23_Handler); // IN3 - transmit data
usbON = 1;
}
}else{
usbON = 0;
}
}
void USB_send(char *buf){
uint16_t l = 0, ctr = 0;
char *p = buf;
while(*p++) ++l;
while(l){
uint16_t s = (l > USB_TXBUFSZ) ? USB_TXBUFSZ : l;
tx_succesfull = 0;
EP_Write(3, (uint8_t*)&buf[ctr], s);
uint32_t ctra = 1000000;
while(--ctra && tx_succesfull == 0);
l -= s;
ctr += s;
}
}
/**
* @brief USB_receive
* @param buf (i) - buffer for received data
* @param bufsize - its size
* @return amount of received bytes
*/
int USB_receive(char *buf, int bufsize){
if(!bufsize || !idatalen) return 0;
USB->CNTR = 0;
int sz = (idatalen > bufsize) ? bufsize : idatalen, rest = idatalen - sz;
for(int i = 0; i < sz; ++i) buf[i] = incoming_data[i];
if(rest > 0){
uint8_t *ptr = &incoming_data[sz];
for(int i = 0; i < rest; ++i) incoming_data[i] = *ptr++;
//memmove(incoming_data, &incoming_data[sz], rest); - hardfault on memcpy&memmove
idatalen = rest;
}else idatalen = 0;
if(ovfl){
EP23_Handler(endpoints[2]);
uint16_t epstatus = USB->EPnR[2];
epstatus = CLEAR_DTOG_RX(epstatus);
epstatus = SET_VALID_RX(epstatus);
USB->EPnR[2] = epstatus;
}
USB->CNTR = USB_CNTR_RESETM | USB_CNTR_CTRM;
return sz;
}
/**
* @brief USB_configured
* @return 1 if USB is in configured state
*/
int USB_configured(){
return usbON;
}

View File

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

View File

@ -0,0 +1,117 @@
/*
* 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 <stm32f1.h>
// max endpoints number
#define STM32ENDPOINTS 8
/**
* Buffers size definition
**/
#define USB_BTABLE_SIZE 512
// first 64 bytes of USB_BTABLE are registers!
//#define USB_EP0_BASEADDR 64
// for USB FS EP0 buffers are from 8 to 64 bytes long (64 for PL2303)
#define USB_EP0_BUFSZ 64
// USB transmit buffer size (64 for PL2303)
#define USB_TXBUFSZ 64
// USB receive buffer size (64 for PL2303)
#define USB_RXBUFSZ 64
#define USB_BTABLE_BASE 0x40006000
#define USB_BASE ((uint32_t)0x40005C00)
#define USB ((USB_TypeDef *) USB_BASE)
#ifdef USB_BTABLE
#undef USB_BTABLE
#endif
#define USB_BTABLE ((USB_BtableDef *)(USB_BTABLE_BASE))
#define USB_ISTR_EPID 0x0000000F
#define USB_FNR_LSOF_0 0x00000800
#define USB_FNR_lSOF_1 0x00001000
#define USB_LPMCSR_BESL_0 0x00000010
#define USB_LPMCSR_BESL_1 0x00000020
#define USB_LPMCSR_BESL_2 0x00000040
#define USB_LPMCSR_BESL_3 0x00000080
#define USB_EPnR_CTR_RX 0x00008000
#define USB_EPnR_DTOG_RX 0x00004000
#define USB_EPnR_STAT_RX 0x00003000
#define USB_EPnR_STAT_RX_0 0x00001000
#define USB_EPnR_STAT_RX_1 0x00002000
#define USB_EPnR_SETUP 0x00000800
#define USB_EPnR_EP_TYPE 0x00000600
#define USB_EPnR_EP_TYPE_0 0x00000200
#define USB_EPnR_EP_TYPE_1 0x00000400
#define USB_EPnR_EP_KIND 0x00000100
#define USB_EPnR_CTR_TX 0x00000080
#define USB_EPnR_DTOG_TX 0x00000040
#define USB_EPnR_STAT_TX 0x00000030
#define USB_EPnR_STAT_TX_0 0x00000010
#define USB_EPnR_STAT_TX_1 0x00000020
#define USB_EPnR_EA 0x0000000F
#define USB_COUNTn_RX_BLSIZE 0x00008000
#define USB_COUNTn_NUM_BLOCK 0x00007C00
#define USB_COUNTn_RX 0x0000003F
#ifdef USB_TypeDef
#define USB_TypeDef USB_TypeDef_custom
#endif
typedef struct {
__IO uint32_t EPnR[STM32ENDPOINTS];
__IO uint32_t RESERVED[STM32ENDPOINTS];
__IO uint32_t CNTR;
__IO uint32_t ISTR;
__IO uint32_t FNR;
__IO uint32_t DADDR;
__IO uint32_t BTABLE;
} USB_TypeDef;
/*
typedef struct{
__IO uint16_t USB_ADDR_TX;
__IO uint16_t res1;
__IO uint16_t USB_COUNT_TX;
__IO uint16_t res2;
__IO uint16_t USB_ADDR_RX;
__IO uint16_t res3;
__IO uint16_t USB_COUNT_RX;
__IO uint16_t res4;
} USB_EPDATA_TypeDef;*/
typedef struct{
__IO uint32_t USB_ADDR_TX;
__IO uint32_t USB_COUNT_TX;
__IO uint32_t USB_ADDR_RX;
__IO uint32_t USB_COUNT_RX;
} USB_EPDATA_TypeDef;
typedef struct{
__IO USB_EPDATA_TypeDef EP[STM32ENDPOINTS];
} USB_BtableDef;
#endif // __USB_DEFS_H__

View File

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

View File

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

Binary file not shown.