nwxt appr. to canusbrelay

This commit is contained in:
Edward Emelianov 2021-07-23 23:37:52 +03:00
parent 813549e0f2
commit 4fc13b2b11
21 changed files with 647 additions and 7988 deletions

View File

@ -9,7 +9,7 @@ MCU = F042x6
#DEFS += -DEBUG #DEFS += -DEBUG
# change this linking script depending on particular MCU model, # change this linking script depending on particular MCU model,
# for example, if you have STM32F103VBT6, you should write: # for example, if you have STM32F103VBT6, you should write:
LDSCRIPT = stm32f042k.ld LDSCRIPT = stm32f042x6.ld
INDEPENDENT_HEADERS= INDEPENDENT_HEADERS=
@ -131,7 +131,7 @@ clean:
dfuboot: $(BIN) dfuboot: $(BIN)
@echo " LOAD $(BIN) THROUGH DFU" @echo " LOAD $(BIN) THROUGH DFU"
$(DFUUTIL) -a0 -D $(BIN) -s 0x08000000 $(DFUUTIL) -a0 -R -D $(BIN) -s 0x08000000
flash: $(BIN) flash: $(BIN)
@echo " FLASH $(BIN)" @echo " FLASH $(BIN)"

View File

@ -1,10 +1,21 @@
Simple code for CAN/USB development board CAN/USB management of 2 relays and some other things
Simultaneous work of USB CDC (PL2303 emulation) and CAN ===================================================
The device can also work as USB-CAN converter.
CAN protocol is quite simple. The node receives data to selected CAN ID, transmission done with the
ID = CANID + 0x100.
Pinout: Pinout:
PB0 - LED0 - short blink when message received - PA0/1 - Relay0/1
PB1 - LED1 - shine when line OK - PA2..5 - Button0..3 (user buttons)
- PA6/7 - ADC inputs through resistive divider (0..5 and 0..12V)
PB8, PB9 - CAN Rx/Tx - PA8..10 - PWM0..2 outputs (opendrain through SI2300, 5 or 12V)
- PA13/14 - SWD; the SWD pin +3.3V connected through 22Ohm resistor
PA11. PA12 - USB DM/DP - PA11. PA12 - USB DM/DP
- PB0..PB7 - CAN ID
- PB8, PB9 - CAN Rx/Tx
- PB12..15 - LED0..3 outputs (direct outputs without any protection!!!)
The pins LEDr0 and LEDr1 are indicated relay works (12V through 2.2kOhm resistor)

View File

@ -0,0 +1,81 @@
/*
* 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 "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
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_RELEASE){ // released
if(k->counter > PRESSTHRESHOLD) k->counter = PRESSTHRESHOLD;
else if((k->counter -= d) < 0){
k->event = EVT_NONE; // button released
}
}
}
if(e != k->event){
k->lastTms = 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;
}

View File

@ -0,0 +1,42 @@
/*
* 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 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);
#define BUTTONS_H__
#endif // BUTTONS_H__

View File

@ -1,12 +1,10 @@
/* /*
* geany_encoding=koi8-r * This file is part of the canrelay project.
* can.c * Copyright 2021 Edward V. Emelianov <edward.emelianoff@gmail.com>.
* *
* Copyright 2018 Edward V. Emelianov <eddy@sao.ru, edward.emelianoff@gmail.com> * This program is free software: you can redistribute it and/or modify
*
* 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 * it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or * the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version. * (at your option) any later version.
* *
* This program is distributed in the hope that it will be useful, * This program is distributed in the hope that it will be useful,
@ -15,11 +13,9 @@
* GNU General Public License for more details. * GNU General Public License for more details.
* *
* You should have received a copy of the GNU General Public License * You should have received a copy of the GNU General Public License
* along with this program; if not, write to the Free Software * along with this program. If not, see <http://www.gnu.org/licenses/>.
* Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston,
* MA 02110-1301, USA.
*
*/ */
#include "can.h" #include "can.h"
#include "hardware.h" #include "hardware.h"
#include "proto.h" #include "proto.h"
@ -42,6 +38,7 @@ static void can_process_fifo(uint8_t fifo_num);
static CAN_message loc_flood_msg; static CAN_message loc_flood_msg;
static CAN_message *flood_msg = NULL; // == loc_flood_msg - to flood static CAN_message *flood_msg = NULL; // == loc_flood_msg - to flood
CAN_status CAN_get_status(){ CAN_status CAN_get_status(){
CAN_status st = can_status; CAN_status st = can_status;
// give overrun message only once // give overrun message only once
@ -108,7 +105,6 @@ so if TBS1=4 and TBS2=3, sum=8, bit sampling freq is 48/8 = 6MHz
// speed - in kbps // speed - in kbps
void CAN_setup(uint16_t speed){ void CAN_setup(uint16_t speed){
LED_off(LED1);
if(speed == 0) speed = oldspeed; if(speed == 0) speed = oldspeed;
else if(speed < 50) speed = 50; else if(speed < 50) speed = 50;
else if(speed > 3000) speed = 3000; else if(speed > 3000) speed = 3000;
@ -123,46 +119,32 @@ void CAN_setup(uint16_t speed){
| (4 << (0 * 4)) | (4 << (1 * 4)); /* (2) */ | (4 << (0 * 4)) | (4 << (1 * 4)); /* (2) */
/* Enable the peripheral clock CAN */ /* Enable the peripheral clock CAN */
RCC->APB1ENR |= RCC_APB1ENR_CANEN; RCC->APB1ENR |= RCC_APB1ENR_CANEN;
/* Configure CAN */ // Configure CAN
/* (1) Enter CAN init mode to write the configuration */ while((CAN->MSR & CAN_MSR_INAK)!=CAN_MSR_INAK)
/* (2) Wait the init mode entering */
/* (3) Exit sleep mode */
/* (4) Normal mode, set timing to 100kb/s: TBS1 = 4, TBS2 = 3, prescaler = 60 */
/* (5) Leave init mode */
/* (6) Wait the init mode leaving */
/* (7) Enter filter init mode, (16-bit + mask, bank 0 for FIFO 0) */
/* (8) Acivate filter 0 for two IDs */
/* (9) Identifier list mode */
/* (10) Set the Id list */
/* (12) Leave filter init */
/* (13) Set error interrupts enable */
CAN->MCR |= CAN_MCR_INRQ; /* (1) */
while((CAN->MSR & CAN_MSR_INAK)!=CAN_MSR_INAK) /* (2) */
{ {
if(--tmout == 0) break; if(--tmout == 0) break;
} }
CAN->MCR &=~ CAN_MCR_SLEEP; /* (3) */ CAN->MCR &=~ CAN_MCR_SLEEP;
CAN->MCR |= CAN_MCR_ABOM; /* allow automatically bus-off */ CAN->MCR |= CAN_MCR_ABOM; // allow automatically bus-off
CAN->BTR = 2 << 20 | 3 << 16 | (6000/speed - 1); // speed
CAN->BTR = 2 << 20 | 3 << 16 | (6000/speed - 1); /* (4) */ CAN->MCR &=~ CAN_MCR_INRQ;
CAN->MCR &=~ CAN_MCR_INRQ; /* (5) */
tmout = 16000000; tmout = 16000000;
while((CAN->MSR & CAN_MSR_INAK)==CAN_MSR_INAK) if(--tmout == 0) break; /* (6) */ while((CAN->MSR & CAN_MSR_INAK)==CAN_MSR_INAK) if(--tmout == 0) break;
// accept ALL // accept self ID at filter 0, ALL other at filters 1 and 2
CAN->FMR = CAN_FMR_FINIT; /* (7) */ CAN->FMR = CAN_FMR_FINIT;
CAN->FA1R = CAN_FA1R_FACT0 | CAN_FA1R_FACT1; /* (8) */ 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 // set to 1 all needed bits of CAN->FFA1R to switch given filters to FIFO1
CAN->sFilterRegister[0].FR1 = (1<<21)|(1<<5); // all odd IDs CAN->sFilterRegister[0].FR1 = CANID << 5; // self ID
CAN->FFA1R = 2; // filter 1 for FIFO1, filter 0 - for FIFO0 CAN->sFilterRegister[1].FR1 = (1<<21)|(1<<5); // all odd IDs
CAN->sFilterRegister[1].FR1 = (1<<21); // all even IDs CAN->sFilterRegister[2].FR1 = (1<<21); // all even IDs
CAN->FMR &=~ CAN_FMR_FINIT; /* (12) */ CAN->FFA1R = 2; // filter 1 for FIFO1, filters 0&2 - for FIFO0
CAN->IER |= CAN_IER_ERRIE | CAN_IER_FOVIE0 | CAN_IER_FOVIE1; /* (13) */ CAN->FMR &=~ CAN_FMR_FINIT; // end of filters init
CAN->IER |= CAN_IER_ERRIE | CAN_IER_FOVIE0 | CAN_IER_FOVIE1;
/* Configure IT */ /* Configure IT */
/* (14) Set priority for CAN_IRQn */ NVIC_SetPriority(CEC_CAN_IRQn, 0);
/* (15) Enable CAN_IRQn */ NVIC_EnableIRQ(CEC_CAN_IRQn);
NVIC_SetPriority(CEC_CAN_IRQn, 0); /* (14) */
NVIC_EnableIRQ(CEC_CAN_IRQn); /* (15) */
can_status = CAN_READY; can_status = CAN_READY;
} }
@ -284,7 +266,6 @@ void set_flood(CAN_message *msg){
static void can_process_fifo(uint8_t fifo_num){ static void can_process_fifo(uint8_t fifo_num){
if(fifo_num > 1) return; if(fifo_num > 1) return;
LED_on(LED1); // Turn on LED1 - message received
CAN_FIFOMailBox_TypeDef *box = &CAN->sFIFOMailBox[fifo_num]; CAN_FIFOMailBox_TypeDef *box = &CAN->sFIFOMailBox[fifo_num];
volatile uint32_t *RFxR = (fifo_num) ? &CAN->RF1R : &CAN->RF0R; volatile uint32_t *RFxR = (fifo_num) ? &CAN->RF1R : &CAN->RF0R;
// read all // read all

View File

@ -1,12 +1,10 @@
/* /*
* geany_encoding=koi8-r * This file is part of the canrelay project.
* can.h * Copyright 2021 Edward V. Emelianov <edward.emelianoff@gmail.com>.
* *
* Copyright 2018 Edward V. Emelianov <eddy@sao.ru, edward.emelianoff@gmail.com> * This program is free software: you can redistribute it and/or modify
*
* 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 * it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or * the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version. * (at your option) any later version.
* *
* This program is distributed in the hope that it will be useful, * This program is distributed in the hope that it will be useful,
@ -15,21 +13,22 @@
* GNU General Public License for more details. * GNU General Public License for more details.
* *
* You should have received a copy of the GNU General Public License * You should have received a copy of the GNU General Public License
* along with this program; if not, write to the Free Software * along with this program. If not, see <http://www.gnu.org/licenses/>.
* Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston,
* MA 02110-1301, USA.
*
*/ */
#pragma once #pragma once
#ifndef __CAN_H__ #ifndef __CAN_H__
#define __CAN_H__ #define __CAN_H__
#include "hardware.h" #include "hardware.h"
// CAN ID mask (11 bits)
#define CANIDMASK (0x7ff)
// amount of filter banks in STM32F0 // amount of filter banks in STM32F0
#define STM32F0FBANKNO 28 #define STM32F0FBANKNO (28)
// flood period in milliseconds // flood period in milliseconds
#define FLOOD_PERIOD_MS 5 #define FLOOD_PERIOD_MS (5)
// incoming message buffer size // incoming message buffer size
#define CAN_INMESSAGE_SIZE (8) #define CAN_INMESSAGE_SIZE (8)

View File

@ -1,12 +1,10 @@
/* /*
* geany_encoding=koi8-r * This file is part of the canrelay project.
* hardware.c - hardware-dependent macros & functions * Copyright 2021 Edward V. Emelianov <edward.emelianoff@gmail.com>.
* *
* Copyright 2018 Edward V. Emelianov <eddy@sao.ru, edward.emelianoff@gmail.com> * This program is free software: you can redistribute it and/or modify
*
* 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 * it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or * the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version. * (at your option) any later version.
* *
* This program is distributed in the hope that it will be useful, * This program is distributed in the hope that it will be useful,
@ -15,24 +13,37 @@
* GNU General Public License for more details. * GNU General Public License for more details.
* *
* You should have received a copy of the GNU General Public License * You should have received a copy of the GNU General Public License
* along with this program; if not, write to the Free Software * along with this program. If not, see <http://www.gnu.org/licenses/>.
* Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston,
* MA 02110-1301, USA.
*
*/ */
#include "hardware.h" #include "hardware.h"
#include "can.h"
uint8_t ledsON = 0; uint16_t CANID = 0xFFFF; // self CAN ID (read @ init)
// LEDS: 0 - PB12, 1 - PB13, 2 - PB14, 3 - PB15
GPIO_TypeDef *LEDports[LEDSNO] = {GPIOB, GPIOB, GPIOB, GPIOB};
const uint32_t LEDpins[LEDSNO] = {1<<12, 1<<13, 1<<14, 1<<15};
// Buttons: PA2..PA5, pullup
GPIO_TypeDef *BTNports[BTNSNO] = {GPIOA, GPIOA, GPIOA, GPIOA};
const uint32_t BTNpins[BTNSNO] = {1<<2, 1<<3, 1<<4, 1<<5};
void gpio_setup(void){ void gpio_setup(void){
RCC->AHBENR |= RCC_AHBENR_GPIOBEN; RCC->AHBENR |= RCC_AHBENR_GPIOAEN | RCC_AHBENR_GPIOBEN;
// Set LEDS (PB0/1) as output // Set LEDS (PB12..15) as output, ADDR (PB0..7) - pullup inputs
pin_set(LED0_port, LED0_pin); // clear LEDs // WARNING! All code here is hardcore!
pin_set(LED1_port, LED1_pin); pin_set(GPIOB, 0xf<<12); // clear LEDs
GPIOB->MODER = (GPIOB->MODER & ~(GPIO_MODER_MODER0 | GPIO_MODER_MODER1) GPIOB->MODER = GPIO_MODER_MODER12_O | GPIO_MODER_MODER13_O | GPIO_MODER_MODER14_O | GPIO_MODER_MODER15_O;
) | GPIOB->PUPDR = GPIO_PUPDR0_PU | GPIO_PUPDR1_PU | GPIO_PUPDR2_PU | GPIO_PUPDR3_PU | GPIO_PUPDR4_PU |
GPIO_MODER_MODER0_O | GPIO_MODER_MODER1_O; GPIO_PUPDR5_PU | GPIO_PUPDR6_PU | GPIO_PUPDR7_PU;
// relays (PA0..1) as outputs, buttons (PA2..5) as pullup inputs
// PA8..10 - PWM @ TIM1
GPIOA->MODER = GPIO_MODER_MODER0_O | GPIO_MODER_MODER1_O |
GPIO_MODER_MODER8_AF | GPIO_MODER_MODER9_AF | GPIO_MODER_MODER10_AF;
GPIOA->PUPDR = GPIO_PUPDR2_PU | GPIO_PUPDR3_PU | GPIO_PUPDR4_PU | GPIO_PUPDR5_PU;
CANID = (~READ_INV_CAN_ADDR()) & CAN_INV_ID_MASK;
// alternate functions @TIM1 PWM (AF2), PA8..10
GPIOA->AFR[1] = (2 << (0*4)) | (2 << (1*4)) | (2 << (2*4));
} }
void iwdg_setup(){ void iwdg_setup(){
@ -58,6 +69,21 @@ void iwdg_setup(){
IWDG->KR = IWDG_REFRESH; /* (6) */ IWDG->KR = IWDG_REFRESH; /* (6) */
} }
void tim1_setup(){
// 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
}
// pause in milliseconds for some purposes // pause in milliseconds for some purposes
void pause_ms(uint32_t pause){ void pause_ms(uint32_t pause){
uint32_t Tnxt = Tms + pause; uint32_t Tnxt = Tms + pause;
@ -65,12 +91,13 @@ void pause_ms(uint32_t pause){
} }
void Jump2Boot(){ void Jump2Boot(){
__disable_irq();
IWDG->KR = IWDG_REFRESH;
void (*SysMemBootJump)(void); void (*SysMemBootJump)(void);
volatile uint32_t addr = 0x1FFFC800; volatile uint32_t addr = SystemMem;
// reset systick // reset systick
SysTick->CTRL = 0; SysTick->CTRL = 0;
// reset clocks // reset clocks
RCC->APB1RSTR = RCC_APB1RSTR_CECRST | RCC_APB1RSTR_DACRST | RCC_APB1RSTR_PWRRST | RCC_APB1RSTR_CRSRST | 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_CANRST | RCC_APB1RSTR_USBRST | RCC_APB1RSTR_I2C2RST | RCC_APB1RSTR_I2C1RST |
RCC_APB1RSTR_USART4RST | RCC_APB1RSTR_USART3RST | RCC_APB1RSTR_USART2RST | RCC_APB1RSTR_SPI2RST | RCC_APB1RSTR_USART4RST | RCC_APB1RSTR_USART3RST | RCC_APB1RSTR_USART2RST | RCC_APB1RSTR_SPI2RST |
@ -87,11 +114,15 @@ void Jump2Boot(){
RCC->AHBRSTR = 0; RCC->AHBRSTR = 0;
RCC->APB1RSTR = 0; RCC->APB1RSTR = 0;
RCC->APB2RSTR = 0; RCC->APB2RSTR = 0;
// remap memory to 0 (only for STM32F0) // enable SYSCFG clocking
RCC->APB2ENR |= RCC_APB2ENR_SYSCFGEN;
__DSB();
// remap system flash memory to 0 (only for STM32F0)
SYSCFG->CFGR1 = 0x01; __DSB(); __ISB(); SYSCFG->CFGR1 = 0x01; __DSB(); __ISB();
SysMemBootJump = (void (*)(void)) (*((uint32_t *)(addr + 4))); SysMemBootJump = (void (*)(void)) (*((uint32_t *)(addr + 4)));
// set main stack pointer // set main stack pointer
__set_MSP(*((uint32_t *)addr)); __set_MSP(*((uint32_t *)addr));
IWDG->KR = IWDG_REFRESH;
// jump to bootloader // jump to bootloader
SysMemBootJump(); SysMemBootJump();
} }

View File

@ -1,12 +1,10 @@
/* /*
* geany_encoding=koi8-r * This file is part of the canrelay project.
* hardware.h * Copyright 2021 Edward V. Emelianov <edward.emelianoff@gmail.com>.
* *
* Copyright 2018 Edward V. Emelianov <eddy@sao.ru, edward.emelianoff@gmail.com> * This program is free software: you can redistribute it and/or modify
*
* 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 * it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or * the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version. * (at your option) any later version.
* *
* This program is distributed in the hope that it will be useful, * This program is distributed in the hope that it will be useful,
@ -15,17 +13,25 @@
* GNU General Public License for more details. * GNU General Public License for more details.
* *
* You should have received a copy of the GNU General Public License * You should have received a copy of the GNU General Public License
* along with this program; if not, write to the Free Software * along with this program. If not, see <http://www.gnu.org/licenses/>.
* Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston,
* MA 02110-1301, USA.
*
*/ */
#pragma once #pragma once
#ifndef __HARDWARE_H__ #ifndef __HARDWARE_H__
#define __HARDWARE_H__ #define __HARDWARE_H__
#include <stm32f0.h> #include <stm32f0.h>
#define SYSMEM03x 0x1FFFEC00
#define SYSMEM04x 0x1FFFC400
#define SYSMEM05x 0x1FFFEC00
#define SYSMEM07x 0x1FFFC800
#define SYSMEM09x 0x1FFFD800
// define SystemMem to other in MAKEFILE
#ifndef SystemMem
#define SystemMem SYSMEM04x
#endif
#define CONCAT(a,b) a ## b #define CONCAT(a,b) a ## b
#define STR_HELPER(s) #s #define STR_HELPER(s) #s
#define STR(s) STR_HELPER(s) #define STR(s) STR_HELPER(s)
@ -33,29 +39,36 @@
#define FORMUSART(X) CONCAT(USART, X) #define FORMUSART(X) CONCAT(USART, X)
#define USARTX FORMUSART(USARTNUM) #define USARTX FORMUSART(USARTNUM)
// LEDS: 0 - PB0, 1 - PB1 // LEDs amount
// LED0 #define LEDSNO (4)
#define LED0_port GPIOB // LEDs ports & pins
#define LED0_pin (1<<0) extern GPIO_TypeDef *LEDports[LEDSNO];
// LED1 extern const uint32_t LEDpins[LEDSNO];
#define LED1_port GPIOB // LEDS: 0 - PB12, 1 - PB13, 2 - PB14, 3 - PB15
#define LED1_pin (1<<1) #define LED_toggle(x) do{pin_toggle(LEDports[x], LEDpins[x]);}while(0)
#define LED_on(x) do{pin_clear(LEDports[x], LEDpins[x]);}while(0)
#define LED_off(x) do{pin_set(LEDports[x], LEDpins[x]);}while(0)
#define LED_blink(x) do{if(ledsON) pin_toggle(x ## _port, x ## _pin);}while(0) // Buttons amount
#define LED_on(x) do{if(ledsON) pin_clear(x ## _port, x ## _pin);}while(0) #define BTNSNO (4)
#define LED_off(x) do{pin_set(x ## _port, x ## _pin);}while(0) // Buttons ports & pins
extern GPIO_TypeDef *BTNports[BTNSNO];
extern const uint32_t BTNpins[BTNSNO];
// state 1 - pressed, 0 - released
#define BTN_state(x) ((BTNports[x]->IDR & BTNpins[x]) ? 0 : 1)
// mask for PB0..7
#define CAN_INV_ID_MASK (0xff)
// CAN address - PB0..7
#define READ_INV_CAN_ADDR() (GPIOB->IDR & 0xff)
// CAN address - PB14(0), PB15(1), PA8(2) extern uint16_t CANID; // self CAN ID (read @ init)
#define READ_CAN_INV_ADDR() (((GPIOA->IDR & (1<<8))>>6)|((GPIOB->IDR & (3<<14))>>14))
extern volatile uint32_t Tms; extern volatile uint32_t Tms;
extern uint8_t ledsON;
void gpio_setup(void); void gpio_setup(void);
void iwdg_setup(); void iwdg_setup();
void tim1_setup();
void pause_ms(uint32_t pause); void pause_ms(uint32_t pause);
void Jump2Boot(); void Jump2Boot();

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,151 @@
"Source:","/home/eddy/Docs/SAO/ELECTRONICS/STM32/F0-srcs/CANUSB+relays/kicad/stm32.sch"
"Date:","óÒ 16 ÉÀÎ 2021 11:40:04"
"Tool:","Eeschema 5.1.7"
"Generator:","/usr/local/share/kicad/plugins/bom_csv_grouped_by_value.py"
"Component Count:","93"
"Individual Components:"
"Item","Qty","Reference(s)","Value","LibPart","Footprint","Datasheet","Manufacturer"
"","","C1","1","stm32-rescue:C","Capacitor_SMD:C_0805_2012Metric_Pad1.15x1.40mm_HandSolder","",""
"","","C2","0.1","stm32-rescue:C","Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder","",""
"","","C3","0.1","stm32-rescue:C","Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder","",""
"","","C4","0.1","stm32-rescue:C","Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder","",""
"","","C5","1","stm32-rescue:C","Capacitor_SMD:C_0805_2012Metric_Pad1.15x1.40mm_HandSolder","",""
"","","C6","0.1","stm32-rescue:C","Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder","",""
"","","C7","0.1","Device:C","Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder","~",""
"","","C8","0.1","Device:C","Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder","~",""
"","","C9","0.1","Device:C","Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder","~",""
"","","C10","47u 16V","Device:CP","Capacitor_Tantalum_SMD:CP_EIA-6032-28_Kemet-C_Pad2.25x2.35mm_HandSolder","~",""
"","","C11","0.1","stm32-rescue:C","Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder","",""
"","","C12","47u 10V","stm32-rescue:CP","Capacitor_Tantalum_SMD:CP_EIA-1608-08_AVX-J_Pad1.25x1.05mm_HandSolder","",""
"","","C13","47u 10V","Device:CP","Capacitor_Tantalum_SMD:CP_EIA-1608-08_AVX-J_Pad1.25x1.05mm_HandSolder","~",""
"","","C14","0.1","Device:C","Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder","~",""
"","","C15","0.1","stm32-rescue:C","Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder","",""
"","","D1","PESD1CAN","elements:PESD1CAN","TO_SOT_Packages_SMD:SOT-23","",""
"","","D2","SS14","Device:D_Schottky","Diode_SMD:D_SMA-SMB_Universal_Handsoldering","~",""
"","","D3","USB6B1","elements:USB6B1","Package_SO:SOIC-8_3.9x4.9mm_P1.27mm","",""
"","","D4","SS14","Device:D_Schottky","Diode_SMD:D_SMA-SMB_Universal_Handsoldering","~",""
"","","D5","MM3Z7V5","Device:D_Zener","Diode_SMD:D_0805_2012Metric_Pad1.15x1.40mm_HandSolder","~",""
"","","D6","CESD3v3","Device:D","Diode_SMD:D_SOD-523","~",""
"","","D7","CESD3v3","Device:D","Diode_SMD:D_SOD-523","~",""
"","","D8","SS14","Device:D_Schottky","Diode_SMD:D_SMA-SMB_Universal_Handsoldering","~",""
"","","D9","SS14","Device:D_Schottky","Diode_SMD:D_SMA-SMB_Universal_Handsoldering","~",""
"","","D10","SS14","Device:D_Schottky","Diode_SMD:D_SMA-SMB_Universal_Handsoldering","~",""
"","","D11","1N5822","Device:D","Diode_THT:D_DO-201_P12.70mm_Horizontal","~",""
"","","J1","Conn_01x01_Female","Connector:Conn_01x01_Female","Connector_PinHeader_2.54mm:PinHeader_1x01_P2.54mm_Vertical","~",""
"","","J2","Conn_01x01_Female","Connector:Conn_01x01_Female","Connector_PinHeader_2.54mm:PinHeader_1x01_P2.54mm_Vertical","~",""
"","","J3","Conn_01x01_Female","Connector:Conn_01x01_Female","Connector_PinHeader_2.54mm:PinHeader_1x01_P2.54mm_Vertical","~",""
"","","J4","Conn_01x01_Female","Connector:Conn_01x01_Female","Connector_PinHeader_2.54mm:PinHeader_1x01_P2.54mm_Vertical","~",""
"","","J5","Conn_01x01_Female","Connector:Conn_01x01_Female","Connector_PinHeader_2.54mm:PinHeader_1x01_P2.54mm_Vertical","~",""
"","","J6","Conn_01x01_Female","Connector:Conn_01x01_Female","Connector_PinHeader_2.54mm:PinHeader_1x01_P2.54mm_Vertical","~",""
"","","J7","01x05","Connector:Conn_01x05_Male","Connector_PinHeader_2.54mm:PinHeader_1x05_P2.54mm_Vertical","~",""
"","","J8","Connector_Generic:Conn_02x04_Odd_Even","Connector_Generic:Conn_02x04_Odd_Even","Connector_PinHeader_2.54mm:PinHeader_2x04_P2.54mm_Vertical","~",""
"","","J9","Conn_01x02_Female","Connector:Conn_01x02_Female","Connector_PinSocket_2.54mm:PinSocket_1x02_P2.54mm_Vertical","~",""
"","","J10","Screw_Terminal_01x02","Connector:Screw_Terminal_01x02","TerminalBlock_Phoenix:TerminalBlock_Phoenix_MKDS-3-2-5.08_1x02_P5.08mm_Horizontal","~",""
"","","J11","Screw_Terminal_01x03","Connector:Screw_Terminal_01x03","TerminalBlock_Phoenix:TerminalBlock_Phoenix_MKDS-1,5-3_1x03_P5.00mm_Horizontal","~",""
"","","J12","Screw_Terminal_01x03","Connector:Screw_Terminal_01x03","TerminalBlock_Phoenix:TerminalBlock_Phoenix_MKDS-1,5-3_1x03_P5.00mm_Horizontal","~",""
"","","J13","USB_B","Connector:USB_B","Connectors_USB:USB_B_OST_USB-B1HSxx_Horizontal"," ~",""
"","","J14","DB9_Female","Connector:DB9_Female","Connector_Dsub:DSUB-9_Female_Horizontal_P2.77x2.84mm_EdgePinOffset7.70mm_Housed_MountingHolesOffset9.12mm"," ~",""
"","","J15","01x03","Connector:Conn_01x03_Male","Connector_PinSocket_2.54mm:PinSocket_1x03_P2.54mm_Vertical","~",""
"","","J16","Conn_01x02_Female","Connector:Conn_01x02_Female","Connector_PinSocket_2.54mm:PinSocket_1x02_P2.54mm_Vertical","~",""
"","","J17","Screw_Terminal_01x03","Connector:Screw_Terminal_01x03","TerminalBlock_Phoenix:TerminalBlock_Phoenix_MKDS-1,5-3_1x03_P5.00mm_Horizontal","~",""
"","","J18","01x05","Connector:Conn_01x05_Male","Connector_PinSocket_2.54mm:PinSocket_1x05_P2.54mm_Vertical","~",""
"","","JP1","NON-ISOL","Device:Jumper","Resistor_THT:R_Axial_DIN0207_L6.3mm_D2.5mm_P5.08mm_Vertical","~",""
"","","K1","G5LE-1","Relay:G5LE-1","Relay_THT:Relay_SPDT_Omron-G5LE-1","http://www.omron.com/ecb/products/pdf/en-g5le.pdf",""
"","","K2","G5LE-1","Relay:G5LE-1","Relay_THT:Relay_SPDT_Omron-G5LE-1","http://www.omron.com/ecb/products/pdf/en-g5le.pdf",""
"","","L1","100u","Device:L","Inductor_SMD:L_12x12mm_H4.5mm","~",""
"","","P1","Hole","stm32-rescue:CONN_01X01","my_footprints:Hole_3mm","",""
"","","P2","Hole","stm32-rescue:CONN_01X01","my_footprints:Hole_3mm","",""
"","","P3","Hole","stm32-rescue:CONN_01X01","my_footprints:Hole_3mm","",""
"","","P4","Hole","stm32-rescue:CONN_01X01","my_footprints:Hole_3mm","",""
"","","Q1","B0505S","elements:B0505S","my_footprints:B0x0xS","",""
"","","Q2","SI2300","Device:Q_NMOS_GSD","TO_SOT_Packages_SMD:SOT-23_Handsoldering","~",""
"","","Q3","SI2300","Device:Q_NMOS_GSD","TO_SOT_Packages_SMD:SOT-23_Handsoldering","~",""
"","","Q4","AO3407","Device:Q_PMOS_GSD","TO_SOT_Packages_SMD:SOT-23_Handsoldering","~",""
"","","Q5","SI2300","Device:Q_NMOS_GSD","TO_SOT_Packages_SMD:SOT-23_Handsoldering","~",""
"","","Q6","SI2300","Device:Q_NMOS_GSD","TO_SOT_Packages_SMD:SOT-23_Handsoldering","~",""
"","","Q7","SI2300","Device:Q_NMOS_GSD","TO_SOT_Packages_SMD:SOT-23_Handsoldering","~",""
"","","R1","10k","Device:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder","~",""
"","","R2","4k7","stm32-rescue:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder","",""
"","","R3","22","Device:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder","~",""
"","","R4","680","Device:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder","~",""
"","","R5","680","Device:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder","~",""
"","","R6","680","Device:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder","~",""
"","","R7","680","Device:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder","~",""
"","","R8","10k","Device:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder","~",""
"","","R9","330","Device:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder","~",""
"","","R10","22","stm32-rescue:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder","",""
"","","R11","22","stm32-rescue:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder","",""
"","","R12","2k2","Device:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder","~",""
"","","R13","120","stm32-rescue:R","Resistor_SMD:R_1210_3225Metric_Pad1.42x2.65mm_HandSolder","",""
"","","R14","10k","Device:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder","~",""
"","","R15","330","Device:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder","~",""
"","","R16","2k2","Device:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder","~",""
"","","R17","10k","Device:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder","~",""
"","","R18","47k","Device:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder","~",""
"","","R19","15k","Device:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder","~",""
"","","R20","15k","Device:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder","~",""
"","","R21","10k","Device:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder","~",""
"","","R22","330","Device:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder","~",""
"","","R23","330","Device:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder","~",""
"","","R24","330","Device:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder","~",""
"","","R25","10k","Device:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder","~",""
"","","R26","10k","Device:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder","~",""
"","","R27","10k","Device:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder","~",""
"","","SW1","SW_DIP_x08","Switch:SW_DIP_x08","Button_Switch_THT:SW_DIP_SPSTx08_Slide_9.78x22.5mm_W7.62mm_P2.54mm","~",""
"","","SW2","SW_DIP_x01","Switch:SW_DIP_x01","Button_Switch_THT:SW_DIP_SPSTx01_Slide_6.7x4.1mm_W7.62mm_P2.54mm_LowProfile","~",""
"","","U1","MCP2551-I/SN","stm32-rescue:MCP2551-I_SN","Package_SO:SOIC-8_3.9x4.9mm_P1.27mm","",""
"","","U2","ISO1050DUB","Interface_CAN_LIN:ISO1050DUB","Package_SO:SOP-8_6.62x9.15mm_P2.54mm","http://www.ti.com/lit/ds/symlink/iso1050.pdf",""
"","","U3","STM32F072C8Tx","MCU_ST_STM32F0:STM32F072C8Tx","Package_QFP:LQFP-48_7x7mm_P0.5mm","http://www.st.com/st-web-ui/static/active/en/resource/technical/document/datasheet/DM00090510.pdf",""
"","","U4","LM2576","vreg:LM2576","TO_SOT_Packages_THT:TO-220-5_P3.4x3.7mm_StaggerEven_Lead3.8mm_Vertical","","Texas Instruments"
"","","U5","LM1117-3.3","Regulator_Linear:LM1117-3.3","TO_SOT_Packages_SMD:SOT-223-3_TabPin2","http://www.ti.com/lit/ds/symlink/lm1117.pdf",""
"Collated Components:"
"Item","Qty","Reference(s)","Value","LibPart","Footprint","Datasheet","Manufacturer"
"1","2","C1, C5","1","stm32-rescue:C","Capacitor_SMD:C_0805_2012Metric_Pad1.15x1.40mm_HandSolder","",""
"2","10","C2, C3, C4, C6, C7, C8, C9, C11, C14, C15","0.1","stm32-rescue:C","Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder","~",""
"3","1","C10","47u 16V","Device:CP","Capacitor_Tantalum_SMD:CP_EIA-6032-28_Kemet-C_Pad2.25x2.35mm_HandSolder","~",""
"4","2","C12, C13","47u 10V","Device:CP","Capacitor_Tantalum_SMD:CP_EIA-1608-08_AVX-J_Pad1.25x1.05mm_HandSolder","~",""
"5","1","D1","PESD1CAN","elements:PESD1CAN","TO_SOT_Packages_SMD:SOT-23","",""
"6","5","D2, D4, D8, D9, D10","SS14","Device:D_Schottky","Diode_SMD:D_SMA-SMB_Universal_Handsoldering","~",""
"7","1","D3","USB6B1","elements:USB6B1","Package_SO:SOIC-8_3.9x4.9mm_P1.27mm","",""
"8","1","D5","MM3Z7V5","Device:D_Zener","Diode_SMD:D_0805_2012Metric_Pad1.15x1.40mm_HandSolder","~",""
"9","2","D6, D7","CESD3v3","Device:D","Diode_SMD:D_SOD-523","~",""
"10","1","D11","1N5822","Device:D","Diode_THT:D_DO-201_P12.70mm_Horizontal","~",""
"11","6","J1, J2, J3, J4, J5, J6","Conn_01x01_Female","Connector:Conn_01x01_Female","Connector_PinHeader_2.54mm:PinHeader_1x01_P2.54mm_Vertical","~",""
"12","1","J7","01x05","Connector:Conn_01x05_Male","Connector_PinHeader_2.54mm:PinHeader_1x05_P2.54mm_Vertical","~",""
"13","1","J8","Connector_Generic:Conn_02x04_Odd_Even","Connector_Generic:Conn_02x04_Odd_Even","Connector_PinHeader_2.54mm:PinHeader_2x04_P2.54mm_Vertical","~",""
"14","2","J9, J16","Conn_01x02_Female","Connector:Conn_01x02_Female","Connector_PinSocket_2.54mm:PinSocket_1x02_P2.54mm_Vertical","~",""
"15","1","J10","Screw_Terminal_01x02","Connector:Screw_Terminal_01x02","TerminalBlock_Phoenix:TerminalBlock_Phoenix_MKDS-3-2-5.08_1x02_P5.08mm_Horizontal","~",""
"16","3","J11, J12, J17","Screw_Terminal_01x03","Connector:Screw_Terminal_01x03","TerminalBlock_Phoenix:TerminalBlock_Phoenix_MKDS-1,5-3_1x03_P5.00mm_Horizontal","~",""
"17","1","J13","USB_B","Connector:USB_B","Connectors_USB:USB_B_OST_USB-B1HSxx_Horizontal"," ~",""
"18","1","J14","DB9_Female","Connector:DB9_Female","Connector_Dsub:DSUB-9_Female_Horizontal_P2.77x2.84mm_EdgePinOffset7.70mm_Housed_MountingHolesOffset9.12mm"," ~",""
"19","1","J15","01x03","Connector:Conn_01x03_Male","Connector_PinSocket_2.54mm:PinSocket_1x03_P2.54mm_Vertical","~",""
"20","1","J18","01x05","Connector:Conn_01x05_Male","Connector_PinSocket_2.54mm:PinSocket_1x05_P2.54mm_Vertical","~",""
"21","1","JP1","NON-ISOL","Device:Jumper","Resistor_THT:R_Axial_DIN0207_L6.3mm_D2.5mm_P5.08mm_Vertical","~",""
"22","2","K1, K2","G5LE-1","Relay:G5LE-1","Relay_THT:Relay_SPDT_Omron-G5LE-1","http://www.omron.com/ecb/products/pdf/en-g5le.pdf",""
"23","1","L1","100u","Device:L","Inductor_SMD:L_12x12mm_H4.5mm","~",""
"24","4","P1, P2, P3, P4","Hole","stm32-rescue:CONN_01X01","my_footprints:Hole_3mm","",""
"25","1","Q1","B0505S","elements:B0505S","my_footprints:B0x0xS","",""
"26","5","Q2, Q3, Q5, Q6, Q7","SI2300","Device:Q_NMOS_GSD","TO_SOT_Packages_SMD:SOT-23_Handsoldering","~",""
"27","1","Q4","AO3407","Device:Q_PMOS_GSD","TO_SOT_Packages_SMD:SOT-23_Handsoldering","~",""
"28","8","R1, R8, R14, R17, R21, R25, R26, R27","10k","Device:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder","~",""
"29","1","R2","4k7","stm32-rescue:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder","",""
"30","3","R3, R10, R11","22","stm32-rescue:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder","~",""
"31","4","R4, R5, R6, R7","680","Device:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder","~",""
"32","5","R9, R15, R22, R23, R24","330","Device:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder","~",""
"33","2","R12, R16","2k2","Device:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder","~",""
"34","1","R13","120","stm32-rescue:R","Resistor_SMD:R_1210_3225Metric_Pad1.42x2.65mm_HandSolder","",""
"35","1","R18","47k","Device:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder","~",""
"36","2","R19, R20","15k","Device:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder","~",""
"37","1","SW1","SW_DIP_x08","Switch:SW_DIP_x08","Button_Switch_THT:SW_DIP_SPSTx08_Slide_9.78x22.5mm_W7.62mm_P2.54mm","~",""
"38","1","SW2","SW_DIP_x01","Switch:SW_DIP_x01","Button_Switch_THT:SW_DIP_SPSTx01_Slide_6.7x4.1mm_W7.62mm_P2.54mm_LowProfile","~",""
"39","1","U1","MCP2551-I/SN","stm32-rescue:MCP2551-I_SN","Package_SO:SOIC-8_3.9x4.9mm_P1.27mm","",""
"40","1","U2","ISO1050DUB","Interface_CAN_LIN:ISO1050DUB","Package_SO:SOP-8_6.62x9.15mm_P2.54mm","http://www.ti.com/lit/ds/symlink/iso1050.pdf",""
"41","1","U3","STM32F072C8Tx","MCU_ST_STM32F0:STM32F072C8Tx","Package_QFP:LQFP-48_7x7mm_P0.5mm","http://www.st.com/st-web-ui/static/active/en/resource/technical/document/datasheet/DM00090510.pdf",""
"42","1","U4","LM2576","vreg:LM2576","TO_SOT_Packages_THT:TO-220-5_P3.4x3.7mm_StaggerEven_Lead3.8mm_Vertical","","Texas Instruments"
"43","1","U5","LM1117-3.3","Regulator_Linear:LM1117-3.3","TO_SOT_Packages_SMD:SOT-223-3_TabPin2","http://www.ti.com/lit/ds/symlink/lm1117.pdf",""
Can't render this file because it has a wrong number of fields in line 7.

View File

@ -1,8 +1,8 @@
"Source:","/home/eddy/Docs/SAO/ELECTRONICS/STM32/F0-srcs/CANUSB+relays/kicad/stm32.sch" "Source:","/home/eddy/Yandex.Disk/Projects/stm32samples/F0-nolib/usbcan_relay/kicad/stm32.sch"
"Date:","óÒ 16 ÉÀÎ 2021 11:40:04" "Date:","÷Ô 20 ÉÀÌ 2021 17:37:47"
"Tool:","Eeschema 5.1.7" "Tool:","Eeschema 5.1.10"
"Generator:","/usr/local/share/kicad/plugins/bom_csv_grouped_by_value.py" "Generator:","/usr/local/share/kicad/plugins/bom_csv_grouped_by_value.py"
"Component Count:","93" "Component Count:","96"
"Individual Components:" "Individual Components:"
@ -16,11 +16,11 @@
"","","C7","0.1","Device:C","Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder","~","" "","","C7","0.1","Device:C","Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder","~",""
"","","C8","0.1","Device:C","Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder","~","" "","","C8","0.1","Device:C","Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder","~",""
"","","C9","0.1","Device:C","Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder","~","" "","","C9","0.1","Device:C","Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder","~",""
"","","C10","47u 16V","Device:CP","Capacitor_Tantalum_SMD:CP_EIA-6032-28_Kemet-C_Pad2.25x2.35mm_HandSolder","~","" "","","C10","100u 16V","Device:CP","Capacitor_THT:CP_Radial_D8.0mm_P3.50mm","~",""
"","","C11","0.1","stm32-rescue:C","Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder","","" "","","C11","0.1","stm32-rescue:C","Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder","",""
"","","C12","47u 10V","stm32-rescue:CP","Capacitor_Tantalum_SMD:CP_EIA-1608-08_AVX-J_Pad1.25x1.05mm_HandSolder","","" "","","C12","47u 6V","stm32-rescue:CP","Capacitor_Tantalum_SMD:CP_EIA-3216-18_Kemet-A_Pad1.58x1.35mm_HandSolder","",""
"","","C13","47u 10V","Device:CP","Capacitor_Tantalum_SMD:CP_EIA-1608-08_AVX-J_Pad1.25x1.05mm_HandSolder","~","" "","","C13","47u 10V","Device:CP","Capacitor_Tantalum_SMD:CP_EIA-6032-28_Kemet-C_Pad2.25x2.35mm_HandSolder","~",""
"","","C14","0.1","Device:C","Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder","~","" "","","C14","100u 16V","Device:CP","Capacitor_THT:CP_Radial_D8.0mm_P3.50mm","~",""
"","","C15","0.1","stm32-rescue:C","Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder","","" "","","C15","0.1","stm32-rescue:C","Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder","",""
"","","D1","PESD1CAN","elements:PESD1CAN","TO_SOT_Packages_SMD:SOT-23","","" "","","D1","PESD1CAN","elements:PESD1CAN","TO_SOT_Packages_SMD:SOT-23","",""
"","","D2","SS14","Device:D_Schottky","Diode_SMD:D_SMA-SMB_Universal_Handsoldering","~","" "","","D2","SS14","Device:D_Schottky","Diode_SMD:D_SMA-SMB_Universal_Handsoldering","~",""
@ -32,33 +32,35 @@
"","","D8","SS14","Device:D_Schottky","Diode_SMD:D_SMA-SMB_Universal_Handsoldering","~","" "","","D8","SS14","Device:D_Schottky","Diode_SMD:D_SMA-SMB_Universal_Handsoldering","~",""
"","","D9","SS14","Device:D_Schottky","Diode_SMD:D_SMA-SMB_Universal_Handsoldering","~","" "","","D9","SS14","Device:D_Schottky","Diode_SMD:D_SMA-SMB_Universal_Handsoldering","~",""
"","","D10","SS14","Device:D_Schottky","Diode_SMD:D_SMA-SMB_Universal_Handsoldering","~","" "","","D10","SS14","Device:D_Schottky","Diode_SMD:D_SMA-SMB_Universal_Handsoldering","~",""
"","","D11","1N5822","Device:D","Diode_THT:D_DO-201_P12.70mm_Horizontal","~","" "","","D11","1N5822","Device:D","Diode_THT:D_DO-201_P3.81mm_Vertical_AnodeUp","~",""
"","","J1","Conn_01x01_Female","Connector:Conn_01x01_Female","Connector_PinHeader_2.54mm:PinHeader_1x01_P2.54mm_Vertical","~","" "","","J1","+3.3V","Connector:Conn_01x01_Female","Connector_PinHeader_2.54mm:PinHeader_1x01_P2.54mm_Vertical","~",""
"","","J2","Conn_01x01_Female","Connector:Conn_01x01_Female","Connector_PinHeader_2.54mm:PinHeader_1x01_P2.54mm_Vertical","~","" "","","J2","NRST","Connector:Conn_01x01_Female","Connector_PinHeader_2.54mm:PinHeader_1x01_P2.54mm_Vertical","~",""
"","","J3","Conn_01x01_Female","Connector:Conn_01x01_Female","Connector_PinHeader_2.54mm:PinHeader_1x01_P2.54mm_Vertical","~","" "","","J3","BOOT0","Connector:Conn_01x01_Female","Connector_PinHeader_2.54mm:PinHeader_1x01_P2.54mm_Vertical","~",""
"","","J4","Conn_01x01_Female","Connector:Conn_01x01_Female","Connector_PinHeader_2.54mm:PinHeader_1x01_P2.54mm_Vertical","~","" "","","J4","SWDIO","Connector:Conn_01x01_Female","Connector_PinHeader_2.54mm:PinHeader_1x01_P2.54mm_Vertical","~",""
"","","J5","Conn_01x01_Female","Connector:Conn_01x01_Female","Connector_PinHeader_2.54mm:PinHeader_1x01_P2.54mm_Vertical","~","" "","","J5","SWCLK","Connector:Conn_01x01_Female","Connector_PinHeader_2.54mm:PinHeader_1x01_P2.54mm_Vertical","~",""
"","","J6","Conn_01x01_Female","Connector:Conn_01x01_Female","Connector_PinHeader_2.54mm:PinHeader_1x01_P2.54mm_Vertical","~","" "","","J6","GND","Connector:Conn_01x01_Female","Connector_PinHeader_2.54mm:PinHeader_1x01_P2.54mm_Vertical","~",""
"","","J7","01x05","Connector:Conn_01x05_Male","Connector_PinHeader_2.54mm:PinHeader_1x05_P2.54mm_Vertical","~","" "","","J7","01x05","Connector:Conn_01x05_Male","Connector_PinHeader_2.54mm:PinHeader_1x05_P2.54mm_Vertical","~",""
"","","J8","Connector_Generic:Conn_02x04_Odd_Even","Connector_Generic:Conn_02x04_Odd_Even","Connector_PinHeader_2.54mm:PinHeader_2x04_P2.54mm_Vertical","~","" "","","J8","Connector_Generic:Conn_02x04_Odd_Even","Connector_Generic:Conn_02x04_Odd_Even","Connector_PinHeader_2.54mm:PinHeader_2x04_P2.54mm_Vertical","~",""
"","","J9","Conn_01x02_Female","Connector:Conn_01x02_Female","Connector_PinSocket_2.54mm:PinSocket_1x02_P2.54mm_Vertical","~","" "","","J9","Conn_01x02_Female","Connector:Conn_01x02_Female","Connector_PinSocket_2.54mm:PinSocket_1x02_P2.54mm_Vertical","~",""
"","","J10","Screw_Terminal_01x02","Connector:Screw_Terminal_01x02","TerminalBlock_Phoenix:TerminalBlock_Phoenix_MKDS-3-2-5.08_1x02_P5.08mm_Horizontal","~","" "","","J10","Screw_Terminal_01x02","Connector:Screw_Terminal_01x02","TerminalBlock_Phoenix:TerminalBlock_Phoenix_MKDS-1,5-2_1x02_P5.00mm_Horizontal","~",""
"","","J11","Screw_Terminal_01x03","Connector:Screw_Terminal_01x03","TerminalBlock_Phoenix:TerminalBlock_Phoenix_MKDS-1,5-3_1x03_P5.00mm_Horizontal","~","" "","","J11","Screw_Terminal_01x03","Connector:Screw_Terminal_01x03","TerminalBlock_Phoenix:TerminalBlock_Phoenix_MKDS-1,5-3_1x03_P5.00mm_Horizontal","~",""
"","","J12","Screw_Terminal_01x03","Connector:Screw_Terminal_01x03","TerminalBlock_Phoenix:TerminalBlock_Phoenix_MKDS-1,5-3_1x03_P5.00mm_Horizontal","~","" "","","J12","Screw_Terminal_01x03","Connector:Screw_Terminal_01x03","TerminalBlock_Phoenix:TerminalBlock_Phoenix_MKDS-1,5-3_1x03_P5.00mm_Horizontal","~",""
"","","J13","USB_B","Connector:USB_B","Connectors_USB:USB_B_OST_USB-B1HSxx_Horizontal"," ~","" "","","J13","USB_B","Connector:USB_B","Connectors_USB:USB_B_OST_USB-B1HSxx_Horizontal"," ~",""
"","","J14","DB9_Female","Connector:DB9_Female","Connector_Dsub:DSUB-9_Female_Horizontal_P2.77x2.84mm_EdgePinOffset7.70mm_Housed_MountingHolesOffset9.12mm"," ~",""
"","","J15","01x03","Connector:Conn_01x03_Male","Connector_PinSocket_2.54mm:PinSocket_1x03_P2.54mm_Vertical","~","" "","","J15","01x03","Connector:Conn_01x03_Male","Connector_PinSocket_2.54mm:PinSocket_1x03_P2.54mm_Vertical","~",""
"","","J16","Conn_01x02_Female","Connector:Conn_01x02_Female","Connector_PinSocket_2.54mm:PinSocket_1x02_P2.54mm_Vertical","~","" "","","J16","Conn_01x02_Female","Connector:Conn_01x02_Female","Connector_PinSocket_2.54mm:PinSocket_1x02_P2.54mm_Vertical","~",""
"","","J17","Screw_Terminal_01x03","Connector:Screw_Terminal_01x03","TerminalBlock_Phoenix:TerminalBlock_Phoenix_MKDS-1,5-3_1x03_P5.00mm_Horizontal","~","" "","","J17","Screw_Terminal_01x03","Connector:Screw_Terminal_01x03","TerminalBlock_Phoenix:TerminalBlock_Phoenix_MKDS-1,5-3_1x03_P5.00mm_Horizontal","~",""
"","","J18","01x05","Connector:Conn_01x05_Male","Connector_PinSocket_2.54mm:PinSocket_1x05_P2.54mm_Vertical","~","" "","","J18","01x05","Connector:Conn_01x05_Male","Connector_PinSocket_2.54mm:PinSocket_1x05_P2.54mm_Vertical","~",""
"","","JP1","NON-ISOL","Device:Jumper","Resistor_THT:R_Axial_DIN0207_L6.3mm_D2.5mm_P5.08mm_Vertical","~","" "","","JP1","NON-ISOL","Device:Jumper","Resistor_THT:R_Axial_DIN0207_L6.3mm_D2.5mm_P5.08mm_Vertical","~",""
"","","K1","G5LE-1","Relay:G5LE-1","Relay_THT:Relay_SPDT_Omron-G5LE-1","http://www.omron.com/ecb/products/pdf/en-g5le.pdf","" "","","K1","G5LE-1","Relay:G5LE-1","Relay_THT:Relay_SPDT_SANYOU_SRD_Series_Form_C","http://www.omron.com/ecb/products/pdf/en-g5le.pdf",""
"","","K2","G5LE-1","Relay:G5LE-1","Relay_THT:Relay_SPDT_Omron-G5LE-1","http://www.omron.com/ecb/products/pdf/en-g5le.pdf","" "","","K2","G5LE-1","Relay:G5LE-1","Relay_THT:Relay_SPDT_SANYOU_SRD_Series_Form_C","http://www.omron.com/ecb/products/pdf/en-g5le.pdf",""
"","","L1","100u","Device:L","Inductor_SMD:L_12x12mm_H4.5mm","~","" "","","L1","100u","Device:L","Inductor_SMD:L_12x12mm_H4.5mm","~",""
"","","P1","Hole","stm32-rescue:CONN_01X01","my_footprints:Hole_3mm","","" "","","P1","Hole","stm32-rescue:CONN_01X01","my_footprints:Hole_3mm","",""
"","","P2","Hole","stm32-rescue:CONN_01X01","my_footprints:Hole_3mm","","" "","","P2","Hole","stm32-rescue:CONN_01X01","my_footprints:Hole_3mm","",""
"","","P3","Hole","stm32-rescue:CONN_01X01","my_footprints:Hole_3mm","","" "","","P3","Hole","stm32-rescue:CONN_01X01","my_footprints:Hole_3mm","",""
"","","P4","Hole","stm32-rescue:CONN_01X01","my_footprints:Hole_3mm","","" "","","P4","Hole","stm32-rescue:CONN_01X01","my_footprints:Hole_3mm","",""
"","","P5","Hole","stm32-rescue:CONN_01X01","my_footprints:Hole_3mm","",""
"","","P6","Hole","stm32-rescue:CONN_01X01","my_footprints:Hole_3mm","",""
"","","P7","Hole","stm32-rescue:CONN_01X01","my_footprints:Hole_3mm","",""
"","","Q1","B0505S","elements:B0505S","my_footprints:B0x0xS","","" "","","Q1","B0505S","elements:B0505S","my_footprints:B0x0xS","",""
"","","Q2","SI2300","Device:Q_NMOS_GSD","TO_SOT_Packages_SMD:SOT-23_Handsoldering","~","" "","","Q2","SI2300","Device:Q_NMOS_GSD","TO_SOT_Packages_SMD:SOT-23_Handsoldering","~",""
"","","Q3","SI2300","Device:Q_NMOS_GSD","TO_SOT_Packages_SMD:SOT-23_Handsoldering","~","" "","","Q3","SI2300","Device:Q_NMOS_GSD","TO_SOT_Packages_SMD:SOT-23_Handsoldering","~",""
@ -100,6 +102,7 @@
"","","U3","STM32F072C8Tx","MCU_ST_STM32F0:STM32F072C8Tx","Package_QFP:LQFP-48_7x7mm_P0.5mm","http://www.st.com/st-web-ui/static/active/en/resource/technical/document/datasheet/DM00090510.pdf","" "","","U3","STM32F072C8Tx","MCU_ST_STM32F0:STM32F072C8Tx","Package_QFP:LQFP-48_7x7mm_P0.5mm","http://www.st.com/st-web-ui/static/active/en/resource/technical/document/datasheet/DM00090510.pdf",""
"","","U4","LM2576","vreg:LM2576","TO_SOT_Packages_THT:TO-220-5_P3.4x3.7mm_StaggerEven_Lead3.8mm_Vertical","","Texas Instruments" "","","U4","LM2576","vreg:LM2576","TO_SOT_Packages_THT:TO-220-5_P3.4x3.7mm_StaggerEven_Lead3.8mm_Vertical","","Texas Instruments"
"","","U5","LM1117-3.3","Regulator_Linear:LM1117-3.3","TO_SOT_Packages_SMD:SOT-223-3_TabPin2","http://www.ti.com/lit/ds/symlink/lm1117.pdf","" "","","U5","LM1117-3.3","Regulator_Linear:LM1117-3.3","TO_SOT_Packages_SMD:SOT-223-3_TabPin2","http://www.ti.com/lit/ds/symlink/lm1117.pdf",""
"","","U6","IP4220CZ6","Power_Protection:NUP4202","Package_SO:TSOP-6_1.65x3.05mm_P0.95mm","http://www.onsemi.com/pub_link/Collateral/NUP4202W1-D.PDF",""
@ -107,45 +110,51 @@
"Item","Qty","Reference(s)","Value","LibPart","Footprint","Datasheet","Manufacturer" "Item","Qty","Reference(s)","Value","LibPart","Footprint","Datasheet","Manufacturer"
"1","2","C1, C5","1","stm32-rescue:C","Capacitor_SMD:C_0805_2012Metric_Pad1.15x1.40mm_HandSolder","","" "1","2","C1, C5","1","stm32-rescue:C","Capacitor_SMD:C_0805_2012Metric_Pad1.15x1.40mm_HandSolder","",""
"2","10","C2, C3, C4, C6, C7, C8, C9, C11, C14, C15","0.1","stm32-rescue:C","Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder","~","" "2","9","C2, C3, C4, C6, C7, C8, C9, C11, C15","0.1","stm32-rescue:C","Capacitor_SMD:C_0603_1608Metric_Pad1.05x0.95mm_HandSolder","~",""
"3","1","C10","47u 16V","Device:CP","Capacitor_Tantalum_SMD:CP_EIA-6032-28_Kemet-C_Pad2.25x2.35mm_HandSolder","~","" "3","2","C10, C14","100u 16V","Device:CP","Capacitor_THT:CP_Radial_D8.0mm_P3.50mm","~",""
"4","2","C12, C13","47u 10V","Device:CP","Capacitor_Tantalum_SMD:CP_EIA-1608-08_AVX-J_Pad1.25x1.05mm_HandSolder","~","" "4","1","C12","47u 6V","stm32-rescue:CP","Capacitor_Tantalum_SMD:CP_EIA-3216-18_Kemet-A_Pad1.58x1.35mm_HandSolder","",""
"5","1","D1","PESD1CAN","elements:PESD1CAN","TO_SOT_Packages_SMD:SOT-23","","" "5","1","C13","47u 10V","Device:CP","Capacitor_Tantalum_SMD:CP_EIA-6032-28_Kemet-C_Pad2.25x2.35mm_HandSolder","~",""
"6","5","D2, D4, D8, D9, D10","SS14","Device:D_Schottky","Diode_SMD:D_SMA-SMB_Universal_Handsoldering","~","" "6","1","D1","PESD1CAN","elements:PESD1CAN","TO_SOT_Packages_SMD:SOT-23","",""
"7","1","D3","USB6B1","elements:USB6B1","Package_SO:SOIC-8_3.9x4.9mm_P1.27mm","","" "7","5","D2, D4, D8, D9, D10","SS14","Device:D_Schottky","Diode_SMD:D_SMA-SMB_Universal_Handsoldering","~",""
"8","1","D5","MM3Z7V5","Device:D_Zener","Diode_SMD:D_0805_2012Metric_Pad1.15x1.40mm_HandSolder","~","" "8","1","D3","USB6B1","elements:USB6B1","Package_SO:SOIC-8_3.9x4.9mm_P1.27mm","",""
"9","2","D6, D7","CESD3v3","Device:D","Diode_SMD:D_SOD-523","~","" "9","1","D5","MM3Z7V5","Device:D_Zener","Diode_SMD:D_0805_2012Metric_Pad1.15x1.40mm_HandSolder","~",""
"10","1","D11","1N5822","Device:D","Diode_THT:D_DO-201_P12.70mm_Horizontal","~","" "10","2","D6, D7","CESD3v3","Device:D","Diode_SMD:D_SOD-523","~",""
"11","6","J1, J2, J3, J4, J5, J6","Conn_01x01_Female","Connector:Conn_01x01_Female","Connector_PinHeader_2.54mm:PinHeader_1x01_P2.54mm_Vertical","~","" "11","1","D11","1N5822","Device:D","Diode_THT:D_DO-201_P3.81mm_Vertical_AnodeUp","~",""
"12","1","J7","01x05","Connector:Conn_01x05_Male","Connector_PinHeader_2.54mm:PinHeader_1x05_P2.54mm_Vertical","~","" "12","1","J1","+3.3V","Connector:Conn_01x01_Female","Connector_PinHeader_2.54mm:PinHeader_1x01_P2.54mm_Vertical","~",""
"13","1","J8","Connector_Generic:Conn_02x04_Odd_Even","Connector_Generic:Conn_02x04_Odd_Even","Connector_PinHeader_2.54mm:PinHeader_2x04_P2.54mm_Vertical","~","" "13","1","J2","NRST","Connector:Conn_01x01_Female","Connector_PinHeader_2.54mm:PinHeader_1x01_P2.54mm_Vertical","~",""
"14","2","J9, J16","Conn_01x02_Female","Connector:Conn_01x02_Female","Connector_PinSocket_2.54mm:PinSocket_1x02_P2.54mm_Vertical","~","" "14","1","J3","BOOT0","Connector:Conn_01x01_Female","Connector_PinHeader_2.54mm:PinHeader_1x01_P2.54mm_Vertical","~",""
"15","1","J10","Screw_Terminal_01x02","Connector:Screw_Terminal_01x02","TerminalBlock_Phoenix:TerminalBlock_Phoenix_MKDS-3-2-5.08_1x02_P5.08mm_Horizontal","~","" "15","1","J4","SWDIO","Connector:Conn_01x01_Female","Connector_PinHeader_2.54mm:PinHeader_1x01_P2.54mm_Vertical","~",""
"16","3","J11, J12, J17","Screw_Terminal_01x03","Connector:Screw_Terminal_01x03","TerminalBlock_Phoenix:TerminalBlock_Phoenix_MKDS-1,5-3_1x03_P5.00mm_Horizontal","~","" "16","1","J5","SWCLK","Connector:Conn_01x01_Female","Connector_PinHeader_2.54mm:PinHeader_1x01_P2.54mm_Vertical","~",""
"17","1","J13","USB_B","Connector:USB_B","Connectors_USB:USB_B_OST_USB-B1HSxx_Horizontal"," ~","" "17","1","J6","GND","Connector:Conn_01x01_Female","Connector_PinHeader_2.54mm:PinHeader_1x01_P2.54mm_Vertical","~",""
"18","1","J14","DB9_Female","Connector:DB9_Female","Connector_Dsub:DSUB-9_Female_Horizontal_P2.77x2.84mm_EdgePinOffset7.70mm_Housed_MountingHolesOffset9.12mm"," ~","" "18","1","J7","01x05","Connector:Conn_01x05_Male","Connector_PinHeader_2.54mm:PinHeader_1x05_P2.54mm_Vertical","~",""
"19","1","J15","01x03","Connector:Conn_01x03_Male","Connector_PinSocket_2.54mm:PinSocket_1x03_P2.54mm_Vertical","~","" "19","1","J8","Connector_Generic:Conn_02x04_Odd_Even","Connector_Generic:Conn_02x04_Odd_Even","Connector_PinHeader_2.54mm:PinHeader_2x04_P2.54mm_Vertical","~",""
"20","1","J18","01x05","Connector:Conn_01x05_Male","Connector_PinSocket_2.54mm:PinSocket_1x05_P2.54mm_Vertical","~","" "20","2","J9, J16","Conn_01x02_Female","Connector:Conn_01x02_Female","Connector_PinSocket_2.54mm:PinSocket_1x02_P2.54mm_Vertical","~",""
"21","1","JP1","NON-ISOL","Device:Jumper","Resistor_THT:R_Axial_DIN0207_L6.3mm_D2.5mm_P5.08mm_Vertical","~","" "21","1","J10","Screw_Terminal_01x02","Connector:Screw_Terminal_01x02","TerminalBlock_Phoenix:TerminalBlock_Phoenix_MKDS-1,5-2_1x02_P5.00mm_Horizontal","~",""
"22","2","K1, K2","G5LE-1","Relay:G5LE-1","Relay_THT:Relay_SPDT_Omron-G5LE-1","http://www.omron.com/ecb/products/pdf/en-g5le.pdf","" "22","3","J11, J12, J17","Screw_Terminal_01x03","Connector:Screw_Terminal_01x03","TerminalBlock_Phoenix:TerminalBlock_Phoenix_MKDS-1,5-3_1x03_P5.00mm_Horizontal","~",""
"23","1","L1","100u","Device:L","Inductor_SMD:L_12x12mm_H4.5mm","~","" "23","1","J13","USB_B","Connector:USB_B","Connectors_USB:USB_B_OST_USB-B1HSxx_Horizontal"," ~",""
"24","4","P1, P2, P3, P4","Hole","stm32-rescue:CONN_01X01","my_footprints:Hole_3mm","","" "24","1","J15","01x03","Connector:Conn_01x03_Male","Connector_PinSocket_2.54mm:PinSocket_1x03_P2.54mm_Vertical","~",""
"25","1","Q1","B0505S","elements:B0505S","my_footprints:B0x0xS","","" "25","1","J18","01x05","Connector:Conn_01x05_Male","Connector_PinSocket_2.54mm:PinSocket_1x05_P2.54mm_Vertical","~",""
"26","5","Q2, Q3, Q5, Q6, Q7","SI2300","Device:Q_NMOS_GSD","TO_SOT_Packages_SMD:SOT-23_Handsoldering","~","" "26","1","JP1","NON-ISOL","Device:Jumper","Resistor_THT:R_Axial_DIN0207_L6.3mm_D2.5mm_P5.08mm_Vertical","~",""
"27","1","Q4","AO3407","Device:Q_PMOS_GSD","TO_SOT_Packages_SMD:SOT-23_Handsoldering","~","" "27","2","K1, K2","G5LE-1","Relay:G5LE-1","Relay_THT:Relay_SPDT_SANYOU_SRD_Series_Form_C","http://www.omron.com/ecb/products/pdf/en-g5le.pdf",""
"28","8","R1, R8, R14, R17, R21, R25, R26, R27","10k","Device:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder","~","" "28","1","L1","100u","Device:L","Inductor_SMD:L_12x12mm_H4.5mm","~",""
"29","1","R2","4k7","stm32-rescue:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder","","" "29","7","P1, P2, P3, P4, P5, P6, P7","Hole","stm32-rescue:CONN_01X01","my_footprints:Hole_3mm","",""
"30","3","R3, R10, R11","22","stm32-rescue:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder","~","" "30","1","Q1","B0505S","elements:B0505S","my_footprints:B0x0xS","",""
"31","4","R4, R5, R6, R7","680","Device:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder","~","" "31","5","Q2, Q3, Q5, Q6, Q7","SI2300","Device:Q_NMOS_GSD","TO_SOT_Packages_SMD:SOT-23_Handsoldering","~",""
"32","5","R9, R15, R22, R23, R24","330","Device:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder","~","" "32","1","Q4","AO3407","Device:Q_PMOS_GSD","TO_SOT_Packages_SMD:SOT-23_Handsoldering","~",""
"33","2","R12, R16","2k2","Device:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder","~","" "33","8","R1, R8, R14, R17, R21, R25, R26, R27","10k","Device:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder","~",""
"34","1","R13","120","stm32-rescue:R","Resistor_SMD:R_1210_3225Metric_Pad1.42x2.65mm_HandSolder","","" "34","1","R2","4k7","stm32-rescue:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder","",""
"35","1","R18","47k","Device:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder","~","" "35","3","R3, R10, R11","22","stm32-rescue:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder","~",""
"36","2","R19, R20","15k","Device:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder","~","" "36","4","R4, R5, R6, R7","680","Device:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder","~",""
"37","1","SW1","SW_DIP_x08","Switch:SW_DIP_x08","Button_Switch_THT:SW_DIP_SPSTx08_Slide_9.78x22.5mm_W7.62mm_P2.54mm","~","" "37","5","R9, R15, R22, R23, R24","330","Device:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder","~",""
"38","1","SW2","SW_DIP_x01","Switch:SW_DIP_x01","Button_Switch_THT:SW_DIP_SPSTx01_Slide_6.7x4.1mm_W7.62mm_P2.54mm_LowProfile","~","" "38","2","R12, R16","2k2","Device:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder","~",""
"39","1","U1","MCP2551-I/SN","stm32-rescue:MCP2551-I_SN","Package_SO:SOIC-8_3.9x4.9mm_P1.27mm","","" "39","1","R13","120","stm32-rescue:R","Resistor_SMD:R_1210_3225Metric_Pad1.42x2.65mm_HandSolder","",""
"40","1","U2","ISO1050DUB","Interface_CAN_LIN:ISO1050DUB","Package_SO:SOP-8_6.62x9.15mm_P2.54mm","http://www.ti.com/lit/ds/symlink/iso1050.pdf","" "40","1","R18","47k","Device:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder","~",""
"41","1","U3","STM32F072C8Tx","MCU_ST_STM32F0:STM32F072C8Tx","Package_QFP:LQFP-48_7x7mm_P0.5mm","http://www.st.com/st-web-ui/static/active/en/resource/technical/document/datasheet/DM00090510.pdf","" "41","2","R19, R20","15k","Device:R","Resistor_SMD:R_0603_1608Metric_Pad1.05x0.95mm_HandSolder","~",""
"42","1","U4","LM2576","vreg:LM2576","TO_SOT_Packages_THT:TO-220-5_P3.4x3.7mm_StaggerEven_Lead3.8mm_Vertical","","Texas Instruments" "42","1","SW1","SW_DIP_x08","Switch:SW_DIP_x08","Button_Switch_THT:SW_DIP_SPSTx08_Slide_9.78x22.5mm_W7.62mm_P2.54mm","~",""
"43","1","U5","LM1117-3.3","Regulator_Linear:LM1117-3.3","TO_SOT_Packages_SMD:SOT-223-3_TabPin2","http://www.ti.com/lit/ds/symlink/lm1117.pdf","" "43","1","SW2","SW_DIP_x01","Switch:SW_DIP_x01","Button_Switch_THT:SW_DIP_SPSTx01_Slide_6.7x4.1mm_W7.62mm_P2.54mm_LowProfile","~",""
"44","1","U1","MCP2551-I/SN","stm32-rescue:MCP2551-I_SN","Package_SO:SOIC-8_3.9x4.9mm_P1.27mm","",""
"45","1","U2","ISO1050DUB","Interface_CAN_LIN:ISO1050DUB","Package_SO:SOP-8_6.62x9.15mm_P2.54mm","http://www.ti.com/lit/ds/symlink/iso1050.pdf",""
"46","1","U3","STM32F072C8Tx","MCU_ST_STM32F0:STM32F072C8Tx","Package_QFP:LQFP-48_7x7mm_P0.5mm","http://www.st.com/st-web-ui/static/active/en/resource/technical/document/datasheet/DM00090510.pdf",""
"47","1","U4","LM2576","vreg:LM2576","TO_SOT_Packages_THT:TO-220-5_P3.4x3.7mm_StaggerEven_Lead3.8mm_Vertical","","Texas Instruments"
"48","1","U5","LM1117-3.3","Regulator_Linear:LM1117-3.3","TO_SOT_Packages_SMD:SOT-223-3_TabPin2","http://www.ti.com/lit/ds/symlink/lm1117.pdf",""
"49","1","U6","IP4220CZ6","Power_Protection:NUP4202","Package_SO:TSOP-6_1.65x3.05mm_P0.95mm","http://www.onsemi.com/pub_link/Collateral/NUP4202W1-D.PDF",""

Can't render this file because it has a wrong number of fields in line 7.

View File

@ -1,11 +1,10 @@
/* /*
* main.c * This file is part of the canrelay project.
* Copyright 2021 Edward V. Emelianov <edward.emelianoff@gmail.com>.
* *
* Copyright 2017 Edward V. Emelianoff <eddy@sao.ru, edward.emelianoff@gmail.com> * This program is free software: you can redistribute it and/or modify
*
* 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 * it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or * the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version. * (at your option) any later version.
* *
* This program is distributed in the hope that it will be useful, * This program is distributed in the hope that it will be useful,
@ -14,11 +13,10 @@
* GNU General Public License for more details. * GNU General Public License for more details.
* *
* You should have received a copy of the GNU General Public License * You should have received a copy of the GNU General Public License
* along with this program; if not, write to the Free Software * along with this program. If not, see <http://www.gnu.org/licenses/>.
* Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston,
* MA 02110-1301, USA.
*/ */
#include "buttons.h"
#include "can.h" #include "can.h"
#include "hardware.h" #include "hardware.h"
#include "proto.h" #include "proto.h"
@ -66,13 +64,13 @@ static char *get_USB(){
} }
int main(void){ int main(void){
uint32_t lastT = 0;
uint8_t ctr, len; uint8_t ctr, len;
CAN_message *can_mesg; CAN_message *can_mesg;
char *txt; char *txt;
sysreset(); sysreset();
SysTick_Config(6000, 1); SysTick_Config(6000, 1);
gpio_setup(); gpio_setup();
tim1_setup();
USB_setup(); USB_setup();
CAN_setup(100); CAN_setup(100);
RCC->CSR |= RCC_CSR_RMVF; // remove reset flags RCC->CSR |= RCC_CSR_RMVF; // remove reset flags
@ -80,10 +78,7 @@ int main(void){
while (1){ while (1){
IWDG->KR = IWDG_REFRESH; // refresh watchdog IWDG->KR = IWDG_REFRESH; // refresh watchdog
if(lastT && (Tms - lastT > 199)){ process_keys();
LED_off(LED0);
lastT = 0;
}
can_proc(); can_proc();
usb_proc(); usb_proc();
if(CAN_get_status() == CAN_FIFO_OVERRUN){ if(CAN_get_status() == CAN_FIFO_OVERRUN){
@ -92,9 +87,6 @@ int main(void){
} }
can_mesg = CAN_messagebuf_pop(); can_mesg = CAN_messagebuf_pop();
if(can_mesg && isgood(can_mesg->ID)){ if(can_mesg && isgood(can_mesg->ID)){
LED_on(LED0);
lastT = Tms;
if(!lastT) lastT = 1;
if(ShowMsgs){ // new data in buff if(ShowMsgs){ // new data in buff
IWDG->KR = IWDG_REFRESH; IWDG->KR = IWDG_REFRESH;
len = can_mesg->length; len = can_mesg->length;

View File

@ -1,12 +1,10 @@
/* /*
* geany_encoding=koi8-r * This file is part of the canrelay project.
* proto.c * Copyright 2021 Edward V. Emelianov <edward.emelianoff@gmail.com>.
* *
* Copyright 2018 Edward V. Emelianov <eddy@sao.ru, edward.emelianoff@gmail.com> * This program is free software: you can redistribute it and/or modify
*
* 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 * it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or * the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version. * (at your option) any later version.
* *
* This program is distributed in the hope that it will be useful, * This program is distributed in the hope that it will be useful,
@ -15,11 +13,10 @@
* GNU General Public License for more details. * GNU General Public License for more details.
* *
* You should have received a copy of the GNU General Public License * You should have received a copy of the GNU General Public License
* along with this program; if not, write to the Free Software * along with this program. If not, see <http://www.gnu.org/licenses/>.
* Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston,
* MA 02110-1301, USA.
*
*/ */
#include "buttons.h"
#include "can.h" #include "can.h"
#include "hardware.h" #include "hardware.h"
#include "proto.h" #include "proto.h"
@ -29,7 +26,7 @@
extern volatile uint8_t canerror; extern volatile uint8_t canerror;
uint8_t ShowMsgs = 07; uint8_t ShowMsgs = 0;
uint16_t Ignore_IDs[IGN_SIZE]; uint16_t Ignore_IDs[IGN_SIZE];
uint8_t IgnSz = 0; uint8_t IgnSz = 0;
static char buff[BUFSZ+1], *bptr = buff; static char buff[BUFSZ+1], *bptr = buff;
@ -57,17 +54,17 @@ void addtobuf(const char *txt){
while(*txt) bufputchar(*txt++); while(*txt) bufputchar(*txt++);
} }
char *omit_spaces(char *buf){ char *omit_spaces(const char *buf){
while(*buf){ while(*buf){
if(*buf > ' ') break; if(*buf > ' ') break;
++buf; ++buf;
} }
return buf; return (char*) buf;
} }
// THERE'S NO OVERFLOW PROTECTION IN NUMBER READ PROCEDURES! // THERE'S NO OVERFLOW PROTECTION IN NUMBER READ PROCEDURES!
// read decimal number // read decimal number
static char *getdec(char *buf, uint32_t *N){ static char *getdec(const char *buf, uint32_t *N){
uint32_t num = 0; uint32_t num = 0;
while(*buf){ while(*buf){
char c = *buf; char c = *buf;
@ -79,10 +76,10 @@ static char *getdec(char *buf, uint32_t *N){
++buf; ++buf;
} }
*N = num; *N = num;
return buf; return (char *)buf;
} }
// read hexadecimal number (without 0x prefix!) // read hexadecimal number (without 0x prefix!)
static char *gethex(char *buf, uint32_t *N){ static char *gethex(const char *buf, uint32_t *N){
uint32_t num = 0; uint32_t num = 0;
while(*buf){ while(*buf){
char c = *buf; char c = *buf;
@ -103,10 +100,10 @@ static char *gethex(char *buf, uint32_t *N){
++buf; ++buf;
} }
*N = num; *N = num;
return buf; return (char *)buf;
} }
// read binary number (without 0b prefix!) // read binary number (without 0b prefix!)
static char *getbin(char *buf, uint32_t *N){ static char *getbin(const char *buf, uint32_t *N){
uint32_t num = 0; uint32_t num = 0;
while(*buf){ while(*buf){
char c = *buf; char c = *buf;
@ -118,7 +115,7 @@ static char *getbin(char *buf, uint32_t *N){
++buf; ++buf;
} }
*N = num; *N = num;
return buf; return (char *)buf;
} }
/** /**
@ -127,7 +124,7 @@ static char *getbin(char *buf, uint32_t *N){
* @param N - the number read * @param N - the number read
* @return pointer to first non-number symbol in buf (if it is == buf, there's no number) * @return pointer to first non-number symbol in buf (if it is == buf, there's no number)
*/ */
char *getnum(char *txt, uint32_t *N){ char *getnum(const char *txt, uint32_t *N){
if(*txt == '0'){ if(*txt == '0'){
if(txt[1] == 'x' || txt[1] == 'X') return gethex(txt+2, N); if(txt[1] == 'x' || txt[1] == 'X') return gethex(txt+2, N);
if(txt[1] == 'b' || txt[1] == 'B') return getbin(txt+2, N); if(txt[1] == 'b' || txt[1] == 'B') return getbin(txt+2, N);
@ -167,13 +164,7 @@ static CAN_message *parseCANmsg(char *txt){
return NULL; return NULL;
} }
canmsg.data[ctr++] = (uint8_t)(N&0xff); canmsg.data[ctr++] = (uint8_t)(N&0xff);
//printu(N); SEND(", hex: ");
//printuhex(N); newline();
}while(1); }while(1);
/*if(*n){
SEND("\nUnusefull data: ");
SEND(n);
}*/
if(canmsg.ID == 0xffff){ if(canmsg.ID == 0xffff){
SEND("NO ID given, send nothing!\n"); SEND("NO ID given, send nothing!\n");
return NULL; return NULL;
@ -226,6 +217,10 @@ TRUE_INLINE void addIGN(char *txt){
SEND("No ID given"); SEND("No ID given");
return; return;
} }
if(N == CANID){
SEND("You can't ignore self ID!");
return;
}
if(N > 0x7ff){ if(N > 0x7ff){
SEND("ID should be 11-bit number!"); SEND("ID should be 11-bit number!");
return; return;
@ -322,8 +317,8 @@ static void add_filter(char *str){
SEND("No bank# given"); SEND("No bank# given");
return; return;
} }
if(N > STM32F0FBANKNO-1){ if(N == 0 || N > STM32F0FBANKNO-1){
SEND("bank# > 27"); SEND("0 (reserved for self) < bank# < 28 (max bank# is 27)!!!");
return; return;
} }
uint8_t bankno = (uint8_t)N; uint8_t bankno = (uint8_t)N;
@ -397,6 +392,69 @@ static void add_filter(char *str){
printu(nfilt); SEND(" parameters"); printu(nfilt); SEND(" parameters");
} }
/**
* @brief ledsOp - turn on/off LEDs
* @param str - LED number (0..3)
* @param state = 1 to turn on, 0 to turn off (toggling only available for CAN bus commands)
*/
static void ledsOp(const char *str, uint8_t state){
uint32_t N;
char *x = getnum(str, &N);
if(!x || x == str || N > LEDSNO - 1){
SEND("Wrong LED number\n");
return;
}
if(state) LED_on(N);
else LED_off(N);
SEND("LED"); printu(N); SEND(" is ");
if(state) SEND("on"); else SEND("off");
}
// 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(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");
}
/** /**
* @brief cmd_parser - command parsing * @brief cmd_parser - command parsing
* @param txt - buffer with commands & data * @param txt - buffer with commands & data
@ -412,7 +470,7 @@ void cmd_parser(char *txt){
addIGN(txt + 1); addIGN(txt + 1);
goto eof; goto eof;
break; break;
case 'b': case 'C':
CANini(txt + 1); CANini(txt + 1);
goto eof; goto eof;
break; break;
@ -424,14 +482,29 @@ void cmd_parser(char *txt){
set_flood(parseCANmsg(txt + 1)); set_flood(parseCANmsg(txt + 1));
goto eof; goto eof;
break; break;
case 'o':
ledsOp(txt + 1, 0);
goto eof;
break;
case 'O':
ledsOp(txt + 1, 1);
goto eof;
break;
case 's': case 's':
case 'S': case 'S':
sendCANcommand(txt + 1); sendCANcommand(txt + 1);
goto eof; goto eof;
break; break;
case 'W':
changePWM(txt + 1);
goto eof;
break;
} }
if(txt[1] != '\n') *txt = '?'; // help for wrong message length if(txt[1] != '\n') *txt = '?'; // help for wrong message length
switch(_1st){ switch(_1st){
case 'b':
getBtnState();
break;
case 'd': case 'd':
IgnSz = 0; IgnSz = 0;
break; break;
@ -441,19 +514,11 @@ void cmd_parser(char *txt){
Jump2Boot(); Jump2Boot();
break; break;
case 'I': case 'I':
CAN_reinit(0); SEND("CAN ID: "); printuhex(CANID);
break; break;
case 'l': case 'l':
list_filters(); list_filters();
break; break;
case 'o':
ledsON = 0;
LED_off(LED0);
LED_off(LED1);
break;
case 'O':
ledsON = 1;
break;
case 'p': case 'p':
print_ign_buf(); print_ign_buf();
break; break;
@ -471,25 +536,31 @@ void cmd_parser(char *txt){
case 'T': case 'T':
SEND("Time (ms): "); SEND("Time (ms): ");
printu(Tms); printu(Tms);
newline(); break;
case 'w':
getPWM();
return;
break; break;
default: // help default: // help
SEND( SEND(
"'a' - add ID to ignore list (max 10 IDs)\n" "'a' - add ID to ignore list (max 10 IDs)\n"
"'b' - reinit CAN with given baudrate\n" "'b' - get buttons' state\n"
"'C' - reinit CAN with given baudrate\n"
"'d' - delete ignore list\n" "'d' - delete ignore list\n"
"'D' - activate DFU mode\n" "'D' - activate DFU mode\n"
"'f' - add/delete filter, format: bank# FIFO# mode(M/I) num0 [num1 [num2 [num3]]]\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" "'F' - send/clear flood message: F ID byte0 ... byteN\n"
"'I' - reinit CAN\n" "'I' - read CAN ID\n"
"'l' - list all active filters\n" "'l' - list all active filters\n"
"'o' - turn LEDs OFF\n" "'o' - turn nth LED OFF\n"
"'O' - turn LEDs ON\n" "'O' - turn nth LED ON\n"
"'p' - print ignore buffer\n" "'p' - print ignore buffer\n"
"'P' - pause/resume in packets displaying\n" "'P' - pause/resume in packets displaying\n"
"'R' - software reset\n" "'R' - software reset\n"
"'s/S' - send data over CAN: s ID byte0 .. byteN\n" "'s/S' - send data over CAN: s ID byte0 .. byteN\n"
"'T' - get time from start (ms)\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; break;
} }

View File

@ -1,12 +1,10 @@
/* /*
* geany_encoding=koi8-r * This file is part of the canrelay project.
* proto.h * Copyright 2021 Edward V. Emelianov <edward.emelianoff@gmail.com>.
* *
* Copyright 2018 Edward V. Emelianov <eddy@sao.ru, edward.emelianoff@gmail.com> * This program is free software: you can redistribute it and/or modify
*
* 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 * it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or * the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version. * (at your option) any later version.
* *
* This program is distributed in the hope that it will be useful, * This program is distributed in the hope that it will be useful,
@ -15,10 +13,7 @@
* GNU General Public License for more details. * GNU General Public License for more details.
* *
* You should have received a copy of the GNU General Public License * You should have received a copy of the GNU General Public License
* along with this program; if not, write to the Free Software * along with this program. If not, see <http://www.gnu.org/licenses/>.
* Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston,
* MA 02110-1301, USA.
*
*/ */
#pragma once #pragma once
#ifndef __PROTO_H__ #ifndef __PROTO_H__
@ -54,8 +49,8 @@ void printu(uint32_t val);
void printuhex(uint32_t val); void printuhex(uint32_t val);
void sendbuf(); void sendbuf();
char *omit_spaces(char *buf); char *omit_spaces(const char *buf);
char *getnum(char *buf, uint32_t *N); char *getnum(const char *buf, uint32_t *N);
uint8_t isgood(uint16_t ID); uint8_t isgood(uint16_t ID);

View File

@ -1,12 +1,10 @@
/* /*
* geany_encoding=koi8-r * This file is part of the canrelay project.
* usb.c - base functions for different USB types * Copyright 2021 Edward V. Emelianov <edward.emelianoff@gmail.com>.
* *
* Copyright 2018 Edward V. Emelianov <eddy@sao.ru, edward.emelianoff@gmail.com> * This program is free software: you can redistribute it and/or modify
*
* 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 * it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or * the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version. * (at your option) any later version.
* *
* This program is distributed in the hope that it will be useful, * This program is distributed in the hope that it will be useful,
@ -15,10 +13,7 @@
* GNU General Public License for more details. * GNU General Public License for more details.
* *
* You should have received a copy of the GNU General Public License * You should have received a copy of the GNU General Public License
* along with this program; if not, write to the Free Software * along with this program. If not, see <http://www.gnu.org/licenses/>.
* Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston,
* MA 02110-1301, USA.
*
*/ */
#include "usb.h" #include "usb.h"

View File

@ -1,12 +1,10 @@
/* /*
* geany_encoding=koi8-r * This file is part of the canrelay project.
* usb.h * Copyright 2021 Edward V. Emelianov <edward.emelianoff@gmail.com>.
* *
* Copyright 2018 Edward V. Emelianov <eddy@sao.ru, edward.emelianoff@gmail.com> * This program is free software: you can redistribute it and/or modify
*
* 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 * it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or * the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version. * (at your option) any later version.
* *
* This program is distributed in the hope that it will be useful, * This program is distributed in the hope that it will be useful,
@ -15,11 +13,9 @@
* GNU General Public License for more details. * GNU General Public License for more details.
* *
* You should have received a copy of the GNU General Public License * You should have received a copy of the GNU General Public License
* along with this program; if not, write to the Free Software * along with this program. If not, see <http://www.gnu.org/licenses/>.
* Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston,
* MA 02110-1301, USA.
*
*/ */
#pragma once #pragma once
#ifndef __USB_H__ #ifndef __USB_H__
#define __USB_H__ #define __USB_H__

View File

@ -1,12 +1,10 @@
/* /*
* geany_encoding=koi8-r * This file is part of the canrelay project.
* usb_defs.h * Copyright 2021 Edward V. Emelianov <edward.emelianoff@gmail.com>.
* *
* Copyright 2018 Edward V. Emelianov <eddy@sao.ru, edward.emelianoff@gmail.com> * This program is free software: you can redistribute it and/or modify
*
* 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 * it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or * the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version. * (at your option) any later version.
* *
* This program is distributed in the hope that it will be useful, * This program is distributed in the hope that it will be useful,
@ -15,10 +13,7 @@
* GNU General Public License for more details. * GNU General Public License for more details.
* *
* You should have received a copy of the GNU General Public License * You should have received a copy of the GNU General Public License
* along with this program; if not, write to the Free Software * along with this program. If not, see <http://www.gnu.org/licenses/>.
* Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston,
* MA 02110-1301, USA.
*
*/ */
#pragma once #pragma once

View File

@ -1,12 +1,10 @@
/* /*
* geany_encoding=koi8-r * This file is part of the canrelay project.
* usb_lib.c * Copyright 2021 Edward V. Emelianov <edward.emelianoff@gmail.com>.
* *
* Copyright 2018 Edward V. Emelianov <eddy@sao.ru, edward.emelianoff@gmail.com> * This program is free software: you can redistribute it and/or modify
*
* 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 * it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or * the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version. * (at your option) any later version.
* *
* This program is distributed in the hope that it will be useful, * This program is distributed in the hope that it will be useful,
@ -15,10 +13,7 @@
* GNU General Public License for more details. * GNU General Public License for more details.
* *
* You should have received a copy of the GNU General Public License * You should have received a copy of the GNU General Public License
* along with this program; if not, write to the Free Software * along with this program. If not, see <http://www.gnu.org/licenses/>.
* Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston,
* MA 02110-1301, USA.
*
*/ */
#include <stdint.h> #include <stdint.h>

View File

@ -1,12 +1,10 @@
/* /*
* geany_encoding=koi8-r * This file is part of the canrelay project.
* usb_lib.h * Copyright 2021 Edward V. Emelianov <edward.emelianoff@gmail.com>.
* *
* Copyright 2018 Edward V. Emelianov <eddy@sao.ru, edward.emelianoff@gmail.com> * This program is free software: you can redistribute it and/or modify
*
* 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 * it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or * the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version. * (at your option) any later version.
* *
* This program is distributed in the hope that it will be useful, * This program is distributed in the hope that it will be useful,
@ -15,10 +13,7 @@
* GNU General Public License for more details. * GNU General Public License for more details.
* *
* You should have received a copy of the GNU General Public License * You should have received a copy of the GNU General Public License
* along with this program; if not, write to the Free Software * along with this program. If not, see <http://www.gnu.org/licenses/>.
* Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston,
* MA 02110-1301, USA.
*
*/ */
#pragma once #pragma once

BIN
F0-nolib/usbcan_relay/usbcan.bin Normal file → Executable file

Binary file not shown.

Binary file not shown.