add first approx to 3steppersLB

This commit is contained in:
Edward Emelianov 2021-10-22 22:34:16 +03:00
parent 8edd290483
commit 9ece1bd91e
38 changed files with 6481 additions and 2287 deletions

View File

@ -0,0 +1,147 @@
BINARY = steppers
BOOTPORT ?= /dev/ttyUSB0
BOOTSPEED ?= 57600
# MCU FAMILY
FAMILY ?= F0
# MCU code
MCU ?= F072xB
DEFS += -DEBUG
# change this linking script depending on particular MCU model,
# for example, if you have STM32F103VBT6, you should write:
LDSCRIPT ?= stm32f072B.ld
INDEPENDENT_HEADERS=
FP_FLAGS ?= -msoft-float
ASM_FLAGS = -mthumb -mcpu=cortex-m0 -march=armv6-m -mtune=cortex-m0
ARCH_FLAGS = $(ASM_FLAGS) $(FP_FLAGS)
###############################################################################
# Executables
OPREFIX ?= /opt/bin/arm-none-eabi
#PREFIX ?= /usr/x86_64-pc-linux-gnu/arm-none-eabi/gcc-bin/7.3.0/arm-none-eabi
PREFIX ?= $(OPREFIX)
RM := rm -f
RMDIR := rmdir
CC := $(PREFIX)-gcc
LD := $(PREFIX)-gcc
AR := $(PREFIX)-ar
AS := $(PREFIX)-as
OBJCOPY := $(OPREFIX)-objcopy
OBJDUMP := $(OPREFIX)-objdump
GDB := $(OPREFIX)-gdb
STFLASH := $(shell which st-flash)
STBOOT := $(shell which stm32flash)
DFUUTIL := $(shell which dfu-util)
###############################################################################
# Source files
OBJDIR = mk
LDSCRIPT ?= $(BINARY).ld
SRC := $(wildcard *.c)
OBJS := $(addprefix $(OBJDIR)/, $(SRC:%.c=%.o))
STARTUP = $(OBJDIR)/startup.o
OBJS += $(STARTUP)
DEPS := $(OBJS:.o=.d)
INC_DIR ?= ../inc
INCLUDE := -I$(INC_DIR)/Fx -I$(INC_DIR)/cm
LIB_DIR := $(INC_DIR)/ld
###############################################################################
# C flags
CFLAGS += -O2 -g -MD -D__thumb2__=1
CFLAGS += -Wall -Werror -Wextra -Wshadow -Wimplicit-function-declaration
CFLAGS += -Wredundant-decls $(INCLUDE)
# -Wmissing-prototypes -Wstrict-prototypes
CFLAGS += -fno-common -ffunction-sections -fdata-sections
###############################################################################
# Linker flags
LDFLAGS += --static -nostartfiles
#--specs=nano.specs
LDFLAGS += -L$(LIB_DIR)
LDFLAGS += -T$(LDSCRIPT)
LDFLAGS += -Wl,-Map=$(OBJDIR)/$(BINARY).map
LDFLAGS += -Wl,--gc-sections
###############################################################################
# Used libraries
LDLIBS += -Wl,--start-group -lc -lgcc -Wl,--end-group
LDLIBS += $(shell $(CC) $(CFLAGS) -print-libgcc-file-name)
DEFS += -DSTM32$(FAMILY) -DSTM32$(MCU)
#.SUFFIXES: .elf .bin .hex .srec .list .map .images
#.SECONDEXPANSION:
#.SECONDARY:
ELF := $(OBJDIR)/$(BINARY).elf
LIST := $(OBJDIR)/$(BINARY).list
BIN := $(BINARY).bin
HEX := $(BINARY).hex
all: bin list
elf: $(ELF)
bin: $(BIN)
hex: $(HEX)
list: $(LIST)
ifneq ($(MAKECMDGOALS),clean)
-include $(DEPS)
endif
$(OBJDIR):
mkdir $(OBJDIR)
$(STARTUP): $(INC_DIR)/startup/vector.c
$(CC) $(CFLAGS) $(DEFS) $(INCLUDE) $(ARCH_FLAGS) -o $@ -c $<
$(OBJDIR)/%.o: %.c
@echo " CC $<"
$(CC) $(CFLAGS) $(DEFS) $(INCLUDE) $(ARCH_FLAGS) -o $@ -c $<
%.s: %.c
@echo " ASM $<"
$(CC) $(CFLAGS) $(DEFS) $(INCLUDE) $(ARCH_FLAGS) -S -o $(OBJDIR)/$@ -c $<
#$(OBJDIR)/%.d: %.c $(OBJDIR)
# $(CC) -MM -MG $< | sed -e 's,^\([^:]*\)\.o[ ]*:,$(@D)/\1.o $(@D)/\1.d:,' >$@
$(BIN): $(ELF)
@echo " OBJCOPY $(BIN)"
$(OBJCOPY) -Obinary $(ELF) $(BIN)
$(HEX): $(ELF)
@echo " OBJCOPY $(HEX)"
$(OBJCOPY) -Oihex $(ELF) $(HEX)
$(LIST): $(ELF)
@echo " OBJDUMP $(LIST)"
$(OBJDUMP) -S $(ELF) > $(LIST)
$(ELF): $(OBJDIR) $(OBJS)
@echo " LD $(ELF)"
$(LD) $(LDFLAGS) $(ARCH_FLAGS) $(OBJS) $(LDLIBS) -o $(ELF)
clean:
@echo " CLEAN"
$(RM) $(OBJS) $(DEPS) $(ELF) $(HEX) $(LIST) $(OBJDIR)/*.map $(OBJDIR)/*.d $(OBJDIR)/*.s
@rmdir $(OBJDIR) 2>/dev/null || true
dfuboot: $(BIN)
@echo " LOAD $(BIN) THROUGH DFU"
$(DFUUTIL) -a0 -R -D $(BIN) -s 0x08000000
flash: $(BIN)
@echo " FLASH $(BIN)"
$(STFLASH) write $(BIN) 0x8000000
boot: $(BIN)
@echo " LOAD $(BIN) through bootloader"
$(STBOOT) -b$(BOOTSPEED) $(BOOTPORT) -w $(BIN)
.PHONY: clean dfuboot flash boot

104
F0-nolib/3steppersLB/adc.c Normal file
View File

@ -0,0 +1,104 @@
/*
* This file is part of the 3steppers project.
* Copyright 2021 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 & 1 - external channels
* 2 - internal Tsens
* 3 - Vref
*/
static uint16_t ADC_array[NUMBER_OF_ADC_CHANNELS*9];
void adc_setup(){
uint16_t ctr = 0; // 0xfff0 - more than 1.3ms
ADC1->CR &= ~ADC_CR_ADEN;
DMA1_Channel1->CCR &= ~DMA_CCR_EN;
RCC->APB2ENR |= RCC_APB2ENR_ADC1EN; // Enable the peripheral clock of the ADC
RCC->CR2 |= RCC_CR2_HSI14ON; // Start HSI14 RC oscillator
while ((RCC->CR2 & RCC_CR2_HSI14RDY) == 0 && ++ctr < 0xfff0){}; // Wait HSI14 is ready
// calibration
if(ADC1->CR & ADC_CR_ADEN){ // Ensure that ADEN = 0
ADC1->CR &= (uint32_t)(~ADC_CR_ADEN); // Clear ADEN
}
ADC1->CR |= ADC_CR_ADCAL; // Launch the calibration by setting ADCAL
ctr = 0; // ADC calibration time is 5.9us
while(ADC1->CR & ADC_CR_ADCAL && ++ctr < 0xfff0); // Wait until ADCAL=0
// enable ADC
ctr = 0;
do{
ADC1->CR |= ADC_CR_ADEN;
}while((ADC1->ISR & ADC_ISR_ADRDY) == 0 && ++ctr < 0xfff0);
// configure ADC
ADC1->CFGR1 |= ADC_CFGR1_CONT; // Select the continuous mode
// channels 3,5,16 and 17
ADC1->CHSELR = ADC_CHSELR_CHSEL3 | ADC_CHSELR_CHSEL5 | ADC_CHSELR_CHSEL16 | ADC_CHSELR_CHSEL17;
ADC1->SMPR |= ADC_SMPR_SMP; // Select a sampling mode of 111 i.e. 239.5 ADC clk to be greater than 17.1us
ADC->CCR |= ADC_CCR_TSEN | ADC_CCR_VREFEN; // Wake-up the VREFINT and Temperature sensor
// configure DMA for ADC
RCC->AHBENR |= RCC_AHBENR_DMA1EN; // Enable the peripheral clock on DMA
ADC1->CFGR1 |= ADC_CFGR1_DMAEN | ADC_CFGR1_DMACFG; // Enable DMA transfer on ADC and circular mode
DMA1_Channel1->CPAR = (uint32_t) (&(ADC1->DR)); // Configure the peripheral data register address
DMA1_Channel1->CMAR = (uint32_t)(ADC_array); // Configure the memory address
DMA1_Channel1->CNDTR = NUMBER_OF_ADC_CHANNELS * 9; // Configure the number of DMA tranfer to be performs on DMA channel 1
DMA1_Channel1->CCR |= DMA_CCR_MINC | DMA_CCR_MSIZE_0 | DMA_CCR_PSIZE_0 | DMA_CCR_CIRC; // Configure increment, size, interrupts and circular mode
DMA1_Channel1->CCR |= DMA_CCR_EN; // Enable DMA Channel 1
ADC1->CR |= ADC_CR_ADSTART; // start the ADC conversions
}
/**
* @brief getADCval - calculate median value for `nch` channel
* @param nch - number of channel
* @return
*/
uint16_t getADCval(int nch){
int i, addr = nch;
#define PIX_SORT(a,b) { if ((a)>(b)) PIX_SWAP((a),(b)); }
#define PIX_SWAP(a,b) {register uint16_t 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(){
int32_t ADval = getADCval(2);
int32_t temperature = (int32_t) *TEMP30_CAL_ADDR - ADval;
temperature *= (int32_t)(1100 - 300);
temperature /= (int32_t)(*TEMP30_CAL_ADDR - *TEMP110_CAL_ADDR);
temperature += 300;
return(temperature);
}
// return Vdd * 100 (V)
uint32_t getVdd(){
uint32_t vdd = ((uint32_t) *VREFINT_CAL_ADDR) * (uint32_t)330; // 3.3V
vdd /= getADCval(3);
return vdd;
}

View File

@ -0,0 +1,32 @@
/*
* This file is part of the 3steppers project.
* Copyright 2021 Edward V. Emelianov <edward.emelianoff@gmail.com>.
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#ifndef ADC_H
#define ADC_H
#include "stm32f0.h"
// 2 external & 2 internal
#define NUMBER_OF_ADC_CHANNELS (4)
void adc_setup();
int32_t getMCUtemp();
uint32_t getVdd();
uint16_t getADCval(int nch);
int16_t getNTC(int nch);
#endif // ADC_H

View File

@ -0,0 +1,90 @@
/*
* This file is part of the 3steppers project.
* Copyright 2021 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 "buttons.h"
#include "hardware.h"
typedef struct{
keyevent event; // current key event
int16_t counter; // press/release counter
uint32_t lastTms; // time of last event change
} keybase;
static keybase allkeys[BTNSNO] = {0}; // array for buttons' states
uint32_t lastUnsleep = 0; // last keys activity time
void process_keys(){
static uint32_t lastT = 0;
if(Tms == lastT) return;
uint16_t d = (uint16_t)(Tms - lastT);
lastT = Tms;
for(int i = 0; i < BTNSNO; ++i){
keybase *k = &allkeys[i];
keyevent e = k->event;
if(BTN_state(i)){ // key is in pressed state
switch(e){
case EVT_NONE: // just pressed
case EVT_RELEASE:
if((k->counter += d) > PRESSTHRESHOLD){
k->event = EVT_PRESS;
}
break;
case EVT_PRESS: // hold
if((k->counter += d)> HOLDTHRESHOLD){
k->event = EVT_HOLD;
}
break;
default:
break;
}
}else{ // released
if(e == EVT_PRESS || e == EVT_HOLD){ // released
if(k->counter > PRESSTHRESHOLD) k->counter = PRESSTHRESHOLD;
else if((k->counter -= d) < 0){
k->event = EVT_RELEASE; // button released
}
}
}
if(e != k->event){
k->lastTms = Tms;
lastUnsleep = Tms;
}
}
}
/**
* @brief keystate - curent key state
* @param k - key number
* @param T - last event changing time
* @return key event
*/
keyevent keystate(uint8_t k, uint32_t *T){
if(k >= BTNSNO) return EVT_NONE;
keyevent evt = allkeys[k].event;
// change state `release` to `none` after 1st check
if(evt == EVT_RELEASE) allkeys[k].event = EVT_NONE;
if(T) *T = allkeys[k].lastTms;
return evt;
}
// getter of keyevent for allkeys[]
keyevent keyevt(uint8_t k){
if(k >= BTNSNO) return EVT_NONE;
return allkeys[k].event;
}

View File

@ -0,0 +1,43 @@
/*
* This file is part of the 3steppers project.
* Copyright 2021 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 BUTTONS_H__
#include <stm32f0.h>
// threshold in ms for press/hold
#define PRESSTHRESHOLD (9)
#define HOLDTHRESHOLD (199)
// events
typedef enum{
EVT_NONE, // no events with given key
EVT_PRESS, // pressed (hold more than PRESSTHRESHOLD ms)
EVT_HOLD, // hold more than HOLDTHRESHOLD ms
EVT_RELEASE // released after press or hold state
} keyevent;
extern uint32_t lastUnsleep; // last keys activity time
void process_keys();
keyevent keystate(uint8_t k, uint32_t *T);
keyevent keyevt(uint8_t k);
#define BUTTONS_H__
#endif // BUTTONS_H__

373
F0-nolib/3steppersLB/can.c Normal file
View File

@ -0,0 +1,373 @@
/*
* This file is part of the 3steppers project.
* Copyright 2021 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 "can.h"
#include "commonproto.h"
#include "flash.h"
#include "hardware.h"
#include "strfunct.h"
#include <string.h> // memcpy
// circular buffer for received messages
static CAN_message messages[CAN_INMESSAGE_SIZE];
static uint8_t first_free_idx = 0; // index of first empty cell
static int8_t first_nonfree_idx = -1; // index of first data cell
static uint16_t oldspeed = DEFAULT_CAN_SPEED; // speed of last init
#ifdef EBUG
static uint32_t last_err_code = 0;
#endif
static CAN_status can_status = CAN_STOP;
static void can_process_fifo(uint8_t fifo_num);
static void parseCANcommand(CAN_message *msg);
CAN_status CAN_get_status(){
CAN_status st = can_status;
if(st == CAN_FIFO_OVERRUN) can_status = CAN_READY;
return st;
}
// push next message into buffer; return 1 if buffer overfull
static int CAN_messagebuf_push(CAN_message *msg){
//DBG("Try to push\n");
if(first_free_idx == first_nonfree_idx) return 1; // no free space
if(first_nonfree_idx < 0) first_nonfree_idx = 0; // first message in empty buffer
memcpy(&messages[first_free_idx++], msg, sizeof(CAN_message));
// need to roll?
if(first_free_idx == CAN_INMESSAGE_SIZE) first_free_idx = 0;
return 0;
}
// pop message from buffer
CAN_message *CAN_messagebuf_pop(){
if(first_nonfree_idx < 0) return NULL;
#ifdef EBUG
//DBG("read from idx "); printu(first_nonfree_idx); NL();
#endif
CAN_message *msg = &messages[first_nonfree_idx++];
if(first_nonfree_idx == CAN_INMESSAGE_SIZE) first_nonfree_idx = 0;
if(first_nonfree_idx == first_free_idx){ // buffer is empty - refresh it
first_nonfree_idx = -1;
first_free_idx = 0;
}
return msg;
}
void CAN_reinit(uint16_t speed){
CAN->TSR |= CAN_TSR_ABRQ0 | CAN_TSR_ABRQ1 | CAN_TSR_ABRQ2;
RCC->APB1RSTR |= RCC_APB1RSTR_CANRST;
RCC->APB1RSTR &= ~RCC_APB1RSTR_CANRST;
CAN_setup(speed);
}
/*
Can filtering: FSCx=0 (CAN->FS1R) -> 16-bit identifiers
MASK: FBMx=0 (CAN->FM1R), two filters (n in FR1 and n+1 in FR2)
ID: CAN->sFilterRegister[x].FRn[0..15]
MASK: CAN->sFilterRegister[x].FRn[16..31]
FR bits: STID[10:0] RTR IDE EXID[17:15]
LIST: FBMx=1, four filters (n&n+1 in FR1, n+2&n+3 in FR2)
IDn: CAN->sFilterRegister[x].FRn[0..15]
IDn+1: CAN->sFilterRegister[x].FRn[16..31]
*/
/*
Can timing: main freq - APB (PLL=48MHz)
segment = 1sync + TBS1 + TBS2, sample point is between TBS1 and TBS2,
so if TBS1=4 and TBS2=3, sum=8, bit sampling freq is 48/8 = 6MHz
-> to get 100kbps we need prescaler=60
250kbps - 24
500kbps - 12
1MBps - 6
*/
// speed - in kbps
void CAN_setup(uint16_t speed){
if(speed == 0) speed = oldspeed;
else if(speed < 50) speed = 50;
else if(speed > 3000) speed = 3000;
oldspeed = speed;
uint32_t tmout = 16000000;
// Configure GPIO: PB8 - CAN_Rx, PB9 - CAN_Tx
/* (1) Select AF mode (10) on PB8 and PB9 */
/* (2) AF4 for CAN signals */
GPIOB->MODER = (GPIOB->MODER & ~(GPIO_MODER_MODER8 | GPIO_MODER_MODER9))
| (GPIO_MODER_MODER8_AF | GPIO_MODER_MODER9_AF); /* (1) */
GPIOB->AFR[1] = (GPIOB->AFR[1] &~ (GPIO_AFRH_AFRH0 | GPIO_AFRH_AFRH1))\
| (4 << (0 * 4)) | (4 << (1 * 4)); /* (2) */
/* Enable the peripheral clock CAN */
RCC->APB1ENR |= RCC_APB1ENR_CANEN;
// Configure CAN
CAN->MCR |= CAN_MCR_INRQ; // Enter CAN init mode to write the configuration
while((CAN->MSR & CAN_MSR_INAK) != CAN_MSR_INAK){
IWDG->KR = IWDG_REFRESH;
if(--tmout == 0) break;
}
CAN->MCR &=~ CAN_MCR_SLEEP;
CAN->MCR |= CAN_MCR_ABOM; // allow automatically bus-off
CAN->BTR = 2 << 20 | 3 << 16 | (6000/speed - 1); // speed
CAN->MCR &=~ CAN_MCR_INRQ;
tmout = 16000000;
while((CAN->MSR & CAN_MSR_INAK) == CAN_MSR_INAK){ // Wait the init mode leaving
IWDG->KR = IWDG_REFRESH;
if(--tmout == 0) break;
}
// accept self ID at filter 0, ALL other at filters 1 and 2
CAN->FMR = CAN_FMR_FINIT;
CAN->FA1R = CAN_FA1R_FACT0 | CAN_FA1R_FACT1 | CAN_FA1R_FACT2;
CAN->FM1R = CAN_FM1R_FBM0; // identifier mode for bank#0, mask mode for #1 and #2
// set to 1 all needed bits of CAN->FFA1R to switch given filters to FIFO1
CAN->sFilterRegister[0].FR1 = the_conf.CANID << 5; // self ID
CAN->sFilterRegister[1].FR1 = (1<<21)|(1<<5); // all odd IDs
CAN->sFilterRegister[2].FR1 = (1<<21); // all even IDs
CAN->FFA1R = 2; // filter 1 for FIFO1, filters 0&2 - for FIFO0
CAN->FMR &=~ CAN_FMR_FINIT; // end of filters init
CAN->IER |= CAN_IER_ERRIE | CAN_IER_FOVIE0 | CAN_IER_FOVIE1;
/* Configure IT */
NVIC_SetPriority(CEC_CAN_IRQn, 0);
NVIC_EnableIRQ(CEC_CAN_IRQn);
can_status = CAN_READY;
}
void can_proc(){
#ifdef EBUG
if(last_err_code){
DBG("Error, ESR=");
printu(last_err_code);
NL();
last_err_code = 0;
}
#endif
// check for messages in FIFO0 & FIFO1
if(CAN->RF0R & CAN_RF0R_FMP0){
can_process_fifo(0);
}
if(CAN->RF1R & CAN_RF1R_FMP1){
can_process_fifo(1);
}
IWDG->KR = IWDG_REFRESH;
if(CAN->ESR & (CAN_ESR_BOFF | CAN_ESR_EPVF | CAN_ESR_EWGF)){ // much errors - restart CAN BUS
SEND("\nToo much errors, restarting CAN!\n");
SEND("Receive error counter: ");
printu((CAN->ESR & CAN_ESR_REC)>>24);
SEND("\nTransmit error counter: ");
printu((CAN->ESR & CAN_ESR_TEC)>>16);
SEND("\nLast error code: ");
int lec = (CAN->ESR & CAN_ESR_LEC) >> 4;
const char *errmsg = "No";
switch(lec){
case 1: errmsg = "Stuff"; break;
case 2: errmsg = "Form"; break;
case 3: errmsg = "Ack"; break;
case 4: errmsg = "Bit recessive"; break;
case 5: errmsg = "Bit dominant"; break;
case 6: errmsg = "CRC"; break;
case 7: errmsg = "(set by software)"; break;
}
SEND(errmsg); SEND(" error\n");
if(CAN->ESR & CAN_ESR_BOFF) SEND("Bus off");
if(CAN->ESR & CAN_ESR_EPVF) SEND("Passive error limit");
if(CAN->ESR & CAN_ESR_EWGF) SEND("Error counter limit");
NL();
IWDG->KR = IWDG_REFRESH;
// request abort for all mailboxes
CAN->TSR |= CAN_TSR_ABRQ0 | CAN_TSR_ABRQ1 | CAN_TSR_ABRQ2;
// reset CAN bus
RCC->APB1RSTR |= RCC_APB1RSTR_CANRST;
RCC->APB1RSTR &= ~RCC_APB1RSTR_CANRST;
CAN_setup(0);
}
}
CAN_status can_send(uint8_t *msg, uint8_t len, uint16_t target_id){
uint8_t mailbox = 0;
// check first free mailbox
if(CAN->TSR & (CAN_TSR_TME)){
mailbox = (CAN->TSR & CAN_TSR_CODE) >> 24;
}else{ // no free mailboxes
//SEND("No free mailboxes"); NL();
return CAN_BUSY;
}
#ifdef EBUG
DBG("Send data. Len="); printu(len);
SEND(", tagid="); printuhex(target_id);
SEND(", data=");
for(int i = 0; i < len; ++i){
SEND(" "); printuhex(msg[i]);
}
NL();
#endif
CAN_TxMailBox_TypeDef *box = &CAN->sTxMailBox[mailbox];
uint32_t lb = 0, hb = 0;
switch(len){
case 8:
hb |= (uint32_t)msg[7] << 24;
__attribute__((fallthrough));
case 7:
hb |= (uint32_t)msg[6] << 16;
__attribute__((fallthrough));
case 6:
hb |= (uint32_t)msg[5] << 8;
__attribute__((fallthrough));
case 5:
hb |= (uint32_t)msg[4];
__attribute__((fallthrough));
case 4:
lb |= (uint32_t)msg[3] << 24;
__attribute__((fallthrough));
case 3:
lb |= (uint32_t)msg[2] << 16;
__attribute__((fallthrough));
case 2:
lb |= (uint32_t)msg[1] << 8;
__attribute__((fallthrough));
default:
lb |= (uint32_t)msg[0];
}
box->TDLR = lb;
box->TDHR = hb;
box->TDTR = len;
box->TIR = (target_id & 0x7FF) << 21 | CAN_TI0R_TXRQ;
return CAN_OK;
}
static void can_process_fifo(uint8_t fifo_num){
if(fifo_num > 1) return;
CAN_FIFOMailBox_TypeDef *box = &CAN->sFIFOMailBox[fifo_num];
volatile uint32_t *RFxR = (fifo_num) ? &CAN->RF1R : &CAN->RF0R;
// read all
while(*RFxR & CAN_RF0R_FMP0){ // amount of messages pending
// CAN_RDTxR: (16-31) - timestamp, (8-15) - filter match index, (0-3) - data length
CAN_message msg;
uint8_t *dat = msg.data;
uint8_t len = box->RDTR & 0x0f;
msg.length = len;
msg.ID = box->RIR >> 21;
//msg.filterNo = (box->RDTR >> 8) & 0xff;
//msg.fifoNum = fifo_num;
if(len){ // message can be without data
uint32_t hb = box->RDHR, lb = box->RDLR;
switch(len){
case 8:
dat[7] = hb>>24;
__attribute__((fallthrough));
case 7:
dat[6] = (hb>>16) & 0xff;
__attribute__((fallthrough));
case 6:
dat[5] = (hb>>8) & 0xff;
__attribute__((fallthrough));
case 5:
dat[4] = hb & 0xff;
__attribute__((fallthrough));
case 4:
dat[3] = lb>>24;
__attribute__((fallthrough));
case 3:
dat[2] = (lb>>16) & 0xff;
__attribute__((fallthrough));
case 2:
dat[1] = (lb>>8) & 0xff;
__attribute__((fallthrough));
case 1:
dat[0] = lb & 0xff;
}
}
if(msg.ID == OUTPID) parseCANcommand(&msg);
if(CAN_messagebuf_push(&msg)) return; // error: buffer is full, try later
*RFxR |= CAN_RF0R_RFOM0; // release fifo for access to next message
}
//if(*RFxR & CAN_RF0R_FULL0) *RFxR &= ~CAN_RF0R_FULL0;
*RFxR = 0; // clear FOVR & FULL
}
static void formerr(CAN_message *msg, errcodes err){
if(msg->length < 4) msg->length = 4;
msg->data[3] = (uint8_t)err;
}
/**
* @brief parseCANcommand - parser
* @param msg - incoming message @ my CANID
* FORMAT:
* 0 1 2 3 4 5 6 7
* [CMD][PAR][errcode][VALUE]
* CMD - uint16_t, PAR - uint8_t, errcode - one of CAN_errcodes, VALUE - int32_t
* `errcode` of incoming message doesn't matter
*/
TRUE_INLINE void parseCANcommand(CAN_message *msg){
int N = 1000;
// we don't check msg here as it cannot be NULL
#ifdef EBUG
SEND("Get data: ");
for(int i = 0; i < msg->length; ++i){
printuhex(msg->data[i]); bufputchar(' ');
}
NL();
#endif
if(msg->length == 0) goto sendmessage; // PING
uint16_t Index = *(uint16_t*)msg->data;
if(Index >= CMD_AMOUNT){
formerr(msg, ERR_BADCMD);
goto sendmessage;
}
msg->data[3] = ERR_OK;
uint8_t *par = (uint8_t *)(&msg->data[2]);
if(*par & 0x80){
formerr(msg, ERR_BADPAR);
goto sendmessage;
}
int32_t *val = (int32_t *)(&msg->data[4]);
if(msg->length == 8) *par |= 0x80;
else if(msg->length == 2) *par = CANMESG_NOPAR; // no parameter
else if(msg->length != 3){ // wrong length
formerr(msg, ERR_WRONGLEN);
goto sendmessage;
}
errcodes ec = cmdlist[Index].function(par, val);
if(ec != ERR_OK){
formerr(msg, ec);
}
sendmessage:
while(CAN_BUSY == can_send(msg->data, msg->length, OUTPID))
if(--N == 0) break;
}
void cec_can_isr(){
if(CAN->RF0R & CAN_RF0R_FOVR0){ // FIFO overrun
CAN->RF0R &= ~CAN_RF0R_FOVR0;
can_status = CAN_FIFO_OVERRUN;
}
if(CAN->RF1R & CAN_RF1R_FOVR1){
CAN->RF1R &= ~CAN_RF1R_FOVR1;
can_status = CAN_FIFO_OVERRUN;
}
if(CAN->MSR & CAN_MSR_ERRI){ // Error
CAN->MSR &= ~CAN_MSR_ERRI;
// request abort for problem mailbox
if(CAN->TSR & CAN_TSR_TERR0) CAN->TSR |= CAN_TSR_ABRQ0;
if(CAN->TSR & CAN_TSR_TERR1) CAN->TSR |= CAN_TSR_ABRQ1;
if(CAN->TSR & CAN_TSR_TERR2) CAN->TSR |= CAN_TSR_ABRQ2;
#ifdef EBUG
last_err_code = CAN->ESR;
#endif
}
}

View File

@ -0,0 +1,63 @@
/*
* This file is part of the 3steppers project.
* Copyright 2021 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 __CAN_H__
#define __CAN_H__
#include "flash.h"
#include "hardware.h"
// output messages identifier
#define OUTPID (the_conf.CANID)
// CAN ID mask (11 bits)
#define CANIDMASK (0x7ff)
// amount of filter banks in STM32F0
#define STM32F0FBANKNO (28)
// incoming message buffer size
#define CAN_INMESSAGE_SIZE (8)
// CAN message
typedef struct{
uint8_t data[8]; // up to 8 bytes of data
uint8_t length; // data length
uint16_t ID; // ID of receiver
} CAN_message;
typedef enum{
CAN_STOP,
CAN_READY,
CAN_BUSY,
CAN_OK,
CAN_FIFO_OVERRUN
} CAN_status;
CAN_status CAN_get_status();
void CAN_reinit(uint16_t speed);
void CAN_setup(uint16_t speed);
CAN_status can_send(uint8_t *msg, uint8_t len, uint16_t target_id);
void can_proc();
CAN_message *CAN_messagebuf_pop();
#endif // __CAN_H__

View File

@ -0,0 +1,133 @@
/*
* This file is part of the 3steppers project.
* Copyright 2021 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"
#include "buttons.h"
#include "can.h"
#include "commonproto.h"
#include "hardware.h"
/******* All functions from cmdlist[i].function *******/
static errcodes pingparser(uint8_t _U_ *par, int32_t _U_ *val){
return ERR_OK; // just echo all input data over CAN (or return OK to USB)
}
static errcodes relayparser(uint8_t _U_ *par, int32_t _U_ *val){
if(ISSETTER(*par)){
if(*val) ON(RELAY);
else OFF(RELAY);
}
*val = CHK(RELAY);
return ERR_OK;
}
static errcodes buzzerparser(uint8_t _U_ *par, int32_t _U_ *val){
if(ISSETTER(*par)){
if(*val) ON(BUZZER);
else OFF(BUZZER);
}
*val = CHK(BUZZER);
return ERR_OK;
}
static errcodes adcparser(uint8_t _U_ *par, int32_t _U_ *val){
uint8_t n = PARBASE(*par);
if(n > NUMBER_OF_ADC_CHANNELS) return ERR_BADPAR;
*val = (int32_t) getADCval(n);
return ERR_OK;
}
// NON-STANDARD COMMAND!!!!!!!
// errcode == keystate, value = last time!!!!
static errcodes buttonsparser(uint8_t _U_ *par, int32_t _U_ *val){
#if BTNSNO > 4
#error "change the code!!!"
#endif
uint8_t n = PARBASE(*par);
if(n >= BTNSNO){
*par = CANMESG_NOPAR; // the only chance to understand error
return ERR_BADPAR;
}
return (uint8_t) keystate(n, (uint32_t*)val);
}
static errcodes eswparser(uint8_t _U_ *par, int32_t _U_ *val){
uint8_t n = PARBASE(*par);
if(n > ESWNO-1) return ERR_BADPAR;
*val = (int32_t)ESW_state(n);
return ERR_OK;
}
static errcodes mcutparser(uint8_t _U_ *par, int32_t _U_ *val){
*val = getMCUtemp();
return ERR_OK;
}
static errcodes mcuvddparser(uint8_t _U_ *par, int32_t _U_ *val){
*val = getVdd();
return ERR_OK;
}
static errcodes resetparser(uint8_t _U_ *par, int32_t _U_ *val){
NVIC_SystemReset();
return ERR_OK;
}
static errcodes timeparser(uint8_t _U_ *par, int32_t _U_ *val){
*val = Tms;
return ERR_OK;
}
static errcodes pwmparser(uint8_t _U_ *par, int32_t _U_ *val){
if(PARBASE(*par) > PWMCHMAX && *par != CANMESG_NOPAR) return ERR_BADPAR;
#if PWMCHMAX != 0
#error "change the code!!!"
#endif
if(ISSETTER(*par)){
if(*val < 0 || *val > PWMMAX) return ERR_BADVAL;
PWMset((uint32_t)*val);
}
*val = (int32_t) PWMget();
return ERR_OK;
}
static errcodes extparser(uint8_t _U_ *par, int32_t _U_ *val){
return ERR_OK;
}
/*
static CAN_errcodes parser(const uint8_t _U_ *par, const int32_t _U_ *val){
return CANERR_OK;
}*/
// the main commands list, index is CAN command code
const commands cmdlist[CMD_AMOUNT] = {
[CMD_PING] = {"ping", pingparser, "echo given command back"},
[CMD_RELAY] = {"relay", relayparser, "change relay state (1/0)"},
[CMD_BUZZER] = {"buzzer", buzzerparser, "change buzzer state (1/0)"},
[CMD_ADC] = {"adc", adcparser, "get ADC values"},
[CMD_BUTTONS] = {"button", buttonsparser, "get buttons state"},
[CMD_ESWSTATE] = {"esw", eswparser, "get end switches state"},
[CMD_MCUT] = {"mcut", mcutparser, "get MCU T"},
[CMD_MCUVDD] = {"mcuvdd", mcuvddparser, "get MCU Vdd"},
[CMD_RESET] = {"reset", resetparser, "reset MCU"},
[CMD_TIMEFROMSTART] = {"time", timeparser, "get time from start"},
[CMD_PWM] = {"pwm", pwmparser, "pwm value"},
[CMD_EXT] = {"ext", extparser, "external outputs"},
};

View File

@ -0,0 +1,76 @@
/*
* This file is part of the 3steppers project.
* Copyright 2021 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 COMMONPROTO_H__
#define COMMONPROTO_H__
#include <stm32f0.h>
#include "can.h"
#define _U_ __attribute__((unused))
// message have no parameter
#define CANMESG_NOPAR (127)
// message is setter (have value)
#define ISSETTER(x) ((x & 0x80) ? 1 : 0)
// base value of parameter (even if it is a setter)
#define PARBASE(x) (x & 0x7f)
// error codes for answer message
typedef enum{
ERR_OK, // all OK
ERR_BADPAR, // parameter's value is wrong
ERR_BADVAL, // wrong parameter's value
ERR_WRONGLEN, // wrong message length
ERR_BADCMD, // unknown command
ERR_CANTRUN, // can't run given command due to bad parameters or other
} errcodes;
// pointer to function for command execution, both should be non-NULL for common cases
// if(par &0x80) it is setter, if not - getter
// if par == 0x127 it means absense of parameter!!!
// @return CANERR_OK (0) if OK or error code
typedef errcodes (*fpointer)(uint8_t *par, int32_t *val);
typedef struct{
const char *command; // text command (up to 65536 commands)
fpointer function; // function to execute: function(&par, &val)
const char *help; // help message for text protocol
} commands;
enum{
CMD_PING // ping device
,CMD_RELAY // relay on/off
,CMD_BUZZER // buzzer on/off
,CMD_ADC // ADC ch#
,CMD_BUTTONS // buttons
,CMD_ESWSTATE // end-switches state
,CMD_MCUT // MCU temperature
,CMD_MCUVDD // MCU Vdd
,CMD_RESET // software reset
,CMD_TIMEFROMSTART // get time from start
,CMD_PWM // PWM value
,CMD_EXT // value on EXTx outputs
,CMD_AMOUNT // amount of CANBUS commands, pure USB commands coming after it
};
extern const commands cmdlist[CMD_AMOUNT];
#endif // COMMONPROTO_H__

View File

@ -0,0 +1,67 @@
/*
* This file is part of the 3steppers project.
* Copyright 2021 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/>.
*/
// custom standalone buttons reaction
#include <stm32f0.h>
#include "buttons.h"
#include "custom_buttons.h"
#include "hardware.h"
/*
* check buttons, on long press of button:
* 1 - switch relay
* 2 - switch buzzer
* 3 - work with PWM out 0 (when btn3 pressed, btn1 increased & btn2 decreased PWM width)
* press once btn2/3 to change PWM @1, hold to change @25 (repeat as many times as need)
*/
void custom_buttons_process(){
static uint32_t lastT = 0;
static uint8_t pwmval = 127;
static uint8_t trig = 0; // == 1 if given btn3 was off
if(lastUnsleep == lastT) return; // no buttons activity
lastT = lastUnsleep;
if(keyevt(3) == EVT_HOLD){ // PWM
if(keyevt(2) == EVT_HOLD){ // decrease PWM by 25
if(pwmval > 25) pwmval -= 25;
else pwmval = 0;
}else if(keyevt(2) == EVT_PRESS){ // decrease PWM by 1
if(pwmval > 0) --pwmval;
}else if(keyevt(1) == EVT_HOLD){ // increase PWM by 25
if(pwmval < 230) pwmval += 25;
else pwmval = 255;
}else if(keyevt(1) == EVT_PRESS){
if(pwmval < 254) ++pwmval;
}
if(trig == 0){ // first hold after release
if(TIM1->CCR1) TIM1->CCR1 = 0; // turn off if was ON
else{
TIM1->CCR1 = pwmval;
trig = 1;
}
}else TIM1->CCR1 = pwmval;
return;
}else trig = 0;
if(keyevt(1) == EVT_HOLD){ // relay
TGL(RELAY);
}
if(keyevt(2) == EVT_HOLD){ // buzzer
TGL(BUZZER);
}
}

View File

@ -0,0 +1,25 @@
/*
* This file is part of the 3steppers project.
* Copyright 2021 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 CUSTOM_BUTTONS_H__
#define CUSTOM_BUTTONS_H__
void custom_buttons_process();
#endif // CUSTOM_BUTTONS_H__

View File

@ -0,0 +1,206 @@
/*
* geany_encoding=koi8-r
* flash.c
*
* Copyright 2017 Edward V. Emelianov <eddy@sao.ru, edward.emelianoff@gmail.com>
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; if not, write to the Free Software
* Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston,
* MA 02110-1301, USA.
*
*/
#include <stm32f0.h>
#include <string.h> // memcpy
#include "flash.h"
#include "strfunct.h"
// max amount of Config records stored (will be recalculate in flashstorage_init()
static uint32_t maxCnum = FLASH_BLOCK_SIZE / sizeof(user_conf);
#define USERCONF_INITIALIZER { \
.userconf_sz = sizeof(user_conf) \
,.defflags.reverse = 0 \
,.CANspeed = 100 \
,.microsteps = 16 \
,.accdecsteps = 25 \
,.motspd = 1000 \
,.maxsteps = 50000 \
}
static int erase_flash(const void*, const void*);
static int write2flash(const void*, const void*, uint32_t);
// don't write `static` here, or get error:
// 'memcpy' forming offset 8 is out of the bounds [0, 4] of object '__varsstart' with type 'uint32_t'
const user_conf *Flash_Data = (const user_conf *)(&__varsstart);
user_conf the_conf = USERCONF_INITIALIZER;
static int currentconfidx = -1; // index of current configuration
/**
* @brief binarySearch - binary search in flash for last non-empty cell
* any struct searched should have its sizeof() @ the first field!!!
* @param l - left index
* @param r - right index (should be @1 less than last index!)
* @param start - starting address
* @param stor_size - size of structure to search
* @return index of non-empty cell or -1
*/
static int binarySearch(int r, const uint8_t *start, int stor_size){
int l = 0;
while(r >= l){
int mid = l + (r - l) / 2;
const uint8_t *s = start + mid * stor_size;
if(*((const uint16_t*)s) == stor_size){
if(*((const uint16_t*)(s + stor_size)) == 0xffff){ // next is free
return mid;
}else{ // element is to the right
l = mid + 1;
}
}else{ // element is to the left
r = mid - 1;
}
}
return -1; // not found
}
/**
* @brief flashstorage_init - initialization of user conf storage
* run in once @ start
*/
void flashstorage_init(){
if(FLASH_SIZE > 0 && FLASH_SIZE < 20000){
uint32_t flsz = FLASH_SIZE * 1024; // size in bytes
flsz -= (uint32_t)(&__varsstart) - FLASH_BASE;
maxCnum = flsz / sizeof(user_conf);
}
// -1 if there's no data at all & flash is clear; maxnum-1 if flash is full
currentconfidx = binarySearch((int)maxCnum-2, (const uint8_t*)Flash_Data, sizeof(user_conf));
if(currentconfidx > -1){
memcpy(&the_conf, &Flash_Data[currentconfidx], sizeof(user_conf));
}
}
// store new configuration
// @return 0 if all OK
int store_userconf(){
// maxnum - 3 means that there always should be at least one empty record after last data
// for binarySearch() checking that there's nothing more after it!
if(currentconfidx > (int)maxCnum - 3){ // there's no more place
currentconfidx = 0;
if(erase_flash(Flash_Data, (&__varsstart))) return 1;
}else ++currentconfidx; // take next data position (0 - within first run after firmware flashing)
return write2flash((const void*)&Flash_Data[currentconfidx], &the_conf, sizeof(the_conf));
}
static int write2flash(const void *start, const void *wrdata, uint32_t stor_size){
int ret = 0;
if (FLASH->CR & FLASH_CR_LOCK){ // unloch flash
FLASH->KEYR = FLASH_KEY1;
FLASH->KEYR = FLASH_KEY2;
}
while (FLASH->SR & FLASH_SR_BSY);
if(FLASH->SR & FLASH_SR_WRPRTERR){
return 1; // write protection
}
FLASH->SR = FLASH_SR_EOP | FLASH_SR_PGERR | FLASH_SR_WRPRTERR; // clear all flags
FLASH->CR |= FLASH_CR_PG;
const uint16_t *data = (const uint16_t*) wrdata;
volatile uint16_t *address = (volatile uint16_t*) start;
uint32_t i, count = (stor_size + 1) / 2;
for (i = 0; i < count; ++i){
IWDG->KR = IWDG_REFRESH;
*(volatile uint16_t*)(address + i) = data[i];
while (FLASH->SR & FLASH_SR_BSY);
if(FLASH->SR & FLASH_SR_PGERR){
ret = 1; // program error - meet not 0xffff
break;
}else while (!(FLASH->SR & FLASH_SR_EOP));
FLASH->SR = FLASH_SR_EOP | FLASH_SR_PGERR | FLASH_SR_WRPRTERR;
}
FLASH->CR |= FLASH_CR_LOCK; // lock it back
FLASH->CR &= ~(FLASH_CR_PG);
return ret;
}
/**
* @brief erase_flash - erase N pages of flash memory
* @param start - first address
* @param end - last address (or NULL if need to erase all flash remaining)
* @return 0 if succeed
*/
static int erase_flash(const void *start, const void *end){
int ret = 0;
uint32_t nblocks = 1, flsz = 0;
if(!end){ // erase all remaining
if(FLASH_SIZE > 0 && FLASH_SIZE < 20000){
flsz = FLASH_SIZE * 1024; // size in bytes
flsz -= (uint32_t)start - FLASH_BASE;
}
}else{ // erase a part
flsz = (uint32_t)end - (uint32_t)start;
}
nblocks = flsz / FLASH_BLOCK_SIZE;
if(nblocks == 0 || nblocks >= FLASH_SIZE) return 1;
for(uint32_t i = 0; i < nblocks; ++i){
IWDG->KR = IWDG_REFRESH;
/* (1) Wait till no operation is on going */
/* (2) Clear error & EOP bits */
/* (3) Check that the Flash is unlocked */
/* (4) Perform unlock sequence */
while ((FLASH->SR & FLASH_SR_BSY) != 0){} /* (1) */
FLASH->SR = FLASH_SR_EOP | FLASH_SR_PGERR | FLASH_SR_WRPRTERR; /* (2) */
/* if (FLASH->SR & FLASH_SR_EOP){
FLASH->SR |= FLASH_SR_EOP;
}*/
if ((FLASH->CR & FLASH_CR_LOCK) != 0){ /* (3) */
FLASH->KEYR = FLASH_KEY1; /* (4) */
FLASH->KEYR = FLASH_KEY2;
}
/* (1) Set the PER bit in the FLASH_CR register to enable page erasing */
/* (2) Program the FLASH_AR register to select a page to erase */
/* (3) Set the STRT bit in the FLASH_CR register to start the erasing */
/* (4) Wait until the EOP flag in the FLASH_SR register set */
/* (5) Clear EOP flag by software by writing EOP at 1 */
/* (6) Reset the PER Bit to disable the page erase */
FLASH->CR |= FLASH_CR_PER; /* (1) */
FLASH->AR = (uint32_t)Flash_Data + i*FLASH_BLOCK_SIZE; /* (2) */
FLASH->CR |= FLASH_CR_STRT; /* (3) */
while(!(FLASH->SR & FLASH_SR_EOP));
FLASH->SR |= FLASH_SR_EOP; /* (5)*/
if(FLASH->SR & FLASH_SR_WRPRTERR){ /* Check Write protection error */
ret = 1;
FLASH->SR |= FLASH_SR_WRPRTERR; /* Clear the flag by software by writing it at 1*/
break;
}
FLASH->CR &= ~FLASH_CR_PER; /* (6) */
}
return ret;
}
void dump_userconf(){
SEND("userconf_addr="); printuhex((uint32_t)Flash_Data);
SEND("\nuserconf_sz="); printu(the_conf.userconf_sz);
SEND("\nCANspeed="); printu(the_conf.CANspeed);
SEND("\nmicrosteps="); printu(the_conf.microsteps);
SEND("\naccdecsteps="); printu(the_conf.accdecsteps);
SEND("\nmotspd="); printu(the_conf.motspd);
SEND("\nmaxsteps="); printu(the_conf.maxsteps);
//flags
SEND("\nreverse="); bufputchar('0' + the_conf.defflags.reverse);
newline();
sendbuf();
}

View File

@ -0,0 +1,59 @@
/*
* flash.h
*
* Copyright 2017 Edward V. Emelianov <eddy@sao.ru, edward.emelianoff@gmail.com>
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; if not, write to the Free Software
* Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston,
* MA 02110-1301, USA.
*
*/
#pragma once
#ifndef __FLASH_H__
#define __FLASH_H__
#include "hardware.h"
#define FLASH_BLOCK_SIZE (1024)
#define FLASH_SIZE_REG ((uint32_t)0x1FFFF7CC)
#define FLASH_SIZE *((uint16_t*)FLASH_SIZE_REG)
typedef struct{
uint8_t reverse : 1;
} defflags_t;
/*
* struct to save user configurations
*/
typedef struct __attribute__((packed, aligned(4))){
uint16_t userconf_sz; // "magick number"
uint32_t maxsteps; // maximal amount of steps from ESW0 to EWS3
uint16_t CANspeed; // default CAN speed
uint16_t CANID; // identifier
uint16_t microsteps; // microsteps amount per step
uint16_t accdecsteps; // amount of steps need for full acceleration/deceleration cycle
uint16_t motspd; // max motor speed (steps per second)
defflags_t defflags; // default flags
} user_conf;
extern user_conf the_conf; // global user config (read from FLASH to RAM)
// data from ld-file: start address of storage
extern const uint32_t __varsstart;
void flashstorage_init();
int store_userconf();
void dump_userconf();
#endif // __FLASH_H__

View File

@ -0,0 +1,127 @@
/*
* This file is part of the 3steppers project.
* Copyright 2021 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 "hardware.h"
#include "can.h"
// Buttons: PA10, PA13, PA14, PA15, pullup (0 active)
volatile GPIO_TypeDef *BTNports[BTNSNO] = {GPIOA, GPIOA, GPIOA, GPIOA};
const uint32_t BTNpins[BTNSNO] = {1<<10, 1<<13, 1<<14, 1<<15};
// Limit switches: PC13, PC14, PC15, pulldown (0 active)
volatile GPIO_TypeDef *ESWports[ESWNO] = {GPIOC, GPIOC, GPIOC};
const uint32_t ESWpins[ESWNO] = {1<<13, 1<<14, 1<<15};
// external GPIO
volatile GPIO_TypeDef *EXTports[EXTNO] = {GPIOB, GPIOB, GPIOB};
const uint32_t EXTpins[EXTNO] = {1<<13, 1<<14, 1<<15};
// motors: DIR/EN
volatile GPIO_TypeDef *ENports[MOTORSNO] = {GPIOB, GPIOB, GPIOB};
const uint32_t ENpins[MOTORSNO] = {1<<0, 1<<2, 1<<11};
volatile GPIO_TypeDef *DIRports[MOTORSNO] = {GPIOB, GPIOB, GPIOB};
const uint32_t DIRpins[MOTORSNO] = {1<<1, 1<<10, 1<<12};
void gpio_setup(void){
RCC->AHBENR |= RCC_AHBENR_GPIOAEN | RCC_AHBENR_GPIOBEN | RCC_AHBENR_GPIOCEN | RCC_AHBENR_GPIOFEN;
GPIOA->MODER = GPIO_MODER_MODER0_AF | GPIO_MODER_MODER1_AF | GPIO_MODER_MODER2_AF | GPIO_MODER_MODER3_AI |
GPIO_MODER_MODER4_AF | GPIO_MODER_MODER5_AI | GPIO_MODER_MODER6_AF | GPIO_MODER_MODER7_AF |
GPIO_MODER_MODER8_AF | GPIO_MODER_MODER9_AF;
GPIOA->PUPDR = GPIO_PUPDR10_PU | GPIO_PUPDR13_PU | GPIO_PUPDR14_PU | GPIO_PUPDR15_PU;
GPIOA->AFR[0] = (2 << (0*4)) | (2 << (1*4)) | (0 << (2*4)) | (4 << (4*4)) | (5 << (6*4)) | (5 << (7*4));
GPIOA->AFR[1] = (2 << (0*4)) | (2 << (1*4));
pin_set(GPIOB, (1<<0) | (1<<2) | (1<<11)); // turn off motors @ start
GPIOB->MODER = GPIO_MODER_MODER0_O | GPIO_MODER_MODER1_O | GPIO_MODER_MODER2_O | GPIO_MODER_MODER3_O |
GPIO_MODER_MODER4_AF | GPIO_MODER_MODER5_AF | GPIO_MODER_MODER6_AF | GPIO_MODER_MODER7_AF |
GPIO_MODER_MODER10_O | GPIO_MODER_MODER11_O | GPIO_MODER_MODER12_O | GPIO_MODER_MODER13_O |
GPIO_MODER_MODER14_O | GPIO_MODER_MODER15_O ;
GPIOB->AFR[0] = (1 << (4*4)) | (1 << (5*4)) | (1 << (6*4)) | (1 << (7*4));
GPIOC->PUPDR = GPIO_PUPDR13_PD | GPIO_PUPDR14_PD | GPIO_PUPDR15_PD;
GPIOF->MODER = GPIO_MODER_MODER0_O;
}
void iwdg_setup(){
uint32_t tmout = 16000000;
/* Enable the peripheral clock RTC */
/* (1) Enable the LSI (40kHz) */
/* (2) Wait while it is not ready */
RCC->CSR |= RCC_CSR_LSION; /* (1) */
while((RCC->CSR & RCC_CSR_LSIRDY) != RCC_CSR_LSIRDY){if(--tmout == 0) break;} /* (2) */
/* Configure IWDG */
/* (1) Activate IWDG (not needed if done in option bytes) */
/* (2) Enable write access to IWDG registers */
/* (3) Set prescaler by 64 (1.6ms for each tick) */
/* (4) Set reload value to have a rollover each 2s */
/* (5) Check if flags are reset */
/* (6) Refresh counter */
IWDG->KR = IWDG_START; /* (1) */
IWDG->KR = IWDG_WRITE_ACCESS; /* (2) */
IWDG->PR = IWDG_PR_PR_1; /* (3) */
IWDG->RLR = 1250; /* (4) */
tmout = 16000000;
while(IWDG->SR){if(--tmout == 0) break;} /* (5) */
IWDG->KR = IWDG_REFRESH; /* (6) */
}
void timers_setup(){
#if 0
// TIM1 channels 1..3 - PWM output
RCC->APB2ENR |= RCC_APB2ENR_TIM1EN; // enable clocking
TIM1->PSC = 9; // F=48/10 = 4.8MHz
TIM1->ARR = 255; // PWM frequency = 4800/256 = 18.75kHz
// PWM mode 1 (OCxM = 110), preload enable
TIM1->CCMR1 = TIM_CCMR1_OC1M_2 | TIM_CCMR1_OC1M_1 | TIM_CCMR1_OC1PE |
TIM_CCMR1_OC2M_2 | TIM_CCMR1_OC2M_1 | TIM_CCMR1_OC2PE;
TIM1->CCMR2 = TIM_CCMR2_OC3M_2 | TIM_CCMR2_OC3M_1 | TIM_CCMR2_OC3PE;
TIM1->CCER = TIM_CCER_CC1E | TIM_CCER_CC2E | TIM_CCER_CC3E; // active high (CC1P=0), enable outputs
TIM1->BDTR |= TIM_BDTR_MOE; // enable main output
TIM1->CR1 |= TIM_CR1_CEN; // enable timer
TIM1->EGR |= TIM_EGR_UG; // force update generation
#endif
}
// pause in milliseconds for some purposes
void pause_ms(uint32_t pause){
uint32_t Tnxt = Tms + pause;
while(Tms < Tnxt) nop();
}
void Jump2Boot(){ // for STM32F072
void (*SysMemBootJump)(void);
volatile uint32_t addr = 0x1FFFC800;
// reset systick
SysTick->CTRL = 0;
// reset clocks
RCC->APB1RSTR = RCC_APB1RSTR_CECRST | RCC_APB1RSTR_DACRST | RCC_APB1RSTR_PWRRST | RCC_APB1RSTR_CRSRST |
RCC_APB1RSTR_CANRST | RCC_APB1RSTR_USBRST | RCC_APB1RSTR_I2C2RST | RCC_APB1RSTR_I2C1RST |
RCC_APB1RSTR_USART4RST | RCC_APB1RSTR_USART3RST | RCC_APB1RSTR_USART2RST | RCC_APB1RSTR_SPI2RST |
RCC_APB1RSTR_WWDGRST | RCC_APB1RSTR_TIM14RST | RCC_APB1RSTR_TIM7RST | RCC_APB1RSTR_TIM6RST |
RCC_APB1RSTR_TIM3RST | RCC_APB1RSTR_TIM2RST;
RCC->APB2RSTR = RCC_APB2RSTR_DBGMCURST | RCC_APB2RSTR_TIM17RST | RCC_APB2RSTR_TIM16RST | RCC_APB2RSTR_TIM15RST |
RCC_APB2RSTR_USART1RST | RCC_APB2RSTR_SPI1RST | RCC_APB2RSTR_TIM1RST | RCC_APB2RSTR_ADCRST | RCC_APB2RSTR_SYSCFGRST;
RCC->AHBRSTR = 0;
RCC->APB1RSTR = 0;
RCC->APB2RSTR = 0;
// Enable the SYSCFG peripheral.
RCC->APB2ENR |= RCC_APB2ENR_SYSCFGEN;
// remap memory to 0 (only for STM32F0)
SYSCFG->CFGR1 = 0x01; __DSB(); __ISB();
SysMemBootJump = (void (*)(void)) (*((uint32_t *)(addr + 4)));
// set main stack pointer
__set_MSP(*((uint32_t *)addr));
// jump to bootloader
SysMemBootJump();
}

View File

@ -0,0 +1,182 @@
/*
* This file is part of the 3steppers project.
* Copyright 2021 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 __HARDWARE_H__
#define __HARDWARE_H__
#include <stm32f0.h>
// default CAN bus speed in kbaud
#define DEFAULT_CAN_SPEED (250)
#define CONCAT(a,b) a ## b
#define STR_HELPER(s) #s
#define STR(s) STR_HELPER(s)
/** Pinout:
---- Motors' encoders ---------------
PA0 Enc2a (motor2 encoder) - TIM2CH1/2 [AF2]
PA1 Enc2b [AF2]
PA8 Enc1a (motor1 encoder) - TIM1CH1/2 [AF2]
PA9 Enc1b [AF2]
PB4 Enc3a (motor3 encoder) - TIM3CH1/2 [AF1]
PB5 Enc3b [AF1]
---- Motors' clocks + PWM -----------
PA2 CLK1 (motor1 clock) - TIM15CH1 [AF0]
PA4 CLK2 (motor2 clock) - TIM14CH1 [AF4]
PA6 CLK3 (motor3 clock) - TIM16CH1 [AF5]
PA7 PWM (opendrain PWM, up to 12V) - TIM17CH1 [AF5]
---- GPIO out (push-pull) -----------
PB0 ~EN1 (motor1 not enable)
PB1 DIR1 (motor1 direction)
PB2 ~EN2 (motor2 not enable)
PB3 Buzzer (external buzzer or other non-inductive opendrain load up to 12V)
PB10 DIR2 (motor2 direction)
PB11 ~EN3 (motor3 not enable)
PB12 DIR3 (motor3 direction)
PB13 Ext0 (3 external outputs: 5V, up to 20mA)
PB14 Ext1
PB15 Ext2
PF0 Relay (10A 250VAC, 10A 30VDC)
---- GPIO in -----------------------
PA10 BTN1 (user button 1) - pullup
PA13 BTN2 (user button 2) - pullup
PA14 BTN3 (user button 3) - pullup
PA15 BTN4 (user button 4) - pullup
PC13 ESW1 (motor1 zero limit switch) - pulldown
PC14 ESW2 (motor2 zero limit switch) - pulldown
PC15 ESW3 (motor3 zero limit switch) - pulldown
---- ADC ----------------------------
PA3 ADC1 (ADC1 in, 0-3.3V) [ADC3]
PA5 ADC2 (ADC2 in, 0-3.3V) [ADC5]
---- USB ----------------------------
PA11 USBDM
PA12 USBDP
---- I2C ----------------------------
PB6 I2C SCL (external I2C bus, have internal pullups of 4.7kOhm to +3.3V) - I2C1 [AF1]
PB7 I2C SDA [AF1]
---- CAN ----------------------------
PB8 CAN Rx (external CAN bus, with local galvanic isolation) [AF4]
PB9 CAN Tx [AF4]
COMMON setup:
PORT FN AFR[1]idx
PA0 AF2
PA1 AF2
PA2 AF0
PA3 AI
PA4 AF4
PA5 AI
PA6 AF5
PA7 AF5
PA8 AF2 0
PA9 AF2 1
PA10 PU
PA11 USB
PA12 USB
PA13 PU
PA14 PU
PA15 PU
PB0 PP
PB1 PP
PB2 PP
PB3 PP
PB4 AF1
PB5 AF1
PB6 AF1
PB7 AF1
PB8 CAN
PB9 CAN
PB10 PP
PB11 PP
PB12 PP
PB13 PP
PB14 PP
PB15 PP
PC13 PD
PC14 PD
PC15 PD
PF0 PP
**/
// buzzer
#define BUZZERport (GPIOB)
#define BUZZERpin (1<<3)
// relay
#define RELAYport (GPIOF)
#define RELAYpin (1<<0)
// ON(RELAY), OFF(BUZZER) etc
#define ON(x) do{pin_set(CONCAT(x, port), CONCAT(x, pin));}while(0)
#define OFF(x) do{pin_clear(CONCAT(x, port), CONCAT(x, pin));}while(0)
#define TGL(x) do{pin_toggle(CONCAT(x, port), CONCAT(x, pin));}while(0)
#define CHK(x) (pin_read(CONCAT(x, port), CONCAT(x, pin)))
// max value of PWM
#define PWMMAX (255)
// max index of PWM channels
#define PWMCHMAX (0)
#define PWMset(val) do{TIM17->CCR1 = val;}while(0)
#define PWMget() (TIM17->CCR1)
// extpins amount
#define EXTNO (3)
extern volatile GPIO_TypeDef *EXTports[EXTNO];
extern const uint32_t EXTpins[EXTNO];
#define EXT_SET(x) do{ pin_set(EXTports[x], EXTpins[x]); }while(0)
#define EXT_CLEAR(x) do{ pin_clear(EXTports[x], EXTpins[x]); }while(0)
#define EXT_TOGGLE(x) do{ pin_toggle(EXTports[x], EXTpins[x]); }while(0)
#define EXT_CHK(x) (pin_read(EXTports[x], EXTpins[x]))
// Buttons amount
#define BTNSNO (4)
// Buttons ports & pins
extern volatile GPIO_TypeDef *BTNports[BTNSNO];
extern const uint32_t BTNpins[BTNSNO];
// state 1 - pressed, 0 - released (pin active is zero)
#define BTN_state(x) ((BTNports[x]->IDR & BTNpins[x]) ? 0 : 1)
// Limit switches
#define ESWNO (3)
// ESW ports & pins
extern volatile GPIO_TypeDef *ESWports[ESWNO];
extern const uint32_t ESWpins[ESWNO];
// state 1 - pressed, 0 - released (pin active is zero)
#define ESW_state(x) ((ESWports[x]->IDR & ESWpins[x]) ? 0 : 1)
// motors
#define MOTORSNO (3)
extern volatile GPIO_TypeDef *ENports[MOTORSNO];
extern const uint32_t ENpins[MOTORSNO];
#define MOTOR_EN(x) do{ pin_clear(ENports[x], ENpins[x]); }while(0)
#define MOTOR_DIS(x) do{ pin_set(ENports[x], ENpins[x]); }while(0)
extern volatile GPIO_TypeDef *DIRports[MOTORSNO];
extern const uint32_t DIRpins[MOTORSNO];
#define MOTOR_CW(x) do{ pin_set(DIRports[x], DIRpins[x]); }while(0)
#define MOTOR_CCW(x) do{ pin_clear(DIRports[x], DIRpins[x]); }while(0)
extern volatile uint32_t Tms;
void gpio_setup();
void iwdg_setup();
void timers_setup();
void pause_ms(uint32_t pause);
void Jump2Boot();
#endif // __HARDWARE_H__

View File

@ -1,12 +1,12 @@
%TF.GenerationSoftware,KiCad,Pcbnew,5.1.10*%
%TF.CreationDate,2021-10-03T17:58:42+03:00*%
%TF.CreationDate,2021-10-03T18:13:03+03:00*%
%TF.ProjectId,stm32,73746d33-322e-46b6-9963-61645f706362,rev?*%
%TF.SameCoordinates,Original*%
%TF.FileFunction,Copper,L2,Bot*%
%TF.FilePolarity,Positive*%
%FSLAX46Y46*%
G04 Gerber Fmt 4.6, Leading zero omitted, Abs format (unit mm)*
G04 Created by KiCad (PCBNEW 5.1.10) date 2021-10-03 17:58:42*
G04 Created by KiCad (PCBNEW 5.1.10) date 2021-10-03 18:13:03*
%MOMM*%
%LPD*%
G01*

View File

@ -1,12 +1,12 @@
%TF.GenerationSoftware,KiCad,Pcbnew,5.1.10*%
%TF.CreationDate,2021-10-03T17:58:42+03:00*%
%TF.CreationDate,2021-10-03T18:13:03+03:00*%
%TF.ProjectId,stm32,73746d33-322e-46b6-9963-61645f706362,rev?*%
%TF.SameCoordinates,Original*%
%TF.FileFunction,Soldermask,Bot*%
%TF.FilePolarity,Negative*%
%FSLAX46Y46*%
G04 Gerber Fmt 4.6, Leading zero omitted, Abs format (unit mm)*
G04 Created by KiCad (PCBNEW 5.1.10) date 2021-10-03 17:58:42*
G04 Created by KiCad (PCBNEW 5.1.10) date 2021-10-03 18:13:03*
%MOMM*%
%LPD*%
G01*

View File

@ -1,12 +1,12 @@
%TF.GenerationSoftware,KiCad,Pcbnew,5.1.10*%
%TF.CreationDate,2021-10-03T17:58:42+03:00*%
%TF.CreationDate,2021-10-03T18:13:03+03:00*%
%TF.ProjectId,stm32,73746d33-322e-46b6-9963-61645f706362,rev?*%
%TF.SameCoordinates,Original*%
%TF.FileFunction,Paste,Bot*%
%TF.FilePolarity,Positive*%
%FSLAX46Y46*%
G04 Gerber Fmt 4.6, Leading zero omitted, Abs format (unit mm)*
G04 Created by KiCad (PCBNEW 5.1.10) date 2021-10-03 17:58:42*
G04 Created by KiCad (PCBNEW 5.1.10) date 2021-10-03 18:13:03*
%MOMM*%
%LPD*%
G01*

File diff suppressed because it is too large Load Diff

View File

@ -1,11 +1,11 @@
%TF.GenerationSoftware,KiCad,Pcbnew,5.1.10*%
%TF.CreationDate,2021-10-03T17:58:42+03:00*%
%TF.CreationDate,2021-10-03T18:13:03+03:00*%
%TF.ProjectId,stm32,73746d33-322e-46b6-9963-61645f706362,rev?*%
%TF.SameCoordinates,Original*%
%TF.FileFunction,Profile,NP*%
%FSLAX46Y46*%
G04 Gerber Fmt 4.6, Leading zero omitted, Abs format (unit mm)*
G04 Created by KiCad (PCBNEW 5.1.10) date 2021-10-03 17:58:42*
G04 Created by KiCad (PCBNEW 5.1.10) date 2021-10-03 18:13:03*
%MOMM*%
%LPD*%
G01*

View File

@ -1,12 +1,12 @@
%TF.GenerationSoftware,KiCad,Pcbnew,5.1.10*%
%TF.CreationDate,2021-10-03T17:58:42+03:00*%
%TF.CreationDate,2021-10-03T18:13:03+03:00*%
%TF.ProjectId,stm32,73746d33-322e-46b6-9963-61645f706362,rev?*%
%TF.SameCoordinates,Original*%
%TF.FileFunction,Copper,L1,Top*%
%TF.FilePolarity,Positive*%
%FSLAX46Y46*%
G04 Gerber Fmt 4.6, Leading zero omitted, Abs format (unit mm)*
G04 Created by KiCad (PCBNEW 5.1.10) date 2021-10-03 17:58:42*
G04 Created by KiCad (PCBNEW 5.1.10) date 2021-10-03 18:13:03*
%MOMM*%
%LPD*%
G01*

View File

@ -1,12 +1,12 @@
%TF.GenerationSoftware,KiCad,Pcbnew,5.1.10*%
%TF.CreationDate,2021-10-03T17:58:42+03:00*%
%TF.CreationDate,2021-10-03T18:13:03+03:00*%
%TF.ProjectId,stm32,73746d33-322e-46b6-9963-61645f706362,rev?*%
%TF.SameCoordinates,Original*%
%TF.FileFunction,Soldermask,Top*%
%TF.FilePolarity,Negative*%
%FSLAX46Y46*%
G04 Gerber Fmt 4.6, Leading zero omitted, Abs format (unit mm)*
G04 Created by KiCad (PCBNEW 5.1.10) date 2021-10-03 17:58:42*
G04 Created by KiCad (PCBNEW 5.1.10) date 2021-10-03 18:13:03*
%MOMM*%
%LPD*%
G01*

View File

@ -1,12 +1,12 @@
%TF.GenerationSoftware,KiCad,Pcbnew,5.1.10*%
%TF.CreationDate,2021-10-03T17:58:42+03:00*%
%TF.CreationDate,2021-10-03T18:13:03+03:00*%
%TF.ProjectId,stm32,73746d33-322e-46b6-9963-61645f706362,rev?*%
%TF.SameCoordinates,Original*%
%TF.FileFunction,Paste,Top*%
%TF.FilePolarity,Positive*%
%FSLAX46Y46*%
G04 Gerber Fmt 4.6, Leading zero omitted, Abs format (unit mm)*
G04 Created by KiCad (PCBNEW 5.1.10) date 2021-10-03 17:58:42*
G04 Created by KiCad (PCBNEW 5.1.10) date 2021-10-03 18:13:03*
%MOMM*%
%LPD*%
G01*

View File

@ -1,12 +1,12 @@
%TF.GenerationSoftware,KiCad,Pcbnew,5.1.10*%
%TF.CreationDate,2021-10-03T17:58:42+03:00*%
%TF.CreationDate,2021-10-03T18:13:03+03:00*%
%TF.ProjectId,stm32,73746d33-322e-46b6-9963-61645f706362,rev?*%
%TF.SameCoordinates,Original*%
%TF.FileFunction,Legend,Top*%
%TF.FilePolarity,Positive*%
%FSLAX46Y46*%
G04 Gerber Fmt 4.6, Leading zero omitted, Abs format (unit mm)*
G04 Created by KiCad (PCBNEW 5.1.10) date 2021-10-03 17:58:42*
G04 Created by KiCad (PCBNEW 5.1.10) date 2021-10-03 18:13:03*
%MOMM*%
%LPD*%
G01*
@ -213,429 +213,429 @@ X115903285Y-70810380D01*
X115808047Y-70762761D01*
X115760428Y-70715142D01*
%TO.C,U5*%
X116586200Y-111307800D02*
X116586200Y-111332800D01*
X120736200Y-111307800D02*
X120736200Y-111412800D01*
X120736200Y-121457800D02*
X120736200Y-121352800D01*
X116586200Y-111332800D02*
X115211200Y-111332800D01*
X116586200Y-121457800D02*
X116586200Y-121352800D01*
X120736200Y-121457800D01*
X116586200Y-111307800D02*
X120736200Y-111307800D01*
X116586200Y-121457800D02*
X120736200Y-121457800D01*
X116586200Y-111332800D02*
X115211200Y-111332800D01*
X116586200Y-121352800D01*
X120736200Y-121457800D02*
X120736200Y-121352800D01*
X120736200Y-111307800D02*
X120736200Y-111412800D01*
X116586200Y-111307800D02*
X116586200Y-111332800D01*
D12*
%TO.C,C1*%
X94235748Y-73127800D02*
X94758252Y-73127800D01*
X94235748Y-74547800D02*
X94758252Y-74547800D01*
X94235748Y-73127800D02*
X94758252Y-73127800D01*
%TO.C,C5*%
X104706267Y-91082400D02*
X104363733Y-91082400D01*
X104706267Y-92102400D02*
X104363733Y-92102400D01*
X104706267Y-91082400D02*
X104363733Y-91082400D01*
%TO.C,C6*%
X116076000Y-94419267D02*
X116076000Y-94076733D01*
X117096000Y-94419267D02*
X117096000Y-94076733D01*
X116076000Y-94419267D02*
X116076000Y-94076733D01*
%TO.C,C7*%
X113380733Y-105285000D02*
X113723267Y-105285000D01*
X113380733Y-104265000D02*
X113723267Y-104265000D01*
X113380733Y-105285000D02*
X113723267Y-105285000D01*
%TO.C,C4*%
X88673148Y-74547800D02*
X89195652Y-74547800D01*
X88673148Y-73127800D02*
X89195652Y-73127800D01*
X88673148Y-74547800D02*
X89195652Y-74547800D01*
%TO.C,C8*%
X101602000Y-98775733D02*
X101602000Y-99118267D01*
X100582000Y-98775733D02*
X100582000Y-99118267D01*
X101602000Y-98775733D02*
X101602000Y-99118267D01*
%TO.C,C9*%
X152833800Y-114800533D02*
X152833800Y-115143067D01*
X151813800Y-114800533D02*
X151813800Y-115143067D01*
X152833800Y-114800533D02*
X152833800Y-115143067D01*
%TO.C,C11*%
X131643333Y-106275600D02*
X131985867Y-106275600D01*
X131643333Y-105255600D02*
X131985867Y-105255600D01*
X131643333Y-106275600D02*
X131985867Y-106275600D01*
%TO.C,C12*%
X87522300Y-97759800D02*
X91607300Y-97759800D01*
X87522300Y-95889800D02*
X87522300Y-97759800D01*
X91607300Y-95889800D02*
X87522300Y-95889800D01*
X87522300Y-95889800D02*
X87522300Y-97759800D01*
X87522300Y-97759800D02*
X91607300Y-97759800D01*
%TO.C,C15*%
X131109933Y-118670800D02*
X131452467Y-118670800D01*
X131109933Y-117650800D02*
X131452467Y-117650800D01*
X131109933Y-118670800D02*
X131452467Y-118670800D01*
%TO.C,D10*%
X62557200Y-96554400D02*
X70107200Y-96554400D01*
X62557200Y-100854400D01*
X62557200Y-100854400D02*
X70107200Y-100854400D01*
X62557200Y-96554400D02*
X62557200Y-100854400D01*
X70107200Y-96554400D01*
D11*
%TO.C,D9*%
X145712000Y-90256600D02*
X147112000Y-90256600D01*
X145712000Y-90306600D02*
X145712000Y-90256600D01*
X141562000Y-90306600D02*
X141562000Y-90161600D01*
X141562000Y-85156600D02*
X141562000Y-85301600D01*
X145712000Y-85156600D02*
X141562000Y-85156600D01*
X145712000Y-85301600D01*
X145712000Y-90306600D02*
X141562000Y-90306600D01*
X145712000Y-85156600D02*
X145712000Y-85301600D01*
X141562000Y-85156600D02*
X141562000Y-85301600D01*
X141562000Y-90306600D02*
X141562000Y-90161600D01*
X145712000Y-90306600D02*
X145712000Y-90256600D01*
X141562000Y-85156600D01*
X145712000Y-90256600D02*
X147112000Y-90256600D01*
D12*
%TO.C,D11*%
X146681800Y-117048400D02*
X143821800Y-117048400D01*
X146681800Y-118968400D02*
X146681800Y-117048400D01*
X143821800Y-118968400D02*
X146681800Y-118968400D01*
X146681800Y-118968400D02*
X146681800Y-117048400D01*
X146681800Y-117048400D02*
X143821800Y-117048400D01*
%TO.C,Q5*%
X148254400Y-123383600D02*
X148254400Y-119933600D01*
X148254400Y-123383600D02*
X148254400Y-125333600D01*
X143134400Y-123383600D02*
X143134400Y-121433600D01*
X143134400Y-123383600D02*
X143134400Y-125333600D01*
X143134400Y-123383600D02*
X143134400Y-121433600D01*
X148254400Y-123383600D02*
X148254400Y-125333600D01*
X148254400Y-123383600D02*
X148254400Y-119933600D01*
%TO.C,R2*%
X94007400Y-117822767D02*
X94007400Y-117480233D01*
X92987400Y-117822767D02*
X92987400Y-117480233D01*
X94007400Y-117822767D02*
X94007400Y-117480233D01*
%TO.C,R14*%
X102922800Y-77691133D02*
X102922800Y-78033667D01*
X101902800Y-77691133D02*
X101902800Y-78033667D01*
X102922800Y-77691133D02*
X102922800Y-78033667D01*
%TO.C,R15*%
X103909400Y-77691133D02*
X103909400Y-78033667D01*
X104929400Y-77691133D02*
X104929400Y-78033667D01*
X103909400Y-77691133D02*
X103909400Y-78033667D01*
%TO.C,R20*%
X82466333Y-97280000D02*
X82808867Y-97280000D01*
X82466333Y-98300000D02*
X82808867Y-98300000D01*
X82466333Y-97280000D02*
X82808867Y-97280000D01*
%TO.C,R21*%
X82466333Y-100205000D02*
X82808867Y-100205000D01*
X82466333Y-99185000D02*
X82808867Y-99185000D01*
X82466333Y-100205000D02*
X82808867Y-100205000D01*
%TO.C,R30*%
X136710267Y-87958200D02*
X136367733Y-87958200D01*
X136710267Y-88978200D02*
X136367733Y-88978200D01*
X136710267Y-87958200D02*
X136367733Y-87958200D01*
%TO.C,R31*%
X136710267Y-86358000D02*
X136367733Y-86358000D01*
X136710267Y-87378000D02*
X136367733Y-87378000D01*
X136710267Y-86358000D02*
X136367733Y-86358000D01*
%TO.C,R19*%
X83046400Y-76559164D02*
X83046400Y-75355036D01*
X80326400Y-76559164D02*
X80326400Y-75355036D01*
X83046400Y-76559164D02*
X83046400Y-75355036D01*
%TO.C,R1*%
X90980800Y-117822767D02*
X90980800Y-117480233D01*
X92000800Y-117822767D02*
X92000800Y-117480233D01*
X90980800Y-117822767D02*
X90980800Y-117480233D01*
%TO.C,R34*%
X140695467Y-118518400D02*
X140352933Y-118518400D01*
X140695467Y-117498400D02*
X140352933Y-117498400D01*
X140695467Y-118518400D02*
X140352933Y-118518400D01*
%TO.C,R16*%
X121502900Y-129672233D02*
X121502900Y-130014767D01*
X120482900Y-129672233D02*
X120482900Y-130014767D01*
X121502900Y-129672233D02*
X121502900Y-130014767D01*
%TO.C,R18*%
X121699233Y-132039900D02*
X122041767Y-132039900D01*
X121699233Y-133059900D02*
X122041767Y-133059900D01*
X121699233Y-132039900D02*
X122041767Y-132039900D01*
%TO.C,TP1*%
X121479000Y-100974200D02*
X122809000Y-98314200D02*
X124139000Y-98314200D01*
X124139000Y-98314200D02*
X124139000Y-99644200D01*
X124139000Y-100854200D02*
X124139000Y-100974200D01*
X121479000Y-100854200D02*
X121479000Y-100974200D01*
X124139000Y-100854200D02*
X121479000Y-100974200D02*
X124139000Y-100974200D01*
X124139000Y-98314200D02*
X124139000Y-99644200D01*
X122809000Y-98314200D02*
X124139000Y-98314200D01*
%TO.C,TP2*%
X126568200Y-118481800D02*
X127898200Y-118481800D01*
X127898200Y-118481800D02*
X127898200Y-119811800D01*
X127898200Y-121021800D02*
X125238200Y-121141800D02*
X127898200Y-121141800D01*
X125238200Y-121021800D02*
X125238200Y-121141800D01*
X125238200Y-121141800D02*
X127898200Y-121021800D02*
X127898200Y-121141800D01*
X127898200Y-118481800D02*
X127898200Y-119811800D01*
X126568200Y-118481800D02*
X127898200Y-118481800D01*
D11*
%TO.C,U4*%
X104953000Y-111332800D02*
X103578000Y-111332800D01*
X104953000Y-111307800D02*
X104953000Y-111332800D01*
X109103000Y-111307800D02*
X109103000Y-111412800D01*
X109103000Y-121457800D02*
X109103000Y-121352800D01*
X104953000Y-121457800D02*
X109103000Y-121457800D01*
X104953000Y-121352800D01*
X104953000Y-111307800D02*
X109103000Y-111307800D01*
X104953000Y-121457800D02*
X104953000Y-121352800D01*
X109103000Y-121457800D02*
X109103000Y-121352800D01*
X109103000Y-111307800D02*
X109103000Y-111412800D01*
X104953000Y-111307800D02*
X104953000Y-111332800D01*
X109103000Y-121457800D01*
X104953000Y-111332800D02*
X103578000Y-111332800D01*
D12*
%TO.C,U2*%
X105892500Y-94634000D02*
X104602500Y-94634000D01*
X105892500Y-94184000D02*
X105892500Y-94634000D01*
X106342500Y-94184000D02*
X105892500Y-94184000D01*
X113112500Y-94184000D02*
X113112500Y-94634000D01*
X112662500Y-94184000D02*
X113112500Y-94184000D01*
X105892500Y-101404000D02*
X105892500Y-100954000D01*
X106342500Y-101404000D02*
X105892500Y-101404000D01*
X113112500Y-101404000D02*
X113112500Y-100954000D01*
X112662500Y-101404000D02*
X113112500Y-101404000D01*
X113112500Y-101404000D02*
X113112500Y-100954000D01*
X106342500Y-101404000D02*
X105892500Y-101404000D01*
X105892500Y-101404000D02*
X105892500Y-100954000D01*
X112662500Y-94184000D02*
X113112500Y-94184000D01*
X113112500Y-94184000D02*
X113112500Y-94634000D01*
X106342500Y-94184000D02*
X105892500Y-94184000D01*
X105892500Y-94184000D02*
X105892500Y-94634000D01*
X105892500Y-94634000D02*
X104602500Y-94634000D01*
%TO.C,R4*%
X149912800Y-71419933D02*
X149912800Y-71762467D01*
X148892800Y-71419933D02*
X148892800Y-71762467D01*
X149912800Y-71419933D02*
X149912800Y-71762467D01*
%TO.C,R5*%
X147944300Y-77830467D02*
X147944300Y-77487933D01*
X146924300Y-77830467D02*
X146924300Y-77487933D01*
X147944300Y-77830467D02*
X147944300Y-77487933D01*
%TO.C,R6*%
X144879600Y-77830467D02*
X144879600Y-77487933D01*
X145899600Y-77830467D02*
X145899600Y-77487933D01*
X144879600Y-77830467D02*
X144879600Y-77487933D01*
%TO.C,R7*%
X137543000Y-71419933D02*
X137543000Y-71762467D01*
X136523000Y-71419933D02*
X136523000Y-71762467D01*
X137543000Y-71419933D02*
X137543000Y-71762467D01*
%TO.C,R8*%
X135511000Y-77830467D02*
X135511000Y-77487933D01*
X134491000Y-77830467D02*
X134491000Y-77487933D01*
X135511000Y-77830467D02*
X135511000Y-77487933D01*
%TO.C,R9*%
X132484400Y-77830467D02*
X132484400Y-77487933D01*
X133504400Y-77830467D02*
X133504400Y-77487933D01*
X132484400Y-77830467D02*
X132484400Y-77487933D01*
%TO.C,R10*%
X124077000Y-71419933D02*
X124077000Y-71762467D01*
X125097000Y-71419933D02*
X125097000Y-71762467D01*
X124077000Y-71419933D02*
X124077000Y-71762467D01*
%TO.C,R11*%
X122095800Y-77830467D02*
X122095800Y-77487933D01*
X123115800Y-77830467D02*
X123115800Y-77487933D01*
X122095800Y-77830467D02*
X122095800Y-77487933D01*
%TO.C,R12*%
X121083800Y-77830467D02*
X121083800Y-77487933D01*
X120063800Y-77830467D02*
X120063800Y-77487933D01*
X121083800Y-77830467D02*
X121083800Y-77487933D01*
%TO.C,R22*%
X89068500Y-107589367D02*
X89068500Y-107246833D01*
X88048500Y-107589367D02*
X88048500Y-107246833D01*
X89068500Y-107589367D02*
X89068500Y-107246833D01*
%TO.C,R23*%
X91024300Y-107589367D02*
X91024300Y-107246833D01*
X90004300Y-107589367D02*
X90004300Y-107246833D01*
X91024300Y-107589367D02*
X91024300Y-107246833D01*
%TO.C,R24*%
X93005500Y-107589367D02*
X93005500Y-107246833D01*
X91985500Y-107589367D02*
X91985500Y-107246833D01*
X93005500Y-107589367D02*
X93005500Y-107246833D01*
%TO.C,R25*%
X93966700Y-107589367D02*
X93966700Y-107246833D01*
X94986700Y-107589367D02*
X94986700Y-107246833D01*
X93966700Y-107589367D02*
X93966700Y-107246833D01*
%TO.C,R26*%
X127078200Y-87241167D02*
X127078200Y-86898633D01*
X126058200Y-87241167D02*
X126058200Y-86898633D01*
X127078200Y-87241167D02*
X127078200Y-86898633D01*
%TO.C,R27*%
X123988100Y-87241167D02*
X123988100Y-86898633D01*
X125008100Y-87241167D02*
X125008100Y-86898633D01*
X123988100Y-87241167D02*
X123988100Y-86898633D01*
%TO.C,R28*%
X123103100Y-87241167D02*
X123103100Y-86898633D01*
X122083100Y-87241167D02*
X122083100Y-86898633D01*
X123103100Y-87241167D02*
X123103100Y-86898633D01*
%TO.C,R29*%
X120063800Y-87241167D02*
X120063800Y-86898633D01*
X121083800Y-87241167D02*
X121083800Y-86898633D01*
X120063800Y-87241167D02*
X120063800Y-86898633D01*
%TO.C,R32*%
X110660333Y-83741800D02*
X111002867Y-83741800D01*
X110660333Y-84761800D02*
X111002867Y-84761800D01*
X110660333Y-83741800D02*
X111002867Y-83741800D01*
%TO.C,R33*%
X113053400Y-83545467D02*
X113053400Y-83202933D01*
X114073400Y-83545467D02*
X114073400Y-83202933D01*
X113053400Y-83545467D02*
X113053400Y-83202933D01*
%TO.C,TP3*%
X99584200Y-104123800D02*
X100914200Y-101463800D02*
X102244200Y-101463800D01*
X102244200Y-101463800D02*
X102244200Y-102793800D01*
X102244200Y-104003800D02*
X102244200Y-104123800D01*
X99584200Y-104003800D02*
X99584200Y-104123800D01*
X102244200Y-104003800D02*
X99584200Y-104123800D02*
X102244200Y-104123800D01*
X102244200Y-101463800D02*
X102244200Y-102793800D01*
X100914200Y-101463800D02*
X102244200Y-101463800D01*
%TO.C,TP4*%
X134569200Y-94377200D02*
X135899200Y-94377200D01*
X135899200Y-94377200D02*
X135899200Y-95707200D01*
X135899200Y-96917200D02*
X133239200Y-97037200D02*
X135899200Y-97037200D01*
X133239200Y-96917200D02*
X133239200Y-97037200D01*
X133239200Y-97037200D02*
X135899200Y-96917200D02*
X135899200Y-97037200D01*
X135899200Y-94377200D02*
X135899200Y-95707200D01*
X134569200Y-94377200D02*
X135899200Y-94377200D01*
%TO.C,D8*%
X86041200Y-81224000D02*
X86041200Y-82154000D01*
X86041200Y-84384000D02*
X86041200Y-83454000D01*
X87501200Y-81224000D01*
X86041200Y-84384000D02*
X88201200Y-84384000D01*
X86041200Y-84384000D02*
X86041200Y-83454000D01*
X86041200Y-81224000D02*
X87501200Y-81224000D01*
X86041200Y-82154000D01*
%TO.C,Q2*%
X125739300Y-131488300D02*
X125739300Y-130558300D01*
X125739300Y-128328300D02*
X125739300Y-129258300D01*
X124279300Y-131488300D01*
X125739300Y-128328300D02*
X122579300Y-128328300D01*
X125739300Y-128328300D02*
X125739300Y-129258300D01*
X125739300Y-131488300D02*
X124279300Y-131488300D01*
X125739300Y-130558300D01*
%TO.C,Q3*%
X76480000Y-97165000D02*
X76480000Y-98095000D01*
X76480000Y-100325000D02*
X76480000Y-99395000D01*
X77940000Y-97165000D01*
X76480000Y-100325000D02*
X79640000Y-100325000D01*
X76480000Y-100325000D02*
X76480000Y-99395000D01*
X76480000Y-97165000D02*
X77940000Y-97165000D01*
X76480000Y-98095000D01*
%TO.C,Q4*%
X112476400Y-79276800D02*
X112476400Y-80736800D01*
X109316400Y-79276800D02*
X109316400Y-82436800D01*
X111546400Y-79276800D01*
X109316400Y-79276800D02*
X110246400Y-79276800D01*
X109316400Y-79276800D02*
X109316400Y-82436800D01*
X112476400Y-79276800D02*
X111546400Y-79276800D01*
X112476400Y-80736800D01*
%TO.C,U6*%
X126993600Y-114203000D02*
X128253600Y-114203000D01*
X133813600Y-114203000D02*
X132553600Y-114203000D01*
X126993600Y-110443000D02*
X126993600Y-114203000D01*
X133813600Y-108193000D02*
X133813600Y-114203000D01*
X126993600Y-110443000D02*
X126993600Y-114203000D01*
X133813600Y-114203000D02*
X132553600Y-114203000D01*
X126993600Y-114203000D02*
X128253600Y-114203000D01*
%TO.C,D7*%
X127737000Y-132517000D02*
X124877000Y-132517000D01*
X124877000Y-132517000D02*
X124877000Y-134437000D01*
X124877000Y-134437000D02*
X127737000Y-134437000D01*
X124877000Y-132517000D02*
X124877000Y-134437000D01*
X127737000Y-132517000D02*
X124877000Y-132517000D01*
%TO.C,JP1*%
X109456000Y-70831200D02*
X113556000Y-70831200D01*
X113556000Y-70831200D02*
X113556000Y-72831200D01*
X113556000Y-72831200D02*
X109456000Y-72831200D01*
X109456000Y-72831200D02*
X109456000Y-70831200D01*
X110206000Y-73031200D02*
X109906000Y-73331200D01*
X110506000Y-73331200D01*
X109906000Y-73331200D02*
X110506000Y-73331200D01*
X110206000Y-73031200D02*
X110506000Y-73331200D01*
X109906000Y-73331200D01*
X109456000Y-72831200D02*
X109456000Y-70831200D01*
X113556000Y-72831200D02*
X109456000Y-72831200D01*
X113556000Y-70831200D02*
X113556000Y-72831200D01*
X109456000Y-70831200D02*
X113556000Y-70831200D01*
%TO.C,D2*%
X131866200Y-77576800D02*
X129006200Y-77576800D01*
X131866200Y-79496800D02*
X131866200Y-77576800D01*
X129006200Y-79496800D02*
X131866200Y-79496800D01*
X131866200Y-79496800D02*
X131866200Y-77576800D01*
X131866200Y-77576800D02*
X129006200Y-77576800D01*
%TO.C,D5*%
X138963800Y-77576800D02*
X136103800Y-77576800D01*
X136103800Y-77576800D02*
X136103800Y-79496800D01*
X136103800Y-79496800D02*
X138963800Y-79496800D01*
X136103800Y-77576800D02*
X136103800Y-79496800D01*
X138963800Y-77576800D02*
X136103800Y-77576800D01*
%TO.C,U5*%
D11*
X117899295Y-109835180D02*

View File

@ -7,7 +7,7 @@
"Application": "Pcbnew",
"Version": "5.1.10"
},
"CreationDate": "2021-10-03T17:58:42+03:00"
"CreationDate": "2021-10-03T18:13:03+03:00"
},
"GeneralSpecs":
{

117
F0-nolib/3steppersLB/main.c Normal file
View File

@ -0,0 +1,117 @@
/*
* This file is part of the canrelay project.
* Copyright 2021 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"
#include "buttons.h"
#include "can.h"
#include "custom_buttons.h"
#include "flash.h"
#include "hardware.h"
#include "strfunct.h"
#include "usb.h"
#include "usb_lib.h"
volatile uint32_t Tms = 0;
/* Called when systick fires */
void sys_tick_handler(void){
++Tms;
}
#define USBBUF 63
// usb getline
static char *get_USB(){
static char tmpbuf[USBBUF+1], *curptr = tmpbuf;
static int rest = USBBUF;
uint8_t x = USB_receive((uint8_t*)curptr);
if(!x) return NULL;
curptr[x] = 0;
if(x == 1 && *curptr == 0x7f){ // backspace
if(curptr > tmpbuf){
--curptr;
USND("\b \b");
}
return NULL;
}
USB_sendstr(curptr); // echo
if(curptr[x-1] == '\n'){ // || curptr[x-1] == '\r'){
curptr = tmpbuf;
rest = USBBUF;
// omit empty lines
if(tmpbuf[0] == '\n') return NULL;
// and wrong empty lines
if(tmpbuf[0] == '\r' && tmpbuf[1] == '\n') return NULL;
return tmpbuf;
}
curptr += x; rest -= x;
if(rest <= 0){ // buffer overflow
curptr = tmpbuf;
rest = USBBUF;
}
return NULL;
}
int main(void){
uint8_t ctr, len;
CAN_message *can_mesg;
char *txt;
sysreset();
SysTick_Config(6000, 1);
flashstorage_init();
gpio_setup();
USB_setup();
CAN_setup(DEFAULT_CAN_SPEED);
adc_setup();
timers_setup();
RCC->CSR |= RCC_CSR_RMVF; // remove reset flags
iwdg_setup();
while (1){
IWDG->KR = IWDG_REFRESH; // refresh watchdog
process_keys();
custom_buttons_process();
can_proc();
usb_proc();
if(CAN_get_status() == CAN_FIFO_OVERRUN){
SEND("CAN bus fifo overrun occured!\n");
sendbuf();
}
while((can_mesg = CAN_messagebuf_pop())){
if(can_mesg && isgood(can_mesg->ID)){
if(ShowMsgs){ // new data in buff
IWDG->KR = IWDG_REFRESH;
len = can_mesg->length;
printu(Tms);
SEND(" #");
printuhex(can_mesg->ID);
for(ctr = 0; ctr < len; ++ctr){
SEND(" ");
printuhex(can_mesg->data[ctr]);
}
newline(); sendbuf();
}
}
}
if((txt = get_USB())){
IWDG->KR = IWDG_REFRESH;
cmd_parser(txt);
}
}
return 0;
}

View File

@ -0,0 +1,626 @@
/*
* This file is part of the canrelay project.
* Copyright 2021 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"
#include "buttons.h"
#include "can.h"
#include "hardware.h"
#include "proto.h"
#include "usb.h"
#include <string.h> // strlen
extern volatile uint8_t canerror;
uint8_t ShowMsgs = 0;
uint16_t Ignore_IDs[IGN_SIZE];
uint8_t IgnSz = 0;
static char buff[BUFSZ+1], *bptr = buff;
static uint8_t blen = 0;
void sendbuf(){
IWDG->KR = IWDG_REFRESH;
if(blen == 0) return;
*bptr = 0;
USB_sendstr(buff);
bptr = buff;
blen = 0;
}
void bufputchar(char ch){
if(blen > BUFSZ-1){
sendbuf();
}
*bptr++ = ch;
++blen;
}
void addtobuf(const char *txt){
IWDG->KR = IWDG_REFRESH;
while(*txt) bufputchar(*txt++);
}
char *omit_spaces(const char *buf){
while(*buf){
if(*buf > ' ') break;
++buf;
}
return (char*) buf;
}
// THERE'S NO OVERFLOW PROTECTION IN NUMBER READ PROCEDURES!
// read decimal number
static char *getdec(const char *buf, uint32_t *N){
uint32_t num = 0;
while(*buf){
char c = *buf;
if(c < '0' || c > '9'){
break;
}
num *= 10;
num += c - '0';
++buf;
}
*N = num;
return (char *)buf;
}
// read hexadecimal number (without 0x prefix!)
static char *gethex(const char *buf, uint32_t *N){
uint32_t num = 0;
while(*buf){
char c = *buf;
uint8_t M = 0;
if(c >= '0' && c <= '9'){
M = '0';
}else if(c >= 'A' && c <= 'F'){
M = 'A' - 10;
}else if(c >= 'a' && c <= 'f'){
M = 'a' - 10;
}
if(M){
num <<= 4;
num += c - M;
}else{
break;
}
++buf;
}
*N = num;
return (char *)buf;
}
// read binary number (without 0b prefix!)
static char *getbin(const char *buf, uint32_t *N){
uint32_t num = 0;
while(*buf){
char c = *buf;
if(c < '0' || c > '1'){
break;
}
num <<= 1;
if(c == '1') num |= 1;
++buf;
}
*N = num;
return (char *)buf;
}
/**
* @brief getnum - read uint32_t from string (dec, hex or bin: 127, 0x7f, 0b1111111)
* @param buf - buffer with number and so on
* @param N - the number read
* @return pointer to first non-number symbol in buf (if it is == buf, there's no number)
*/
char *getnum(const char *txt, uint32_t *N){
if(*txt == '0'){
if(txt[1] == 'x' || txt[1] == 'X') return gethex(txt+2, N);
if(txt[1] == 'b' || txt[1] == 'B') return getbin(txt+2, N);
}
return getdec(txt, N);
}
// parse `txt` to CAN_message
static CAN_message *parseCANmsg(char *txt){
static CAN_message canmsg;
//SEND("CAN command with arguments:\n");
uint32_t N;
char *n;
int ctr = -1;
canmsg.ID = 0xffff;
do{
txt = omit_spaces(txt);
n = getnum(txt, &N);
if(txt == n) break;
txt = n;
if(ctr == -1){
if(N > 0x7ff){
SEND("ID should be 11-bit number!\n");
return NULL;
}
canmsg.ID = (uint16_t)(N&0x7ff);
//SEND("ID="); printuhex(canmsg.ID); newline();
ctr = 0;
continue;
}
if(ctr > 7){
SEND("ONLY 8 data bytes allowed!\n");
return NULL;
}
if(N > 0xff){
SEND("Every data portion is a byte!\n");
return NULL;
}
canmsg.data[ctr++] = (uint8_t)(N&0xff);
}while(1);
if(canmsg.ID == 0xffff){
SEND("NO ID given, send nothing!\n");
return NULL;
}
SEND("Message parsed OK\n");
sendbuf();
canmsg.length = (uint8_t) ctr;
return &canmsg;
}
// send command, format: ID (hex/bin/dec) data bytes (up to 8 bytes, space-delimeted)
TRUE_INLINE void sendCANcommand(char *txt){
CAN_message *msg = parseCANmsg(txt);
if(!msg) return;
uint32_t N = 1000;
while(CAN_BUSY == can_send(msg->data, msg->length, msg->ID)){
if(--N == 0) break;
}
}
TRUE_INLINE void CANini(char *txt){
txt = omit_spaces(txt);
uint32_t N;
char *n = getnum(txt, &N);
if(txt == n){
SEND("No speed given");
return;
}
if(N < 50){
SEND("Lowest speed is 50kbps");
return;
}else if(N > 3000){
SEND("Highest speed is 3000kbps");
return;
}
CAN_reinit((uint16_t)N);
SEND("Reinit CAN bus with speed ");
printu(N); SEND("kbps");
}
TRUE_INLINE void addIGN(char *txt){
if(IgnSz == IGN_SIZE){
MSG("Ignore buffer is full");
return;
}
txt = omit_spaces(txt);
uint32_t N;
char *n = getnum(txt, &N);
if(txt == n){
SEND("No ID given");
return;
}
if(N == CANID){
SEND("You can't ignore self ID!");
return;
}
if(N > 0x7ff){
SEND("ID should be 11-bit number!");
return;
}
Ignore_IDs[IgnSz++] = (uint16_t)(N & 0x7ff);
SEND("Added ID "); printu(N);
SEND("\nIgn buffer size: "); printu(IgnSz);
}
TRUE_INLINE void print_ign_buf(){
if(IgnSz == 0){
SEND("Ignore buffer is empty");
return;
}
SEND("Ignored IDs:\n");
for(int i = 0; i < IgnSz; ++i){
printu(i);
SEND(": ");
printuhex(Ignore_IDs[i]);
newline();
}
}
// print ID/mask of CAN->sFilterRegister[x] half
static void printID(uint16_t FRn){
if(FRn & 0x1f) return; // trash
printuhex(FRn >> 5);
}
/*
Can filtering: FSCx=0 (CAN->FS1R) -> 16-bit identifiers
CAN->FMR = (sb)<<8 | FINIT - init filter in starting bank sb
CAN->FFA1R FFAx = 1 -> FIFO1, 0 -> FIFO0
CAN->FA1R FACTx=1 - filter active
MASK: FBMx=0 (CAN->FM1R), two filters (n in FR1 and n+1 in FR2)
ID: CAN->sFilterRegister[x].FRn[0..15]
MASK: CAN->sFilterRegister[x].FRn[16..31]
FR bits: STID[10:0] RTR IDE EXID[17:15]
LIST: FBMx=1, four filters (n&n+1 in FR1, n+2&n+3 in FR2)
IDn: CAN->sFilterRegister[x].FRn[0..15]
IDn+1: CAN->sFilterRegister[x].FRn[16..31]
*/
TRUE_INLINE void list_filters(){
uint32_t fa = CAN->FA1R, ctr = 0, mask = 1;
while(fa){
if(fa & 1){
SEND("Filter "); printu(ctr); SEND(", FIFO");
if(CAN->FFA1R & mask) SEND("1");
else SEND("0");
SEND(" in ");
if(CAN->FM1R & mask){ // up to 4 filters in LIST mode
SEND("LIST mode, IDs: ");
printID(CAN->sFilterRegister[ctr].FR1 & 0xffff);
SEND(" ");
printID(CAN->sFilterRegister[ctr].FR1 >> 16);
SEND(" ");
printID(CAN->sFilterRegister[ctr].FR2 & 0xffff);
SEND(" ");
printID(CAN->sFilterRegister[ctr].FR2 >> 16);
}else{ // up to 2 filters in MASK mode
SEND("MASK mode: ");
if(!(CAN->sFilterRegister[ctr].FR1&0x1f)){
SEND("ID="); printID(CAN->sFilterRegister[ctr].FR1 & 0xffff);
SEND(", MASK="); printID(CAN->sFilterRegister[ctr].FR1 >> 16);
SEND(" ");
}
if(!(CAN->sFilterRegister[ctr].FR2&0x1f)){
SEND("ID="); printID(CAN->sFilterRegister[ctr].FR2 & 0xffff);
SEND(", MASK="); printID(CAN->sFilterRegister[ctr].FR2 >> 16);
}
}
newline();
}
fa >>= 1;
++ctr;
mask <<= 1;
}
sendbuf();
}
/**
* @brief add_filter - add/modify filter
* @param str - string in format "bank# FIFO# mode num0 .. num3"
* where bank# - 0..27
* if there's nothing after bank# - delete filter
* FIFO# - 0,1
* mode - 'I' for ID, 'M' for mask
* num0..num3 - IDs in ID mode, ID/MASK for mask mode
*/
static void add_filter(char *str){
uint32_t N;
str = omit_spaces(str);
char *n = getnum(str, &N);
if(n == str){
SEND("No bank# given");
return;
}
if(N == 0 || N > STM32F0FBANKNO-1){
SEND("0 (reserved for self) < bank# < 28 (max bank# is 27)!!!");
return;
}
uint8_t bankno = (uint8_t)N;
str = omit_spaces(n);
if(!*str){ // deactivate filter
SEND("Deactivate filters in bank ");
printu(bankno);
CAN->FMR = CAN_FMR_FINIT;
CAN->FA1R &= ~(1<<bankno);
CAN->FMR &=~ CAN_FMR_FINIT;
return;
}
uint8_t fifono = 0;
if(*str == '1') fifono = 1;
else if(*str != '0'){
SEND("FIFO# is 0 or 1");
return;
}
str = omit_spaces(str + 1);
char c = *str;
uint8_t mode = 0; // ID
if(c == 'M' || c == 'm') mode = 1;
else if(c != 'I' && c != 'i'){
SEND("mode is 'M/m' for MASK and 'I/i' for IDLIST");
return;
}
str = omit_spaces(str + 1);
uint32_t filters[4];
uint32_t nfilt;
for(nfilt = 0; nfilt < 4; ++nfilt){
n = getnum(str, &N);
if(n == str) break;
filters[nfilt] = N;
str = omit_spaces(n);
}
if(nfilt == 0){
SEND("You should add at least one filter!");
return;
}
if(mode && (nfilt&1)){
SEND("In MASK mode you should point pairs of ID/MASK");
return;
}
CAN->FMR = CAN_FMR_FINIT;
uint32_t mask = 1<<bankno;
CAN->FA1R |= mask; // activate given filter
if(fifono) CAN->FFA1R |= mask; // set FIFO number
else CAN->FFA1R &= ~mask;
if(mode) CAN->FM1R &= ~mask; // MASK
else CAN->FM1R |= mask; // LIST
uint32_t F1 = (0x8f<<16);
uint32_t F2 = (0x8f<<16);
// reset filter registers to wrong value
CAN->sFilterRegister[bankno].FR1 = (0x8f<<16) | 0x8f;
CAN->sFilterRegister[bankno].FR2 = (0x8f<<16) | 0x8f;
switch(nfilt){
case 4:
F2 = filters[3] << 21;
// fallthrough
case 3:
CAN->sFilterRegister[bankno].FR2 = (F2 & 0xffff0000) | (filters[2] << 5);
// fallthrough
case 2:
F1 = filters[1] << 21;
// fallthrough
case 1:
CAN->sFilterRegister[bankno].FR1 = (F1 & 0xffff0000) | (filters[0] << 5);
}
CAN->FMR &=~ CAN_FMR_FINIT;
SEND("Added filter with ");
printu(nfilt); SEND(" parameters");
}
// print current buttons state
TRUE_INLINE void getBtnState(){
const char *states[] = {[EVT_NONE] = NULL, [EVT_PRESS] = "pressed", [EVT_HOLD] = "holded", [EVT_RELEASE] = "released"};
for(int i = 0; i < BTNSNO; ++i){
uint32_t T;
keyevent e = keystate(i, &T);
if(e != EVT_NONE){
SEND("The key "); printu(i);
SEND(" is "); addtobuf(states[e]); SEND(" at ");
printu(T); NL();
}
}
}
TRUE_INLINE void getPWM(){
volatile uint32_t *reg = &TIM1->CCR1;
for(int n = 0; n < 3; ++n){
SEND("PWM");
bufputchar('0' + n);
bufputchar('=');
printu(*reg++);
bufputchar('\n');
}
sendbuf();
}
TRUE_INLINE void changePWM(char *str){
str = omit_spaces(str);
uint32_t N, pwm;
char *nxt = getnum(str, &N);
if(nxt == str || N > 2){
SEND("Nch = 0..2");
return;
}
str = omit_spaces(nxt);
nxt = getnum(str, &pwm);
if(nxt == str || pwm > 255){
SEND("PWM should be from 0 to 255");
return;
}
volatile uint32_t *reg = &TIM1->CCR1;
reg[N] = pwm;
SEND("OK, changed");
}
TRUE_INLINE void printADC(){ // show all 4 channels ADC
for(int i = 0; i < NUMBER_OF_ADC_CHANNELS; ++i){
SEND("ADC"); bufputchar('0' + i); bufputchar('=');
printu(getADCval(i)); bufputchar('\n');
}
sendbuf();
}
TRUE_INLINE void printVT(){ // show T and Vdd
int32_t t = getMCUtemp();
SEND("T=");
if(t < 0){ bufputchar('-'); t = -t; }
printu(t); SEND("/10degC\nVDD=");
printu(getVdd()); SEND("/100V");
}
// set or check relay state
TRUE_INLINE void relay(const char *txt){
txt = omit_spaces(txt);
uint32_t sr;
char *b = getnum(txt, &sr);
if(b && b != txt && sr < 2){
if(sr) Relay_ON(); else Relay_OFF();
}
SEND("Relay"); bufputchar('=');
bufputchar('0' + Relay_chk());
}
/**
* @brief cmd_parser - command parsing
* @param txt - buffer with commands & data
* @param isUSB - == 1 if data got from USB
*/
void cmd_parser(char *txt){
char _1st = txt[0];
/*
* parse long commands here
*/
switch(_1st){
case '0':
relay(txt + 1);
goto eof;
break;
case 'a':
addIGN(txt + 1);
goto eof;
break;
case 'C':
CANini(txt + 1);
goto eof;
break;
case 'f':
add_filter(txt + 1);
goto eof;
break;
case 'F':
set_flood(parseCANmsg(txt + 1));
goto eof;
break;
case 's':
case 'S':
sendCANcommand(txt + 1);
goto eof;
break;
case 'W':
changePWM(txt + 1);
goto eof;
break;
}
if(txt[1] != '\n') *txt = '?'; // help for wrong message length
switch(_1st){
case 'A':
printADC();
return;
break;
case 'b':
getBtnState();
break;
case 'd':
IgnSz = 0;
break;
case 'D':
SEND("Go into DFU mode\n");
sendbuf();
Jump2Boot();
break;
case 'I':
SEND("CAN ID: "); printuhex(CANID);
break;
case 'l':
list_filters();
break;
case 'm':
printVT();
break;
case 'p':
print_ign_buf();
break;
case 'P':
ShowMsgs = !ShowMsgs;
if(ShowMsgs) SEND("Resume\n");
else SEND("Pause\n");
break;
case 'R':
SEND("Soft reset\n");
sendbuf();
pause_ms(5); // a little pause to transmit data
NVIC_SystemReset();
break;
case 'T':
SEND("Time (ms): ");
printu(Tms);
break;
case 'w':
getPWM();
return;
break;
default: // help
SEND(
"'0' - turn relay on(1) or off(0)\n"
"'a' - add ID to ignore list (max 10 IDs)\n"
"'A' - get ADC values @ all 4 channels\n"
"'b' - get buttons' state\n"
"'C' - reinit CAN with given baudrate\n"
"'d' - delete ignore list\n"
"'D' - activate DFU mode\n"
"'f' - add/delete filter, format: bank# FIFO# mode(M/I) num0 [num1 [num2 [num3]]]\n"
"'F' - send/clear flood message: F ID byte0 ... byteN\n"
"'I' - read CAN ID\n"
"'l' - list all active filters\n"
"'m' - get MCU temp & Vdd\n"
"'p' - print ignore buffer\n"
"'P' - pause/resume in packets displaying\n"
"'R' - software reset\n"
"'s/S' - send data over CAN: s ID byte0 .. byteN\n"
"'T' - get time from start (ms)\n"
"'w' - get PWM settings\n"
"'W' - set PWM @nth channel (ch: 0..2, PWM: 0..255)\n"
);
break;
}
eof:
newline();
sendbuf();
}
// print 32bit unsigned int
void printu(uint32_t val){
char buf[11], *bufptr = &buf[10];
*bufptr = 0;
if(!val){
*(--bufptr) = '0';
}else{
while(val){
*(--bufptr) = val % 10 + '0';
val /= 10;
}
}
addtobuf(bufptr);
}
// print 32bit unsigned int as hex
void printuhex(uint32_t val){
addtobuf("0x");
uint8_t *ptr = (uint8_t*)&val + 3;
int8_t i, j, z=1;
for(i = 0; i < 4; ++i, --ptr){
if(*ptr == 0){ // omit leading zeros
if(i == 3) z = 0;
if(z) continue;
}
else z = 0;
for(j = 1; j > -1; --j){
uint8_t half = (*ptr >> (4*j)) & 0x0f;
if(half < 10) bufputchar(half + '0');
else bufputchar(half - 10 + 'a');
}
}
}
// check Ignore_IDs & return 1 if ID isn't in list
uint8_t isgood(uint16_t ID){
for(int i = 0; i < IgnSz; ++i)
if(Ignore_IDs[i] == ID) return 0;
return 1;
}

View File

@ -0,0 +1,57 @@
/*
* This file is part of the canrelay project.
* Copyright 2021 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 __PROTO_H__
#define __PROTO_H__
#include "stm32f0.h"
#include "hardware.h"
#define BUFSZ (64)
// macro for static strings
#define SEND(str) do{addtobuf(str);}while(0)
#ifdef EBUG
#define MSG(str) do{addtobuf(__FILE__ " (L" STR(__LINE__) "): " str);}while(0)
#else
#define MSG(str)
#endif
#define newline() do{bufputchar('\n');}while(0)
// newline with buffer sending over USART
#define NL() do{bufputchar('\n'); sendbuf();}while(0)
#define IGN_SIZE 10
extern uint16_t Ignore_IDs[IGN_SIZE];
extern uint8_t IgnSz;
extern uint8_t ShowMsgs;
void cmd_parser(char *buf);
void addtobuf(const char *txt);
void bufputchar(char ch);
void printu(uint32_t val);
void printuhex(uint32_t val);
void sendbuf();
char *omit_spaces(const char *buf);
char *getnum(const char *buf, uint32_t *N);
uint8_t isgood(uint16_t ID);
#endif // __PROTO_H__

BIN
F0-nolib/3steppersLB/steppers.bin Executable file

Binary file not shown.

View File

@ -0,0 +1,627 @@
/*
* This file is part of the 3steppers project.
* Copyright 2021 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"
#include "buttons.h"
#include "can.h"
#include "commonproto.h"
#include "flash.h"
#include "hardware.h"
#include "strfunct.h"
#include "usb.h"
#include <string.h> // strlen
extern volatile uint8_t canerror;
uint8_t ShowMsgs = 0;
uint16_t Ignore_IDs[IGN_SIZE];
uint8_t IgnSz = 0;
static char buff[BUFSZ+1], *bptr = buff;
static uint8_t blen = 0;
void sendbuf(){
IWDG->KR = IWDG_REFRESH;
if(blen == 0) return;
*bptr = 0;
USB_sendstr(buff);
bptr = buff;
blen = 0;
}
void bufputchar(char ch){
if(blen > BUFSZ-1){
sendbuf();
}
*bptr++ = ch;
++blen;
}
void addtobuf(const char *txt){
IWDG->KR = IWDG_REFRESH;
while(*txt) bufputchar(*txt++);
}
/**
* @brief cmpstr - the same as strncmp
* @param s1,s2 - strings to compare
* @return 0 if strings equal or 1/-1
*/
int cmpstr(const char *s1, const char *s2){
int ret = 0;
do{
ret = *s1 - *s2;
if(ret == 0 && *s1 && *s2){
++s1; ++s2;
continue;
}
break;
}while(1);
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;
}
// parse `txt` to CAN_message
static CAN_message *parseCANmsg(char *txt){
static CAN_message canmsg;
//SEND("CAN command with arguments:\n");
int32_t N;
char *n;
int ctr = -1;
canmsg.ID = 0xffff;
do{
txt = omit_spaces(txt);
n = getnum(txt, &N);
if(txt == n) break;
txt = n;
if(ctr == -1){
if(N > 0x7ff){
SEND("ID should be 11-bit number!\n");
return NULL;
}
canmsg.ID = (uint16_t)(N&0x7ff);
//SEND("ID="); printuhex(canmsg.ID); newline();
ctr = 0;
continue;
}
if(ctr > 7){
SEND("ONLY 8 data bytes allowed!\n");
return NULL;
}
if(N > 0xff){
SEND("Every data portion is a byte!\n");
return NULL;
}
canmsg.data[ctr++] = (uint8_t)(N&0xff);
}while(1);
if(canmsg.ID == 0xffff){
SEND("NO ID given, send nothing!\n");
return NULL;
}
SEND("Message parsed OK\n");
sendbuf();
canmsg.length = (uint8_t) ctr;
return &canmsg;
}
// send command, format: ID (hex/bin/dec) data bytes (up to 8 bytes, space-delimeted)
static void sendCANcommand(char *txt){
CAN_message *msg = parseCANmsg(txt);
if(!msg) return;
uint32_t N = 1000;
while(CAN_BUSY == can_send(msg->data, msg->length, msg->ID)){
if(--N == 0) break;
}
}
static void CANini(char *txt){
txt = omit_spaces(txt);
int32_t N;
char *n = getnum(txt, &N);
if(txt == n){
SEND("No speed given");
return;
}
if(N < 50){
SEND("Lowest speed is 50kbps");
return;
}else if(N > 3000){
SEND("Highest speed is 3000kbps");
return;
}
CAN_reinit((uint16_t)N);
SEND("Reinit CAN bus with speed ");
printu(N); SEND("kbps");
}
static void addIGN(char *txt){
if(IgnSz == IGN_SIZE){
DBG("Ignore buffer is full");
return;
}
txt = omit_spaces(txt);
int32_t N;
char *n = getnum(txt, &N);
if(txt == n){
SEND("No ID given");
return;
}
if(N == the_conf.CANID){
SEND("You can't ignore self ID!");
return;
}
if(N > 0x7ff){
SEND("ID should be 11-bit number!");
return;
}
Ignore_IDs[IgnSz++] = (uint16_t)(N & 0x7ff);
SEND("Added ID "); printu(N);
SEND("\nIgn buffer size: "); printu(IgnSz);
}
static void print_ign_buf(_U_ char *txt){
if(IgnSz == 0){
SEND("Ignore buffer is empty");
return;
}
SEND("Ignored IDs:\n");
for(int i = 0; i < IgnSz; ++i){
if(i) newline();
printu(i);
SEND(": ");
printuhex(Ignore_IDs[i]);
}
}
// print ID/mask of CAN->sFilterRegister[x] half
static void printID(uint16_t FRn){
if(FRn & 0x1f) return; // trash
printuhex(FRn >> 5);
}
/*
Can filtering: FSCx=0 (CAN->FS1R) -> 16-bit identifiers
CAN->FMR = (sb)<<8 | FINIT - init filter in starting bank sb
CAN->FFA1R FFAx = 1 -> FIFO1, 0 -> FIFO0
CAN->FA1R FACTx=1 - filter active
MASK: FBMx=0 (CAN->FM1R), two filters (n in FR1 and n+1 in FR2)
ID: CAN->sFilterRegister[x].FRn[0..15]
MASK: CAN->sFilterRegister[x].FRn[16..31]
FR bits: STID[10:0] RTR IDE EXID[17:15]
LIST: FBMx=1, four filters (n&n+1 in FR1, n+2&n+3 in FR2)
IDn: CAN->sFilterRegister[x].FRn[0..15]
IDn+1: CAN->sFilterRegister[x].FRn[16..31]
*/
static void list_filters(_U_ char *txt){
uint32_t fa = CAN->FA1R, ctr = 0, mask = 1;
while(fa){
if(fa & 1){
SEND("Filter "); printu(ctr); SEND(", FIFO");
if(CAN->FFA1R & mask) SEND("1");
else SEND("0");
SEND(" in ");
if(CAN->FM1R & mask){ // up to 4 filters in LIST mode
SEND("LIST mode, IDs: ");
printID(CAN->sFilterRegister[ctr].FR1 & 0xffff);
SEND(" ");
printID(CAN->sFilterRegister[ctr].FR1 >> 16);
SEND(" ");
printID(CAN->sFilterRegister[ctr].FR2 & 0xffff);
SEND(" ");
printID(CAN->sFilterRegister[ctr].FR2 >> 16);
}else{ // up to 2 filters in MASK mode
SEND("MASK mode: ");
if(!(CAN->sFilterRegister[ctr].FR1&0x1f)){
SEND("ID="); printID(CAN->sFilterRegister[ctr].FR1 & 0xffff);
SEND(", MASK="); printID(CAN->sFilterRegister[ctr].FR1 >> 16);
SEND(" ");
}
if(!(CAN->sFilterRegister[ctr].FR2&0x1f)){
SEND("ID="); printID(CAN->sFilterRegister[ctr].FR2 & 0xffff);
SEND(", MASK="); printID(CAN->sFilterRegister[ctr].FR2 >> 16);
}
}
newline();
}
fa >>= 1;
++ctr;
mask <<= 1;
}
}
/**
* @brief add_filter - add/modify filter
* @param str - string in format "bank# FIFO# mode num0 .. num3"
* where bank# - 0..27
* if there's nothing after bank# - delete filter
* FIFO# - 0,1
* mode - 'I' for ID, 'M' for mask
* num0..num3 - IDs in ID mode, ID/MASK for mask mode
*/
static void add_filter(char *str){
int32_t N;
str = omit_spaces(str);
char *n = getnum(str, &N);
if(n == str){
SEND("No bank# given");
return;
}
if(N == 0 || N > STM32F0FBANKNO-1){
SEND("0 (reserved for self) < bank# < 28 (max bank# is 27)!!!");
return;
}
uint8_t bankno = (uint8_t)N;
str = omit_spaces(n);
if(!*str){ // deactivate filter
SEND("Deactivate filters in bank ");
printu(bankno);
CAN->FMR = CAN_FMR_FINIT;
CAN->FA1R &= ~(1<<bankno);
CAN->FMR &=~ CAN_FMR_FINIT;
return;
}
uint8_t fifono = 0;
if(*str == '1') fifono = 1;
else if(*str != '0'){
SEND("FIFO# is 0 or 1");
return;
}
str = omit_spaces(str + 1);
char c = *str;
uint8_t mode = 0; // ID
if(c == 'M' || c == 'm') mode = 1;
else if(c != 'I' && c != 'i'){
SEND("mode is 'M/m' for MASK and 'I/i' for IDLIST");
return;
}
str = omit_spaces(str + 1);
uint32_t filters[4];
uint32_t nfilt;
for(nfilt = 0; nfilt < 4; ++nfilt){
n = getnum(str, &N);
if(n == str) break;
filters[nfilt] = N;
str = omit_spaces(n);
}
if(nfilt == 0){
SEND("You should add at least one filter!");
return;
}
if(mode && (nfilt&1)){
SEND("In MASK mode you should point pairs of ID/MASK");
return;
}
CAN->FMR = CAN_FMR_FINIT;
uint32_t mask = 1<<bankno;
CAN->FA1R |= mask; // activate given filter
if(fifono) CAN->FFA1R |= mask; // set FIFO number
else CAN->FFA1R &= ~mask;
if(mode) CAN->FM1R &= ~mask; // MASK
else CAN->FM1R |= mask; // LIST
uint32_t F1 = (0x8f<<16);
uint32_t F2 = (0x8f<<16);
// reset filter registers to wrong value
CAN->sFilterRegister[bankno].FR1 = (0x8f<<16) | 0x8f;
CAN->sFilterRegister[bankno].FR2 = (0x8f<<16) | 0x8f;
switch(nfilt){
case 4:
F2 = filters[3] << 21;
// fallthrough
case 3:
CAN->sFilterRegister[bankno].FR2 = (F2 & 0xffff0000) | (filters[2] << 5);
// fallthrough
case 2:
F1 = filters[1] << 21;
// fallthrough
case 1:
CAN->sFilterRegister[bankno].FR1 = (F1 & 0xffff0000) | (filters[0] << 5);
}
CAN->FMR &=~ CAN_FMR_FINIT;
SEND("Added filter with ");
printu(nfilt); SEND(" parameters");
}
void getcanid(_U_ char *txt){
SEND("canid="); printuhex(the_conf.CANID);
}
void inpause(_U_ char *txt){
ShowMsgs = FALSE;
}
void inresume(_U_ char *txt){
ShowMsgs = TRUE;
}
void delignlist(_U_ char *txt){
IgnSz = 0;
}
void bootldr(_U_ char *txt){
SEND("Go into DFU mode\n");
sendbuf();
Jump2Boot();
}
typedef void(*specfpointer)(char *arg);
typedef struct{
const char *command;
specfpointer function;
const char *help;
} speccommands;
const speccommands scmdlist[] = {
{"ignore", addIGN, "add ID to ignore list (max 10 IDs)"},
{"delignlist", delignlist, "delete ignore list"},
{"dfu", bootldr, "activate DFU mode"},
{"filter", add_filter, "add/modify filter, format: bank# FIFO# mode(M/I) num0 [num1 [num2 [num3]]]"},
{"canspeed", CANini, "CAN bus speed"},
{"canid", getcanid, "read CAN ID"},
{"listfilters", list_filters, "list all active filters"},
{"ignbuf", print_ign_buf, "print ignore buffer"},
{"pause", inpause, "pause IN packets displaying"},
{"resume", inresume, "resume IN packets displaying"},
{"send", sendCANcommand, "send data over CAN: send ID byte0 .. byteN"},
{NULL, NULL, NULL}
};
static void showHelp(){
SEND("USAGE. Common commands format is cmd[ N[ = val]]\n\twhere N is command argument (0..127), val is its value\n");
SEND("Common commands:\n");
for(int i = 0; i < CMD_AMOUNT; ++i){
bufputchar('\t'); SEND(cmdlist[i].command); SEND(" - ");
SEND(cmdlist[i].help); newline();
}
SEND("USB-only commands:\n");
const speccommands *cmd = scmdlist;
while(cmd->command){
bufputchar('\t'); SEND(cmd->command); SEND(" - ");
SEND(cmd->help); newline();
++cmd;
}
NL();
}
/**
* @brief cmd_parser - command parsing
* @param txt - buffer with commands & data (will be broken by this function!)
* @param isUSB - == 1 if data got from USB
* Common commands format: command [[N]=I], where
* command - one of `command` from `cmdlist`
* N - optional parameter (0..255)
* I - value (int32_t), need for setter
* Special commands format: s_command [text], where
* s_command - one of `spec_cmdlist`
* text - optional list of arguments
* The space after command name is mandatory (it will be substituted by \0)
*/
void cmd_parser(char *txt){
char cmd[32], *pcmd = cmd;
int i = 0;
// first try to find command in `cmdlist`
char *eptr = omit_spaces(txt);
if(!*eptr) return;
while(*eptr && i < 30){
if(*eptr < 'a' || *eptr > 'z') break;
*pcmd++ = *eptr++;
++i;
}
*pcmd = 0;
if(eptr && *eptr){
eptr = omit_spaces(eptr);
}
// find command
int idx = 0;
do{
if(0 == cmpstr(cmdlist[idx].command, cmd)) break;
}while(++idx < CMD_AMOUNT);
if(idx < CMD_AMOUNT){
#ifdef EBUG
SEND("Find known command: "); SEND(cmd);
if(eptr && *eptr) SEND(", args: "); SEND(eptr);
NL();
#endif
uint8_t par = CANMESG_NOPAR;
int32_t val = 0;
if(eptr && *eptr){
char *nxt = getnum(eptr, &val);
if(nxt && nxt != eptr){ // command has parameter?
if(val < 0 || val >= CANMESG_NOPAR){
SEND("Command parameter should be 0..126!"); NL();
return;
}
par = (uint8_t)val;
}else nxt = eptr;
eptr = getchr(nxt, '=');
if(eptr){ // command has value?
eptr = omit_spaces(eptr + 1);
nxt = getnum(eptr, &val);
if(nxt != eptr){
par |= 0x80; // setter
}
}
}
// here we got command & ppar/pval -> call CMD
errcodes retcode = cmdlist[idx].function(&par, &val);
SEND(cmd);
if(par != CANMESG_NOPAR) printu(par & 0x7f);
bufputchar('='); printi(val);
if(ERR_OK != retcode){
SEND("\nERRCODE=");
printu(retcode);
}
NL();
return;
}
/*-> find USB-only commands here and show help if not found <-*/
const speccommands *c = scmdlist;
while(c->command){
if(0 == cmpstr(c->command, cmd)){
c->function(eptr);
NL();
return;
}
++c;
}
showHelp();
}
// print 32bit unsigned int
void printu(uint32_t val){
char buf[11], *bufptr = &buf[10];
*bufptr = 0;
if(!val){
*(--bufptr) = '0';
}else{
while(val){
register uint32_t o = val;
val /= 10;
*(--bufptr) = (o - 10*val) + '0';
}
}
addtobuf(bufptr);
}
void printi(int32_t val){
if(val < 0){
val = -val;
bufputchar('-');
}
printu((uint32_t)val);
}
// print 32bit unsigned int as hex
void printuhex(uint32_t val){
addtobuf("0x");
uint8_t *ptr = (uint8_t*)&val + 3;
int i, j, z = 1;
for(i = 0; i < 4; ++i, --ptr){
if(*ptr == 0){ // omit leading zeros
if(i == 3) z = 0;
if(z) continue;
}
else z = 0;
for(j = 1; j > -1; --j){
uint8_t half = (*ptr >> (4*j)) & 0x0f;
if(half < 10) bufputchar(half + '0');
else bufputchar(half - 10 + 'a');
}
}
}
// check Ignore_IDs & return 1 if ID isn't in list
uint8_t isgood(uint16_t ID){
for(int i = 0; i < IgnSz; ++i)
if(Ignore_IDs[i] == ID) return 0;
return 1;
}
char *omit_spaces(char *buf){
while(*buf){
if(*buf > ' ') break;
++buf;
}
return buf;
}
// THERE'S NO OVERFLOW PROTECTION IN NUMBER READ PROCEDURES!
// read decimal number
static char *getdec(const char *buf, int32_t *N){
int32_t num = 0;
int positive = TRUE;
if(*buf == '-'){
positive = FALSE;
++buf;
}
while(*buf){
char c = *buf;
if(c < '0' || c > '9'){
break;
}
num *= 10;
num += c - '0';
++buf;
}
*N = (positive) ? num : -num;
return (char *)buf;
}
// read hexadecimal number (without 0x prefix!)
static char *gethex(const char *buf, int32_t *N){
uint32_t num = 0;
while(*buf){
char c = *buf;
uint8_t M = 0;
if(c >= '0' && c <= '9'){
M = '0';
}else if(c >= 'A' && c <= 'F'){
M = 'A' - 10;
}else if(c >= 'a' && c <= 'f'){
M = 'a' - 10;
}
if(M){
num <<= 4;
num += c - M;
}else{
break;
}
++buf;
}
*N = (int32_t)num;
return (char *)buf;
}
// read binary number (without 0b prefix!)
static char *getbin(const char *buf, int32_t *N){
uint32_t num = 0;
while(*buf){
char c = *buf;
if(c < '0' || c > '1'){
break;
}
num <<= 1;
if(c == '1') num |= 1;
++buf;
}
*N = (int32_t)num;
return (char *)buf;
}
/**
* @brief getnum - read uint32_t from string (dec, hex or bin: 127, 0x7f, 0b1111111)
* @param buf - buffer with number and so on
* @param N - the number read
* @return pointer to first non-number symbol in buf (if it is == buf, there's no number)
*/
char *getnum(char *txt, int32_t *N){
if(*txt == '0'){
if(txt[1] == 'x' || txt[1] == 'X') return gethex(txt+2, N);
if(txt[1] == 'b' || txt[1] == 'B') return getbin(txt+2, N);
}
return getdec(txt, N);
}

View File

@ -0,0 +1,61 @@
/*
* This file is part of the 3steppers project.
* Copyright 2021 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 STRFUNCT_H__
#define STRFUNCT_H__
#include "stm32f0.h"
#include "hardware.h"
#define BUFSZ (64)
// macro for static strings
#define SEND(str) do{addtobuf(str);}while(0)
#ifdef EBUG
#define DBG(str) do{addtobuf(__FILE__ " (L" STR(__LINE__) "): " str);}while(0)
#else
#define DBG(str)
#endif
#define newline() do{bufputchar('\n');}while(0)
// newline & send buffer
#define NL() do{bufputchar('\n'); sendbuf();}while(0)
#define IGN_SIZE 10
extern uint16_t Ignore_IDs[IGN_SIZE];
extern uint8_t IgnSz;
extern uint8_t ShowMsgs;
void cmd_parser(char *buf);
void addtobuf(const char *txt);
void bufputchar(char ch);
void printu(uint32_t val);
void printi(int32_t val);
void printuhex(uint32_t val);
void sendbuf();
int cmpstr(const char *s1, const char *s2);
char *getchr(const char *str, char symbol);
char *omit_spaces(char *buf);
char *getnum(char *buf, int32_t *N);
uint8_t isgood(uint16_t ID);
#endif // STRFUNCT_H__

175
F0-nolib/3steppersLB/usb.c Normal file
View File

@ -0,0 +1,175 @@
/*
* This file is part of the canrelay project.
* Copyright 2021 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 "usb.h"
#include "usb_lib.h"
static volatile uint8_t tx_succesfull = 1;
static volatile uint8_t rxNE = 0;
// interrupt IN handler (never used?)
static void EP1_Handler(){
uint16_t epstatus = KEEP_DTOG(USB->EPnR[1]);
if(RX_FLAG(epstatus)) epstatus = (epstatus & ~USB_EPnR_STAT_TX) ^ USB_EPnR_STAT_RX; // set valid RX
else epstatus = epstatus & ~(USB_EPnR_STAT_TX|USB_EPnR_STAT_RX);
// clear CTR
epstatus = (epstatus & ~(USB_EPnR_CTR_RX|USB_EPnR_CTR_TX));
USB->EPnR[1] = epstatus;
}
// data IN/OUT handlers
static void transmit_Handler(){ // EP3IN
tx_succesfull = 1;
uint16_t epstatus = KEEP_DTOG_STAT(USB->EPnR[3]);
// clear CTR keep DTOGs & STATs
USB->EPnR[3] = (epstatus & ~(USB_EPnR_CTR_TX)); // clear TX ctr
}
static void receive_Handler(){ // EP2OUT
rxNE = 1;
uint16_t epstatus = KEEP_DTOG_STAT(USB->EPnR[2]);
USB->EPnR[2] = (epstatus & ~(USB_EPnR_CTR_RX)); // clear RX ctr
}
void USB_setup(){
RCC->APB1ENR |= RCC_APB1ENR_CRSEN | RCC_APB1ENR_USBEN; // enable CRS (hsi48 sync) & USB
RCC->CFGR3 &= ~RCC_CFGR3_USBSW; // reset USB
RCC->CR2 |= RCC_CR2_HSI48ON; // turn ON HSI48
uint32_t tmout = 16000000;
while(!(RCC->CR2 & RCC_CR2_HSI48RDY)){if(--tmout == 0) break;}
FLASH->ACR = FLASH_ACR_PRFTBE | FLASH_ACR_LATENCY;
CRS->CFGR &= ~CRS_CFGR_SYNCSRC;
CRS->CFGR |= CRS_CFGR_SYNCSRC_1; // USB SOF selected as sync source
CRS->CR |= CRS_CR_AUTOTRIMEN; // enable auto trim
CRS->CR |= CRS_CR_CEN; // enable freq counter & block CRS->CFGR as read-only
RCC->CFGR |= RCC_CFGR_SW;
// allow RESET and CTRM interrupts
USB->CNTR = USB_CNTR_RESETM | USB_CNTR_WKUPM;
// clear flags
USB->ISTR = 0;
// and activate pullup
USB->BCDR |= USB_BCDR_DPPU;
NVIC_EnableIRQ(USB_IRQn);
}
static int usbwr(const uint8_t *buf, uint16_t l){
uint32_t ctra = 1000000;
while(--ctra && tx_succesfull == 0){
IWDG->KR = IWDG_REFRESH;
}
tx_succesfull = 0;
EP_Write(3, buf, l);
ctra = 1000000;
while(--ctra && tx_succesfull == 0){
IWDG->KR = IWDG_REFRESH;
}
if(tx_succesfull == 0){usbON = 0; return 1;} // usb is OFF?
return 0;
}
static uint8_t usbbuff[USB_TXBUFSZ-1]; // temporary buffer (63 - to prevent need of ZLP)
static uint8_t buflen = 0; // amount of symbols in usbbuff
// send next up to 63 bytes of data in usbbuff
static void send_next(){
if(!buflen || !tx_succesfull) return;
tx_succesfull = 0;
EP_Write(3, usbbuff, buflen);
buflen = 0;
}
// unblocking sending - just fill a buffer
void USB_send(const uint8_t *buf, uint16_t len){
if(!usbON || !len) return;
if(len > USB_TXBUFSZ-1 - buflen){
usbwr(usbbuff, buflen);
buflen = 0;
}
if(len > USB_TXBUFSZ-1){
USB_send_blk(buf, len);
return;
}
while(len--) usbbuff[buflen++] = *buf++;
}
// send zero-terminated string
void USB_sendstr(const char *str){
uint16_t l = 0;
const char *ptr = str;
while(*ptr++) ++l;
USB_send((uint8_t*)str, l);
}
// blocking sending
void USB_send_blk(const uint8_t *buf, uint16_t len){
if(!usbON || !len) return; // USB disconnected
if(buflen){
usbwr(usbbuff, buflen);
buflen = 0;
}
int needzlp = 0;
while(len){
if(len == USB_TXBUFSZ) needzlp = 1;
uint16_t s = (len > USB_TXBUFSZ) ? USB_TXBUFSZ : len;
if(usbwr(buf, s)) return;
len -= s;
buf += s;
}
if(needzlp){
usbwr(NULL, 0);
}
}
void usb_proc(){
switch(USB_Dev.USB_Status){
case USB_STATE_CONFIGURED:
// make new BULK endpoint
// Buffer have 1024 bytes, but last 256 we use for CAN bus (30.2 of RM: USB main features)
EP_Init(1, EP_TYPE_INTERRUPT, USB_EP1BUFSZ, 0, EP1_Handler); // IN1 - transmit
EP_Init(2, EP_TYPE_BULK, 0, USB_RXBUFSZ, receive_Handler); // OUT2 - receive data
EP_Init(3, EP_TYPE_BULK, USB_TXBUFSZ, 0, transmit_Handler); // IN3 - transmit data
USB_Dev.USB_Status = USB_STATE_CONNECTED;
break;
case USB_STATE_DEFAULT:
case USB_STATE_ADDRESSED:
if(usbON){
usbON = 0;
}
break;
default: // USB_STATE_CONNECTED - send next data portion
if(!usbON) return;
send_next();
}
}
/**
* @brief USB_receive
* @param buf (i) - buffer[64] for received data
* @return amount of received bytes
*/
uint8_t USB_receive(uint8_t *buf){
if(!usbON || !rxNE) return 0;
uint8_t sz = EP_Read(2, buf);
uint16_t epstatus = KEEP_DTOG(USB->EPnR[2]);
// keep stat_tx & set ACK rx
USB->EPnR[2] = (epstatus & ~(USB_EPnR_STAT_TX)) ^ USB_EPnR_STAT_RX;
rxNE = 0;
return sz;
}

View File

@ -0,0 +1,37 @@
/*
* This file is part of the canrelay project.
* Copyright 2021 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 __USB_H__
#define __USB_H__
#include "hardware.h"
#define BUFFSIZE (64)
// send string with constant length
#define USND(str) do{USB_send((uint8_t*)str, sizeof(str)-1);}while(0)
void USB_setup();
void usb_proc();
void USB_send(const uint8_t *buf, uint16_t len);
void USB_sendstr(const char *str);
void USB_send_blk(const uint8_t *buf, uint16_t len);
uint8_t USB_receive(uint8_t *buf);
#endif // __USB_H__

View File

@ -0,0 +1,99 @@
/*
* This file is part of the canrelay project.
* Copyright 2021 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 __USB_DEFS_H__
#define __USB_DEFS_H__
#include <stm32f0.h>
// max endpoints number
#define STM32ENDPOINTS 8
/**
* Buffers size definition
**/
// !!! when working with CAN bus change USB_BTABLE_SIZE to 768 !!!
#define USB_BTABLE_SIZE 768
// for USB FS EP0 buffers are from 8 to 64 bytes long (64 for PL2303)
#define USB_EP0_BUFSZ 64
// USB transmit buffer size (64 for PL2303)
#define USB_TXBUFSZ 64
// USB receive buffer size (64 for PL2303)
#define USB_RXBUFSZ 64
// EP1 - interrupt - buffer size
#define USB_EP1BUFSZ 8
#define USB_BTABLE_BASE 0x40006000
#ifdef USB_BTABLE
#undef USB_BTABLE
#endif
#define USB_BTABLE ((USB_BtableDef *)(USB_BTABLE_BASE))
#define USB_ISTR_EPID 0x0000000F
#define USB_FNR_LSOF_0 0x00000800
#define USB_FNR_lSOF_1 0x00001000
#define USB_LPMCSR_BESL_0 0x00000010
#define USB_LPMCSR_BESL_1 0x00000020
#define USB_LPMCSR_BESL_2 0x00000040
#define USB_LPMCSR_BESL_3 0x00000080
#define USB_EPnR_CTR_RX 0x00008000
#define USB_EPnR_DTOG_RX 0x00004000
#define USB_EPnR_STAT_RX 0x00003000
#define USB_EPnR_STAT_RX_0 0x00001000
#define USB_EPnR_STAT_RX_1 0x00002000
#define USB_EPnR_SETUP 0x00000800
#define USB_EPnR_EP_TYPE 0x00000600
#define USB_EPnR_EP_TYPE_0 0x00000200
#define USB_EPnR_EP_TYPE_1 0x00000400
#define USB_EPnR_EP_KIND 0x00000100
#define USB_EPnR_CTR_TX 0x00000080
#define USB_EPnR_DTOG_TX 0x00000040
#define USB_EPnR_STAT_TX 0x00000030
#define USB_EPnR_STAT_TX_0 0x00000010
#define USB_EPnR_STAT_TX_1 0x00000020
#define USB_EPnR_EA 0x0000000F
#define USB_COUNTn_RX_BLSIZE 0x00008000
#define USB_COUNTn_NUM_BLOCK 0x00007C00
#define USB_COUNTn_RX 0x0000003F
#define USB_TypeDef USB_TypeDef_custom
typedef struct{
__IO uint32_t EPnR[STM32ENDPOINTS];
__IO uint32_t RESERVED[STM32ENDPOINTS];
__IO uint32_t CNTR;
__IO uint32_t ISTR;
__IO uint32_t FNR;
__IO uint32_t DADDR;
__IO uint32_t BTABLE;
__IO uint32_t LPMCSR;
__IO uint32_t BCDR;
} USB_TypeDef;
typedef struct{
__IO uint16_t USB_ADDR_TX;
__IO uint16_t USB_COUNT_TX;
__IO uint16_t USB_ADDR_RX;
__IO uint16_t USB_COUNT_RX;
} USB_EPDATA_TypeDef;
typedef struct{
__IO USB_EPDATA_TypeDef EP[STM32ENDPOINTS];
} USB_BtableDef;
#endif // __USB_DEFS_H__

View File

@ -0,0 +1,468 @@
/*
* This file is part of the canrelay project.
* Copyright 2021 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 <stdint.h>
#include "usb_lib.h"
ep_t endpoints[STM32ENDPOINTS];
usb_dev_t USB_Dev;
uint8_t usbON = 0;
static usb_LineCoding lineCoding = {115200, 0, 0, 8};
static config_pack_t setup_packet;
static uint8_t ep0databuf[EP0DATABUF_SIZE];
static uint8_t ep0dbuflen = 0;
usb_LineCoding getLineCoding(){return lineCoding;}
// definition of parts common for USB_DeviceDescriptor & USB_DeviceQualifierDescriptor
#define bcdUSB_L 0x10
#define bcdUSB_H 0x01
#define bDeviceClass 0
#define bDeviceSubClass 0
#define bDeviceProtocol 0
#define bNumConfigurations 1
static const uint8_t USB_DeviceDescriptor[] = {
18, // bLength
0x01, // bDescriptorType - Device descriptor
bcdUSB_L, // bcdUSB_L - 1.10
bcdUSB_H, // bcdUSB_H
bDeviceClass, // bDeviceClass - USB_COMM
bDeviceSubClass, // bDeviceSubClass
bDeviceProtocol, // bDeviceProtocol
USB_EP0_BUFSZ, // bMaxPacketSize
0x7b, // idVendor_L PL2303: VID=0x067b, PID=0x2303
0x06, // idVendor_H
0x03, // idProduct_L
0x23, // idProduct_H
0x00, // bcdDevice_Ver_L
0x03, // bcdDevice_Ver_H
0x01, // iManufacturer
0x02, // iProduct
0x00, // iSerialNumber
bNumConfigurations // bNumConfigurations
};
static const uint8_t USB_DeviceQualifierDescriptor[] = {
10, //bLength
0x06, // bDescriptorType - Device qualifier
bcdUSB_L, // bcdUSB_L
bcdUSB_H, // bcdUSB_H
bDeviceClass, // bDeviceClass
bDeviceSubClass, // bDeviceSubClass
bDeviceProtocol, // bDeviceProtocol
USB_EP0_BUFSZ, // bMaxPacketSize0
bNumConfigurations, // bNumConfigurations
0x00 // Reserved
};
static const uint8_t USB_ConfigDescriptor[] = {
/*Configuration Descriptor*/
0x09, /* bLength: Configuration Descriptor size */
0x02, /* bDescriptorType: Configuration */
39, /* wTotalLength:no of returned bytes */
0x00,
0x01, /* bNumInterfaces: 1 interface */
0x01, /* bConfigurationValue: Configuration value */
0x00, /* iConfiguration: Index of string descriptor describing the configuration */
0xa0, /* bmAttributes - Bus powered, Remote wakeup */
0x32, /* MaxPower 100 mA */
/*---------------------------------------------------------------------------*/
/*Interface Descriptor */
0x09, /* bLength: Interface Descriptor size */
0x04, /* bDescriptorType: Interface */
0x00, /* bInterfaceNumber: Number of Interface */
0x00, /* bAlternateSetting: Alternate setting */
0x03, /* bNumEndpoints: 3 endpoints used */
0xff, /* bInterfaceClass */
0x00, /* bInterfaceSubClass */
0x00, /* bInterfaceProtocol */
0x00, /* iInterface: */
///////////////////////////////////////////////////
/*Endpoint 1 Descriptor*/
0x07, /* bLength: Endpoint Descriptor size */
0x05, /* bDescriptorType: Endpoint */
0x81, /* bEndpointAddress IN1 */
0x03, /* bmAttributes: Interrupt */
0x0a, /* wMaxPacketSize LO: */
0x00, /* wMaxPacketSize HI: */
0x01, /* bInterval: */
/*Endpoint OUT2 Descriptor*/
0x07, /* bLength: Endpoint Descriptor size */
0x05, /* bDescriptorType: Endpoint */
0x02, /* bEndpointAddress: OUT2 */
0x02, /* bmAttributes: Bulk */
(USB_RXBUFSZ & 0xff), /* wMaxPacketSize: 64 */
(USB_RXBUFSZ >> 8),
0x00, /* bInterval: ignore for Bulk transfer */
/*Endpoint IN3 Descriptor*/
0x07, /* bLength: Endpoint Descriptor size */
0x05, /* bDescriptorType: Endpoint */
0x83, /* bEndpointAddress IN3 */
0x02, /* bmAttributes: Bulk */
(USB_TXBUFSZ & 0xff), /* wMaxPacketSize: 64 */
(USB_TXBUFSZ >> 8),
0x00, /* bInterval: ignore for Bulk transfer */
};
_USB_LANG_ID_(USB_StringLangDescriptor, LANG_US);
// these descriptors are not used in PL2303 emulator!
_USB_STRING_(USB_StringSerialDescriptor, u"0");
_USB_STRING_(USB_StringManufacturingDescriptor, u"Prolific Technology Inc.");
_USB_STRING_(USB_StringProdDescriptor, u"USB-Serial Controller");
/*
* default handlers
*/
// SET_LINE_CODING
void WEAK linecoding_handler(usb_LineCoding __attribute__((unused)) *lc){
}
// SET_CONTROL_LINE_STATE
void WEAK clstate_handler(uint16_t __attribute__((unused)) val){
}
// SEND_BREAK
void WEAK break_handler(){
}
// handler of vendor requests
void WEAK vendor_handler(config_pack_t *packet){
if(packet->bmRequestType & 0x80){ // read
uint8_t c;
switch(packet->wValue){
case 0x8484:
c = 2;
break;
case 0x0080:
c = 1;
break;
case 0x8686:
c = 0xaa;
break;
default:
c = 0;
}
EP_WriteIRQ(0, &c, 1);
}else{ // write ZLP
EP_WriteIRQ(0, (uint8_t *)0, 0);
}
}
static void wr0(const uint8_t *buf, uint16_t size){
if(setup_packet.wLength < size) size = setup_packet.wLength; // shortened request
if(size < endpoints[0].txbufsz){
EP_WriteIRQ(0, buf, size);
return;
}
while(size){
uint16_t l = size;
if(l > endpoints[0].txbufsz) l = endpoints[0].txbufsz;
EP_WriteIRQ(0, buf, l);
buf += l;
size -= l;
uint8_t needzlp = (l == endpoints[0].txbufsz) ? 1 : 0;
if(size || needzlp){ // send last data buffer
uint16_t status = KEEP_DTOG(USB->EPnR[0]);
// keep DTOGs, clear CTR_RX,TX, set TX VALID, leave stat_Rx
USB->EPnR[0] = (status & ~(USB_EPnR_CTR_RX|USB_EPnR_CTR_TX|USB_EPnR_STAT_RX))
^ USB_EPnR_STAT_TX;
uint32_t ctr = 1000000;
while(--ctr && (USB->ISTR & USB_ISTR_CTR) == 0){IWDG->KR = IWDG_REFRESH;};
if((USB->ISTR & USB_ISTR_CTR) == 0){
return;
}
if(needzlp) EP_WriteIRQ(0, (uint8_t*)0, 0);
}
}
}
static inline void get_descriptor(){
switch(setup_packet.wValue){
case DEVICE_DESCRIPTOR:
wr0(USB_DeviceDescriptor, sizeof(USB_DeviceDescriptor));
break;
case CONFIGURATION_DESCRIPTOR:
wr0(USB_ConfigDescriptor, sizeof(USB_ConfigDescriptor));
break;
case STRING_LANG_DESCRIPTOR:
wr0((const uint8_t *)&USB_StringLangDescriptor, STRING_LANG_DESCRIPTOR_SIZE_BYTE);
break;
case STRING_MAN_DESCRIPTOR:
wr0((const uint8_t *)&USB_StringManufacturingDescriptor, USB_StringManufacturingDescriptor.bLength);
break;
case STRING_PROD_DESCRIPTOR:
wr0((const uint8_t *)&USB_StringProdDescriptor, USB_StringProdDescriptor.bLength);
break;
case STRING_SN_DESCRIPTOR:
wr0((const uint8_t *)&USB_StringSerialDescriptor, USB_StringSerialDescriptor.bLength);
break;
case DEVICE_QUALIFIER_DESCRIPTOR:
wr0(USB_DeviceQualifierDescriptor, USB_DeviceQualifierDescriptor[0]);
break;
default:
break;
}
}
static uint8_t configuration = 0; // reply for GET_CONFIGURATION (==1 if configured)
static inline void std_d2h_req(){
uint16_t status = 0; // bus powered
switch(setup_packet.bRequest){
case GET_DESCRIPTOR:
get_descriptor();
break;
case GET_STATUS:
EP_WriteIRQ(0, (uint8_t *)&status, 2); // send status: Bus Powered
break;
case GET_CONFIGURATION:
EP_WriteIRQ(0, &configuration, 1);
break;
default:
break;
}
}
static inline void std_h2d_req(){
switch(setup_packet.bRequest){
case SET_ADDRESS:
// new address will be assigned later - after acknowlegement or request to host
USB_Dev.USB_Addr = setup_packet.wValue;
break;
case SET_CONFIGURATION:
// Now device configured
USB_Dev.USB_Status = USB_STATE_CONFIGURED;
configuration = setup_packet.wValue;
break;
default:
break;
}
}
/*
bmRequestType: 76543210
7 direction: 0 - host->device, 1 - device->host
65 type: 0 - standard, 1 - class, 2 - vendor
4..0 getter: 0 - device, 1 - interface, 2 - endpoint, 3 - other
*/
/**
* Endpoint0 (control) handler
*/
static void EP0_Handler(){
uint16_t epstatus = USB->EPnR[0]; // EP0R on input -> return this value after modifications
uint8_t reqtype = setup_packet.bmRequestType & 0x7f;
uint8_t dev2host = (setup_packet.bmRequestType & 0x80) ? 1 : 0;
int rxflag = RX_FLAG(epstatus);
if(rxflag && SETUP_FLAG(epstatus)){
switch(reqtype){
case STANDARD_DEVICE_REQUEST_TYPE: // standard device request
if(dev2host){
std_d2h_req();
}else{
std_h2d_req();
EP_WriteIRQ(0, (uint8_t *)0, 0);
}
break;
case STANDARD_ENDPOINT_REQUEST_TYPE: // standard endpoint request
if(setup_packet.bRequest == CLEAR_FEATURE){
EP_WriteIRQ(0, (uint8_t *)0, 0);
}
break;
case VENDOR_REQUEST_TYPE:
vendor_handler(&setup_packet);
break;
case CONTROL_REQUEST_TYPE:
switch(setup_packet.bRequest){
case GET_LINE_CODING:
EP_WriteIRQ(0, (uint8_t*)&lineCoding, sizeof(lineCoding));
break;
case SET_LINE_CODING: // omit this for next stage, when data will come
break;
case SET_CONTROL_LINE_STATE:
usbON = 1;
clstate_handler(setup_packet.wValue);
break;
case SEND_BREAK:
usbON = 0;
break_handler();
break;
default:
break;
}
if(setup_packet.bRequest != GET_LINE_CODING) EP_WriteIRQ(0, (uint8_t *)0, 0); // write acknowledgement
break;
default:
EP_WriteIRQ(0, (uint8_t *)0, 0);
}
}else if(rxflag){ // got data over EP0 or host acknowlegement
if(endpoints[0].rx_cnt){
if(setup_packet.bRequest == SET_LINE_CODING){
linecoding_handler((usb_LineCoding*)ep0databuf);
}
}
} else if(TX_FLAG(epstatus)){ // package transmitted
// now we can change address after enumeration
if ((USB->DADDR & USB_DADDR_ADD) != USB_Dev.USB_Addr){
USB->DADDR = USB_DADDR_EF | USB_Dev.USB_Addr;
// change state to ADRESSED
USB_Dev.USB_Status = USB_STATE_ADDRESSED;
}
}
epstatus = KEEP_DTOG(USB->EPnR[0]);
if(rxflag) epstatus ^= USB_EPnR_STAT_TX; // start ZLP/data transmission
else epstatus &= ~USB_EPnR_STAT_TX; // or leave unchanged
// keep DTOGs, clear CTR_RX,TX, set RX VALID
USB->EPnR[0] = (epstatus & ~(USB_EPnR_CTR_RX|USB_EPnR_CTR_TX)) ^ USB_EPnR_STAT_RX;
}
static uint16_t lastaddr = LASTADDR_DEFAULT;
/**
* Endpoint initialisation
* !!! when working with CAN bus change USB_BTABLE_SIZE to 768 !!!
* @param number - EP num (0...7)
* @param type - EP type (EP_TYPE_BULK, EP_TYPE_CONTROL, EP_TYPE_ISO, EP_TYPE_INTERRUPT)
* @param txsz - transmission buffer size @ USB/CAN buffer
* @param rxsz - reception buffer size @ USB/CAN buffer
* @param uint16_t (*func)(ep_t *ep) - EP handler function
* @return 0 if all OK
*/
int EP_Init(uint8_t number, uint8_t type, uint16_t txsz, uint16_t rxsz, void (*func)()){
if(number >= STM32ENDPOINTS) return 4; // out of configured amount
if(txsz > USB_BTABLE_SIZE || rxsz > USB_BTABLE_SIZE) return 1; // buffer too large
if(lastaddr + txsz + rxsz >= USB_BTABLE_SIZE) return 2; // out of btable
USB->EPnR[number] = (type << 9) | (number & USB_EPnR_EA);
USB->EPnR[number] ^= USB_EPnR_STAT_RX | USB_EPnR_STAT_TX_1;
if(rxsz & 1 || rxsz > 512) return 3; // wrong rx buffer size
uint16_t countrx = 0;
if(rxsz < 64) countrx = rxsz / 2;
else{
if(rxsz & 0x1f) return 3; // should be multiple of 32
countrx = 31 + rxsz / 32;
}
USB_BTABLE->EP[number].USB_ADDR_TX = lastaddr;
endpoints[number].tx_buf = (uint16_t *)(USB_BTABLE_BASE + lastaddr);
endpoints[number].txbufsz = txsz;
lastaddr += txsz;
USB_BTABLE->EP[number].USB_COUNT_TX = 0;
USB_BTABLE->EP[number].USB_ADDR_RX = lastaddr;
endpoints[number].rx_buf = (uint8_t *)(USB_BTABLE_BASE + lastaddr);
lastaddr += rxsz;
// buffer size: Table127 of RM
USB_BTABLE->EP[number].USB_COUNT_RX = countrx << 10;
endpoints[number].func = func;
return 0;
}
// standard IRQ handler
void usb_isr(){
if (USB->ISTR & USB_ISTR_RESET){
// Reinit registers
USB->CNTR = USB_CNTR_RESETM | USB_CNTR_CTRM | USB_CNTR_SUSPM | USB_CNTR_WKUPM;
USB->ISTR = 0;
// Endpoint 0 - CONTROL
// ON USB LS size of EP0 may be 8 bytes, but on FS it should be 64 bytes!
lastaddr = LASTADDR_DEFAULT; // roll back to beginning of buffer
EP_Init(0, EP_TYPE_CONTROL, USB_EP0_BUFSZ, USB_EP0_BUFSZ, EP0_Handler);
// clear address, leave only enable bit
USB->DADDR = USB_DADDR_EF;
// state is default - wait for enumeration
USB_Dev.USB_Status = USB_STATE_DEFAULT;
}
if(USB->ISTR & USB_ISTR_CTR){
// EP number
uint8_t n = USB->ISTR & USB_ISTR_EPID;
// copy status register
uint16_t epstatus = USB->EPnR[n];
// copy received bytes amount
endpoints[n].rx_cnt = USB_BTABLE->EP[n].USB_COUNT_RX & 0x3FF; // low 10 bits is counter
// check direction
if(USB->ISTR & USB_ISTR_DIR){ // OUT interrupt - receive data, CTR_RX==1 (if CTR_TX == 1 - two pending transactions: receive following by transmit)
if(n == 0){ // control endpoint
if(epstatus & USB_EPnR_SETUP){ // setup packet -> copy data to conf_pack
EP_Read(0, (uint8_t*)&setup_packet);
ep0dbuflen = 0;
// interrupt handler will be called later
}else if(epstatus & USB_EPnR_CTR_RX){ // data packet -> push received data to ep0databuf
ep0dbuflen = endpoints[0].rx_cnt;
EP_Read(0, (uint8_t*)&ep0databuf);
}
}
}
// call EP handler
if(endpoints[n].func) endpoints[n].func(endpoints[n]);
}
if(USB->ISTR & USB_ISTR_SUSP){ // suspend -> still no connection, may sleep
usbON = 0;
USB->CNTR |= USB_CNTR_FSUSP | USB_CNTR_LPMODE;
USB->ISTR = ~USB_ISTR_SUSP;
}
if(USB->ISTR & USB_ISTR_WKUP){ // wakeup
USB->CNTR &= ~(USB_CNTR_FSUSP | USB_CNTR_LPMODE); // clear suspend flags
USB->ISTR = ~USB_ISTR_WKUP;
}
}
/**
* Write data to EP buffer (called from IRQ handler)
* @param number - EP number
* @param *buf - array with data
* @param size - its size
*/
void EP_WriteIRQ(uint8_t number, const uint8_t *buf, uint16_t size){
uint8_t i;
if(size > USB_TXBUFSZ) size = USB_TXBUFSZ;
uint16_t N2 = (size + 1) >> 1;
// the buffer is 16-bit, so we should copy data as it would be uint16_t
uint16_t *buf16 = (uint16_t *)buf;
for (i = 0; i < N2; i++){
endpoints[number].tx_buf[i] = buf16[i];
}
USB_BTABLE->EP[number].USB_COUNT_TX = size;
}
/**
* Write data to EP buffer (called outside IRQ handler)
* @param number - EP number
* @param *buf - array with data
* @param size - its size
*/
void EP_Write(uint8_t number, const uint8_t *buf, uint16_t size){
EP_WriteIRQ(number, buf, size);
uint16_t status = KEEP_DTOG(USB->EPnR[number]);
// keep DTOGs, clear CTR_TX & set TX VALID to start transmission
USB->EPnR[number] = (status & ~(USB_EPnR_CTR_TX)) ^ USB_EPnR_STAT_TX;
}
/*
* Copy data from EP buffer into user buffer area
* @param *buf - user array for data
* @return amount of data read
*/
int EP_Read(uint8_t number, uint8_t *buf){
int n = endpoints[number].rx_cnt;
if(n){
for(int i = 0; i < n; ++i)
buf[i] = endpoints[number].rx_buf[i];
}
return n;
}

View File

@ -0,0 +1,184 @@
/*
* This file is part of the canrelay project.
* Copyright 2021 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 __USB_LIB_H__
#define __USB_LIB_H__
#include <wchar.h>
#include "usb_defs.h"
#define EP0DATABUF_SIZE (64)
#define LASTADDR_DEFAULT (STM32ENDPOINTS * 8)
// bmRequestType & 0x7f
#define STANDARD_DEVICE_REQUEST_TYPE 0
#define STANDARD_ENDPOINT_REQUEST_TYPE 2
#define VENDOR_REQUEST_TYPE 0x40
#define CONTROL_REQUEST_TYPE 0x21
// bRequest, standard; for bmRequestType == 0x80
#define GET_STATUS 0x00
#define GET_DESCRIPTOR 0x06
#define GET_CONFIGURATION 0x08
// for bmRequestType == 0
#define CLEAR_FEATURE 0x01
#define SET_FEATURE 0x03 // unused
#define SET_ADDRESS 0x05
#define SET_DESCRIPTOR 0x07 // unused
#define SET_CONFIGURATION 0x09
// for bmRequestType == 0x81, 1 or 0xB2
#define GET_INTERFACE 0x0A // unused
#define SET_INTERFACE 0x0B // unused
#define SYNC_FRAME 0x0C // unused
#define VENDOR_REQUEST 0x01 // unused
// Class-Specific Control Requests
#define SEND_ENCAPSULATED_COMMAND 0x00 // unused
#define GET_ENCAPSULATED_RESPONSE 0x01 // unused
#define SET_COMM_FEATURE 0x02 // unused
#define GET_COMM_FEATURE 0x03 // unused
#define CLEAR_COMM_FEATURE 0x04 // unused
#define SET_LINE_CODING 0x20
#define GET_LINE_CODING 0x21
#define SET_CONTROL_LINE_STATE 0x22
#define SEND_BREAK 0x23
// control line states
#define CONTROL_DTR 0x01
#define CONTROL_RTS 0x02
// wValue
#define DEVICE_DESCRIPTOR 0x100
#define CONFIGURATION_DESCRIPTOR 0x200
#define STRING_LANG_DESCRIPTOR 0x300
#define STRING_MAN_DESCRIPTOR 0x301
#define STRING_PROD_DESCRIPTOR 0x302
#define STRING_SN_DESCRIPTOR 0x303
#define DEVICE_QUALIFIER_DESCRIPTOR 0x600
#define RX_FLAG(epstat) (epstat & USB_EPnR_CTR_RX)
#define TX_FLAG(epstat) (epstat & USB_EPnR_CTR_TX)
#define SETUP_FLAG(epstat) (epstat & USB_EPnR_SETUP)
// EPnR bits manipulation
#define KEEP_DTOG_STAT(EPnR) (EPnR & ~(USB_EPnR_STAT_RX|USB_EPnR_STAT_TX|USB_EPnR_DTOG_RX|USB_EPnR_DTOG_TX))
#define KEEP_DTOG(EPnR) (EPnR & ~(USB_EPnR_DTOG_RX|USB_EPnR_DTOG_TX))
// USB state: uninitialized, addressed, ready for use, client connected
typedef enum{
USB_STATE_DEFAULT,
USB_STATE_ADDRESSED,
USB_STATE_CONFIGURED,
USB_STATE_CONNECTED
} USB_state;
// EP types
#define EP_TYPE_BULK 0x00
#define EP_TYPE_CONTROL 0x01
#define EP_TYPE_ISO 0x02
#define EP_TYPE_INTERRUPT 0x03
#define LANG_US (uint16_t)0x0409
#define _USB_STRING_(name, str) \
static const struct name \
{ \
uint8_t bLength; \
uint8_t bDescriptorType; \
uint16_t bString[(sizeof(str) - 2) / 2]; \
\
} \
name = {sizeof(name), 0x03, str}
#define _USB_LANG_ID_(name, lng_id) \
\
static const struct name \
{ \
uint8_t bLength; \
uint8_t bDescriptorType; \
uint16_t bString; \
\
} \
name = {0x04, 0x03, lng_id}
#define STRING_LANG_DESCRIPTOR_SIZE_BYTE (4)
// EP0 configuration packet
typedef struct {
uint8_t bmRequestType;
uint8_t bRequest;
uint16_t wValue;
uint16_t wIndex;
uint16_t wLength;
} config_pack_t;
// endpoints state
typedef struct __ep_t{
uint16_t *tx_buf; // transmission buffer address
uint16_t txbufsz; // transmission buffer size
uint8_t *rx_buf; // reception buffer address
void (*func)(); // endpoint action function
uint16_t rx_cnt; // received data counter
} ep_t;
// USB status & its address
typedef struct {
uint8_t USB_Status;
uint16_t USB_Addr;
}usb_dev_t;
typedef struct {
uint32_t dwDTERate;
uint8_t bCharFormat;
#define USB_CDC_1_STOP_BITS 0
#define USB_CDC_1_5_STOP_BITS 1
#define USB_CDC_2_STOP_BITS 2
uint8_t bParityType;
#define USB_CDC_NO_PARITY 0
#define USB_CDC_ODD_PARITY 1
#define USB_CDC_EVEN_PARITY 2
#define USB_CDC_MARK_PARITY 3
#define USB_CDC_SPACE_PARITY 4
uint8_t bDataBits;
} __attribute__ ((packed)) usb_LineCoding;
typedef struct {
uint8_t bmRequestType;
uint8_t bNotificationType;
uint16_t wValue;
uint16_t wIndex;
uint16_t wLength;
} __attribute__ ((packed)) usb_cdc_notification;
extern ep_t endpoints[];
extern usb_dev_t USB_Dev;
extern uint8_t usbON;
void USB_Init();
uint8_t USB_GetState();
int EP_Init(uint8_t number, uint8_t type, uint16_t txsz, uint16_t rxsz, void (*func)());
void EP_WriteIRQ(uint8_t number, const uint8_t *buf, uint16_t size);
void EP_Write(uint8_t number, const uint8_t *buf, uint16_t size);
int EP_Read(uint8_t number, uint8_t *buf);
usb_LineCoding getLineCoding();
void linecoding_handler(usb_LineCoding *lc);
void clstate_handler(uint16_t val);
void break_handler();
void vendor_handler(config_pack_t *packet);
#endif // __USB_LIB_H__

View File

@ -24,6 +24,14 @@
#include <stdint.h>
#ifndef TRUE
#define TRUE 1
#endif
#ifndef FALSE
#define FALSE 0
#endif
#ifndef TRUE_INLINE
#define TRUE_INLINE __attribute__((always_inline)) static inline
#endif

View File

@ -24,6 +24,14 @@
#include <stdint.h>
#ifndef TRUE
#define TRUE 1
#endif
#ifndef FALSE
#define FALSE 0
#endif
#ifndef TRUE_INLINE
#define TRUE_INLINE __attribute__((always_inline)) static inline
#endif