add code for STM8-based 2stepper management board

This commit is contained in:
eddyem 2018-10-09 18:18:58 +03:00
parent c975836b2c
commit 3f6b0a3500
40 changed files with 3485 additions and 607 deletions

View File

@ -0,0 +1,40 @@
NAME=twosteppers
SDCC=sdcc
CCFLAGS=-DSTM8S105 -I../ -I/usr/share/sdcc/include -mstm8 --out-fmt-ihx
LDFLAGS= -mstm8 --out-fmt-ihx -lstm8
FLASHFLAGS=-cstlinkv2 -pstm8s105?4
SRC=$(wildcard *.c)
OBJ=$(SRC:%.c=%.rel)
TRASH=$(OBJ) $(SRC:%.c=%.rst) $(SRC:%.c=%.asm) $(SRC:%.c=%.lst)
TRASH+=$(SRC:%.c=%.sym) $(NAME).lk $(NAME).map $(NAME).cdb
INDEPENDENT_HEADERS=../stm8l.h ports_definition.h Makefile
all: $(NAME).ihx
#$(SRC) : %.c : %.h $(INDEPENDENT_HEADERS)
# @touch $@
#
#%.h: ;
clean:
rm -f $(TRASH)
load: $(NAME).ihx
stm8flash $(FLASHFLAGS) -w $(NAME).ihx
gentags:
CFLAGS="$(CFLAGS) $(DEFS)" geany -g $(NAME).c.tags *[hc] 2>/dev/null
%.rel: %.c
$(SDCC) $(CCFLAGS) -c $<
bin: $(NAME).ihx
objcopy -I ihex -O binary $< $(NAME).bin
$(NAME).ihx: $(OBJ)
$(SDCC) $(LDFLAGS) $(OBJ) -o $(NAME).ihx
.PHONY: clean load gentags

View File

View File

@ -0,0 +1,92 @@
/*
* geany_encoding=koi8-r
* hardware.c
*
* Copyright 2018 Edward V. Emelianov <eddy@sao.ru, edward.emelianoff@gmail.com>
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; if not, write to the Free Software
* Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston,
* MA 02110-1301, USA.
*
*/
#include "hardware.h"
volatile unsigned long Global_time = 0L; // global time in ms
U8 MCU_no = 0; // unit number read from onboard jumpers
void hw_init(){
CFG_GCR |= 1; // disable SWIM
// Configure clocking
CLK_CKDIVR = 0; // F_HSI = 16MHz, f_CPU = 16MHz
// Timer 4 (8 bit) used as system tick timer
// prescaler == 128 (2^7), Tfreq = 125kHz
// period = 1ms, so ARR = 125
TIM4_PSCR = 7;
TIM4_ARR = 125;
// interrupts: update
TIM4_IER = TIM_IER_UIE;
// auto-reload + interrupt on overflow + enable
TIM4_CR1 = TIM_CR1_APRE | TIM_CR1_URS | TIM_CR1_CEN;
// GPIO; ODR-write, IDR-read, DDR-direction, CR1-pullup/pushpull, CR2-exti/speed
PB_DDR = 0x0f; // motor0
PB_CR1 = 0x0f;
PC_DDR = LED_PIN | PWM_PINS; // LED, PWM
PC_CR1 = LED_PIN | PWM_PINS;
PC_CR2 = PWM_PINS;
PD_DDR = 0x0f; // motor 1
PD_CR1 = 0x0f;
// end-switches
PORT(M0E1_PORT, CR1) |= M0E1_PIN;
PORT(M0E2_PORT, CR1) |= M0E2_PIN;
PORT(M1E1_PORT, CR1) |= M1E1_PIN;
PORT(M1E2_PORT, CR1) |= M1E2_PIN;
// default state setters
LED_OFF();
// Setup watchdog
IWDG_KR = KEY_ENABLE; // start watchdog
IWDG_KR = KEY_ACCESS; // enable access to protected registers
IWDG_PR = 6; // /256
IWDG_RLR = 0xff; // max time for watchdog (1.02s)
IWDG_KR = KEY_REFRESH;
// get board address
MCU_no = GET_ADDR();
// Configure timer 1 - PWM outputs
// prescaler = f_{in}/f_{tim1} - 1
// set Timer1 to 0.2MHz: 16/.2 - 1 = 79 (p-channel mosfet is too slow!)
TIM1_PSCRH = 0;
TIM1_PSCRL = 79; // LSB should be written last as it updates prescaler
// auto-reload each 256ticks:
TIM1_ARRH = 0x0;
TIM1_ARRL = 0xFF;
// P-channel opendrain mosfets are closed
TIM1_CCR1H = 0;
TIM1_CCR1L = 0;
TIM1_CCR2H = 0;
TIM1_CCR2L = 0;
TIM1_CCR3H = 0;
TIM1_CCR3L = 0;
// interrupts: none
// PWM mode 2 - OC1M = 111
TIM1_CCMR1 = 0x70; TIM1_CCMR2 = 0x70; TIM1_CCMR3 = 0x70;
TIM1_CCER1 = 0x11; // CC1E, CC2E
TIM1_CCER2 = 0x01; // CC3E
// auto-reload
TIM1_CR1 = TIM_CR1_APRE | TIM_CR1_CEN;
TIM1_BKR |= 1<<7; // MOE - enable main output
}

View File

@ -0,0 +1,97 @@
/*
* hardware.h - definition of ports pins & so on
*
* Copyright 2018 Edward V. Emelianov <eddy@sao.ru, edward.emelianoff@gmail.com>
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; if not, write to the Free Software
* Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston,
* MA 02110-1301, USA.
*/
#pragma once
#ifndef __HARDWARE_H__
#define __HARDWARE_H__
#include "stm8s.h"
extern volatile unsigned long Global_time; // global time in ms
extern U8 MCU_no;
// macro for using in port constructions like PORT(LED_PORT, ODR) = xx
#define FORMPORT(a, b) a ## _ ## b
#define PORT(a, b) FORMPORT(a , b)
#define CONCAT(a, b) a ## b
/**
* HW:
* PB0-3 motor0 push-pull output
* PB4 M0E1 pullup input
* PB5 M0E2 pullup input
* PC1-3 PWM push-pull output
* PC4 - LED push-pull output
* PC5-7 Addr floating input (externall pull-down)
* PD0-3 motor1 push-pull output
* PD4 M1E1 pullup input
* PD5 - Tx open-drain output \ UART
* PD6 - Rx floating input /
* PD7 M1E2 pullup input
*/
// PWM
#define PWM_PINS (7<<1)
// LED
#define LED_PORT PC
#define LED_PIN GPIO_PIN4
// Address
#define ADDR_MASK (7<<5)
#define GET_ADDR() ((PC_IDR & ADDR_MASK)>>5)
// UART2_TX
#define UART_PORT PD
#define UART_TX_PIN GPIO_PIN5
// steppers
#define STP0_PORT PB
#define STP1_PORT PD
#define STP_PINS (0x0f)
// end-switches
#define M0E1_PORT PB
#define M0E2_PORT PB
#define M1E1_PORT PD
#define M1E2_PORT PD
#define M0E1_PIN (1<<4)
#define M0E2_PIN (1<<5)
#define M1E1_PIN (1<<7)
#define M1E2_PIN (1<<4)
// getters: 1 active, 0 inactive
// inverse state of LED
#define LED_NSTATE() (PORT(LED_PORT, ODR) & LED_PIN)
// end-switches (0 - shuttered)
#define CHK_M0E1() (0 == (PORT(M0E1_PORT, IDR) & M0E1_PIN))
#define CHK_M0E2() (0 == (PORT(M0E2_PORT, IDR) & M0E2_PIN))
#define CHK_M1E1() (0 == (PORT(M1E1_PORT, IDR) & M1E1_PIN))
#define CHK_M1E2() (0 == (PORT(M1E2_PORT, IDR) & M1E2_PIN))
// setters
#define LED_OFF() (PORT(LED_PORT, ODR) |= LED_PIN)
#define LED_ON() (PORT(LED_PORT, ODR) &= ~LED_PIN)
// getters
void hw_init();
#endif // __HARDWARE_H__

View File

@ -0,0 +1,203 @@
/*
* interrupts.c
*
* Copyright 2018 Edward V. Emelianoff <eddy@sao.ru>
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; if not, write to the Free Software
* Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston,
* MA 02110-1301, USA.
*/
#include "hardware.h"
#include "uart.h"
#include "motors.h"
// Top Level Interrupt
INTERRUPT_HANDLER(TLI_IRQHandler, 0){}
// Auto Wake Up Interrupt
INTERRUPT_HANDLER(AWU_IRQHandler, 1){}
// Clock Controller Interrupt
INTERRUPT_HANDLER(CLK_IRQHandler, 2){}
// External Interrupt PORTA
INTERRUPT_HANDLER(EXTI_PORTA_IRQHandler, 3){}
// External Interrupt PORTB
INTERRUPT_HANDLER(EXTI_PORTB_IRQHandler, 4){}
// External Interrupt PORTC
INTERRUPT_HANDLER(EXTI_PORTC_IRQHandler, 5){
}
// External Interrupt PORTD
INTERRUPT_HANDLER(EXTI_PORTD_IRQHandler, 6){
}
// External Interrupt PORTE
INTERRUPT_HANDLER(EXTI_PORTE_IRQHandler, 7){}
#ifdef STM8S903
// External Interrupt PORTF
INTERRUPT_HANDLER(EXTI_PORTF_IRQHandler, 8){}
#endif // STM8S903
#if defined (STM8S208) || defined (STM8AF52Ax)
// CAN RX Interrupt routine.
INTERRUPT_HANDLER(CAN_RX_IRQHandler, 8){}
// CAN TX Interrupt routine.
INTERRUPT_HANDLER(CAN_TX_IRQHandler, 9){}
#endif // STM8S208 || STM8AF52Ax
// SPI Interrupt routine.
INTERRUPT_HANDLER(SPI_IRQHandler, 10){}
// Timer1 Update/Overflow/Trigger/Break Interrupt
INTERRUPT_HANDLER(TIM1_UPD_OVF_TRG_BRK_IRQHandler, 11){
}
// Timer1 Capture/Compare Interrupt routine.
INTERRUPT_HANDLER(TIM1_CAP_COM_IRQHandler, 12){}
#ifdef STM8S903
// Timer5 Update/Overflow/Break/Trigger Interrupt
INTERRUPT_HANDLER(TIM5_UPD_OVF_BRK_TRG_IRQHandler, 13){}
// Timer5 Capture/Compare Interrupt
INTERRUPT_HANDLER(TIM5_CAP_COM_IRQHandler, 14){}
#else // STM8S208, STM8S207, STM8S105 or STM8S103 or STM8AF62Ax or STM8AF52Ax or STM8AF626x
// Timer2 Update/Overflow/Break Interrupt
INTERRUPT_HANDLER(TIM2_UPD_OVF_BRK_IRQHandler, 13){
if(TIM2_SR1 & TIM_SR1_UIF){
TIM2_SR1 &= ~TIM_SR1_UIF; // take off flag
//irq_flag |= 1;
stepper_interrupt(0);
}
}
// Timer2 Capture/Compare Interrupt
INTERRUPT_HANDLER(TIM2_CAP_COM_IRQHandler, 14){
}
#endif // STM8S903
#if defined (STM8S208) || defined(STM8S207) || defined(STM8S007) || defined(STM8S105) || \
defined(STM8S005) || defined (STM8AF62Ax) || defined (STM8AF52Ax) || defined (STM8AF626x)
// Timer3 Update/Overflow/Break Interrupt
INTERRUPT_HANDLER(TIM3_UPD_OVF_BRK_IRQHandler, 15){
if(TIM3_SR1 & TIM_SR1_UIF){
TIM3_SR1 &= ~TIM_SR1_UIF;
//irq_flag |= 2;
stepper_interrupt(1);
}
}
// Timer3 Capture/Compare Interrupt
INTERRUPT_HANDLER(TIM3_CAP_COM_IRQHandler, 16){}
#endif // STM8S208, STM8S207 or STM8S105 or STM8AF62Ax or STM8AF52Ax or STM8AF626x
#if defined (STM8S208) || defined(STM8S207) || defined(STM8S007) || defined(STM8S103) || \
defined(STM8S003) || defined (STM8AF62Ax) || defined (STM8AF52Ax) || defined (STM8S903)
// UART1 TX Interrupt
INTERRUPT_HANDLER(UART1_TX_IRQHandler, 17){}
// UART1 RX Interrupt
INTERRUPT_HANDLER(UART1_RX_IRQHandler, 18){}
#endif // STM8S208 or STM8S207 or STM8S103 or STM8S903 or STM8AF62Ax or STM8AF52Ax
// I2C Interrupt
INTERRUPT_HANDLER(I2C_IRQHandler, 19){}
#if defined(STM8S105) || defined(STM8S005) || defined (STM8AF626x)
// UART2 TX interrupt
INTERRUPT_HANDLER(UART2_TX_IRQHandler, 20){
if(UART2_SR & UART_SR_TXE){
if(tx_len == 0){
UART2_CR2 &= ~UART_CR2_TIEN; // disable TXE interrupt
tx_idx = 0;
return;
}
if(tx_idx < tx_len){
UART2_DR = UART_tx[tx_idx++];
}else{
UART2_CR2 &= ~UART_CR2_TIEN;
tx_idx = 0;
tx_len = 0;
return;
}
}
}
// UART2 RX interrupt
INTERRUPT_HANDLER(UART2_RX_IRQHandler, 21){
U8 rb;
static U8 msg_begin = 0;
if(UART2_SR & UART_SR_RXNE){ // data received
rb = UART2_DR; // read received byte & clear RXNE flag
if(uart_rdy) return; // forget new data while old didn't managed
if(rb == ' ' || rb == '\t' || rb == '\r' || rb == '\n') return; // omit spaces
if(rb == '['){
msg_begin = 1;
rx_idx = 0; // start of message
return;
}
if(!msg_begin) return; // no message data
if(rx_idx == UART_BUF_LEN-1 && rb != ']'){ // Oops: buffer overflow! Just forget old data
rx_idx = 0;
return;
}
if(rb == ']'){
msg_begin = 0;
if(rx_idx) uart_rdy = 1; // don't set ready flag for empty messages
UART_rx[rx_idx] = 0;
}else UART_rx[rx_idx++] = rb; // put received byte into cycled buffer
}
}
#endif // STM8S105 or STM8AF626x
#if defined(STM8S207) || defined(STM8S007) || defined(STM8S208) || defined (STM8AF52Ax) || defined (STM8AF62Ax)
// UART3 TX interrupt
INTERRUPT_HANDLER(UART3_TX_IRQHandler, 20){}
// UART3 RX interrupt
INTERRUPT_HANDLER(UART3_RX_IRQHandler, 21){}
#endif // STM8S208 or STM8S207 or STM8AF52Ax or STM8AF62Ax
#if defined(STM8S207) || defined(STM8S007) || defined(STM8S208) || defined (STM8AF52Ax) || defined (STM8AF62Ax)
// ADC2 interrupt
INTERRUPT_HANDLER(ADC2_IRQHandler, 22){}
#else
// ADC1 interrupt
INTERRUPT_HANDLER(ADC1_IRQHandler, 22){
}
#endif // STM8S208 or STM8S207 or STM8AF52Ax or STM8AF62Ax
#ifdef STM8S903
// Timer6 Update/Overflow/Trigger Interrupt
INTERRUPT_HANDLER(TIM6_UPD_OVF_TRG_IRQHandler, 23){}
#else // STM8S208, STM8S207, STM8S105 or STM8S103 or STM8AF52Ax or STM8AF62Ax or STM8AF626x
// Timer4 Update/Overflow Interrupt
INTERRUPT_HANDLER(TIM4_UPD_OVF_IRQHandler, 23){
if(TIM4_SR & TIM_SR1_UIF){ // update interrupt
Global_time++; // increase timer
}
TIM4_SR = 0; // clear all interrupt flags
}
#endif // STM8S903
// Eeprom EEC Interrupt
INTERRUPT_HANDLER(EEPROM_EEC_IRQHandler, 24){}

View File

@ -0,0 +1,55 @@
/*
* main.c
*
* Copyright 2018 Edward V. Emelianoff <eddy@sao.ru>
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; if not, write to the Free Software
* Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston,
* MA 02110-1301, USA.
*/
#include "hardware.h"
#include "interrupts.h"
#include "uart.h"
#include "proto.h"
#include "motors.h"
int main() {
char A[3] = {'x', '\n', 0};
unsigned long T = 0L;
if(RST_SR) RST_SR = 0x1f; // clear reset flags writing 1
hw_init();
motors_init();
uart_init();
// enable all interrupts
enableInterrupts();
// remove this code if nesessary
uart_write("\n\nHello! My address is ");
A[0] = MCU_no + '0';
uart_write(A);
show_help(); // show protocol help @start
// Loop
do{
/*if(Global_time - T > paused_val){
}*/
IWDG_KR = KEY_REFRESH; // refresh watchdog
if(uart_rdy){
process_string();
}
process_stepper(0);
process_stepper(1);
}while(1);
}

View File

@ -0,0 +1,423 @@
/*
* geany_encoding=koi8-r
* motors.c
*
* Copyright 2018 Edward V. Emelianov <eddy@sao.ru, edward.emelianoff@gmail.com>
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; if not, write to the Free Software
* Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston,
* MA 02110-1301, USA.
*
*/
#include "motors.h"
#include "uart.h"
#include "hardware.h"
//U8 irq_flag = 0; // |1 - 1st motor, |2 - second
// motor states
typedef enum{
MOTOR_RELAX, // do nothing
MOTOR_INFMOVE, // infinite moving
MOTOR_STOP, // stop
MOTOR_ZEROSTOP, // stop and set current position to zero
MOTOR_MOVENSTEPS, // move for N steps
MOTOR_OFFSWITCH, // try to pull off the positive switch (for turrets and to return from switch back)
} motor_state;
// direction of rotation
typedef enum{
DIR_CW, // clockwise
DIR_CCW, // counter-clockwise
DIR_STOP // stopped
} motor_direction;
static U16 Stepper_speed[2] = {DEFAULT_USTEP_PERIOD, DEFAULT_USTEP_PERIOD}; // length of one MICROstep in us
static volatile motor_direction Dir[2] = {DIR_STOP, DIR_STOP}; // direction of moving
static volatile motor_state state[2] = {MOTOR_RELAX, MOTOR_RELAX};
static long Steps_left[2] = {0,0}; // steppers left (when moving for given steps amount)
static long Current_pos[2] = {0,0}; // current position
static long Steps_left_at_esw[2] = {0,0}; // amount of `Steps_left` when MOTOR_OFFSWITCH activated
static U16 Acceleration[2] = {0, 0}; // current acceleration (to reach target speed by ACCEL_STEPS microsteps)
// microsteps profile
// microsteps: DCBA = 1000, 1010, 0010, 0110, 0100, 0101, 0001, 1001 - half-step
// 1010, 0110, 0101, 1001 - full step
static const U8 usteps[8] = {0b1000, 0b1010, 0b0010, 0b0110, 0b0100, 0b0101, 0b0001, 0b1001};
static U8 Ustep[2] = {0, 0}; // microstep counter
// init timers & GPIO for motors
void motors_init(){
// Configure timer 2 to generate signals for CLK of motor 0
TIM2_PSCR = 4; // 1MHz
TIM2_ARRH = DEFAULT_USTEP_PERIOD >> 8; // set speed
TIM2_ARRL = DEFAULT_USTEP_PERIOD & 0xff;
TIM2_IER = TIM_IER_UIE; // update interrupt enable
TIM2_CR1 |= TIM_CR1_APRE | TIM_CR1_URS; // auto reload + interrupt on overflow
// timer 3 for motor 1
TIM3_PSCR = 4;
TIM3_ARRH = DEFAULT_USTEP_PERIOD >> 8;
TIM3_ARRL = DEFAULT_USTEP_PERIOD & 0xff;
TIM3_IER = TIM_IER_UIE;
TIM3_CR1 |= TIM_CR1_APRE | TIM_CR1_URS;
}
void show_motors_help(){
// "start end"
uart_write("\tE - get end-switches\n");
uart_write("\tL - move CCW\n");
uart_write("\tM - get motor state\n");
uart_write("\tN - go for N st./get rest\n");
uart_write("\tO - pull off the switch\n");
uart_write("\tP - get current position\n");
uart_write("\tR - move CW\n");
uart_write("\tS - get/set speed\n");
uart_write("\tX - stop motor\n");
uart_write("\tZ - stop and zero position\n");
}
/**
* Check endswitches
* @return 0 if none pressed, 1 if "-", 2 if "+", 3 if both!
*/
static U8 check_endsw(U8 motor){
U8 ret = 0;
switch(motor){
case 0:
if(CHK_M0E1()) ++ret;
if(CHK_M0E2()) ret += 2;
break;
case 1:
if(CHK_M1E1()) ++ret;
if(CHK_M1E2()) ret += 2;
break;
default:
return 0;
}
return ret;
}
static void stop_motor(U8 motorNum){
// stop timers & turn off power
switch(motorNum){
case 0:
PORT(STP0_PORT, ODR) &= ~STP_PINS;
TIM2_CR1 &= ~TIM_CR1_CEN;
break;
case 1:
PORT(STP1_PORT, ODR) &= ~STP_PINS;
TIM3_CR1 &= ~TIM_CR1_CEN;
break;
default: return;
}
Steps_left[motorNum] = 0;
Ustep[motorNum] = 0;
Dir[motorNum] = DIR_STOP;
}
static void strtobuf(const char *str, char **buff){
while(*str) *((*buff)++) = *str++;
}
static void get_motor_state(U8 nmotor, char **buff){
char sig = '+';
if(nmotor > 1) return;
if(Dir[nmotor] == DIR_CCW) sig = '-';
switch(state[nmotor]){
case MOTOR_RELAX:
strtobuf("RELAX", buff);
break;
case MOTOR_INFMOVE:
strtobuf("INFMV", buff); // INVMV+ or INFMV-
*((*buff)++) = sig;
break;
break;
case MOTOR_STOP:
strtobuf("STOP", buff);
break;
case MOTOR_MOVENSTEPS:
strtobuf("MVSTP", buff); // MVSTP+ or MVSTP-
*((*buff)++) = sig;
break;
case MOTOR_OFFSWITCH:
strtobuf("OFFSW", buff); // OFFSW+ or OFFSW-
*((*buff)++) = sig;
break;
default:
strtobuf("UNDEF", buff);
}
}
// turn on motor's timer starting from the lowest speed
static void turnontimer(U8 motorNum){
switch(motorNum){
case 0:
TIM2_ARRH = MAX_USTEP_PERIOD >> 8;
TIM2_ARRL = MAX_USTEP_PERIOD & 0xff;
TIM2_CR1 |= TIM_CR1_CEN;
break;
case 1:
TIM3_ARRH = MAX_USTEP_PERIOD >> 8;
TIM3_ARRL = MAX_USTEP_PERIOD & 0xff;
TIM3_CR1 |= TIM_CR1_CEN;
break;
default: return;
}
Acceleration[motorNum] = 1 + (MAX_USTEP_PERIOD - Stepper_speed[motorNum]) / ACCEL_USTEPS;
}
/**
* try to move motor motorNum for nsteps
* @return 1 if all OK; 0 if still moving or on end-switch
*/
static int moveNsteps(U8 motorNum, long nsteps){
U8 sw;
if(Dir[motorNum] != DIR_STOP) return 0;
sw = check_endsw(motorNum);
if(nsteps < 0){
if(sw) return 0; // on zero end-switch: no moving backward, on positive - no moving at all!
Dir[motorNum] = DIR_CCW;
nsteps = -nsteps;
Ustep[motorNum] = 7;
state[motorNum] = MOTOR_MOVENSTEPS;
}else{
if(sw & 2) return 0; // for positive direction no moving to any side when on end-switch 2!
else if(sw & 1) state[motorNum] = MOTOR_OFFSWITCH;
else state[motorNum] = MOTOR_MOVENSTEPS;
Dir[motorNum] = DIR_CW;
}
Steps_left[motorNum] = nsteps;
// turn On timer
turnontimer(motorNum);
return 1;
}
/**
* try to move motor motorNum off the end-switch for nsteps
* @return 1 if all OK; 0 if still moving, motor is @ zero endswitch
*/
static int pullofftheswitch(U8 motorNum, long nsteps){
U8 sw;
if(Dir[motorNum] != DIR_STOP) return 0;
sw = check_endsw(motorNum);
if(sw == 0) return moveNsteps(motorNum, nsteps);
if(nsteps < 0){
if(sw & 1) return 0; // on zero end-switch: no moving backward
Dir[motorNum] = DIR_CCW;
nsteps = -nsteps;
Ustep[motorNum] = 7;
}else{
Dir[motorNum] = DIR_CW;
}
Steps_left[motorNum] = nsteps;
Steps_left_at_esw[motorNum] = nsteps;
state[motorNum] = MOTOR_OFFSWITCH;
turnontimer(motorNum);
return 1;
}
void motor_command(const char *cmd, char **buff){
U8 motorNum = *cmd++ - '0';
U16 spd;
long l;
char c;
if(motorNum > 1) goto someerr;
*((*buff)++) = '0' + motorNum;
*((*buff)++) = ' ';
c = *cmd++;
*((*buff)++) = c; *((*buff)++) = ' ';
switch(c){
case 'E': // check endswitches state
*((*buff)++) = '0' + check_endsw(motorNum);
break;
case 'L': // infinite move left
if(1 == check_endsw(motorNum)){
*((*buff)++) = 'E'; *((*buff)++) = ' ';
*((*buff)++) = '1';
}else{
state[motorNum] = MOTOR_INFMOVE;
Dir[motorNum] = DIR_CCW;
Ustep[motorNum] = 7;
turnontimer(motorNum);
}
break;
case 'M': // get motor state
get_motor_state(motorNum, buff);
break;
case 'N': // go for N steps or get steps left
if(!readLong(cmd, &l)){ // get
long2buf(Steps_left[motorNum], buff);
}else{
if(!moveNsteps(motorNum, l)) goto someerr;
else long2buf(l, buff);
}
break;
case 'O': // pull off the switch (if no steps given, go for PULLOFFTHESW_STEPS)
if(!readLong(cmd, &l)){ // get
l = PULLOFFTHESW_STEPS;
}
if(!pullofftheswitch(motorNum, l)) goto someerr;
else long2buf(l, buff);
break;
case 'P': // get current position
long2buf(Current_pos[motorNum], buff);
break;
case 'R': // infinite move right
if(2 == check_endsw(motorNum)){
*((*buff)++) = 'E'; *((*buff)++) = ' ';
*((*buff)++) = '2';
}else{
state[motorNum] = MOTOR_INFMOVE;
Dir[motorNum] = DIR_CW;
turnontimer(motorNum);
}
break;
case 'S': // change speed
if(!readLong(cmd, &l) || l < MIN_USTEP_PERIOD || l > MAX_USTEP_PERIOD){ // get speed
if(motorNum == 0) spd = TIM2_ARRH << 8 | TIM2_ARRL;
else spd = TIM3_ARRH << 8 | TIM3_ARRL;
long2buf(spd, buff);
}else{
long2buf(l, buff);
spd = (U16)l;
Stepper_speed[motorNum] = spd;
Acceleration[motorNum] = 0;
if(motorNum == 0){
TIM2_ARRH = spd >> 8;
TIM2_ARRL = spd & 0xff;
}else{
TIM3_ARRH = spd >> 8;
TIM3_ARRL = spd & 0xff;
}
}
break;
case 'X': // stop
state[motorNum] = MOTOR_STOP;
break;
case 'Z':
state[motorNum] = MOTOR_ZEROSTOP;
break;
default: // return err
goto someerr;
}
return;
someerr:
*((*buff)++) = 'e';
*((*buff)++) = 'r';
*((*buff)++) = 'r';
}
/**
* this function calls from timer interrupt (TIM2 or TIM3 - motors 0/1)
*/
void stepper_interrupt(U8 motor_num){
U8 tmp;
U16 spd;
//irq_flag ^= 1 << motor_num;
switch(motor_num){
case 0:
if(Acceleration[0]){
spd = (TIM2_ARRH << 8 | TIM2_ARRL) - Acceleration[0];
if(spd < Stepper_speed[0]){
spd = Stepper_speed[0];
Acceleration[0] = 0;
}
//printUint((U8*)&spd, 2);
//uart_write(" - speed0\n");
TIM2_ARRH = spd >> 8;
TIM2_ARRL = spd & 0xff;
}
tmp = PORT(STP0_PORT, ODR) & ~STP_PINS;
PORT(STP0_PORT, ODR) = tmp | usteps[Ustep[0]];
break;
case 1:
if(Acceleration[1]){
spd = (TIM3_ARRH << 8 | TIM3_ARRL) - Acceleration[1];
if(spd < Stepper_speed[1]){
spd = Stepper_speed[1];
Acceleration[1] = 0;
}
//printUint((U8*)&spd, 2);
//uart_write(" - speed1\n");
TIM3_ARRH = spd >> 8;
TIM3_ARRL = spd & 0xff;
}
tmp = PORT(STP1_PORT, ODR) & ~STP_PINS;
PORT(STP1_PORT, ODR) = tmp | usteps[Ustep[1]];
break;
default: return;
}
if(Dir[motor_num] == DIR_CCW){ // counter-clockwise
if(Ustep[motor_num] == 0){
--Steps_left[motor_num];
--Current_pos[motor_num];
if(state[motor_num] == MOTOR_STOP || state[motor_num] == MOTOR_ZEROSTOP){
stop_motor(motor_num);
return;
}
Ustep[motor_num] = 7;
}else --Ustep[motor_num];
}else{ // clockwise
if(++Ustep[motor_num] > 7){
--Steps_left[motor_num];
++Current_pos[motor_num];
if(state[motor_num] == MOTOR_STOP || state[motor_num] == MOTOR_ZEROSTOP){
stop_motor(motor_num);
return;
}
Ustep[motor_num] = 0;
}
}
}
/**
* Main state-machine process
*/
void process_stepper(U8 motor_num){
U8 sw = check_endsw(motor_num);
U8 ccw = (Dir[motor_num] == DIR_CCW) ? 1 : 0;
switch(state[motor_num]){
case MOTOR_OFFSWITCH: // don't care about endswitch for first PULLOFFTHESW_STEPS steps
if(Steps_left[motor_num] < 2) state[motor_num] = MOTOR_STOP;
else if(Steps_left_at_esw[motor_num] - Steps_left[motor_num] >= PULLOFFTHESW_STEPS)
state[motor_num] = MOTOR_MOVENSTEPS;
break;
case MOTOR_MOVENSTEPS:
if(Steps_left[motor_num] < 2) state[motor_num] = MOTOR_STOP; // stop @given position
case MOTOR_INFMOVE: // set curpos to zero only in this state (after reaching ESW1)
if(sw){
if(ccw){
if(state[motor_num] == MOTOR_INFMOVE){
if(sw & 1) state[motor_num] = MOTOR_ZEROSTOP; // esw1 - stop @ zero when inf. left move
}else state[motor_num] = MOTOR_STOP; // just stop at any esw in steps move
}else{ // +switch when move CW
if(sw & 2) state[motor_num] = MOTOR_STOP; // stop in CW only on esw2 !!!
}
}
break;
case MOTOR_STOP:
if(Dir[motor_num] == DIR_STOP){
state[motor_num] = MOTOR_RELAX;
}
break;
case MOTOR_ZEROSTOP:
if(Dir[motor_num] == DIR_STOP){
Current_pos[motor_num] = 0;
state[motor_num] = MOTOR_RELAX;
}
break;
default: return; // MOTOR_RELAX
}
//if(irq_flag & (1<<motor_num)) stepper_interrupt(motor_num);
}

View File

@ -0,0 +1,49 @@
/*
* geany_encoding=koi8-r
* motors.h
*
* Copyright 2018 Edward V. Emelianov <eddy@sao.ru, edward.emelianoff@gmail.com>
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; if not, write to the Free Software
* Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston,
* MA 02110-1301, USA.
*
*/
#pragma once
#ifndef __MOTORS_H__
#define __MOTORS_H__
// default speed @ start - 50 steps per second
#define DEFAULT_USTEP_PERIOD (2500)
// max speed == 1/(625us*8) = 200 steps per second
#define MIN_USTEP_PERIOD (625)
// min speed as 16-bit timer can - 65535 - near 1.9 steps per second
// default min speed - 10 steps per second
#define MAX_USTEP_PERIOD (12500)
// amount of steps to pull off the switch
#define PULLOFFTHESW_STEPS (100)
// amount of microsteps for acceleration calculation
#define ACCEL_USTEPS (200)
//extern unsigned char irq_flag;
void motors_init();
void show_motors_help();
void motor_command(const char *cmd, char **bufptr);
void stepper_interrupt(unsigned char motor_num);
void process_stepper(unsigned char stepno);
#endif // __MOTORS_H__

View File

@ -0,0 +1,166 @@
/*
* geany_encoding=koi8-r
* proto.c - base protocol definitions
*
* Copyright 2018 Edward V. Emelianov <eddy@sao.ru, edward.emelianoff@gmail.com>
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; if not, write to the Free Software
* Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston,
* MA 02110-1301, USA.
*
*/
#include "proto.h"
#include "hardware.h"
#include "uart.h"
#include "motors.h"
// input command buffer
static char ibuf[UART_BUF_LEN];
// buffer for output data
static char obuf[UART_BUF_LEN] = "[ X "; // constant initializer
void show_help(){
// uart_write transfer not more than UART_BUF_LEN bytes!
// "start end"
uart_write("\n\n");
uart_write("Command protocol: [ addr command");
uart_write(" data ]\n\t broadcast addr: " BROADCAST_CHAR "\n");
uart_write("commands:\n");
uart_write("0/1 - command for given motor:\n");
show_motors_help();
uart_write("r - reset MCU\n");
uart_write("G - get board address\n");
uart_write("L 0/1 - LED on/off\n");
uart_write("P ch val - PWM on channel ch\n");
uart_write("T - time counter value\n");
uart_write("\n\n");
}
static void set_PWM(char *cmd, char **buff){
U8 s = 0;
long l;
U8 N = *cmd++ - '0';
if(N > 2){
long2buf(-1, buff); // error: answer with Nch = -1
return;
}
*((*buff)++) = '0' + N;
*((*buff)++) = ' ';
if(*cmd == 0){ // check PWM value
switch (N){
case 0:
s = TIM1_CCR1L;
break;
case 1:
s = TIM1_CCR2L;
break;
case 2:
s = TIM1_CCR3L;
break;
}
}else{
if(!readLong(cmd, &l) || l < 0 || l > 255){
long2buf(-1, buff); // error: answer with PWM = -1
return;
}
s = (U8) l;
switch (N){
case 0:
TIM1_CCR1L = s;
break;
case 1:
TIM1_CCR2L = s;
break;
case 2:
TIM1_CCR3L = s;
break;
}
}
long2buf(s, buff);
}
// @return 0 in case of error
// @param cmd - string with command sequence
static U8 process_commands(char *cmd){
char s, *bufptr = &obuf[4];
static const char* const endline = " ]\n";
IWDG_KR = KEY_REFRESH; // refresh watchdog
// uart_write("got command: ");
// uart_write(cmd);
s = *cmd;
obuf[2] = MCU_no + '0';
if(s == '0' || s == '1'){
motor_command(cmd, &bufptr);
goto eof;
}
*bufptr++ = s;
*bufptr++ = ' ';
++cmd;
switch(s){
case 'r':
IWDG_KR = KEY_ACCESS;
IWDG_PR = 0;
IWDG_RLR = 0x1;
IWDG_KR = KEY_REFRESH;
while(1);
break;
case 'G':
*bufptr++ = '0' + MCU_no;
break;
case 'L': // LED on/off
if(*cmd){ // if there's no number after LED command - just check its state
if(*cmd == '0'){
LED_OFF();
}else{
LED_ON();
}
}
*bufptr++ = LED_NSTATE() ? '0' : '1';
break;
case 'P':
set_PWM(cmd, &bufptr);
break;
case 'T':
*bufptr = 0;
uart_write(obuf);
printUint((U8*)&Global_time, 4);
uart_write(endline);
return 1;
break;
default:
return 0;
}
eof:
*bufptr = 0;
uart_write(obuf);
uart_write(endline);
return 1;
}
void process_string(){
U8 ctr;
char *iptr = ibuf, *optr = &UART_rx[1];
U8 mcuno = (U8)UART_rx[0] - '0';
if(uart_rdy == 0) return;
if(mcuno != MCU_no && mcuno != BROADCAST_ADDR){ // alien message
uart_rdy = 0;
rx_idx = 0;
return;
}
// rx_idx is length of incoming message; next char is '\0', copy it too
for(ctr = 0; ctr < rx_idx; ++ctr) *iptr++ = *optr++;
rx_idx = 0; uart_rdy = 0; // command read, buffer ready to get more data
if(!process_commands(ibuf)) show_help();
}

View File

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

View File

@ -0,0 +1,568 @@
/*
* stm8s.h
*
* Copyright 2018 Edward V. Emelianoff <eddy@sao.ru>
*
* 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 __STM8L_H__
#define __STM8L_H__
typedef unsigned char U8;
typedef unsigned int U16;
typedef unsigned long U32;
#define NULL (void*)0
/* functions */
#define enableInterrupts() {__asm__("rim\n");} // enable interrupts
#define disableInterrupts() {__asm__("sim\n");} // disable interrupts
#define iret() {__asm__("iret\n");} // Interrupt routine return
#define pop_ccr() {__asm__("pop cc\n");} // Pop CCR from the stack
#define push_ccr() {__asm__("push cc\n");}// Push CCR on the stack
#define rim() {__asm__("rim\n");} // enable interrupts
#define sim() {__asm__("sim\n");} // disable interrupts
#define nop() {__asm__("nop\n");} // No Operation
#define trap() {__asm__("trap\n");} // Trap (soft IT)
#define wfi() {__asm__("wfi\n");} // Wait For Interrupt
#define halt() {__asm__("halt\n");} // Halt
/*
* Registers map is shown in short datasheet, page 26
*/
/* GPIO */
#define PA_ODR *(unsigned char*)0x5000
#define PA_IDR *(unsigned char*)0x5001
#define PA_DDR *(unsigned char*)0x5002
#define PA_CR1 *(unsigned char*)0x5003
#define PA_CR2 *(unsigned char*)0x5004
#define PB_ODR *(unsigned char*)0x5005
#define PB_IDR *(unsigned char*)0x5006
#define PB_DDR *(unsigned char*)0x5007
#define PB_CR1 *(unsigned char*)0x5008
#define PB_CR2 *(unsigned char*)0x5009
#define PC_ODR *(unsigned char*)0x500A
#define PC_IDR *(unsigned char*)0x500B
#define PC_DDR *(unsigned char*)0x500C
#define PC_CR1 *(unsigned char*)0x500D
#define PC_CR2 *(unsigned char*)0x500E
#define PD_ODR *(unsigned char*)0x500F
#define PD_IDR *(unsigned char*)0x5010
#define PD_DDR *(unsigned char*)0x5011
#define PD_CR1 *(unsigned char*)0x5012
#define PD_CR2 *(unsigned char*)0x5013
#define PE_ODR *(unsigned char*)0x5014
#define PE_IDR *(unsigned char*)0x5015
#define PE_DDR *(unsigned char*)0x5016
#define PE_CR1 *(unsigned char*)0x5017
#define PE_CR2 *(unsigned char*)0x5018
#define PF_ODR *(unsigned char*)0x5019
#define PF_IDR *(unsigned char*)0x501A
#define PF_DDR *(unsigned char*)0x501B
#define PF_CR1 *(unsigned char*)0x501C
#define PF_CR2 *(unsigned char*)0x501D
#ifdef STM8S105
#define PG_ODR *(unsigned char*)0x501E
#define PG_IDR *(unsigned char*)0x501F
#define PG_DDR *(unsigned char*)0x5020
#define PG_CR1 *(unsigned char*)0x5021
#define PG_CR2 *(unsigned char*)0x5022
#define PH_ODR *(unsigned char*)0x5023
#define PH_IDR *(unsigned char*)0x5024
#define PH_DDR *(unsigned char*)0x5025
#define PH_CR1 *(unsigned char*)0x5026
#define PH_CR2 *(unsigned char*)0x5027
#define PI_ODR *(unsigned char*)0x5028
#define PI_IDR *(unsigned char*)0x5029
#define PI_DDR *(unsigned char*)0x502A
#define PI_CR1 *(unsigned char*)0x502B
#define PI_CR2 *(unsigned char*)0x502C
#endif // STM8S105
/* GPIO bits */
#define GPIO_PIN0 (1 << 0)
#define GPIO_PIN1 (1 << 1)
#define GPIO_PIN2 (1 << 2)
#define GPIO_PIN3 (1 << 3)
#define GPIO_PIN4 (1 << 4)
#define GPIO_PIN5 (1 << 5)
#define GPIO_PIN6 (1 << 6)
#define GPIO_PIN7 (1 << 7)
/* -------------------- FLASH/EEPROM -------------------- */
#define FLASH_CR1 *(unsigned char*)0x505A
#define FLASH_CR2 *(unsigned char*)0x505B
#define FLASH_NCR2 *(unsigned char*)0x505C
#define FLASH_FPR *(unsigned char*)0x505D
#define FLASH_NFPR *(unsigned char*)0x505E
#define FLASH_IAPSR *(unsigned char*)0x505F
#define FLASH_PUKR *(unsigned char*)0x5062 // progmem unprotection
#define FLASH_DUKR *(unsigned char*)0x5064 // EEPROM unprotection
#define EEPROM_KEY1 0xAE // keys to manage EEPROM's write access
#define EEPROM_KEY2 0x56
#define EEPROM_START_ADDR (unsigned char*)0x4000
/* ------------------- interrupts ------------------- */
#define EXTI_CR1 *(unsigned char*)0x50A0
#define EXTI_CR2 *(unsigned char*)0x50A1
#define INTERRUPT_HANDLER(fn, num) void fn() __interrupt(num)
#define INTERRUPT_DEFINITION(fn, num) extern void fn() __interrupt(num)
// Reset status register
#define RST_SR *(unsigned char*)0x50B3
/* ------------------- CLOCK ------------------- */
#define CLK_ICKR *(unsigned char*)0x50C0
#define CLK_ECKR *(unsigned char*)0x50C1
#define CLK_CMSR *(unsigned char*)0x50C3
#define CLK_SWR *(unsigned char*)0x50C4
#define CLK_SWCR *(unsigned char*)0x50C5
#define CLK_CKDIVR *(unsigned char*)0x50C6
#define CLK_SPCKENR1 *(unsigned char*)0x50C7
#define CLK_CSSR *(unsigned char*)0x50C8
#define CLK_CCOR *(unsigned char*)0x50C9
#define CLK_PCKENR2 *(unsigned char*)0x50CA
#define CLK_HSITRIMR *(unsigned char*)0x50CC
#define CLK_SWIMCCR *(unsigned char*)0x50CD
/* ------------------- Watchdog ------------------ */
#define WWDG_CR *(unsigned char*)0x50D1
#define WWDG_WR *(unsigned char*)0x50D2
#define IWDG_KR *(unsigned char*)0x50E0
#define IWDG_PR *(unsigned char*)0x50E1
#define IWDG_RLR *(unsigned char*)0x50E2
// enable Watchdog
#define KEY_ENABLE (0xCC)
// refresh Watchdog from IWDG_RLR
#define KEY_REFRESH (0xAA)
// modify IWDG_PR and IWDG_RLR
#define KEY_ACCESS (0x55)
/* ------------------- AWU, BEEP ------------------- */
#define AWU_CSR1 *(unsigned char*)0x50F0
#define AWU_APR *(unsigned char*)0x50F1
#define AWU_TBR *(unsigned char*)0x50F2
#define BEEP_CSR *(unsigned char*)0x50F3
/* ------------------- SPI ------------------- */
#define SPI_CR1 *(unsigned char*)0x5200
#define SPI_CR2 *(unsigned char*)0x5201
#define SPI_ICR *(unsigned char*)0x5202
#define SPI_SR *(unsigned char*)0x5203
#define SPI_DR *(unsigned char*)0x5204
#define SPI_CRCPR *(unsigned char*)0x5205
#define SPI_RXCRCR *(unsigned char*)0x5206
#define SPI_TXCRCR *(unsigned char*)0x5207
// SPI_CR1 (page 271): | LSBFIRST | SPE | BR[2:0] | MSTR | CPOL | CPHA |
#define SPI_CR1_LSBFIRST (1<<7)
#define SPI_CR1_SPE (1<<6)
#define SPI_CR1_BRMASK (0x38)
#define SPI_CR1_MSTR (1<<2)
#define SPI_CR1_CPOL (1<<1)
#define SPI_CR1_CPHA (1)
// SPI_CR2 (page 272): | BDM | BDOE | CRCEN | CRCNEXT | - | RXONLY | SSM | SSI |
#define SPI_CR2_BDM (1<<7)
#define SPI_CR2_BDOE (1<<6)
#define SPI_CR2_CRCEN (1<<5)
#define SPI_CR2_CRCNEXT (1<<4)
#define SPI_CR2_RXONLY (1<<2)
#define SPI_CR2_SSM (1<<1)
#define SPI_CR2_SSI (1)
// SPI_ICR (page 273): | TXIE | RXIE | ERRIE | WKIE | - | - | - | - |
#define SPI_ICR_TXIE (1<<7)
#define SPI_ICR_RXIE (1<<6)
#define SPI_ICR_ERRIE (1<<5)
#define SPI_ICR_WKIE (1<<4)
// SPI_SR (page 274): | BSY | OVR | MODF | CRCERR | WKUP | - | TXE | RXNE |
#define SPI_SR_BSY (1<<7)
#define SPI_SR_OVR (1<<6)
#define SPI_SR_MODF (1<<5)
#define SPI_SR_CRCERR (1<<4)
#define SPI_SR_WKUP (1<<3)
#define SPI_SR_TXE (1<<1)
#define SPI_SR_RXNE (1)
/* ------------------- I2C ------------------- */
#define I2C_CR1 *(unsigned char*)0x5210
#define I2C_CR2 *(unsigned char*)0x5211
#define I2C_FREQR *(unsigned char*)0x5212
#define I2C_OARL *(unsigned char*)0x5213
#define I2C_OARH *(unsigned char*)0x5214
#define I2C_DR *(unsigned char*)0x5216
#define I2C_SR1 *(unsigned char*)0x5217
#define I2C_SR2 *(unsigned char*)0x5218
#define I2C_SR3 *(unsigned char*)0x5219
#define I2C_ITR *(unsigned char*)0x521A
#define I2C_CCRL *(unsigned char*)0x521B
#define I2C_CCRH *(unsigned char*)0x521C
#define I2C_TRISER *(unsigned char*)0x521D
#define I2C_PECR *(unsigned char*)0x521E
/* ------------------- UART ------------------- */
#if defined STM8S003 || defined STM8S103
#define UART1_SR *(unsigned char*)0x5230
#define UART1_DR *(unsigned char*)0x5231
#define UART1_BRR1 *(unsigned char*)0x5232
#define UART1_BRR2 *(unsigned char*)0x5233
#define UART1_CR1 *(unsigned char*)0x5234
#define UART1_CR2 *(unsigned char*)0x5235
#define UART1_CR3 *(unsigned char*)0x5236
#define UART1_CR4 *(unsigned char*)0x5237
#define UART1_CR5 *(unsigned char*)0x5238
#define UART1_GTR *(unsigned char*)0x5239
#define UART1_PSCR *(unsigned char*)0x523A
#endif // STM8S003
#ifdef STM8S105
#define UART2_SR *(unsigned char*)0x5240
#define UART2_DR *(unsigned char*)0x5241
#define UART2_BRR1 *(unsigned char*)0x5242
#define UART2_BRR2 *(unsigned char*)0x5243
#define UART2_CR1 *(unsigned char*)0x5244
#define UART2_CR2 *(unsigned char*)0x5245
#define UART2_CR3 *(unsigned char*)0x5246
#define UART2_CR4 *(unsigned char*)0x5247
#define UART2_CR5 *(unsigned char*)0x5248
#define UART2_CR6 *(unsigned char*)0x5249
#define UART2_GTR *(unsigned char*)0x524A
#define UART2_PSCR *(unsigned char*)0x524B
#endif // STM8S105
/* UART_CR1 bits */
#define UART_CR1_R8 (1 << 7)
#define UART_CR1_T8 (1 << 6)
#define UART_CR1_UARTD (1 << 5)
#define UART_CR1_M (1 << 4)
#define UART_CR1_WAKE (1 << 3)
#define UART_CR1_PCEN (1 << 2)
#define UART_CR1_PS (1 << 1)
#define UART_CR1_PIEN (1 << 0)
/* UART_CR2 bits */
#define UART_CR2_TIEN (1 << 7)
#define UART_CR2_TCIEN (1 << 6)
#define UART_CR2_RIEN (1 << 5)
#define UART_CR2_ILIEN (1 << 4)
#define UART_CR2_TEN (1 << 3)
#define UART_CR2_REN (1 << 2)
#define UART_CR2_RWU (1 << 1)
#define UART_CR2_SBK (1 << 0)
/* USART_CR3 bits */
#define UART_CR3_LINEN (1 << 6)
#define UART_CR3_STOP2 (1 << 5)
#define UART_CR3_STOP1 (1 << 4)
#define UART_CR3_CLKEN (1 << 3)
#define UART_CR3_CPOL (1 << 2)
#define UART_CR3_CPHA (1 << 1)
#define UART_CR3_LBCL (1 << 0)
/* UART_SR bits */
#define UART_SR_TXE (1 << 7)
#define UART_SR_TC (1 << 6)
#define UART_SR_RXNE (1 << 5)
#define UART_SR_IDLE (1 << 4)
#define UART_SR_OR (1 << 3)
#define UART_SR_NF (1 << 2)
#define UART_SR_FE (1 << 1)
#define UART_SR_PE (1 << 0)
/* ------------------- TIMERS ------------------- */
/* TIM1 */
#define TIM1_CR1 *(unsigned char*)0x5250
#define TIM1_CR2 *(unsigned char*)0x5251
#define TIM1_SMCR *(unsigned char*)0x5252
#define TIM1_ETR *(unsigned char*)0x5253
#define TIM1_IER *(unsigned char*)0x5254
#define TIM1_SR1 *(unsigned char*)0x5255
#define TIM1_SR2 *(unsigned char*)0x5256
#define TIM1_EGR *(unsigned char*)0x5257
#define TIM1_CCMR1 *(unsigned char*)0x5258
#define TIM1_CCMR2 *(unsigned char*)0x5259
#define TIM1_CCMR3 *(unsigned char*)0x525A
#define TIM1_CCMR4 *(unsigned char*)0x525B
#define TIM1_CCER1 *(unsigned char*)0x525C
#define TIM1_CCER2 *(unsigned char*)0x525D
#define TIM1_CNTRH *(unsigned char*)0x525E
#define TIM1_CNTRL *(unsigned char*)0x525F
#define TIM1_PSCRH *(unsigned char*)0x5260
#define TIM1_PSCRL *(unsigned char*)0x5261
#define TIM1_ARRH *(unsigned char*)0x5262
#define TIM1_ARRL *(unsigned char*)0x5263
#define TIM1_RCR *(unsigned char*)0x5264
#define TIM1_CCR1H *(unsigned char*)0x5265
#define TIM1_CCR1L *(unsigned char*)0x5266
#define TIM1_CCR2H *(unsigned char*)0x5267
#define TIM1_CCR2L *(unsigned char*)0x5268
#define TIM1_CCR3H *(unsigned char*)0x5269
#define TIM1_CCR3L *(unsigned char*)0x526A
#define TIM1_CCR4H *(unsigned char*)0x526B
#define TIM1_CCR4L *(unsigned char*)0x526C
#define TIM1_BKR *(unsigned char*)0x526D
#define TIM1_DTR *(unsigned char*)0x526E
#define TIM1_OISR *(unsigned char*)0x526F
/* TIM_IER bits */
#define TIM_IER_BIE (1 << 7)
#define TIM_IER_TIE (1 << 6)
#define TIM_IER_COMIE (1 << 5)
#define TIM_IER_CC4IE (1 << 4)
#define TIM_IER_CC3IE (1 << 3)
#define TIM_IER_CC2IE (1 << 2)
#define TIM_IER_CC1IE (1 << 1)
#define TIM_IER_UIE (1 << 0)
/* TIM_CR1 bits */
#define TIM_CR1_APRE (1 << 7)
#define TIM_CR1_CMSH (1 << 6)
#define TIM_CR1_CMSL (1 << 5)
#define TIM_CR1_DIR (1 << 4)
#define TIM_CR1_OPM (1 << 3)
#define TIM_CR1_URS (1 << 2)
#define TIM_CR1_UDIS (1 << 1)
#define TIM_CR1_CEN (1 << 0)
/* TIM_SR1 bits */
#define TIM_SR1_BIF (1 << 7)
#define TIM_SR1_TIF (1 << 6)
#define TIM_SR1_COMIF (1 << 5)
#define TIM_SR1_CC4IF (1 << 4)
#define TIM_SR1_CC3IF (1 << 3)
#define TIM_SR1_CC2IF (1 << 2)
#define TIM_SR1_CC1IF (1 << 1)
#define TIM_SR1_UIF (1 << 0)
/* TIM_EGR bits */
#define TIM_EGR_BG (1 << 7)
#define TIM_EGR_TG (1 << 6)
#define TIM_EGR_COMG (1 << 5)
#define TIM_EGR_CC4G (1 << 4)
#define TIM_EGR_CC3G (1 << 3)
#define TIM_EGR_CC2G (1 << 2)
#define TIM_EGR_CC1G (1 << 1)
#define TIM_EGR_UG (1 << 0)
/* TIM2 */
#define TIM2_CR1 *(unsigned char*)0x5300
#if defined STM8S105 || defined STM8S103
#define TIM2_IER *(unsigned char*)0x5301
#define TIM2_SR1 *(unsigned char*)0x5302
#define TIM2_SR2 *(unsigned char*)0x5303
#define TIM2_EGR *(unsigned char*)0x5304
#define TIM2_CCMR1 *(unsigned char*)0x5305
#define TIM2_CCMR2 *(unsigned char*)0x5306
#define TIM2_CCMR3 *(unsigned char*)0x5307
#define TIM2_CCER1 *(unsigned char*)0x5308
#define TIM2_CCER2 *(unsigned char*)0x5309
#define TIM2_CNTRH *(unsigned char*)0x530A
#define TIM2_CNTRL *(unsigned char*)0x530B
#define TIM2_PSCR *(unsigned char*)0x530C
#define TIM2_ARRH *(unsigned char*)0x530D
#define TIM2_ARRL *(unsigned char*)0x530E
#define TIM2_CCR1H *(unsigned char*)0x530F
#define TIM2_CCR1L *(unsigned char*)0x5310
#define TIM2_CCR2H *(unsigned char*)0x5311
#define TIM2_CCR2L *(unsigned char*)0x5312
#define TIM2_CCR3H *(unsigned char*)0x5313
#define TIM2_CCR3L *(unsigned char*)0x5314
#elif defined STM8S003
#define TIM2_IER *(unsigned char*)0x5303
#define TIM2_SR1 *(unsigned char*)0x5304
#define TIM2_SR2 *(unsigned char*)0x5305
#define TIM2_EGR *(unsigned char*)0x5306
#define TIM2_CCMR1 *(unsigned char*)0x5307
#define TIM2_CCMR2 *(unsigned char*)0x5308
#define TIM2_CCMR3 *(unsigned char*)0x5309
#define TIM2_CCER1 *(unsigned char*)0x530A
#define TIM2_CCER2 *(unsigned char*)0x530B
#define TIM2_CNTRH *(unsigned char*)0x530C
#define TIM2_CNTRL *(unsigned char*)0x530D
#define TIM2_PSCR *(unsigned char*)0x530E
#define TIM2_ARRH *(unsigned char*)0x530F
#define TIM2_ARRL *(unsigned char*)0x5310
#define TIM2_CCR1H *(unsigned char*)0x5311
#define TIM2_CCR1L *(unsigned char*)0x5312
#define TIM2_CCR2H *(unsigned char*)0x5313
#define TIM2_CCR2L *(unsigned char*)0x5314
#define TIM2_CCR3H *(unsigned char*)0x5315
#define TIM2_CCR3L *(unsigned char*)0x5316
#endif
/* TIM3 */
#if defined STM8S105 || defined STM8S103
#define TIM3_CR1 *(unsigned char*)0x5320
#define TIM3_IER *(unsigned char*)0x5321
#define TIM3_SR1 *(unsigned char*)0x5322
#define TIM3_SR2 *(unsigned char*)0x5323
#define TIM3_EGR *(unsigned char*)0x5324
#define TIM3_CCMR1 *(unsigned char*)0x5325
#define TIM3_CCMR2 *(unsigned char*)0x5326
#define TIM3_CCER1 *(unsigned char*)0x5327
#define TIM3_CNTRH *(unsigned char*)0x5328
#define TIM3_CNTRL *(unsigned char*)0x5329
#define TIM3_PSCR *(unsigned char*)0x532A
#define TIM3_ARRH *(unsigned char*)0x532B
#define TIM3_ARRL *(unsigned char*)0x532C
#define TIM3_CCR1H *(unsigned char*)0x532D
#define TIM3_CCR1L *(unsigned char*)0x532E
#define TIM3_CCR2H *(unsigned char*)0x532F
#define TIM3_CCR2L *(unsigned char*)0x5330
#endif
/* TIM4 */
#define TIM4_CR1 *(unsigned char*)0x5340
#if defined STM8S105 || defined STM8S103
#define TIM4_IER *(unsigned char*)0x5341
#define TIM4_SR *(unsigned char*)0x5342
#define TIM4_EGR *(unsigned char*)0x5343
#define TIM4_CNTR *(unsigned char*)0x5344
#define TIM4_PSCR *(unsigned char*)0x5345
#define TIM4_ARR *(unsigned char*)0x5346
#elif defined STM8S003
#define TIM4_IER *(unsigned char*)0x5343
#define TIM4_SR *(unsigned char*)0x5344
#define TIM4_EGR *(unsigned char*)0x5345
#define TIM4_CNTR *(unsigned char*)0x5346
#define TIM4_PSCR *(unsigned char*)0x5347
#define TIM4_ARR *(unsigned char*)0x5348
#endif
/* ------------------- ADC ------------------- */
#define ADC_DB0RH *(unsigned char*)0x53E0
#define ADC_DB0RL *(unsigned char*)0x53E1
#define ADC_DB1RH *(unsigned char*)0x53E2
#define ADC_DB1RL *(unsigned char*)0x53E3
#define ADC_DB2RH *(unsigned char*)0x53E4
#define ADC_DB2RL *(unsigned char*)0x53E5
#define ADC_DB3RH *(unsigned char*)0x53E6
#define ADC_DB3RL *(unsigned char*)0x53E7
#define ADC_DB4RH *(unsigned char*)0x53E8
#define ADC_DB4RL *(unsigned char*)0x53E9
#define ADC_DB5RH *(unsigned char*)0x53EA
#define ADC_DB5RL *(unsigned char*)0x53EB
#define ADC_DB6RH *(unsigned char*)0x53EC
#define ADC_DB6RL *(unsigned char*)0x53ED
#define ADC_DB7RH *(unsigned char*)0x53EE
#define ADC_DB7RL *(unsigned char*)0x53EF
#define ADC_DB8RH *(unsigned char*)0x53F0
#define ADC_DB8RL *(unsigned char*)0x53F1
#define ADC_DB9RH *(unsigned char*)0x53F2
#define ADC_DB9RL *(unsigned char*)0x53F3
#define ADC_CSR *(unsigned char*)0x5400
#define ADC_CR1 *(unsigned char*)0x5401
#define ADC_CR2 *(unsigned char*)0x5402
#define ADC_CR3 *(unsigned char*)0x5403
#define ADC_DRH *(unsigned char*)0x5404
#define ADC_DRL *(unsigned char*)0x5405
#define ADC_TDRH *(unsigned char*)0x5406
#define ADC_TDRL *(unsigned char*)0x5407
#define ADC_HTRH *(unsigned char*)0x5408
#define ADC_HTRL *(unsigned char*)0x5409
#define ADC_LTRH *(unsigned char*)0x540A
#define ADC_LTRL *(unsigned char*)0x540B
#define ADC_AWSRH *(unsigned char*)0x540C
#define ADC_AWSRL *(unsigned char*)0x540D
#define ADC_AWCRH *(unsigned char*)0x540E
#define ADC_AWCRL *(unsigned char*)0x540F
/* ------------------- swim control ------------------- */
#define CFG_GCR *(unsigned char*)0x7F60
#define SWIM_CSR *(unsigned char*)0x7F80
/* ------------------- ITC ------------------- */
#define ITC_SPR1 *(unsigned char*)0x7F70
#define ITC_SPR2 *(unsigned char*)0x7F71
#define ITC_SPR3 *(unsigned char*)0x7F72
#define ITC_SPR4 *(unsigned char*)0x7F73
#define ITC_SPR5 *(unsigned char*)0x7F74
#define ITC_SPR6 *(unsigned char*)0x7F75
#define ITC_SPR7 *(unsigned char*)0x7F76
#define ITC_SPR8 *(unsigned char*)0x7F77
/* -------------------- UNIQUE ID -------------------- */
#if defined STM8S105 || defined STM8S103 // maybe some other MCU have this too???
#define U_ID00 (unsigned char*)0x48CD
#define U_ID01 (unsigned char*)0x48CE
#define U_ID02 (unsigned char*)0x48CF
#define U_ID03 (unsigned char*)0x48D0
#define U_ID04 (unsigned char*)0x48D1
#define U_ID05 (unsigned char*)0x48D2
#define U_ID06 (unsigned char*)0x48D3
#define U_ID07 (unsigned char*)0x48D4
#define U_ID08 (unsigned char*)0x48D5
#define U_ID09 (unsigned char*)0x48D6
#define U_ID10 (unsigned char*)0x48D7
#define U_ID11 (unsigned char*)0x48D8
#endif // defined STM8S105 || defined STM8S103
// CCR REGISTER: bits 3&5 should be 1 if you wanna change EXTI_CRx
#define CCR *(unsigned char*)0x7F0A
/* -------------------- OPTION BYTES -------------------- */
#if defined STM8S105
// readout protection
#define OPT0 *(unsigned char*)0x4800
// user boot code
#define OPT1 *(unsigned char*)0x4801
#define NOPT1 *(unsigned char*)0x4802
// alternate functions remapping
// | AFR7 | ... | AFR0 |
// AFR7 - PD4 = BEEP; AFR6 - PB4/PB5 = I2C; AFR5 - PB0..3 - TIM1
// AFR4 - PD7 = TIM1_CH4; AFR3 - PD0 = TIM1_BKIN
// AFR2 - PD0 = CLK_CCO; AFR1 - PA3 = TIM3_CH1, PD2 = TIM2_CH3
// AFR0 - PD3 = ADC_ETR
#define OPT2 *(unsigned char*)0x4803
#define NOPT2 *(unsigned char*)0x4804
// trim, watchdog
#define OPT3 *(unsigned char*)0x4805
#define NOPT3 *(unsigned char*)0x4806
// extclc, awu
#define OPT4 *(unsigned char*)0x4807
#define NOPT4 *(unsigned char*)0x4808
// HSE stab time
#define OPT5 *(unsigned char*)0x4809
#define NOPT5 *(unsigned char*)0x480a
// none
#define OPT6 *(unsigned char*)0x480b
#define NOPT6 *(unsigned char*)0x480c
// none
#define OPT7 *(unsigned char*)0x480d
#define NOPT7 *(unsigned char*)0x480e
// bootloader opt byte
#define OPTBL *(unsigned char*)0x487e
#define NOPTBL *(unsigned char*)0x487f
#endif
#endif // __STM8L_H__
// #define *(unsigned char*)0x

Binary file not shown.

View File

@ -0,0 +1,629 @@
# format=tagmanager
ADC_AWCRHÌ65536Ö0
ADC_AWCRLÌ65536Ö0
ADC_AWSRHÌ65536Ö0
ADC_AWSRLÌ65536Ö0
ADC_CR1Ì65536Ö0
ADC_CR2Ì65536Ö0
ADC_CR3Ì65536Ö0
ADC_CSRÌ65536Ö0
ADC_DB0RHÌ65536Ö0
ADC_DB0RLÌ65536Ö0
ADC_DB1RHÌ65536Ö0
ADC_DB1RLÌ65536Ö0
ADC_DB2RHÌ65536Ö0
ADC_DB2RLÌ65536Ö0
ADC_DB3RHÌ65536Ö0
ADC_DB3RLÌ65536Ö0
ADC_DB4RHÌ65536Ö0
ADC_DB4RLÌ65536Ö0
ADC_DB5RHÌ65536Ö0
ADC_DB5RLÌ65536Ö0
ADC_DB6RHÌ65536Ö0
ADC_DB6RLÌ65536Ö0
ADC_DB7RHÌ65536Ö0
ADC_DB7RLÌ65536Ö0
ADC_DB8RHÌ65536Ö0
ADC_DB8RLÌ65536Ö0
ADC_DB9RHÌ65536Ö0
ADC_DB9RLÌ65536Ö0
ADC_DRHÌ65536Ö0
ADC_DRLÌ65536Ö0
ADC_HTRHÌ65536Ö0
ADC_HTRLÌ65536Ö0
ADC_LTRHÌ65536Ö0
ADC_LTRLÌ65536Ö0
ADC_TDRHÌ65536Ö0
ADC_TDRLÌ65536Ö0
ADDR_MASKÌ65536Ö0
AWU_APRÌ65536Ö0
AWU_CSR1Ì65536Ö0
AWU_TBRÌ65536Ö0
BEEP_CSRÌ65536Ö0
CCRÌ65536Ö0
CFG_GCRÌ65536Ö0
CHK_M0E1Ì131072Í()Ö0
CHK_M0E2Ì131072Í()Ö0
CHK_M1E1Ì131072Í()Ö0
CHK_M1E2Ì131072Í()Ö0
CLK_CCORÌ65536Ö0
CLK_CKDIVRÌ65536Ö0
CLK_CMSRÌ65536Ö0
CLK_CSSRÌ65536Ö0
CLK_ECKRÌ65536Ö0
CLK_HSITRIMRÌ65536Ö0
CLK_ICKRÌ65536Ö0
CLK_PCKENR2Ì65536Ö0
CLK_SPCKENR1Ì65536Ö0
CLK_SWCRÌ65536Ö0
CLK_SWIMCCRÌ65536Ö0
CLK_SWRÌ65536Ö0
CONCATÌ131072Í(a,b)Ö0
EEPROM_KEY1Ì65536Ö0
EEPROM_KEY2Ì65536Ö0
EEPROM_START_ADDRÌ65536Ö0
EXTI_CR1Ì65536Ö0
EXTI_CR2Ì65536Ö0
FLASH_CR1Ì65536Ö0
FLASH_CR2Ì65536Ö0
FLASH_DUKRÌ65536Ö0
FLASH_FPRÌ65536Ö0
FLASH_IAPSRÌ65536Ö0
FLASH_NCR2Ì65536Ö0
FLASH_NFPRÌ65536Ö0
FLASH_PUKRÌ65536Ö0
FORMPORTÌ131072Í(a,b)Ö0
GET_ADDRÌ131072Í()Ö0
GPIO_PIN0Ì65536Ö0
GPIO_PIN1Ì65536Ö0
GPIO_PIN2Ì65536Ö0
GPIO_PIN3Ì65536Ö0
GPIO_PIN4Ì65536Ö0
GPIO_PIN5Ì65536Ö0
GPIO_PIN6Ì65536Ö0
GPIO_PIN7Ì65536Ö0
Global_timeÌ32768Ö0Ïvolatile unsigned long
I2C_CCRHÌ65536Ö0
I2C_CCRLÌ65536Ö0
I2C_CR1Ì65536Ö0
I2C_CR2Ì65536Ö0
I2C_DRÌ65536Ö0
I2C_FREQRÌ65536Ö0
I2C_ITRÌ65536Ö0
I2C_OARHÌ65536Ö0
I2C_OARLÌ65536Ö0
I2C_PECRÌ65536Ö0
I2C_SR1Ì65536Ö0
I2C_SR2Ì65536Ö0
I2C_SR3Ì65536Ö0
I2C_TRISERÌ65536Ö0
INTERRUPT_DEFINITIONÌ131072Í(fn,num)Ö0
INTERRUPT_HANDLERÌ131072Í(fn,num)Ö0
ITC_SPR1Ì65536Ö0
ITC_SPR2Ì65536Ö0
ITC_SPR3Ì65536Ö0
ITC_SPR4Ì65536Ö0
ITC_SPR5Ì65536Ö0
ITC_SPR6Ì65536Ö0
ITC_SPR7Ì65536Ö0
ITC_SPR8Ì65536Ö0
IWDG_KRÌ65536Ö0
IWDG_PRÌ65536Ö0
IWDG_RLRÌ65536Ö0
KEY_ACCESSÌ65536Ö0
KEY_ENABLEÌ65536Ö0
KEY_REFRESHÌ65536Ö0
LED_NSTATEÌ131072Í()Ö0
LED_OFFÌ131072Í()Ö0
LED_ONÌ131072Í()Ö0
LED_PINÌ65536Ö0
LED_PORTÌ65536Ö0
M0E1_PINÌ65536Ö0
M0E1_PORTÌ65536Ö0
M0E2_PINÌ65536Ö0
M0E2_PORTÌ65536Ö0
M1E1_PINÌ65536Ö0
M1E1_PORTÌ65536Ö0
M1E2_PINÌ65536Ö0
M1E2_PORTÌ65536Ö0
MCU_noÌ32768Ö0ÏU8
NULLÌ65536Ö0
PA_CR1Ì65536Ö0
PA_CR2Ì65536Ö0
PA_DDRÌ65536Ö0
PA_IDRÌ65536Ö0
PA_ODRÌ65536Ö0
PB_CR1Ì65536Ö0
PB_CR2Ì65536Ö0
PB_DDRÌ65536Ö0
PB_IDRÌ65536Ö0
PB_ODRÌ65536Ö0
PC_CR1Ì65536Ö0
PC_CR2Ì65536Ö0
PC_DDRÌ65536Ö0
PC_IDRÌ65536Ö0
PC_ODRÌ65536Ö0
PD_CR1Ì65536Ö0
PD_CR2Ì65536Ö0
PD_DDRÌ65536Ö0
PD_IDRÌ65536Ö0
PD_ODRÌ65536Ö0
PE_CR1Ì65536Ö0
PE_CR2Ì65536Ö0
PE_DDRÌ65536Ö0
PE_IDRÌ65536Ö0
PE_ODRÌ65536Ö0
PF_CR1Ì65536Ö0
PF_CR2Ì65536Ö0
PF_DDRÌ65536Ö0
PF_IDRÌ65536Ö0
PF_ODRÌ65536Ö0
PORTÌ131072Í(a,b)Ö0
PWM_PINSÌ65536Ö0
RST_SRÌ65536Ö0
SPI_CR1Ì65536Ö0
SPI_CR1_BRMASKÌ65536Ö0
SPI_CR1_CPHAÌ65536Ö0
SPI_CR1_CPOLÌ65536Ö0
SPI_CR1_LSBFIRSTÌ65536Ö0
SPI_CR1_MSTRÌ65536Ö0
SPI_CR1_SPEÌ65536Ö0
SPI_CR2Ì65536Ö0
SPI_CR2_BDMÌ65536Ö0
SPI_CR2_BDOEÌ65536Ö0
SPI_CR2_CRCENÌ65536Ö0
SPI_CR2_CRCNEXTÌ65536Ö0
SPI_CR2_RXONLYÌ65536Ö0
SPI_CR2_SSIÌ65536Ö0
SPI_CR2_SSMÌ65536Ö0
SPI_CRCPRÌ65536Ö0
SPI_DRÌ65536Ö0
SPI_ICRÌ65536Ö0
SPI_ICR_ERRIEÌ65536Ö0
SPI_ICR_RXIEÌ65536Ö0
SPI_ICR_TXIEÌ65536Ö0
SPI_ICR_WKIEÌ65536Ö0
SPI_RXCRCRÌ65536Ö0
SPI_SRÌ65536Ö0
SPI_SR_BSYÌ65536Ö0
SPI_SR_CRCERRÌ65536Ö0
SPI_SR_MODFÌ65536Ö0
SPI_SR_OVRÌ65536Ö0
SPI_SR_RXNEÌ65536Ö0
SPI_SR_TXEÌ65536Ö0
SPI_SR_WKUPÌ65536Ö0
SPI_TXCRCRÌ65536Ö0
STP0_PORTÌ65536Ö0
STP1_PORTÌ65536Ö0
STP_PINSÌ65536Ö0
SWIM_CSRÌ65536Ö0
TIM1_ARRHÌ65536Ö0
TIM1_ARRLÌ65536Ö0
TIM1_BKRÌ65536Ö0
TIM1_CCER1Ì65536Ö0
TIM1_CCER2Ì65536Ö0
TIM1_CCMR1Ì65536Ö0
TIM1_CCMR2Ì65536Ö0
TIM1_CCMR3Ì65536Ö0
TIM1_CCMR4Ì65536Ö0
TIM1_CCR1HÌ65536Ö0
TIM1_CCR1LÌ65536Ö0
TIM1_CCR2HÌ65536Ö0
TIM1_CCR2LÌ65536Ö0
TIM1_CCR3HÌ65536Ö0
TIM1_CCR3LÌ65536Ö0
TIM1_CCR4HÌ65536Ö0
TIM1_CCR4LÌ65536Ö0
TIM1_CNTRHÌ65536Ö0
TIM1_CNTRLÌ65536Ö0
TIM1_CR1Ì65536Ö0
TIM1_CR2Ì65536Ö0
TIM1_DTRÌ65536Ö0
TIM1_EGRÌ65536Ö0
TIM1_ETRÌ65536Ö0
TIM1_IERÌ65536Ö0
TIM1_OISRÌ65536Ö0
TIM1_PSCRHÌ65536Ö0
TIM1_PSCRLÌ65536Ö0
TIM1_RCRÌ65536Ö0
TIM1_SMCRÌ65536Ö0
TIM1_SR1Ì65536Ö0
TIM1_SR2Ì65536Ö0
TIM2_CR1Ì65536Ö0
TIM4_CR1Ì65536Ö0
TIM_CR1_APREÌ65536Ö0
TIM_CR1_CENÌ65536Ö0
TIM_CR1_CMSHÌ65536Ö0
TIM_CR1_CMSLÌ65536Ö0
TIM_CR1_DIRÌ65536Ö0
TIM_CR1_OPMÌ65536Ö0
TIM_CR1_UDISÌ65536Ö0
TIM_CR1_URSÌ65536Ö0
TIM_EGR_BGÌ65536Ö0
TIM_EGR_CC1GÌ65536Ö0
TIM_EGR_CC2GÌ65536Ö0
TIM_EGR_CC3GÌ65536Ö0
TIM_EGR_CC4GÌ65536Ö0
TIM_EGR_COMGÌ65536Ö0
TIM_EGR_TGÌ65536Ö0
TIM_EGR_UGÌ65536Ö0
TIM_IER_BIEÌ65536Ö0
TIM_IER_CC1IEÌ65536Ö0
TIM_IER_CC2IEÌ65536Ö0
TIM_IER_CC3IEÌ65536Ö0
TIM_IER_CC4IEÌ65536Ö0
TIM_IER_COMIEÌ65536Ö0
TIM_IER_TIEÌ65536Ö0
TIM_IER_UIEÌ65536Ö0
TIM_SR1_BIFÌ65536Ö0
TIM_SR1_CC1IFÌ65536Ö0
TIM_SR1_CC2IFÌ65536Ö0
TIM_SR1_CC3IFÌ65536Ö0
TIM_SR1_CC4IFÌ65536Ö0
TIM_SR1_COMIFÌ65536Ö0
TIM_SR1_TIFÌ65536Ö0
TIM_SR1_UIFÌ65536Ö0
U16Ì4096Ö0Ïunsigned int
U32Ì4096Ö0Ïunsigned long
U8Ì4096Ö0Ïunsigned char
UART_BUF_LENÌ65536Ö0
UART_CR1_MÌ65536Ö0
UART_CR1_PCENÌ65536Ö0
UART_CR1_PIENÌ65536Ö0
UART_CR1_PSÌ65536Ö0
UART_CR1_R8Ì65536Ö0
UART_CR1_T8Ì65536Ö0
UART_CR1_UARTDÌ65536Ö0
UART_CR1_WAKEÌ65536Ö0
UART_CR2_ILIENÌ65536Ö0
UART_CR2_RENÌ65536Ö0
UART_CR2_RIENÌ65536Ö0
UART_CR2_RWUÌ65536Ö0
UART_CR2_SBKÌ65536Ö0
UART_CR2_TCIENÌ65536Ö0
UART_CR2_TENÌ65536Ö0
UART_CR2_TIENÌ65536Ö0
UART_CR3_CLKENÌ65536Ö0
UART_CR3_CPHAÌ65536Ö0
UART_CR3_CPOLÌ65536Ö0
UART_CR3_LBCLÌ65536Ö0
UART_CR3_LINENÌ65536Ö0
UART_CR3_STOP1Ì65536Ö0
UART_CR3_STOP2Ì65536Ö0
UART_PORTÌ65536Ö0
UART_SR_FEÌ65536Ö0
UART_SR_IDLEÌ65536Ö0
UART_SR_NFÌ65536Ö0
UART_SR_ORÌ65536Ö0
UART_SR_PEÌ65536Ö0
UART_SR_RXNEÌ65536Ö0
UART_SR_TCÌ65536Ö0
UART_SR_TXEÌ65536Ö0
UART_TX_PINÌ65536Ö0
UART_rxÌ32768Ö0ÏU8
UART_txÌ32768Ö0ÏU8
WWDG_CRÌ65536Ö0
WWDG_WRÌ65536Ö0
_FORTIFY_SOURCEÌ65536Ö0
_GNU_SOURCEÌ65536Ö0
_LP64Ì65536Ö0
_STDC_PREDEF_HÌ65536Ö0
__ATOMIC_ACQUIREÌ65536Ö0
__ATOMIC_ACQ_RELÌ65536Ö0
__ATOMIC_CONSUMEÌ65536Ö0
__ATOMIC_HLE_ACQUIREÌ65536Ö0
__ATOMIC_HLE_RELEASEÌ65536Ö0
__ATOMIC_RELAXEDÌ65536Ö0
__ATOMIC_RELEASEÌ65536Ö0
__ATOMIC_SEQ_CSTÌ65536Ö0
__BIGGEST_ALIGNMENT__Ì65536Ö0
__BYTE_ORDER__Ì65536Ö0
__CHAR16_TYPE__Ì65536Ö0
__CHAR32_TYPE__Ì65536Ö0
__CHAR_BIT__Ì65536Ö0
__DBL_DECIMAL_DIG__Ì65536Ö0
__DBL_DENORM_MIN__Ì65536Ö0
__DBL_DIG__Ì65536Ö0
__DBL_EPSILON__Ì65536Ö0
__DBL_HAS_DENORM__Ì65536Ö0
__DBL_HAS_INFINITY__Ì65536Ö0
__DBL_HAS_QUIET_NAN__Ì65536Ö0
__DBL_MANT_DIG__Ì65536Ö0
__DBL_MAX_10_EXP__Ì65536Ö0
__DBL_MAX_EXP__Ì65536Ö0
__DBL_MAX__Ì65536Ö0
__DBL_MIN_10_EXP__Ì65536Ö0
__DBL_MIN_EXP__Ì65536Ö0
__DBL_MIN__Ì65536Ö0
__DEC128_EPSILON__Ì65536Ö0
__DEC128_MANT_DIG__Ì65536Ö0
__DEC128_MAX_EXP__Ì65536Ö0
__DEC128_MAX__Ì65536Ö0
__DEC128_MIN_EXP__Ì65536Ö0
__DEC128_MIN__Ì65536Ö0
__DEC128_SUBNORMAL_MIN__Ì65536Ö0
__DEC32_EPSILON__Ì65536Ö0
__DEC32_MANT_DIG__Ì65536Ö0
__DEC32_MAX_EXP__Ì65536Ö0
__DEC32_MAX__Ì65536Ö0
__DEC32_MIN_EXP__Ì65536Ö0
__DEC32_MIN__Ì65536Ö0
__DEC32_SUBNORMAL_MIN__Ì65536Ö0
__DEC64_EPSILON__Ì65536Ö0
__DEC64_MANT_DIG__Ì65536Ö0
__DEC64_MAX_EXP__Ì65536Ö0
__DEC64_MAX__Ì65536Ö0
__DEC64_MIN_EXP__Ì65536Ö0
__DEC64_MIN__Ì65536Ö0
__DEC64_SUBNORMAL_MIN__Ì65536Ö0
__DECIMAL_BID_FORMAT__Ì65536Ö0
__DECIMAL_DIG__Ì65536Ö0
__DEC_EVAL_METHOD__Ì65536Ö0
__DEPRECATEDÌ65536Ö0
__ELF__Ì65536Ö0
__EXCEPTIONSÌ65536Ö0
__FINITE_MATH_ONLY__Ì65536Ö0
__FLOAT_WORD_ORDER__Ì65536Ö0
__FLT_DECIMAL_DIG__Ì65536Ö0
__FLT_DENORM_MIN__Ì65536Ö0
__FLT_DIG__Ì65536Ö0
__FLT_EPSILON__Ì65536Ö0
__FLT_EVAL_METHOD__Ì65536Ö0
__FLT_HAS_DENORM__Ì65536Ö0
__FLT_HAS_INFINITY__Ì65536Ö0
__FLT_HAS_QUIET_NAN__Ì65536Ö0
__FLT_MANT_DIG__Ì65536Ö0
__FLT_MAX_10_EXP__Ì65536Ö0
__FLT_MAX_EXP__Ì65536Ö0
__FLT_MAX__Ì65536Ö0
__FLT_MIN_10_EXP__Ì65536Ö0
__FLT_MIN_EXP__Ì65536Ö0
__FLT_MIN__Ì65536Ö0
__FLT_RADIX__Ì65536Ö0
__FXSR__Ì65536Ö0
__GCC_ASM_FLAG_OUTPUTS__Ì65536Ö0
__GCC_ATOMIC_BOOL_LOCK_FREEÌ65536Ö0
__GCC_ATOMIC_CHAR16_T_LOCK_FREEÌ65536Ö0
__GCC_ATOMIC_CHAR32_T_LOCK_FREEÌ65536Ö0
__GCC_ATOMIC_CHAR_LOCK_FREEÌ65536Ö0
__GCC_ATOMIC_INT_LOCK_FREEÌ65536Ö0
__GCC_ATOMIC_LLONG_LOCK_FREEÌ65536Ö0
__GCC_ATOMIC_LONG_LOCK_FREEÌ65536Ö0
__GCC_ATOMIC_POINTER_LOCK_FREEÌ65536Ö0
__GCC_ATOMIC_SHORT_LOCK_FREEÌ65536Ö0
__GCC_ATOMIC_TEST_AND_SET_TRUEVALÌ65536Ö0
__GCC_ATOMIC_WCHAR_T_LOCK_FREEÌ65536Ö0
__GCC_HAVE_DWARF2_CFI_ASMÌ65536Ö0
__GCC_HAVE_SYNC_COMPARE_AND_SWAP_1Ì65536Ö0
__GCC_HAVE_SYNC_COMPARE_AND_SWAP_2Ì65536Ö0
__GCC_HAVE_SYNC_COMPARE_AND_SWAP_4Ì65536Ö0
__GCC_HAVE_SYNC_COMPARE_AND_SWAP_8Ì65536Ö0
__GCC_IEC_559Ì65536Ö0
__GCC_IEC_559_COMPLEXÌ65536Ö0
__GLIBCXX_BITSIZE_INT_N_0Ì65536Ö0
__GLIBCXX_TYPE_INT_N_0Ì65536Ö0
__GNUC_MINOR__Ì65536Ö0
__GNUC_PATCHLEVEL__Ì65536Ö0
__GNUC_STDC_INLINE__Ì65536Ö0
__GNUC__Ì65536Ö0
__GNUG__Ì65536Ö0
__GXX_ABI_VERSIONÌ65536Ö0
__GXX_EXPERIMENTAL_CXX0X__Ì65536Ö0
__GXX_RTTIÌ65536Ö0
__GXX_WEAK__Ì65536Ö0
__HARDWARE_H__Ì65536Ö0
__INT16_CÌ131072Í(c)Ö0
__INT16_MAX__Ì65536Ö0
__INT16_TYPE__Ì65536Ö0
__INT32_CÌ131072Í(c)Ö0
__INT32_MAX__Ì65536Ö0
__INT32_TYPE__Ì65536Ö0
__INT64_CÌ131072Í(c)Ö0
__INT64_MAX__Ì65536Ö0
__INT64_TYPE__Ì65536Ö0
__INT8_CÌ131072Í(c)Ö0
__INT8_MAX__Ì65536Ö0
__INT8_TYPE__Ì65536Ö0
__INTERRUPTS_H__Ì65536Ö0
__INTMAX_CÌ131072Í(c)Ö0
__INTMAX_MAX__Ì65536Ö0
__INTMAX_TYPE__Ì65536Ö0
__INTPTR_MAX__Ì65536Ö0
__INTPTR_TYPE__Ì65536Ö0
__INT_FAST16_MAX__Ì65536Ö0
__INT_FAST16_TYPE__Ì65536Ö0
__INT_FAST32_MAX__Ì65536Ö0
__INT_FAST32_TYPE__Ì65536Ö0
__INT_FAST64_MAX__Ì65536Ö0
__INT_FAST64_TYPE__Ì65536Ö0
__INT_FAST8_MAX__Ì65536Ö0
__INT_FAST8_TYPE__Ì65536Ö0
__INT_LEAST16_MAX__Ì65536Ö0
__INT_LEAST16_TYPE__Ì65536Ö0
__INT_LEAST32_MAX__Ì65536Ö0
__INT_LEAST32_TYPE__Ì65536Ö0
__INT_LEAST64_MAX__Ì65536Ö0
__INT_LEAST64_TYPE__Ì65536Ö0
__INT_LEAST8_MAX__Ì65536Ö0
__INT_LEAST8_TYPE__Ì65536Ö0
__INT_MAX__Ì65536Ö0
__LDBL_DENORM_MIN__Ì65536Ö0
__LDBL_DIG__Ì65536Ö0
__LDBL_EPSILON__Ì65536Ö0
__LDBL_HAS_DENORM__Ì65536Ö0
__LDBL_HAS_INFINITY__Ì65536Ö0
__LDBL_HAS_QUIET_NAN__Ì65536Ö0
__LDBL_MANT_DIG__Ì65536Ö0
__LDBL_MAX_10_EXP__Ì65536Ö0
__LDBL_MAX_EXP__Ì65536Ö0
__LDBL_MAX__Ì65536Ö0
__LDBL_MIN_10_EXP__Ì65536Ö0
__LDBL_MIN_EXP__Ì65536Ö0
__LDBL_MIN__Ì65536Ö0
__LONG_LONG_MAX__Ì65536Ö0
__LONG_MAX__Ì65536Ö0
__LP64__Ì65536Ö0
__MMX__Ì65536Ö0
__NO_INLINE__Ì65536Ö0
__ORDER_BIG_ENDIAN__Ì65536Ö0
__ORDER_LITTLE_ENDIAN__Ì65536Ö0
__ORDER_PDP_ENDIAN__Ì65536Ö0
__PIC__Ì65536Ö0
__PIE__Ì65536Ö0
__PRAGMA_REDEFINE_EXTNAMEÌ65536Ö0
__PTRDIFF_MAX__Ì65536Ö0
__PTRDIFF_TYPE__Ì65536Ö0
__REGISTER_PREFIX__Ì65536Ö0
__SCHAR_MAX__Ì65536Ö0
__SEG_FSÌ65536Ö0
__SEG_GSÌ65536Ö0
__SHRT_MAX__Ì65536Ö0
__SIG_ATOMIC_MAX__Ì65536Ö0
__SIG_ATOMIC_MIN__Ì65536Ö0
__SIG_ATOMIC_TYPE__Ì65536Ö0
__SIZEOF_DOUBLE__Ì65536Ö0
__SIZEOF_FLOAT128__Ì65536Ö0
__SIZEOF_FLOAT80__Ì65536Ö0
__SIZEOF_FLOAT__Ì65536Ö0
__SIZEOF_INT128__Ì65536Ö0
__SIZEOF_INT__Ì65536Ö0
__SIZEOF_LONG_DOUBLE__Ì65536Ö0
__SIZEOF_LONG_LONG__Ì65536Ö0
__SIZEOF_LONG__Ì65536Ö0
__SIZEOF_POINTER__Ì65536Ö0
__SIZEOF_PTRDIFF_T__Ì65536Ö0
__SIZEOF_SHORT__Ì65536Ö0
__SIZEOF_SIZE_T__Ì65536Ö0
__SIZEOF_WCHAR_T__Ì65536Ö0
__SIZEOF_WINT_T__Ì65536Ö0
__SIZE_MAX__Ì65536Ö0
__SIZE_TYPE__Ì65536Ö0
__SSE2_MATH__Ì65536Ö0
__SSE2__Ì65536Ö0
__SSE_MATH__Ì65536Ö0
__SSE__Ì65536Ö0
__SSP_STRONG__Ì65536Ö0
__STDC_HOSTED__Ì65536Ö0
__STDC_IEC_559_COMPLEX__Ì65536Ö0
__STDC_IEC_559__Ì65536Ö0
__STDC_ISO_10646__Ì65536Ö0
__STDC_NO_THREADS__Ì65536Ö0
__STDC_UTF_16__Ì65536Ö0
__STDC_UTF_32__Ì65536Ö0
__STDC__Ì65536Ö0
__STM8L_H__Ì65536Ö0
__UART_H__Ì65536Ö0
__UINT16_CÌ131072Í(c)Ö0
__UINT16_MAX__Ì65536Ö0
__UINT16_TYPE__Ì65536Ö0
__UINT32_CÌ131072Í(c)Ö0
__UINT32_MAX__Ì65536Ö0
__UINT32_TYPE__Ì65536Ö0
__UINT64_CÌ131072Í(c)Ö0
__UINT64_MAX__Ì65536Ö0
__UINT64_TYPE__Ì65536Ö0
__UINT8_CÌ131072Í(c)Ö0
__UINT8_MAX__Ì65536Ö0
__UINT8_TYPE__Ì65536Ö0
__UINTMAX_CÌ131072Í(c)Ö0
__UINTMAX_MAX__Ì65536Ö0
__UINTMAX_TYPE__Ì65536Ö0
__UINTPTR_MAX__Ì65536Ö0
__UINTPTR_TYPE__Ì65536Ö0
__UINT_FAST16_MAX__Ì65536Ö0
__UINT_FAST16_TYPE__Ì65536Ö0
__UINT_FAST32_MAX__Ì65536Ö0
__UINT_FAST32_TYPE__Ì65536Ö0
__UINT_FAST64_MAX__Ì65536Ö0
__UINT_FAST64_TYPE__Ì65536Ö0
__UINT_FAST8_MAX__Ì65536Ö0
__UINT_FAST8_TYPE__Ì65536Ö0
__UINT_LEAST16_MAX__Ì65536Ö0
__UINT_LEAST16_TYPE__Ì65536Ö0
__UINT_LEAST32_MAX__Ì65536Ö0
__UINT_LEAST32_TYPE__Ì65536Ö0
__UINT_LEAST64_MAX__Ì65536Ö0
__UINT_LEAST64_TYPE__Ì65536Ö0
__UINT_LEAST8_MAX__Ì65536Ö0
__UINT_LEAST8_TYPE__Ì65536Ö0
__USER_LABEL_PREFIX__Ì65536Ö0
__VERSION__Ì65536Ö0
__WCHAR_MAX__Ì65536Ö0
__WCHAR_MIN__Ì65536Ö0
__WCHAR_TYPE__Ì65536Ö0
__WINT_MAX__Ì65536Ö0
__WINT_MIN__Ì65536Ö0
__WINT_TYPE__Ì65536Ö0
__amd64Ì65536Ö0
__amd64__Ì65536Ö0
__code_model_small__Ì65536Ö0
__cplusplusÌ65536Ö0
__cpp_aggregate_nsdmiÌ65536Ö0
__cpp_alias_templatesÌ65536Ö0
__cpp_attributesÌ65536Ö0
__cpp_binary_literalsÌ65536Ö0
__cpp_constexprÌ65536Ö0
__cpp_decltypeÌ65536Ö0
__cpp_decltype_autoÌ65536Ö0
__cpp_delegating_constructorsÌ65536Ö0
__cpp_digit_separatorsÌ65536Ö0
__cpp_exceptionsÌ65536Ö0
__cpp_generic_lambdasÌ65536Ö0
__cpp_hex_floatÌ65536Ö0
__cpp_inheriting_constructorsÌ65536Ö0
__cpp_init_capturesÌ65536Ö0
__cpp_initializer_listsÌ65536Ö0
__cpp_lambdasÌ65536Ö0
__cpp_nsdmiÌ65536Ö0
__cpp_range_based_forÌ65536Ö0
__cpp_raw_stringsÌ65536Ö0
__cpp_ref_qualifiersÌ65536Ö0
__cpp_return_type_deductionÌ65536Ö0
__cpp_rttiÌ65536Ö0
__cpp_runtime_arraysÌ65536Ö0
__cpp_rvalue_referenceÌ65536Ö0
__cpp_rvalue_referencesÌ65536Ö0
__cpp_sized_deallocationÌ65536Ö0
__cpp_static_assertÌ65536Ö0
__cpp_unicode_charactersÌ65536Ö0
__cpp_unicode_literalsÌ65536Ö0
__cpp_user_defined_literalsÌ65536Ö0
__cpp_variable_templatesÌ65536Ö0
__cpp_variadic_templatesÌ65536Ö0
__gnu_linux__Ì65536Ö0
__has_includeÌ131072Í(STR)Ö0
__has_include_nextÌ131072Í(STR)Ö0
__k8Ì65536Ö0
__k8__Ì65536Ö0
__linuxÌ65536Ö0
__linux__Ì65536Ö0
__pic__Ì65536Ö0
__pie__Ì65536Ö0
__unixÌ65536Ö0
__unix__Ì65536Ö0
__x86_64Ì65536Ö0
__x86_64__Ì65536Ö0
disableInterruptsÌ131072Í()Ö0
enableInterruptsÌ131072Í()Ö0
haltÌ131072Í()Ö0
hw_initÌ1024Í()Ö0Ïvoid
iretÌ131072Í()Ö0
linuxÌ65536Ö0
long2bufÌ1024Í(long Number, char **buf)Ö0Ïvoid
nopÌ131072Í()Ö0
omit_whitespaceÌ1024Í(char *str)Ö0Ïchar *
pop_ccrÌ131072Í()Ö0
printUintÌ1024Í(const U8 *val, U8 len)Ö0Ïvoid
push_ccrÌ131072Í()Ö0
readLongÌ1024Í(const char *buff, long *val)Ö0ÏU8
rimÌ131072Í()Ö0
rx_idxÌ32768Ö0ÏU8
simÌ131072Í()Ö0
trapÌ131072Í()Ö0
tx_idxÌ32768Ö0ÏU8
tx_lenÌ32768Ö0ÏU8
uart_initÌ1024Í()Ö0Ïvoid
uart_rdyÌ32768Ö0ÏU8
uart_writeÌ1024Í(const char *str)Ö0Ïvoid
unixÌ65536Ö0
wfiÌ131072Í()Ö0

View File

@ -0,0 +1,38 @@
[editor]
line_wrapping=false
line_break_column=100
auto_continue_multiline=true
[file_prefs]
final_new_line=true
ensure_convert_new_lines=true
strip_trailing_spaces=true
replace_tabs=true
[indentation]
indent_width=4
indent_type=0
indent_hard_tab_width=4
detect_indent=false
detect_indent_width=false
indent_mode=3
[project]
name=twosteppers
base_path=/home/eddy/Docs/SAO/ELECTRONICS/STM8/SCORPIO_steppers
description=Two unipolar stepper motors management via STM8S105-based board.
file_patterns=
[long line marker]
long_line_behaviour=1
long_line_column=100
[files]
current_page=3
FILE_NAME_0=832;Make;0;EUTF-8;1;1;0;%2Fhome%2Feddy%2FDocs%2FSAO%2FELECTRONICS%2FSTM8%2FSCORPIO_steppers%2FMakefile;0;4
FILE_NAME_1=1253;C;0;EUTF-8;0;1;0;%2Fhome%2Feddy%2FDocs%2FSAO%2FELECTRONICS%2FSTM8%2FSCORPIO_steppers%2Fmain.c;0;4
FILE_NAME_2=891;C;0;EUTF-8;0;1;0;%2Fhome%2Feddy%2FDocs%2FSAO%2FELECTRONICS%2FSTM8%2FSCORPIO_steppers%2Fuart.c;0;4
FILE_NAME_3=0;C;0;EUTF-8;0;1;0;%2Fhome%2Feddy%2FDocs%2FSAO%2FELECTRONICS%2FSTM8%2FSCORPIO_steppers%2Fuart.h;0;4
[VTE]
last_dir=/home/eddy

View File

@ -0,0 +1,201 @@
:2080A40072107F60350050C635075345357D53463501534135855340350F5007350F5008A3
:2080C400351E500C351E500D350E500E350F5011350F5012AE5008F6AA10F7AE5008F6AAFE
:2080E40020F7721E5012AE5012F6AA10F7AE500AF6AA10F735CC50E0355550E0350650E1B6
:2081040035FF50E235AA50E0AE500BF6A4E04EA40F44C7006635005260354F52613500524C
:208124006235FF526335005265350052663500526735005268350052693500526A35705262
:1A81440058357052593570525A3511525C3501525D35815250721E526D8127
:0597E000000000000084
:04808300725F000127
:20815E008080808080808080808080AE5302F6A501270CA4FEAE5302F74B00CD8D24848046
:20817E0080AE5322F6A501270CA4FEAE5322F74B01CD8D24848080805202AE5240F64D2AE4
:20819E0043725D006A260DAE5245F6A47FF7725F00692030C6006AC100692319AE00221FAE
:2081BE0001C6006997725C00694F9572FB01F6AE5241F7200FAE5245F6A47FF7725F006965
:2081DE00725F006A5B02805202AE5240F6A5202603CC8278AE5241F695725D0067267B9EEA
:2081FE00A12027769EA10927719EA10D276C9EA10A27679EA15B260A35010001725F006833
:20821E002058725D000127529EA15D2603A601214F88C60068A11F8426094D2606725F0030
:20823E006820374D271C725F0001725D0068270435010067AE00029FCB006802A900957FBF
:20825E00201890AE00021701C600689097725C00684F909572F9019E90F75B028080AE5382
:20827E0042F644241B90CE006472A90001C60063A90097C60062A9009590CF0064CF006284
:06829E0035005342808010
:2082A400AE5011F6AA20F7AE5012F6A4DFF73568524235035243352C5245815202725D00DA
:2082C4006A270635AA50E020F4AE00221F011E05C6006A9097725C006A4F909572F901F668
:2082E4005C90F7F64D2707C6006AA12025E2AE5245F6AA80F75B028152245F1F031F017B62
:2083040029A1042303CC83D67B29A1032603CC83D60D292603CC83D6961C00061F111E110F
:208324001C000A7F7B29A101270E7B29A10227197B29A104272E20451E27F66B184F5F6BB8
:20834400031F017B186B042034162717131E13FE1F23162317210F200F1F16211703161F74
:20836400170120191627171D1E1DE6036B1CE6026B1BFE1F19161B170316191701A6096B3C
:20838400054B0A5F894B001E07891E0789CD96685B08517B050A055F9772FB11909FAB3064
:2083A400F74B0A5F894B001E07891E0789CD96FF5B081F0317011E0326041E0127067B05C8
:2083C400A1FF2CBD7B054C5F9772FB1189CD82BF5B025B248152130F0F961C00031F121E55
:2083E400121C000B7F0D162A14161890504F1217974F12169517181F16A6016B0FA60B6B96
:20840400024B0A5F894B001E1C891E1C89CD96435B089F0A025F417B024172FB12AB30F7E5
:208424004B0A5F894B001E1C891E1C89CD96D85B081F1817161E1826041E1627040D022634
:20844400C07B020D0227110D0F270D7B024A5F9772FB1288A62DF7846B017B01A10C241D5C
:208464001E1AE6016B11F66B101610905CFF5F7B019772FB12F61E10F70C0120DD5B1381D6
:2084840052120F05A6016B065F1F031F011E15F6A12D2607A6016B055C1F15161517111E6B
:2084A40011F61E115C1F11A12B27F4A1302556A13922520F06881E04891E04894B0A5F8945
:2084C4004B00CD97595B081F10170E84905F90975F905D2A015A72F90F9F190E889E190EE1
:2084E400958472A20030A20002A20095511303909F1202909E12012E06A6016B0620061FC4
:20850400031701209A0D0627034F202F0D05271C7B04406B0C4F12036B0B4F12026B0A4F1B
:1E85240012016B01160B17037B0A6B02161717071E071603EF021601FFA6015B128168
:0497E5000000000080
:2080000082008083820000008200815E8200815F8200816082008161820081628200816304
:208020008200816482008165820000008200000082008166820081678200816882008169C3
:208040008200817E8200817F8200819482000000820000008200819582008196820081E569
:208060008200827B8200827C820082A38200000082000000820000008200000082000000D0
:1D808700AE00612707724F00005A26F9AE004F2709D697DFD700615A26F7CC808071
:03808000CC85426A
:208542005205965C1F041E04A678F71E045CA60AF71E045C5C7FAE50B3F64D2704351F5035
:20856200B3CD80A4CD85BFCD82A49AAE85A789CD82BF5B02C60066AB301E04F71E0489CD51
:2085820082BF5B02CD923435AA50E0725D00672703CD94EB4B00CD8F72844B01CD8F7284B2
:1D85A20020E55B05810A0A48656C6C6F21204D7920616464726573732069732000A5
:2085BF003504530C3509530D35C4530E35015301AE5300F6AA84F73504532A3509532B35BF
:2085DF00C4532C35015321AE5320F6AA84F781AE913489CD82BF5B02AE914B89CD82BF5BEF
:2085FF0002AE915A89CD82BF5B02AE917089CD82BF5B02AE918C89CD82BF5B02AE91A689FD
:20861F00CD82BF5B02AE91C189CD82BF5B02AE91CF89CD82BF5B02AE91E389CD82BF5B02C4
:20863F00AE91F489CD82BF5B02814F90977B03A10027087B03A1012718202BAE5006F6A566
:20865F0010260461A60161A520261E72A900022018AE5010F64D2B0461A60161A51026092D
:20867F0072A9000220034F2002909F8152027B05A10027087B05A101270F2047AE5005F61E
:20869F00A4F0F772115300200DAE500FF6A4F0F7721153202000AE00731F015F7B0597587A
:2086BF005872FB016F036F026F017FAE008F9F1B0502A900957FAE006F9F1B0502A900952C
:2086DF00A602F75B02815206160990F64D27201E0B1F031E03FE1F011E015C1F051E037BA8
:2086FF0006E7017B05F790F6905C1E01F720DB5B06815209A62B6B017B0CA1012303CC8757
:20871F00E8AE006F9F1B0C02A90095F6A1012604A62D6B01AE00719F1B0C02A90095F6957E
:20873F00889EA100842717160D1702A101271EA102273AA1042745A1052761CC87DBAE92BD
:20875F0011160D908989CD86E55B04207CAE9217160D908989CD86E55B041E02FE1F041EDF
:20877F00045C160290FF1E047B01F7205CAE921D160D908989CD86E55B04204DAE92221624
:20879F000D908989CD86E55B041E02FE1F061E065C160290FF1E067B01F7202DAE922816A8
:2087BF000D908989CD86E55B041E02FE1F081E085C160290FF1E087B01F7200DAE922E169C
:2087DF000D908989CD86E55B045B098152047B07A10027087B07A101271020453530530D22
:2087FF0035D4530E72105300200E3530532B35D4532C72105320200090AE008B5F7B07972C
:20881F00581F0372F903AE006B72FB03FE1F01AE30D472F001908990AE00C86590855C9010
:20883F00FF5B04815202AE006F9F1B0502A90095F6A10227045FCC88F47B0588CD86495B60
:20885F00010D062A404D27045FCC88F4AE006F9F1B0502A90095A601F7160890504F12073C
:20887F00974F12069517081F06AE008F9F1B0502A90095A607F7AE00719F1B0502A9009504
:20889F00A604F72031A50227035F204944240FAE00719F1B0502A90095A605F7200DAE001C
:2088BF00719F1B0502A90095A604F7AE006F9F1B0502A900957FAE00731F015F7B059758DE
:2088DF005872FB011608EF021606FF7B0588CD87EB84AE00015B02815204AE006F9F1B07FD
:2088FF0002A90095F6A10227045FCC89A77B0788CD86495B01974D26111E0A891E0A897B00
:20891F000B88CD88435B05CC89A70D082A325424035F2074AE006F9F1B0702A90095A6010D
:20893F00F7160A90504F1209974F120895170A1F08AE008F9F1B0702A90095A607F7200BCD
:20895F00AE006F9F1B0702A900957FAE00731F035F7B079758581F011E0372FB01160AEF32
:20897F00021608FFAE008372FB01160AEF021608FFAE00719F1B0702A90095A605F77B07A8
:20899F0088CD87EB84AE00015B048152411E44F65C1F44A0306B057B05A1012303CC8CEE66
:2089BF001646173C1E3CFE1F3E1E3E5C1F2E1E3C162EFF7B05AB301E3EF71E2E5C1F321ECD
:2089DF003C1632FF1E2EA620F71E44F65C1F441E2E5C5C1F0A1E3C160AFF1E32F7162E7232
:2089FF00A900031E3CFF1E0A88A620F784A145273FA14C2757A14D2603CC8ADCA14E26034A
:208A1F00CC8AEAA14F2603CC8B45A1502603CC8B80A1522603CC8BA8A1532603CC8C0AA116
:208A3F00582603CC8CD0A15A2603CC8CDFCC8CEE1E3CFE1F101E105C163C90FF7B0588CD06
:208A5F0086495B01AB301E10F7CC8D217B0588CD86495B01A10126341E3CFE1F141E145C3D
:208A7F001F161E3C1616FF1E14A645F71E165C1F181E3C1618FF1E16A620F7161672A90083
:208A9F00021E3CFF1E18A631F7CC8D21AE00719F1B0502A90095A601F7AE006F9F1B050244
:208ABF00A90095A601F7AE008F9F1B0502A90095A607F77B0588CD87EB84CC8D211E3C89B3
:208ADF007B0788CD87115B03CC8D21965C891E4689CD84845B044D2628AE00731F1A5F7BC5
:208AFF000597585872FB1AE6036B1FE6026B1EFE163C90891620908989CD83D95B06CC8D7C
:208B1F00211E03891E03897B0988CD88435B055D2603CC8CEE1E3C891E05891E0589CD8366
:208B3F00D95B06CC8D21965C891E4689CD84845B044D2608AE00641F035F1F011E03891ED0
:208B5F0003897B0988CD88F75B055D2603CC8CEE1E3C891E05891E0589CD83D95B06CC8DC8
:208B7F0021AE007B1F245F7B0597585872FB24E6036B29E6026B28FE163C9089162A9089D8
:208B9F0089CD83D95B06CC8D217B0588CD86495B01A10226341E3CFE1F361E365C1F3A1E58
:208BBF003C163AFF1E36A645F71E3A5C1F381E3C1638FF1E3AA620F7163A72A900021E3C47
:208BDF00FF1E38A632F7CC8D21AE00719F1B0502A90095A601F7AE006F9F1B0502A9009500
:208BFF007F7B0588CD87EB84CC8D21965C891E4689CD84845B044D271C1E03A302717B02B2
:208C1F00A2007B01A2002F0DAE30D413034F12024F12012E4B0D052619AE530DF690954F6A
:208C3F000F35AE530EF60F401A3597909E1A4095201BAE532BF690954F0F2DAE532CF60F3B
:208C5F00301A2D6B0F909E1A306B0E1E0E905F7B3D887B3D88899089CD83D95B06CC8D21D2
:208C7F001E3C891E05891E0589CD83D95B061603AE006B1F125F7B0597581F2A1E1272FBF9
:208C9F002AFFAE008B72FB2A6F017F0D052611909E0F08AE530DF74FAE530E909FF7206234
:208CBF00909E0F06AE532BF74FAE532C909FF72051AE00719F1B0502A90095A602F72042FD
:208CDF00AE00719F1B0502A90095A603F720331E46E6016B21F66B201620905C170C160CA5
:208CFF00FF1620A66590F7160C905C17221622FF160CA67290F7160C72A90002FF1E22A62B
:208D1F0072F75B4181524C7B4FA10027097B4FA1012772CC8F6FAE008B1F4B1E4BFE1F413C
:208D3F001E412742AE530DF690954F0F46AE530EF60F471A4697909E1A479572F0411F0641
:208D5F00AE006BFE1F0C1E06130C2409160C17061E4B6F017F7B060F12AE530DF77B0795ED
:208D7F004F9EAE530EF7AE5005F6A4F06B18AE912C1F1DAE008FF65F9772FB1DF61A18AEA1
:208D9F005005F72076AE008D1F1F1E1FFE1F211E212749AE532BF690954F0F28AE532CF63F
:208DBF000F2E1A2897909E1A2E9572F0211F02AE006DFE1F341E0213342409163417021E4E
:208DDF001F6F017F7B020F3BAE532BF77B036B2A0F297B2A6B2BAE532C7B2BF7AE500FF629
:208DFF00A4F06B01AE912C1F2CAE0090F65F9772FB2CF61A01AE500FF72000AE006F9F1BCF
:208E1F004F02A90095F65F417B4F4158581F36A1012703CC8EDDAE008F9F1B4F6B399EA9CA
:208E3F00006B381E38F66B3A0D3A2703CC8ED4AE007372FB36E6039097E6029095E6018890
:208E5F00F66B248472A20001A2006B317B23A2006B30EF021630FFAE007B72FB361F431E3A
:208E7F0043E6039097E6029095FE72A20001173F9FA2006B3E9EA2006B3D1E43163FEF0291
:208E9F00163DFFAE00711F045F7B4F9772FB04F6A102270FAE00719F1B4F02A90095F6A120
:208EBF0003260A7B4F88CD868B84CC8F6F1E38A607F7CC8F6F7B3A4A1E38F7CC8F6FAE005A
:208EDF008F9F1B4F6B4A9EA9006B491E49F64CF7A107237CAE007372FB36E6039097E60288
:208EFF009095E60188F66B098472A20001A2006B0F7B08A2006B0EEF02160EFFAE007B7253
:208F1F00FB36E6039097E6029095E60188F66B158472A90001A900887B15A9006B1A84EFFD
:208F3F0002E7017B19F7AE00719F1B4F02A90095F6A102270FAE00719F1B4F02A90095F608
:208F5F00A10326097B4F88CD868B8420031E497F5B4C8152257B2888CD86495B016B02AE85
:208F7F00006F9F1B2802A90095F6A1012603A601214F6B01AE00719F1B2802A90095F66B5B
:208F9F00217B21A1012603CC90947B21A1022603CC90E65F7B289758581F077B21A10326BB
:208FBF0003CC91027B21A1042603CC905F7B21A1052703CC9129AE00731F171E1772FB0719
:208FDF001F151E15E6036B06E6026B05FE1F031E05A300027B04A2007B03A2002E16AE003E
:208FFF00711F135F7B289772FB131F091E09A602F7CC9129AE00831F191E1972FB071F1BD4
:20901F001E1BE6036B12E6026B11FE1F0F1E1172F0051F247B1012046B237B0F1203881EB5
:20903F0025A300647B24A20084A2002E03CC9129AE00719F1B2802A90095A604F7CC91295F
:20905F00AE00731F0D1E0D72FB071F0B1E0BE6036B20E6026B1FFE1F1D1E1FA300027B1E17
:20907F00A2007B1DA2002E0DAE00719F1B2802A90095A602F70D022603CC91290D012732B5
:20909F00AE00719F1B2802A90095F6A10126147B02442476AE00719F1B2802A90095A60359
:2090BF00F72067AE00719F1B2802A90095A602F720587B02A5022752AE00719F1B2802A972
:2090DF000095A602F72043AE006F9F1B2802A90095F6A1022634AE00719F1B2802A9009567
:2090FF007F2027AE006F9F1B2802A90095F6A1022618AE007B72FB076F036F026F017FAE58
:20911F0000719F1B2802A900957F5B2581080A0206040501090945202D2067657420656E02
:20913F00642D73776974636865730A00094C202D206D6F7665204343570A00094D202D20C8
:20915F00676574206D6F746F722073746174650A00094E202D20676F20666F72204E207312
:20917F00742E2F67657420726573740A00094F202D2070756C6C206F666620746865207306
:20919F0077697463680A000950202D206765742063757272656E7420706F736974696F6EC9
:2091BF000A000952202D206D6F76652043570A000953202D206765742F7365742073706557
:2091DF0065640A000958202D2073746F70206D6F746F720A00095A202D2073746F70206197
:2091FF006E64207A65726F20706F736974696F6E0A0052454C415800494E464D560053545C
:15921F004F50004D56535450004F4646535700554E444546000A
:2097E90009C409C402020000000000000000000000000000000000000000000000000000C2
:0698090000000000000059
:209234005202AE955C1F011E0189CD82BF5B02AE955F89CD82BF5B02AE958089CD82BF5BA9
:2092540002AE959D89CD82BF5B02AE95A889CD82BF5B02CD85EEAE95C889CD82BF5B02AE58
:2092740095D789CD82BF5B02AE95EE89CD82BF5B02AE960289CD82BF5B02AE962089CD82DF
:20929400BF5B021E0189CD82BF5B048152130F011E16F65C1F16A0306B027B02A102231345
:2092B4001E18894BFF4BFF4BFF4BFFCD83D95B06CC93B31618170F1E0FFE1F071E075C1FD2
:2092D400121E0F1612FF7B02AB301E07F71E125C160F90FF1E12A620F7161690F6957B02AF
:2092F400A1002606A6016B1120020F117B02A1012606A6016B0D20020F0D7B02A102260634
:20931400A6016B0E20020F0E9E4D26260D11260A0D0D260E0D0E26122072AE5266F66B015A
:20933400206AAE5268F66B012062AE526AF66B01205A961C0003899089CD84845B044D27FE
:20935400110D032B0DAE00FF13054F12044F12032E121E0F894BFF4BFF4BFF4BFFCD83D9CB
:209374005B06203B7B066B010D11260A0D0D260E0D0E26122016AE52667B01F7200EAE5204
:20939400687B01F72006AE526A7B01F77B010F0B5F160F9089887B0E8889CD83D95B065BA1
:2093B40013815210AE00911F0A1E0A1C00041F0D160D170135AA50E01613170F1E0FF66BA0
:2093D400031E0A5C5CC60066AB30F77B03A13027067B03A131260E965C891E1189CD89AA65
:2093F4005B04CC94D21E0D7B03F71E0D5C1F01A620F71E0D5C5C1F04160417011E0F5C1FE4
:20941400131E0D1C00031F067B03A147272D7B03A14C27357B03A15027717B03A15427781C
:209434007B03A1722703CC94CF355550E0350050E1350150E235AA50E020FEC60066AB3072
:209454001E04F71606170120751E13F64D271BAE500A88F69584A13026099EAA10AE500A61
:20947400F720079EA4EFAE500AF71604170816061701AE500AF6A5102706A6306B0C2004CC
:20949400A6316B0C1E087B0CF72033965C891E1589CD92A05B0420261E047F1E0A89CD82F7
:2094B400BF5B02AE00624B0489CD82FC5B03CE963889CD82BF5B02A60120194F20161E01D7
:2094D4007F1E0A89CD82BF5B02CE963889CD82BF5B02A6015B1081520DAE00421F0A160A22
:2094F4001704AE00021F0C1E0C5C1F011E0CF6A030725D0067274EC10066270EA132270AC1
:20951400725F0067725F0068203B16011708160417060F037B03C1006824141E08F61E08CB
:209534005C1F081E06F71E065C1F060C0320E5725F0068725F00671E0A89CD93B65B024DDE
:209554002603CD92345B0D810A0A00436F6D6D616E642070726F746F636F6C3A205B2061B7
:2095740064647220636F6D6D616E64002064617461205D0A092062726F6164636173742061
:20959400616464723A20620A00636F6D6D616E64733A0A00302F31202D20636F6D6D616E48
:2095B4006420666F7220676976656E206D6F746F723A0A0072202D207265736574204D434C
:2095D400550A0047202D2067657420626F61726420616464726573730A004C20302F3120D0
:2095F4002D204C4544206F6E2F6F66660A00502063682076616C202D2050574D206F6E20A8
:209614006368616E6E656C2063680A0054202D2074696D6520636F756E7465722076616C75
:0F96340075650A00963A205D0A005B20582000F9
:20980F005B2058200000000000000000000000000000000000000000000000000000000046
:209643001E0916072A03CD97D58990891E0916072A03CD97D5899089CD96685B087B032A99
:2096630003CD97D58152030F030F017B0A484F494D262E160C1E0A905859170C1F0A1E08B0
:20968300130C7B07120B7B06120A240D160C1E0A549056170C1F0A20080C017B016B03202C
:2096A300CA7B036B021E0872F00C7B07120B90977B06120A25061F0890951706160C1E0A1D
:2096C300549056170C1F0A7B020A024D26D71E0816065B03811E0916072A03CD97D589904A
:2096E300891E0916072A03CD97D5899089CD96FF5B087B0318072A03CD97D58152065F1F73
:20970300051F03A6206B027B09484F496B01160B1E09905859170B1F0916051E03905859CC
:2097230017051F030D0127067B06AA016B061E0572F00F7B04120E90977B03120D250C1FC9
:2097430005909517037B0CAA016B0C0A0226B81E0B16095B06815F89897B0A977B0E421F8E
:20976300037B09977B0E4272FB021F024FA9006B017B0A977B0D4272FB021F024F19016BBF
:20978300017B0A977B0C4272FB011F017B09977B0D4272FB011F017B08977B0E4272FB018C
:2097A3001F017B07977B0E429F1B016B017B0A977B0B429F1B016B017B09977B0C429F1BD2
:1D97C300016B017B08977B0D429F1B016B019085858190535D2703535C81905C81EF
:00000001FF

View File

@ -0,0 +1,131 @@
/*
* geany_encoding=koi8-r
* uart.c
*
* Copyright 2018 Edward V. Emelianov <eddy@sao.ru, edward.emelianoff@gmail.com>
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; if not, write to the Free Software
* Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston,
* MA 02110-1301, USA.
*
*/
#include "uart.h"
#include "hardware.h"
U8 uart_rdy = 0;
U8 rx_idx = 0, tx_idx = 0, tx_len = 0;
U8 UART_rx[UART_BUF_LEN]; // buffers for received/transmitted data
U8 UART_tx[UART_BUF_LEN];
void uart_init(){
// PD5 - UART2_TX
PORT(UART_PORT, DDR) |= UART_TX_PIN; // output
PORT(UART_PORT, CR1) &= ~UART_TX_PIN; // open-drain
// 8 bit, no parity, 1 stop (UART_CR1/3 = 0 - reset value)
// 9600 on 16MHz: DIV=0x0693 -> BRR1=0x68, BRR2=0x03
UART2_BRR1 = 0x68; UART2_BRR2 = 0x03;
UART2_CR2 = UART_CR2_TEN | UART_CR2_REN | UART_CR2_RIEN; // Allow TX/RX, generate ints on rx
}
void uart_write(const char *str){
while(tx_len) {IWDG_KR = KEY_REFRESH;}
do{
UART_tx[tx_len++] = *str++;
}while(*str && tx_len < UART_BUF_LEN);
UART2_CR2 |= UART_CR2_TIEN; // enable TXE interrupt
}
void printUint(const U8 *val, U8 len){
unsigned long Number = 0;
U8 i = len;
char ch;
U8 decimal_buff[11]; // max len of U32 == 10 + \0
if(len > 4 || len == 3 || len == 0) return;
decimal_buff[10] = 0;
ch = 9;
switch(len){
case 1:
Number = *((U8*)val);
break;
case 2:
Number = *((U16*)val);
break;
case 4:
Number = *((unsigned long*)val);
break;
}
do{
i = Number % 10L;
decimal_buff[ch--] = i + '0';
Number /= 10L;
}while(Number && ch > -1);
uart_write((char*)&decimal_buff[ch+1]);
}
/**
* fill buffer with symbols of signed long
* max len = 10 symbols + 1 for "-" + 1 for 0 = 12
*/
void long2buf(long Number, char **buf){
U8 i, L = 0;
U8 ch;
char decimal_buff[12];
decimal_buff[11] = 0;
ch = 11;
if(Number < 0){
Number = -Number;
L = 1;
}
do{
i = Number % 10L;
decimal_buff[--ch] = i + '0';
Number /= 10L;
}while(Number && ch > 0);
if(ch > 0 && L) decimal_buff[--ch] = '-';
for(i = ch; i < 12; ++i) *((*buf)++) = decimal_buff[i];
}
/**
* read 16 bit integer value from buffer until first non-number
* @param buff (i) - input buffer
* @param val (o) - output value
* @return 1 if all OK or 0 if there's none numbers in buffer
*/
U8 readLong(const char *buff, long *val){
U8 sign = 0, rb, bad = 1;
long R = 0, oR = 0;
if(*buff == '-'){
sign = 1;
++buff;
}
do{
rb = *buff++;
if(rb == '+') continue;
if(rb < '0' || rb > '9') break;
bad = 0;
oR = R * 10L + rb - '0';
if(oR < R){ // bad value
bad = 1;
break;
}
R = oR;
}while(1);
if(bad) return 0;
if(sign) R = -R;
*val = R;
return 1;
}

View File

@ -0,0 +1,49 @@
/*
* geany_encoding=koi8-r
* uart.h
*
* Copyright 2018 Edward V. Emelianov <eddy@sao.ru, edward.emelianoff@gmail.com>
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; if not, write to the Free Software
* Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston,
* MA 02110-1301, USA.
*
*/
#pragma once
#ifndef __UART_H__
#define __UART_H__
#include "hardware.h"
#define UART_BUF_LEN 32
extern U8 UART_rx[];
extern U8 UART_tx[];
extern U8 uart_rdy, rx_idx, tx_idx, tx_len;
void uart_init();
void uart_write(const char *str);
char *omit_whitespace(char *str);
void long2buf(long Number, char **buf);
void printUint(const U8 *val, U8 len);
U8 readLong(const char *buff, long *val);
#endif // __UART_H__

144
STM8/platform/interrupts.h Normal file
View File

@ -0,0 +1,144 @@
/*
* interrupts.h
*
* Copyright 2014 Edward V. Emelianoff <eddy@sao.ru>
*
* 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 __INTERRUPTS_H__
#define __INTERRUPTS_H__
#include "stm8l.h"
// Top Level Interrupt
INTERRUPT_DEFINITION(TLI_IRQHandler, 0);
// Auto Wake Up Interrupt
INTERRUPT_DEFINITION(AWU_IRQHandler, 1);
// Clock Controller Interrupt
INTERRUPT_DEFINITION(CLK_IRQHandler, 2);
// External Interrupt PORTA
INTERRUPT_DEFINITION(EXTI_PORTA_IRQHandler, 3);
// External Interrupt PORTB
INTERRUPT_DEFINITION(EXTI_PORTB_IRQHandler, 4);
// External Interrupt PORTC
INTERRUPT_DEFINITION(EXTI_PORTC_IRQHandler, 5);
// External Interrupt PORTD
INTERRUPT_DEFINITION(EXTI_PORTD_IRQHandler, 6);
// External Interrupt PORTE
INTERRUPT_DEFINITION(EXTI_PORTE_IRQHandler, 7);
#ifdef STM8S903
// External Interrupt PORTF
INTERRUPT_DEFINITION(EXTI_PORTF_IRQHandler, 8);
#endif // STM8S903
#if defined (STM8S208) || defined (STM8AF52Ax)
// CAN RX Interrupt routine.
INTERRUPT_DEFINITION(CAN_RX_IRQHandler, 8);
// CAN TX Interrupt routine.
INTERRUPT_DEFINITION(CAN_TX_IRQHandler, 9);
#endif // STM8S208 || STM8AF52Ax
// SPI Interrupt routine.
INTERRUPT_DEFINITION(SPI_IRQHandler, 10);
// Timer1 Update/Overflow/Trigger/Break Interrupt
INTERRUPT_DEFINITION(TIM1_UPD_OVF_TRG_BRK_IRQHandler, 11);
// Timer1 Capture/Compare Interrupt routine.
INTERRUPT_DEFINITION(TIM1_CAP_COM_IRQHandler, 12);
#ifdef STM8S903
// Timer5 Update/Overflow/Break/Trigger Interrupt
INTERRUPT_DEFINITION(TIM5_UPD_OVF_BRK_TRG_IRQHandler, 13);
// Timer5 Capture/Compare Interrupt
INTERRUPT_DEFINITION(TIM5_CAP_COM_IRQHandler, 14);
#else // STM8S208, STM8S207, STM8S105 or STM8S103 or STM8AF62Ax or STM8AF52Ax or STM8AF626x
// Timer2 Update/Overflow/Break Interrupt
INTERRUPT_DEFINITION(TIM2_UPD_OVF_BRK_IRQHandler, 13);
// Timer2 Capture/Compare Interrupt
INTERRUPT_DEFINITION(TIM2_CAP_COM_IRQHandler, 14);
#endif // STM8S903
#if defined (STM8S208) || defined(STM8S207) || defined(STM8S007) || defined(STM8S105) || \
defined(STM8S005) || defined (STM8AF62Ax) || defined (STM8AF52Ax) || defined (STM8AF626x)
// Timer3 Update/Overflow/Break Interrupt
INTERRUPT_DEFINITION(TIM3_UPD_OVF_BRK_IRQHandler, 15);
// Timer3 Capture/Compare Interrupt
INTERRUPT_DEFINITION(TIM3_CAP_COM_IRQHandler, 16);
#endif // STM8S208, STM8S207 or STM8S105 or STM8AF62Ax or STM8AF52Ax or STM8AF626x
#if defined (STM8S208) || defined(STM8S207) || defined(STM8S007) || defined(STM8S103) || \
defined(STM8S003) || defined (STM8AF62Ax) || defined (STM8AF52Ax) || defined (STM8S903)
// UART1 TX Interrupt
INTERRUPT_DEFINITION(UART1_TX_IRQHandler, 17);
// UART1 RX Interrupt
INTERRUPT_DEFINITION(UART1_RX_IRQHandler, 18);
#endif // STM8S208 or STM8S207 or STM8S103 or STM8S903 or STM8AF62Ax or STM8AF52Ax
// I2C Interrupt
INTERRUPT_DEFINITION(I2C_IRQHandler, 19);
#if defined(STM8S105) || defined(STM8S005) || defined (STM8AF626x)
// UART2 TX interrupt
INTERRUPT_DEFINITION(UART2_TX_IRQHandler, 20);
// UART2 RX interrupt
INTERRUPT_DEFINITION(UART2_RX_IRQHandler, 21);
#endif // STM8S105 or STM8AF626x
#if defined(STM8S207) || defined(STM8S007) || defined(STM8S208) || defined (STM8AF52Ax) || defined (STM8AF62Ax)
// UART3 TX interrupt
INTERRUPT_DEFINITION(UART3_TX_IRQHandler, 20);
// UART3 RX interrupt
INTERRUPT_DEFINITION(UART3_RX_IRQHandler, 21);
#endif // STM8S208 or STM8S207 or STM8AF52Ax or STM8AF62Ax
#if defined(STM8S207) || defined(STM8S007) || defined(STM8S208) || defined (STM8AF52Ax) || defined (STM8AF62Ax)
// ADC2 interrupt
INTERRUPT_DEFINITION(ADC2_IRQHandler, 22);
#else // STM8S105, STM8S103 or STM8S903 or STM8AF626x
// ADC1 interrupt
INTERRUPT_DEFINITION(ADC1_IRQHandler, 22);
#endif // STM8S208 or STM8S207 or STM8AF52Ax or STM8AF62Ax
#ifdef STM8S903
// Timer6 Update/Overflow/Trigger Interrupt
INTERRUPT_DEFINITION(TIM6_UPD_OVF_TRG_IRQHandler, 23);
#else // STM8S208, STM8S207, STM8S105 or STM8S103 or STM8AF52Ax or STM8AF62Ax or STM8AF626x
// Timer4 Update/Overflow Interrupt
INTERRUPT_DEFINITION(TIM4_UPD_OVF_IRQHandler, 23);
#endif // STM8S903
// Eeprom EEC Interrupt
INTERRUPT_DEFINITION(EEPROM_EEC_IRQHandler, 24);
#endif // __INTERRUPTS_H__

View File

@ -0,0 +1,113 @@
:2080A000AE5007F6AA0FF7AE5008F6AA0FF7AE5009F6AA0FF7AE5011F6AA1FF7AE5012F6F1
:2080C000AA1FF7AE5013F6AA1FF7AE5005F6A4F0F7AE500FF6A4F8F7AE500FF6AA18F781C2
:2080E0005204965C891E0989CD868E5B044D27441E01A3FFF72D3D1E01A37FFF2E3616012A
:2081000072A9000AAEFFFF65A3007D24034F2025CF00643504530C9E0F0390AE530D90F7AE
:208120004F9FAE530EF735015301AE5300F6AA84F7A601214F5B048188AE5001F66B017B4A
:2081400001954F417B0141889E1102842704029E014F4CA1FF25F09EA5022604A601200924
:208160009EA5042603A602214F5B018152040D07270F7B07A10622091E082705CE006127FE
:20818000044FCC825590AE004C5F7B0797581F0172F90190FE35AA50E00D082A0B350100E6
:2081A000631E08501F082004725F00637B09C700627B08C70061AE005A9F1B0702A9009506
:2081C000F69095AE500AF6A41F6B03909E4EA4F0481A03AE500AF7AE5005F6A4F0F7AE505F
:2081E0000FF6A4F8F7AE500FF6AA18F7AE500FF695909F4488A6016B05844D270508044A2E
:2082000026FB9E1A04AE500FF7AE500FF690542408A4EFAE500FF72006A4F7AE500FF7CD41
:208220008138027B0701889EC70066844D2714A1012609725D0063260A4F2007725D0063C6
:2082400027014F4D2706CD82584F2009AE5300F6AA01F7A6015B048172115300AE5005F61F
:20826000A4F0F7AE500FF6A4F8F7AE500FF6AA18F7725F00675FCF006135010043815214FA
:20828000965C5C1F131E13A65BF71E135CA632F71E135C5CA620F71E131C00031F0E1E0E8A
:2082A000A630F71E13A620E7041E13A653E7051E13A674E7061E13A63DE7071E131C00086A
:2082C0001F111E11A630F71E13A65DE7091E13A60AE70A1E131C000B7F0D1727627B17A1C5
:2082E00006225C35AA50E0AE005A9F1B1702A90095F66B01AE500AF6A41F6B107B014EA4C6
:20830000F0481A10AE500AF7C60043A1012309C600434AC700432027725F00437B17AB3000
:208320001E0EF7CD8138954D2603A603959EAB301E11F71E1389CD84D35B02725F00665BDF
:208340001481880D0427307B04A106222AAE005A9F1B0402A90095F69095AE500AF6A41F44
:198360006B01909E4EA4F0481A01AE500AF77B04C7006635FF00438481FE
:208D300000080A0206040501090000000300020001000000040005000104030002050000D8
:048D50000000000718
:2083790080808080808080808035005255808088AE5302F6A501277CA4FEAE5302F7AE5024
:2083990005F6A4F06B01AE00449FCB006702A90095F61A01AE5005F7CE00612605CD8258BA
:2083B9002052CD81389095725D00632720725A0067C600674D2A3D35070067CE00615ACFFF
:2083D9000061909EA101262CCD82582027725D0067260B909EA1022605CD82582016725C05
:2083F9000067C60067A1072D0B725F0067CE00615ACF00618480808080805202AE5240F671
:208419004D2A43725D006B260DAE5245F6A47FF7725F006A2030C6006BC1006A2319AE00F6
:20843900221F01C6006A97725C006A4F9572FB01F6AE5241F7200FAE5245F6A47FF7725F0D
:20845900006A725F006B5B02805202AE5240F6A5202761AE5241F6A1202759A1092755A16A
:208479000D2751A10A274DA15B2604725F0069AE00011F0141C600694188C600694C95C700
:20849900006984024F0172FB01F7A15D2603A601214F88C60069A1208426094D2606725F6C
:1A84B900006920104D270D350100685FC600699772FB017F5B028080808082
:018D5400001E
:2084D3005202725D006B270635AA50E020F4721F5245725F006AAE00221F011E05C6006B04
:2084F3009097725C006B4F909572F901F65C90F7F64D2707C6006BA12025E2AE5245F6AA01
:2085130080F75B028152255F1F101F0E7B2AA1042303CC85FC7B2AA1032603CC85FC0D2A0E
:208533002603CC85FC965C1F184F5F9772FB187F4CA10C25F51E18A60AE70A7B2AA10127E8
:208553000E7B2AA10227197B2AA104272E20451E28F66B174F5F6B101F0E7B176B112034F8
:20857300162817121E12FE1F24162417220F210F20162217101620170E20191628171E1EBA
:208593001EE6036B1DE6026B1CFE1F1A161C1710161A170EA6096B0D4B0A5F894B001E1404
:2085B300891E1489CD8BB85B08517B0D0A0D5F9772FB18909FAB30F74B0A5F894B001E14CB
:2085D300891E1489CD8C4F5B081F10170E1E1026041E0E27067B0DA1FF2CBD7B0D4C5F9759
:2085F30072FB1889CD84D35B025B258152100F01961C00031F0F1E0F1C000B7F0D132A1452
:20861300161590504F1214974F12139517151F13A6016B01A60B6B024B0A5F894B001E19D9
:20863300891E1989CD8B935B089F0A025F417B024172FB0FAB30F74B0A5F894B001E1989F1
:208653001E1989CD8C285B081F1517131E1526041E1327040D0226C07B020D0227110D0185
:20867300270D7B024A5F9772FB0F88A62DF7845F9772FB0F89CD84D35B128152140F02A67A
:20869300016B015F1F051F0335AA50E01E17F6A12D2607A6016B025C1F17161717091E0966
:2086B300F61E095C1F09A12B27F4A1302552A139224E0F01881E06891E06894B0A5F894B13
:2086D30000CD8CA95B081F0E170C84905F90975F905D2A015A72F90D9F190C889E190C954B
:2086F3008472A20030A20002A2009517051F03AE7FFE13054F12044F12032EA2A6016B0197
:208713000D0127034F202F0D02271C7B06406B124F12056B114F12046B104F12036B031636
:198733001117057B106B0416191713160517071E131607FFA6015B148190
:048D5500000000001A
:208000008200808382000000820083798200837A8200837B8200837C8200837D8200837E56
:208020008200837F820083808200000082000000820083818200838282008387820083880D
:208040008200840F8200841082008411820000008200000082008412820084138200846241
:20806000820084D0820084D1820084D28200000082000000820000008200000082000000F1
:1D808300AE00422707724F00005A26F9AE00292709D68D2FD700425A26F7CC808093
:03808000CC874C5E
:20874C00AE50C0F6AA08F772107F60350050C6AE500CF6AA0EF7AE500DF6AA0EF7AE500E99
:20876C00F6AA0EF735005260350F52613500526235FF5263350052653501526635005267D0
:20878C0035015268350052693501526A35605258356052593560525A3511525C3501525D62
:2087AC0035815250721E526DAE5011F6AA20F7AE5012F6AA20F7AE5013F6AA20F735035227
:2087CC004335685242352C5245AE03E8CF00643504530C3503530D35E8530E35015301AE6F
:2087EC005300F6AA84F7CD80A0AE5007F6AA30F7AE5008F6AA30F7AE501BF6AA10F7AE50BB
:20880C001CF6AA10F7AE500CF6AAE0F7AE500DF6AAE0F7AE5003F6AA06F79A35CC50E035E8
:20882C005550E0350650E135FF50E2AE886889CD84D35B02AE50B3F64D2704351F50B33582
:20884C00AA50E0725D00682703CD8B2B725D004327ED3B0066CD827E8420E48153636F721A
:20886C0070696F20706C6174666F726D2072656164790A0052021E05F6A030A101250AA131
:20888C0006220690CE006127034F203235AA50E05C1F05965C88891E0889CD868E5B0497FC
:2088AC0084414D4126034F20151E01270B1E018988CD816C5B03200688CD8342844F5B02A3
:2088CC0081521535AA50E01E18F66B147B1AA1372606A6016B0D20020F0D7B1AA13826065A
:2088EC00A6016B1320020F137B1AA1392606A6016B1520020F157B14A12D2703CC89A996E0
:20890C005C1F111E11A65BF71E115CA632F71E115C5CA620F7161172A90003A64E90F71EBC
:20892C0011A620E7041E11A653E7051E11A674E7061E11A63DE7071E111C00081F0F1E0F71
:20894C00A631F71E11A65DE7091E11A60AE70A1E111C000B7F7B1A90F70D0D260A0D1326CA
:20896C00100D152616201EAE5005F6A4106B0E2018AE5005F6A4206B0E200EAE5019F6A4CC
:20898C00106B0E20044FCC8A150D0E26051E0FA630F71E1189CD84D35B024F206C7B14A1E0
:2089AC003026300D0D260A0D13260F0D152614201BAE5005F6A4EFF72015AE5005F6A4DFBB
:2089CC00F7200CAE5019F6A4EFF720034F203AA60120367B14A131262F0D0D260A0D1326C2
:2089EC000F0D152614201BAE5005F6AA10F72015AE5005F6AA20F7200CAE5019F6AA10F742
:208A0C0020034F2004A601214F5B15815202965C891E0789CD868E5B044D27370D012B33D8
:208A2C001E01A300FF2C2C7B02887B08A100842712887B08A101842710887B08A10284276A
:208A4C000E2010AE5266F7200AAE5268F72004AE526AF75B028135AA50E01E035C1F031EB7
:208A6C0003F6A1302D0DA1372E0989CD88805B02CC8B2A5CA130274AA1372759A138275F46
:208A8C00A1392765A13F2713A1612767A162276BA1632771A1642777CC8B25AE8B8589CD56
:208AAC0084D35B0290CE00615F905D2A015A908989CD85FF5B04AE8B9189CD84D35B024FF1
:208ACC00205CCD8258AE5005F6A4CFF7AE5019F6AAEFF720474B3789CD88CD5B03203F4BCB
:208AEC003889CD88CD5B0320354B3989CD88CD5B03202B89CD80E05B0220234B0089CD8A7B
:208B0C00185B0320174B0189CD8A185B03200D4B0289CD8A185B0320034F2002A60181521C
:208B2C0029AE00011F2416241728725D00682746725F00681E285C1F011E01F6A1322636B2
:208B4C00961C00031F264F905F909772F9265F9772FB2488F69790F7844CC1006923E8727F
:208B6C005F00691E0189CD8A625B024D27081E2689CD84D35B025B298153746570735F6CBA
:208B8C006566743D000A001E0916072A03CD8D258990891E0916072A03CD8D25899089CD52
:208BAC008BB85B087B032A03CD8D258152030F030F017B0A484F494D262E160C1E0A9058A9
:208BCC0059170C1F0A1E08130C7B07120B7B06120A240D160C1E0A549056170C1F0A20083A
:208BEC000C017B016B0320CA7B036B021E0872F00C7B07120B90977B06120A25061F0890C4
:208C0C00951706160C1E0A549056170C1F0A7B020A024D26D71E0816065B03811E0916078E
:208C2C002A03CD8D258990891E0916072A03CD8D25899089CD8C4F5B087B0318072A03CDA6
:208C4C008D258152065F1F051F03A6206B027B09484F496B01160B1E09905859170B1F0902
:208C6C0016051E0390585917051F030D0127067B06AA016B061E0572F00F7B04120E9097FB
:208C8C007B03120D250C1F05909517037B0CAA016B0C0A0226B81E0B16095B06815F898969
:208CAC007B0A977B0E421F037B09977B0E4272FB021F024FA9006B017B0A977B0D4272FB72
:208CCC00021F024F19016B017B0A977B0C4272FB011F017B09977B0D4272FB011F017B0827
:208CEC00977B0E4272FB011F017B07977B0E429F1B016B017B0A977B0B429F1B016B017BE7
:208D0C0009977B0C429F1B016B017B08977B0D429F1B016B019085858190535D2703535C78
:048D2C0081905C8155
:00000001FF

View File

@ -1,110 +0,0 @@
:2080A000AE5007F6AA0FF7AE5008F6AA0FF7AE5009F6AA0FF7AE5011F6AA1FF7AE5012F6F1
:2080C000AA1FF7AE5013F6AA1FF7AE5005F6A4F0F7AE500FF6A4F8F7AE500FF6AA18F781C2
:2080E0005204965C891E0989CD86255B044D27441E01A3FFF72D3D1E01A37FFF2E36160193
:2081000072A9000AAEFFFF65A3007D24034F2025CF00643504530C9E0F0390AE530D90F7AE
:208120004F9FAE530EF735015301AE5300F6AA84F7A601214F5B0481AE5001F6A5022604E8
:20814000A6012008A5042603A602214F8152040D07270F7B07A10622091E082705CE006170
:2081600027044FCC823690AE004C5F7B0797581F0372F90390FE35AA50E00D082A0B3501FA
:2081800000631E08501F082004725F00637B09C700627B08C70061AE005A9F1B0702A900BB
:2081A00095F69095AE500AF6A41F6B01909E4EA4F0481A01AE500AF7AE5005F6A4F0F7AE3E
:2081C000500FF6A4F8F7AE500FF6AA18F7AE500FF695909F4488A6016B03844D270508024C
:2081E0004A26FB9E1A02AE500FF7AE500FF690542408A4EFAE500FF72006A4F7AE500FF7E7
:20820000CD8138027B0701889EC70066844D2714A1012609725D0063260A4F2007725D007C
:208220006327014F4D2706CD82394F2009AE5300F6AA01F7A6015B048172115300AE5005F1
:20824000F6A4F0F7AE500FF6A4F8F7AE500FF6AA18F7725F00675FCF006135010043815238
:2082600014965C5C1F0E1E0EA65BF71E0E5CA632F71E0E5C5CA620F71E0E1C00031F101EBB
:2082800010A630F71E0EA620E7041E0EA653E7051E0EA674E7061E0EA63DE7071E0E1C009B
:2082A000081F131E13A630F71E0EA65DE7091E0EA60AE70A1E0E1C000B7F35AA50E00D1795
:2082C000274A7B17A1062244AE005A9F1B1702A90095F66B01AE500AF6A41F6B127B014E0B
:2082E000A4F0481A12AE500AF77B17AB301E10F7CD8138954D2603A603959EAB301E13F775
:0F8300001E0E89CD84695B02725F00665B14817B
:208CCD0000080A02060405010900000003000200010000000400050001040300020500003C
:048CED00000000077C
:20830F0080808080808080808035005255808088AE5302F6A501277CA4FEAE5302F7AE508E
:20832F0005F6A4F06B01AE00449FCB006702A90095F61A01AE5005F7CE00612605CD823943
:20834F002052CD81389095725D00632720725A0067C600674D2A3D35070067CE00615ACF69
:20836F000061909EA101262CCD82392027725D0067260B909EA1022605CD82392016725CAD
:20838F000067C60067A1072D0B725F0067CE00615ACF00618480808080805202AE5240F6DB
:2083AF004D2A43725D006B260DAE5245F6A47FF7725F006A2030C6006BC1006A2319AE0061
:2083CF00221F01C6006A97725C006A4F9572FB01F6AE5241F7200FAE5245F6A47FF7725F78
:2083EF00006A725F006B5B02805202AE5240F6A5202761AE5241F6A1202759A1092755A1D5
:20840F000D2751A10A274DA15B2604725F0069AE00011F0141C600694188C600694C95C76A
:20842F00006984024F0172FB01F7A15D2603A601214F88C60069A1208426094D2606725FD6
:1A844F00006920104D270D350100685FC600699772FB017F5B0280808080EC
:018CF1000082
:208469005202725D006B270635AA50E020F4721F5245725F006AAE00221F011E05C6006B6E
:208489009097725C006B4F909572F901F65C90F7F64D2707C6006BA12025E2AE5245F6AA6B
:2084A90080F75B028152255F1F101F0E7B2AA1042303CC85937B2AA1032603CC85930D2A4B
:2084C9002603CC8593965C5C1F124F5F9772FB127F4CA10C25F51E12A60AE70A7B2AA10199
:2084E900270E7B2AA10227197B2AA104272E20451E28F66B1B4F5F6B101F0E7B1B6B112068
:2085090034162817161E16FE1F14161417240F230F22162417101622170E2019162817201A
:208529001E20E6036B1FE6026B1EFE1F1C161E1710161C170EA6096B014B0A5F894B001E64
:2085490014891E1489CD8B555B08517B010A015F9772FB12909FAB30F74B0A5F894B001EB6
:2085690014891E1489CD8BEC5B081F10170E1E1026041E0E27067B01A1FF2CBD7B014C5FC2
:208589009772FB1289CD84695B025B258152100F01961C00031F0F1E0F1C000B7F0D132AA9
:2085A90014161590504F1214974F12139517151F13A6016B01A60B6B024B0A5F894B001E49
:2085C90019891E1989CD8B305B089F0A025F417B024172FB0FAB30F74B0A5F894B001E192F
:2085E900891E1989CD8BC55B081F1517131E1526041E1327040D0226C07B020D0227110DCC
:2086090001270D7B024A5F9772FB0F88A62DF7845F9772FB0F89CD84695B128152140F06EF
:20862900A6016B055F1F031F0135AA50E01E17F6A12D2607A6016B065C1F171617170B1E2D
:208649000BF61E0B5C1F0BA12B27F4A1302552A139224E0F05881E04891E04894B0A5F89B9
:208669004B00CD8C465B081F0A170884905F90975F905D2A015A72F9099F1908889E190876
:20868900958472A20030A20002A2009517031F01AE7FFE13034F12024F12012EA2A6016B77
:2086A900050D0527034F202F0D06271C7B04406B144F12036B134F12026B124F12016B01AE
:1A86C900161317037B126B021619170F1603170D1E0F160DFFA6015B1481E2
:048CF200000000007E
:2080000082008083820000008200830F8200831082008311820083128200831382008314D2
:208020008200831582008316820000008200000082008317820083188200831D8200831E89
:20804000820083A5820083A6820083A78200000082000000820083A8820083A9820083F8C3
:2080600082008466820084678200846882000000820000008200000082000000820000002F
:1D808300AE00422707724F00005A26F9AE00292709D68CCCD700425A26F7CC8080F7
:03808000CC86E3C8
:2086E300AE50C0F6AA08F772107F60350050C6AE500CF6AA0EF7AE500DF6AA0EF7AE500E03
:20870300F6AA0EF735005260350F52613500526235FF526335005265350152663500526739
:2087230035015268350052693501526A35605258356052593560525A3511525C3501525DCB
:2087430035815250721E526DAE5011F6AA20F7AE5012F6AA20F7AE5013F6AA20F735035290
:208763004335685242352C5245AE03E8CF00643504530C3503530D35E8530E35015301AED8
:208783005300F6AA84F7CD80A0AE5007F6AA30F7AE5008F6AA30F7AE501BF6AA10F7AE5024
:2087A3001CF6AA10F7AE500CF6AAE0F7AE500DF6AAE0F7AE5003F6AA06F79A35CC50E03552
:2087C3005550E0350650E135FF50E2AE880389CD84695B02AE50B3F64D2704351F50B335BB
:2087E300AA50E0725D00682703CD8AC8725D004327ED725F00433B0066CD825F8420E0818E
:2088030053636F7270696F20706C6174666F726D2072656164790A0052021E05F6A030A1D4
:2088230001250AA106220690CE006127034F203435AA50E05C1F05965C88891E0889CD8616
:20884300255B049784414D4126034F20171E01270B1E018988CD814D5B032008C7006635F4
:208863000100434F5B0281521535AA50E01E18F66B157B1AA1372606A6016B1120020F1164
:208883007B1AA1382606A6016B1220020F127B1AA1392606A6016B0D20020F0D7B15A12D7E
:2088A3002703CC8946965C1F131E13A65BF71E135CA632F71E135C5CA620F7161372A9005D
:2088C30003A64E90F71E13A620E7041E13A653E7051E13A674E7061E13A63DE7071E131C98
:2088E30000081F0F1E0FA631F71E13A65DE7091E13A60AE70A1E131C000B7F7B1A90F70D4E
:2089030011260A0D1226100D0D2616201EAE5005F6A4106B0E2018AE5005F6A4206B0E2076
:208923000EAE5019F6A4106B0E20044FCC89B20D0E26051E0FA630F71E1389CD84695B0261
:208943004F206C7B15A13026300D11260A0D12260F0D0D2614201BAE5005F6A4EFF7201599
:20896300AE5005F6A4DFF7200CAE5019F6A4EFF720034F203AA60120367B15A131262F0D31
:2089830011260A0D12260F0D0D2614201BAE5005F6AA10F72015AE5005F6AA20F7200CAE3D
:2089A3005019F6AA10F720034F2004A601214F5B15815202965C891E0789CD86255B044D65
:2089C30027370D012B331E01A300FF2C2C7B02887B08A100842712887B08A10184271088DB
:2089E3007B08A10284270E2010AE5266F7200AAE5268F72004AE526AF75B028135AA50E00D
:208A03001E035C1F031E03F6A1302D0DA1372E0989CD881B5B02CC8AC75CA130274AA1379A
:208A23002759A138275FA1392765A13F2713A1612767A162276BA1632771A1642777CC8A1A
:208A4300C2AE8B2289CD84695B0290CE00615F905D2A015A908989CD85965B04AE8B2E89ED
:208A6300CD84695B024F205CCD8239AE5005F6A4CFF7AE5019F6AAEFF720474B3789CD88C2
:208A83006A5B03203F4B3889CD886A5B0320354B3989CD886A5B03202B89CD80E05B022086
:208AA300234B0089CD89B55B0320174B0189CD89B55B03200D4B0289CD89B55B0320034F00
:208AC3002002A601815229AE00011F2616261728725D00682746725F00681E285C1F011EA2
:208AE30001F6A1322636961C00031F244F905F909772F9245F9772FB2688F69790F7844C6C
:208B0300C1006923E8725F00691E0189CD89FF5B024D27081E2489CD84695B025B298153D3
:208B2300746570735F6C6566743D000A001E0916072A03CD8CC28990891E0916072A03CDB9
:208B43008CC2899089CD8B555B087B032A03CD8CC28152030F030F017B0A484F494D262E4E
:208B6300160C1E0A905859170C1F0A1E08130C7B07120B7B06120A240D160C1E0A549056E5
:208B8300170C1F0A20080C017B016B0320CA7B036B021E0872F00C7B07120B90977B0612A5
:208BA3000A25061F0890951706160C1E0A549056170C1F0A7B020A024D26D71E0816065BD4
:208BC30003811E0916072A03CD8CC28990891E0916072A03CD8CC2899089CD8BEC5B087B90
:208BE3000318072A03CD8CC28152065F1F051F03A6206B027B09484F496B01160B1E0990AF
:208C03005859170B1F0916051E0390585917051F030D0127067B06AA016B061E0572F00F2F
:208C23007B04120E90977B03120D250C1F05909517037B0CAA016B0C0A0226B81E0B16095F
:208C43005B06815F89897B0A977B0E421F037B09977B0E4272FB021F024FA9006B017B0A56
:208C6300977B0D4272FB021F024F19016B017B0A977B0C4272FB011F017B09977B0D427261
:208C8300FB011F017B08977B0E4272FB011F017B07977B0E429F1B016B017B0A977B0B4253
:208CA3009F1B016B017B09977B0C429F1B016B017B08977B0D429F1B016B019085858190C9
:0A8CC300535D2703535C81905C8130
:00000001FF

View File

@ -77,34 +77,6 @@ X P4 4 -200 -150 150 R 50 50 1 1 P
ENDDRAW
ENDDEF
#
# CONN_01X05
#
DEF CONN_01X05 J 0 40 Y N 1 F N
F0 "J" 0 300 50 H V C CNN
F1 "CONN_01X05" 100 0 50 V V C CNN
F2 "" 0 0 50 H I C CNN
F3 "" 0 0 50 H I C CNN
$FPLIST
Pin_Header_Straight_1X*
Pin_Header_Angled_1X*
Socket_Strip_Straight_1X*
Socket_Strip_Angled_1X*
$ENDFPLIST
DRAW
S -50 -195 10 -205 0 1 0 N
S -50 -95 10 -105 0 1 0 N
S -50 5 10 -5 0 1 0 N
S -50 105 10 95 0 1 0 N
S -50 205 10 195 0 1 0 N
S -50 250 50 -250 0 1 0 N
X P1 1 -200 200 150 R 50 50 1 1 P
X P2 2 -200 100 150 R 50 50 1 1 P
X P3 3 -200 0 150 R 50 50 1 1 P
X P4 4 -200 -100 150 R 50 50 1 1 P
X P5 5 -200 -200 150 R 50 50 1 1 P
ENDDRAW
ENDDEF
#
# CONN_02X10
#
DEF CONN_02X10 J 0 1 Y N 1 F N
@ -187,6 +159,32 @@ X ~ 2 0 -150 110 U 50 50 1 1 P
ENDDRAW
ENDDEF
#
# Conn_01x03
#
DEF Conn_01x03 J 0 40 Y N 1 F N
F0 "J" 0 200 50 H V C CNN
F1 "Conn_01x03" 0 -200 50 H V C CNN
F2 "" 0 0 50 H I C CNN
F3 "" 0 0 50 H I C CNN
$FPLIST
Connector*:*_??x*mm*
Connector*:*1x??x*mm*
Pin?Header?Straight?1X*
Pin?Header?Angled?1X*
Socket?Strip?Straight?1X*
Socket?Strip?Angled?1X*
$ENDFPLIST
DRAW
S -50 -95 0 -105 1 1 6 N
S -50 5 0 -5 1 1 6 N
S -50 105 0 95 1 1 6 N
S -50 150 50 -150 1 1 10 f
X Pin_1 1 -200 100 150 R 50 50 1 1 P
X Pin_2 2 -200 0 150 R 50 50 1 1 P
X Pin_3 3 -200 -100 150 R 50 50 1 1 P
ENDDRAW
ENDDEF
#
# GND-RESCUE-stepper
#
DEF ~GND-RESCUE-stepper #PWR 0 0 Y Y 1 F P
@ -283,6 +281,7 @@ DRAW
C 65 0 111 0 1 10 N
C 100 -70 11 0 1 0 F
C 100 70 11 0 1 0 F
P 2 0 1 0 2 0 10 0 N
P 2 0 1 0 30 -70 100 -70 N
P 2 0 1 10 30 -50 30 -90 N
P 2 0 1 0 30 0 100 0 N
@ -297,7 +296,7 @@ P 4 0 1 0 90 0 50 -15 50 15 90 0 F
P 4 0 1 0 100 -70 130 -70 130 70 100 70 N
P 4 0 1 0 110 -20 115 -15 145 -15 150 -10 N
P 4 0 1 0 130 -15 115 10 145 10 130 -15 N
X G 1 -200 0 210 R 50 50 1 1 I
X G 1 -200 0 200 R 50 50 1 1 I
X S 2 100 -200 100 U 50 50 1 1 P
X D 3 100 200 100 D 50 50 1 1 P
ENDDRAW
@ -332,7 +331,7 @@ F1 "SP0504BAHT" 300 25 50 H V L CNN
F2 "TO_SOT_Packages_SMD:SOT-23-5" 300 -50 50 H I L CNN
F3 "" 125 125 50 H I C CNN
$FPLIST
SOT-23*
SOT?23*
$ENDFPLIST
DRAW
X A 2 0 -200 100 U 50 50 0 0 I
@ -409,11 +408,11 @@ X PD4(HS)/TIM2_CH1[BEEP] 29 1400 550 300 L 50 50 1 1 T
ENDDRAW
ENDDEF
#
# SW_DIP_x03
# SW_DIP_x03-RESCUE-stepper
#
DEF SW_DIP_x03 SW 0 0 Y N 1 F N
DEF SW_DIP_x03-RESCUE-stepper SW 0 0 Y N 1 F N
F0 "SW" 0 350 50 H V C CNN
F1 "SW_DIP_x03" 0 -150 50 H V C CNN
F1 "SW_DIP_x03-RESCUE-stepper" 0 -150 50 H V C CNN
F2 "" 0 0 50 H I C CNN
F3 "" 0 0 50 H I C CNN
$FPLIST

View File

@ -1,22 +1,33 @@
EESchema-LIBRARY Version 2.3
#encoding utf-8
#
# LD1117S50CTR-RESCUE-stepper
# SW_DIP_x03-RESCUE-stepper
#
DEF LD1117S50CTR-RESCUE-stepper U 0 30 Y Y 1 F N
F0 "U" 0 250 50 H V C CNN
F1 "LD1117S50CTR-RESCUE-stepper" 0 200 50 H V C CNN
F2 "TO_SOT_Packages_SMD:SOT-223" 0 100 50 H I C CNN
DEF SW_DIP_x03-RESCUE-stepper SW 0 0 Y N 1 F N
F0 "SW" 0 350 50 H V C CNN
F1 "SW_DIP_x03-RESCUE-stepper" 0 -150 50 H V C CNN
F2 "" 0 0 50 H I C CNN
F3 "" 0 0 50 H I C CNN
$FPLIST
SOT223
SW?DIP?x3*
$ENDFPLIST
DRAW
S -250 -150 250 150 0 1 10 f
X GND 1 0 -250 100 U 50 50 1 1 W
X VO 2 400 50 150 L 50 50 1 1 w
X VI 3 -400 50 150 R 50 50 1 1 W
X VO 4 400 50 150 L 50 50 1 1 P N
C -80 0 20 0 0 0 N
C -80 100 20 0 0 0 N
C -80 200 20 0 0 0 N
C 80 0 20 0 0 0 N
C 80 100 20 0 0 0 N
C 80 200 20 0 0 0 N
P 2 0 0 0 -60 5 93 46 N
P 2 0 0 0 -60 105 93 146 N
P 2 0 0 0 -60 205 93 246 N
S -150 300 150 -100 0 1 10 f
X ~ 1 -300 200 200 R 50 50 1 1 I
X ~ 2 -300 100 200 R 50 50 1 1 I
X ~ 3 -300 0 200 R 50 50 1 1 I
X ~ 4 300 0 200 L 50 50 1 1 I
X ~ 5 300 100 200 L 50 50 1 1 I
X ~ 6 300 200 200 L 50 50 1 1 I
ENDDRAW
ENDDEF
#

View File

@ -1,9 +1,9 @@
(kicad_pcb (version 4) (host pcbnew 4.0.6)
(kicad_pcb (version 4) (host pcbnew 4.0.7)
(general
(links 93)
(no_connects 0)
(area 83.150001 22.145 142.071429 83.7)
(area 95.424999 25.924999 140.575001 77.075001)
(thickness 1.6)
(drawings 9)
(tracks 536)
@ -224,116 +224,6 @@
(uvia_drill 0.1)
)
(module Pin_Headers.pretty:Pin_Header_Angled_1x04_Pitch2.54mm placed (layer F.Cu) (tedit 5862ED52) (tstamp 599AD930)
(at 129.5 40.5)
(descr "Through hole angled pin header, 1x04, 2.54mm pitch, 6mm pin length, single row")
(tags "Through hole angled pin header THT 1x04 2.54mm single row")
(path /52FB0A49)
(fp_text reference P2 (at 4.315 -2.27) (layer F.SilkS)
(effects (font (size 1 1) (thickness 0.15)))
)
(fp_text value SWIM (at 4.315 9.89) (layer F.Fab)
(effects (font (size 1 1) (thickness 0.15)))
)
(fp_line (start 1.4 -1.27) (end 1.4 1.27) (layer F.Fab) (width 0.1))
(fp_line (start 1.4 1.27) (end 3.9 1.27) (layer F.Fab) (width 0.1))
(fp_line (start 3.9 1.27) (end 3.9 -1.27) (layer F.Fab) (width 0.1))
(fp_line (start 3.9 -1.27) (end 1.4 -1.27) (layer F.Fab) (width 0.1))
(fp_line (start 0 -0.32) (end 0 0.32) (layer F.Fab) (width 0.1))
(fp_line (start 0 0.32) (end 9.9 0.32) (layer F.Fab) (width 0.1))
(fp_line (start 9.9 0.32) (end 9.9 -0.32) (layer F.Fab) (width 0.1))
(fp_line (start 9.9 -0.32) (end 0 -0.32) (layer F.Fab) (width 0.1))
(fp_line (start 1.4 1.27) (end 1.4 3.81) (layer F.Fab) (width 0.1))
(fp_line (start 1.4 3.81) (end 3.9 3.81) (layer F.Fab) (width 0.1))
(fp_line (start 3.9 3.81) (end 3.9 1.27) (layer F.Fab) (width 0.1))
(fp_line (start 3.9 1.27) (end 1.4 1.27) (layer F.Fab) (width 0.1))
(fp_line (start 0 2.22) (end 0 2.86) (layer F.Fab) (width 0.1))
(fp_line (start 0 2.86) (end 9.9 2.86) (layer F.Fab) (width 0.1))
(fp_line (start 9.9 2.86) (end 9.9 2.22) (layer F.Fab) (width 0.1))
(fp_line (start 9.9 2.22) (end 0 2.22) (layer F.Fab) (width 0.1))
(fp_line (start 1.4 3.81) (end 1.4 6.35) (layer F.Fab) (width 0.1))
(fp_line (start 1.4 6.35) (end 3.9 6.35) (layer F.Fab) (width 0.1))
(fp_line (start 3.9 6.35) (end 3.9 3.81) (layer F.Fab) (width 0.1))
(fp_line (start 3.9 3.81) (end 1.4 3.81) (layer F.Fab) (width 0.1))
(fp_line (start 0 4.76) (end 0 5.4) (layer F.Fab) (width 0.1))
(fp_line (start 0 5.4) (end 9.9 5.4) (layer F.Fab) (width 0.1))
(fp_line (start 9.9 5.4) (end 9.9 4.76) (layer F.Fab) (width 0.1))
(fp_line (start 9.9 4.76) (end 0 4.76) (layer F.Fab) (width 0.1))
(fp_line (start 1.4 6.35) (end 1.4 8.89) (layer F.Fab) (width 0.1))
(fp_line (start 1.4 8.89) (end 3.9 8.89) (layer F.Fab) (width 0.1))
(fp_line (start 3.9 8.89) (end 3.9 6.35) (layer F.Fab) (width 0.1))
(fp_line (start 3.9 6.35) (end 1.4 6.35) (layer F.Fab) (width 0.1))
(fp_line (start 0 7.3) (end 0 7.94) (layer F.Fab) (width 0.1))
(fp_line (start 0 7.94) (end 9.9 7.94) (layer F.Fab) (width 0.1))
(fp_line (start 9.9 7.94) (end 9.9 7.3) (layer F.Fab) (width 0.1))
(fp_line (start 9.9 7.3) (end 0 7.3) (layer F.Fab) (width 0.1))
(fp_line (start 1.28 -1.39) (end 1.28 1.27) (layer F.SilkS) (width 0.12))
(fp_line (start 1.28 1.27) (end 4.02 1.27) (layer F.SilkS) (width 0.12))
(fp_line (start 4.02 1.27) (end 4.02 -1.39) (layer F.SilkS) (width 0.12))
(fp_line (start 4.02 -1.39) (end 1.28 -1.39) (layer F.SilkS) (width 0.12))
(fp_line (start 4.02 -0.44) (end 4.02 0.44) (layer F.SilkS) (width 0.12))
(fp_line (start 4.02 0.44) (end 10.02 0.44) (layer F.SilkS) (width 0.12))
(fp_line (start 10.02 0.44) (end 10.02 -0.44) (layer F.SilkS) (width 0.12))
(fp_line (start 10.02 -0.44) (end 4.02 -0.44) (layer F.SilkS) (width 0.12))
(fp_line (start 0.97 -0.44) (end 1.28 -0.44) (layer F.SilkS) (width 0.12))
(fp_line (start 0.97 0.44) (end 1.28 0.44) (layer F.SilkS) (width 0.12))
(fp_line (start 4.02 -0.32) (end 10.02 -0.32) (layer F.SilkS) (width 0.12))
(fp_line (start 4.02 -0.2) (end 10.02 -0.2) (layer F.SilkS) (width 0.12))
(fp_line (start 4.02 -0.08) (end 10.02 -0.08) (layer F.SilkS) (width 0.12))
(fp_line (start 4.02 0.04) (end 10.02 0.04) (layer F.SilkS) (width 0.12))
(fp_line (start 4.02 0.16) (end 10.02 0.16) (layer F.SilkS) (width 0.12))
(fp_line (start 4.02 0.28) (end 10.02 0.28) (layer F.SilkS) (width 0.12))
(fp_line (start 4.02 0.4) (end 10.02 0.4) (layer F.SilkS) (width 0.12))
(fp_line (start 1.28 1.27) (end 1.28 3.81) (layer F.SilkS) (width 0.12))
(fp_line (start 1.28 3.81) (end 4.02 3.81) (layer F.SilkS) (width 0.12))
(fp_line (start 4.02 3.81) (end 4.02 1.27) (layer F.SilkS) (width 0.12))
(fp_line (start 4.02 1.27) (end 1.28 1.27) (layer F.SilkS) (width 0.12))
(fp_line (start 4.02 2.1) (end 4.02 2.98) (layer F.SilkS) (width 0.12))
(fp_line (start 4.02 2.98) (end 10.02 2.98) (layer F.SilkS) (width 0.12))
(fp_line (start 10.02 2.98) (end 10.02 2.1) (layer F.SilkS) (width 0.12))
(fp_line (start 10.02 2.1) (end 4.02 2.1) (layer F.SilkS) (width 0.12))
(fp_line (start 0.97 2.1) (end 1.28 2.1) (layer F.SilkS) (width 0.12))
(fp_line (start 0.97 2.98) (end 1.28 2.98) (layer F.SilkS) (width 0.12))
(fp_line (start 1.28 3.81) (end 1.28 6.35) (layer F.SilkS) (width 0.12))
(fp_line (start 1.28 6.35) (end 4.02 6.35) (layer F.SilkS) (width 0.12))
(fp_line (start 4.02 6.35) (end 4.02 3.81) (layer F.SilkS) (width 0.12))
(fp_line (start 4.02 3.81) (end 1.28 3.81) (layer F.SilkS) (width 0.12))
(fp_line (start 4.02 4.64) (end 4.02 5.52) (layer F.SilkS) (width 0.12))
(fp_line (start 4.02 5.52) (end 10.02 5.52) (layer F.SilkS) (width 0.12))
(fp_line (start 10.02 5.52) (end 10.02 4.64) (layer F.SilkS) (width 0.12))
(fp_line (start 10.02 4.64) (end 4.02 4.64) (layer F.SilkS) (width 0.12))
(fp_line (start 0.97 4.64) (end 1.28 4.64) (layer F.SilkS) (width 0.12))
(fp_line (start 0.97 5.52) (end 1.28 5.52) (layer F.SilkS) (width 0.12))
(fp_line (start 1.28 6.35) (end 1.28 9.01) (layer F.SilkS) (width 0.12))
(fp_line (start 1.28 9.01) (end 4.02 9.01) (layer F.SilkS) (width 0.12))
(fp_line (start 4.02 9.01) (end 4.02 6.35) (layer F.SilkS) (width 0.12))
(fp_line (start 4.02 6.35) (end 1.28 6.35) (layer F.SilkS) (width 0.12))
(fp_line (start 4.02 7.18) (end 4.02 8.06) (layer F.SilkS) (width 0.12))
(fp_line (start 4.02 8.06) (end 10.02 8.06) (layer F.SilkS) (width 0.12))
(fp_line (start 10.02 8.06) (end 10.02 7.18) (layer F.SilkS) (width 0.12))
(fp_line (start 10.02 7.18) (end 4.02 7.18) (layer F.SilkS) (width 0.12))
(fp_line (start 0.97 7.18) (end 1.28 7.18) (layer F.SilkS) (width 0.12))
(fp_line (start 0.97 8.06) (end 1.28 8.06) (layer F.SilkS) (width 0.12))
(fp_line (start -1.27 0) (end -1.27 -1.27) (layer F.SilkS) (width 0.12))
(fp_line (start -1.27 -1.27) (end 0 -1.27) (layer F.SilkS) (width 0.12))
(fp_line (start -1.6 -1.6) (end -1.6 9.2) (layer F.CrtYd) (width 0.05))
(fp_line (start -1.6 9.2) (end 10.2 9.2) (layer F.CrtYd) (width 0.05))
(fp_line (start 10.2 9.2) (end 10.2 -1.6) (layer F.CrtYd) (width 0.05))
(fp_line (start 10.2 -1.6) (end -1.6 -1.6) (layer F.CrtYd) (width 0.05))
(pad 1 thru_hole rect (at 0 0) (size 1.7 1.7) (drill 1) (layers *.Cu *.Mask)
(net 4 /NRST))
(pad 2 thru_hole oval (at 0 2.54) (size 1.7 1.7) (drill 1) (layers *.Cu *.Mask)
(net 26 /SWIM/PD1))
(pad 3 thru_hole oval (at 0 5.08) (size 1.7 1.7) (drill 1) (layers *.Cu *.Mask)
(net 1 GND))
(pad 4 thru_hole oval (at 0 7.62) (size 1.7 1.7) (drill 1) (layers *.Cu *.Mask))
(model Pin_Headers.3dshapes/Pin_Header_Angled_1x04_Pitch2.54mm.wrl
(at (xyz 0 -0.15 0))
(scale (xyz 1 1 1))
(rotate (xyz 0 0 90))
)
)
(module Resistors_SMD.pretty:R_0805_HandSoldering (layer F.Cu) (tedit 58AADA1D) (tstamp 599AD9C3)
(at 114.3 70.485)
(descr "Resistor SMD 0805, hand soldering")
@ -1697,6 +1587,89 @@
(pad "" thru_hole circle (at 0 0) (size 3 3) (drill 3) (layers *.Cu F.SilkS))
)
(module Connector_PinHeader_2.54mm.pretty:PinHeader_1x03_P2.54mm_Horizontal (layer F.Cu) (tedit 59FED5CB) (tstamp 5BB2DD41)
(at 129.5 40.5)
(descr "Through hole angled pin header, 1x03, 2.54mm pitch, 6mm pin length, single row")
(tags "Through hole angled pin header THT 1x03 2.54mm single row")
(path /5BB234EF)
(fp_text reference P2 (at 4.385 -2.27) (layer F.SilkS)
(effects (font (size 1 1) (thickness 0.15)))
)
(fp_text value SWIM (at 4.385 7.35) (layer F.Fab)
(effects (font (size 1 1) (thickness 0.15)))
)
(fp_line (start 2.135 -1.27) (end 4.04 -1.27) (layer F.Fab) (width 0.1))
(fp_line (start 4.04 -1.27) (end 4.04 6.35) (layer F.Fab) (width 0.1))
(fp_line (start 4.04 6.35) (end 1.5 6.35) (layer F.Fab) (width 0.1))
(fp_line (start 1.5 6.35) (end 1.5 -0.635) (layer F.Fab) (width 0.1))
(fp_line (start 1.5 -0.635) (end 2.135 -1.27) (layer F.Fab) (width 0.1))
(fp_line (start -0.32 -0.32) (end 1.5 -0.32) (layer F.Fab) (width 0.1))
(fp_line (start -0.32 -0.32) (end -0.32 0.32) (layer F.Fab) (width 0.1))
(fp_line (start -0.32 0.32) (end 1.5 0.32) (layer F.Fab) (width 0.1))
(fp_line (start 4.04 -0.32) (end 10.04 -0.32) (layer F.Fab) (width 0.1))
(fp_line (start 10.04 -0.32) (end 10.04 0.32) (layer F.Fab) (width 0.1))
(fp_line (start 4.04 0.32) (end 10.04 0.32) (layer F.Fab) (width 0.1))
(fp_line (start -0.32 2.22) (end 1.5 2.22) (layer F.Fab) (width 0.1))
(fp_line (start -0.32 2.22) (end -0.32 2.86) (layer F.Fab) (width 0.1))
(fp_line (start -0.32 2.86) (end 1.5 2.86) (layer F.Fab) (width 0.1))
(fp_line (start 4.04 2.22) (end 10.04 2.22) (layer F.Fab) (width 0.1))
(fp_line (start 10.04 2.22) (end 10.04 2.86) (layer F.Fab) (width 0.1))
(fp_line (start 4.04 2.86) (end 10.04 2.86) (layer F.Fab) (width 0.1))
(fp_line (start -0.32 4.76) (end 1.5 4.76) (layer F.Fab) (width 0.1))
(fp_line (start -0.32 4.76) (end -0.32 5.4) (layer F.Fab) (width 0.1))
(fp_line (start -0.32 5.4) (end 1.5 5.4) (layer F.Fab) (width 0.1))
(fp_line (start 4.04 4.76) (end 10.04 4.76) (layer F.Fab) (width 0.1))
(fp_line (start 10.04 4.76) (end 10.04 5.4) (layer F.Fab) (width 0.1))
(fp_line (start 4.04 5.4) (end 10.04 5.4) (layer F.Fab) (width 0.1))
(fp_line (start 1.44 -1.33) (end 1.44 6.41) (layer F.SilkS) (width 0.12))
(fp_line (start 1.44 6.41) (end 4.1 6.41) (layer F.SilkS) (width 0.12))
(fp_line (start 4.1 6.41) (end 4.1 -1.33) (layer F.SilkS) (width 0.12))
(fp_line (start 4.1 -1.33) (end 1.44 -1.33) (layer F.SilkS) (width 0.12))
(fp_line (start 4.1 -0.38) (end 10.1 -0.38) (layer F.SilkS) (width 0.12))
(fp_line (start 10.1 -0.38) (end 10.1 0.38) (layer F.SilkS) (width 0.12))
(fp_line (start 10.1 0.38) (end 4.1 0.38) (layer F.SilkS) (width 0.12))
(fp_line (start 4.1 -0.32) (end 10.1 -0.32) (layer F.SilkS) (width 0.12))
(fp_line (start 4.1 -0.2) (end 10.1 -0.2) (layer F.SilkS) (width 0.12))
(fp_line (start 4.1 -0.08) (end 10.1 -0.08) (layer F.SilkS) (width 0.12))
(fp_line (start 4.1 0.04) (end 10.1 0.04) (layer F.SilkS) (width 0.12))
(fp_line (start 4.1 0.16) (end 10.1 0.16) (layer F.SilkS) (width 0.12))
(fp_line (start 4.1 0.28) (end 10.1 0.28) (layer F.SilkS) (width 0.12))
(fp_line (start 1.11 -0.38) (end 1.44 -0.38) (layer F.SilkS) (width 0.12))
(fp_line (start 1.11 0.38) (end 1.44 0.38) (layer F.SilkS) (width 0.12))
(fp_line (start 1.44 1.27) (end 4.1 1.27) (layer F.SilkS) (width 0.12))
(fp_line (start 4.1 2.16) (end 10.1 2.16) (layer F.SilkS) (width 0.12))
(fp_line (start 10.1 2.16) (end 10.1 2.92) (layer F.SilkS) (width 0.12))
(fp_line (start 10.1 2.92) (end 4.1 2.92) (layer F.SilkS) (width 0.12))
(fp_line (start 1.042929 2.16) (end 1.44 2.16) (layer F.SilkS) (width 0.12))
(fp_line (start 1.042929 2.92) (end 1.44 2.92) (layer F.SilkS) (width 0.12))
(fp_line (start 1.44 3.81) (end 4.1 3.81) (layer F.SilkS) (width 0.12))
(fp_line (start 4.1 4.7) (end 10.1 4.7) (layer F.SilkS) (width 0.12))
(fp_line (start 10.1 4.7) (end 10.1 5.46) (layer F.SilkS) (width 0.12))
(fp_line (start 10.1 5.46) (end 4.1 5.46) (layer F.SilkS) (width 0.12))
(fp_line (start 1.042929 4.7) (end 1.44 4.7) (layer F.SilkS) (width 0.12))
(fp_line (start 1.042929 5.46) (end 1.44 5.46) (layer F.SilkS) (width 0.12))
(fp_line (start -1.27 0) (end -1.27 -1.27) (layer F.SilkS) (width 0.12))
(fp_line (start -1.27 -1.27) (end 0 -1.27) (layer F.SilkS) (width 0.12))
(fp_line (start -1.8 -1.8) (end -1.8 6.85) (layer F.CrtYd) (width 0.05))
(fp_line (start -1.8 6.85) (end 10.55 6.85) (layer F.CrtYd) (width 0.05))
(fp_line (start 10.55 6.85) (end 10.55 -1.8) (layer F.CrtYd) (width 0.05))
(fp_line (start 10.55 -1.8) (end -1.8 -1.8) (layer F.CrtYd) (width 0.05))
(fp_text user %R (at 2.77 2.54 90) (layer F.Fab)
(effects (font (size 1 1) (thickness 0.15)))
)
(pad 1 thru_hole rect (at 0 0) (size 1.7 1.7) (drill 1) (layers *.Cu *.Mask)
(net 4 /NRST))
(pad 2 thru_hole oval (at 0 2.54) (size 1.7 1.7) (drill 1) (layers *.Cu *.Mask)
(net 26 /SWIM/PD1))
(pad 3 thru_hole oval (at 0 5.08) (size 1.7 1.7) (drill 1) (layers *.Cu *.Mask)
(net 1 GND))
(model ${KISYS3DMOD}/Connector_PinHeader_2.54mm.3dshapes/PinHeader_1x03_P2.54mm_Horizontal.wrl
(at (xyz 0 0 0))
(scale (xyz 1 1 1))
(rotate (xyz 0 0 0))
)
)
(dimension 51 (width 0.3) (layer Dwgs.User)
(gr_text "51.000 mm" (at 89.65 51.5 270) (layer Dwgs.User)
(effects (font (size 1.5 1.5) (thickness 0.3)))
@ -2401,16 +2374,14 @@
(xy 130.771645 44.813076) (xy 130.381358 44.384817) (xy 130.238447 44.317702) (xy 130.579147 44.090054) (xy 130.901054 43.608285)
(xy 131.014093 43.04) (xy 130.901054 42.471715) (xy 130.579147 41.989946) (xy 130.537548 41.96215) (xy 130.585317 41.953162)
(xy 130.801441 41.81409) (xy 130.946431 41.60189) (xy 130.990352 41.385) (xy 131.44642 41.385) (xy 133.354 43.292579)
(xy 133.354 48.274421) (xy 132.22142 49.407) (xy 130.224531 49.407) (xy 130.579147 49.170054) (xy 130.901054 48.688285)
(xy 131.014093 48.12) (xy 130.901054 47.551715) (xy 130.579147 47.069946) (xy 130.238447 46.842298) (xy 130.381358 46.775183)
(xy 130.771645 46.346924) (xy 130.941476 45.93689) (xy 130.820155 45.707) (xy 129.627 45.707) (xy 129.627 45.727)
(xy 129.373 45.727) (xy 129.373 45.707) (xy 128.179845 45.707) (xy 128.058524 45.93689) (xy 128.228355 46.346924)
(xy 128.618642 46.775183) (xy 128.761553 46.842298) (xy 128.420853 47.069946) (xy 128.098946 47.551715) (xy 127.985907 48.12)
(xy 128.098946 48.688285) (xy 128.420853 49.170054) (xy 128.775469 49.407) (xy 127.381005 49.407) (xy 127.381 49.406999)
(xy 127.098516 49.46319) (xy 127.042325 49.474367) (xy 126.75521 49.66621) (xy 126.755208 49.666213) (xy 125.73921 50.68221)
(xy 125.547367 50.969325) (xy 125.547367 50.969326) (xy 125.479999 51.308) (xy 125.48 51.308005) (xy 125.48 51.957421)
(xy 125.212434 52.224987) (xy 125.218001 52.197) (xy 125.218 52.196995) (xy 125.218 37.06958) (xy 128.065079 34.2225)
(xy 128.073192 34.2225)
(xy 133.354 48.274421) (xy 132.22142 49.407) (xy 127.381005 49.407) (xy 127.381 49.406999) (xy 127.098516 49.46319)
(xy 127.042325 49.474367) (xy 126.75521 49.66621) (xy 126.755208 49.666213) (xy 125.73921 50.68221) (xy 125.547367 50.969325)
(xy 125.547367 50.969326) (xy 125.479999 51.308) (xy 125.48 51.308005) (xy 125.48 51.957421) (xy 125.212434 52.224987)
(xy 125.218001 52.197) (xy 125.218 52.196995) (xy 125.218 45.93689) (xy 128.058524 45.93689) (xy 128.228355 46.346924)
(xy 128.618642 46.775183) (xy 129.143108 47.021486) (xy 129.373 46.900819) (xy 129.373 45.707) (xy 129.627 45.707)
(xy 129.627 46.900819) (xy 129.856892 47.021486) (xy 130.381358 46.775183) (xy 130.771645 46.346924) (xy 130.941476 45.93689)
(xy 130.820155 45.707) (xy 129.627 45.707) (xy 129.373 45.707) (xy 128.179845 45.707) (xy 128.058524 45.93689)
(xy 125.218 45.93689) (xy 125.218 37.06958) (xy 128.065079 34.2225) (xy 128.073192 34.2225)
)
)
(filled_polygon
@ -2579,60 +2550,57 @@
(xy 130.801441 53.81409) (xy 130.946431 53.60189) (xy 130.99744 53.35) (xy 130.99744 51.65) (xy 130.953162 51.414683)
(xy 130.81409 51.198559) (xy 130.60189 51.053569) (xy 130.35 51.00256) (xy 128.65 51.00256) (xy 128.414683 51.046838)
(xy 128.266 51.142513) (xy 128.266 50.419) (xy 128.198633 50.080325) (xy 128.00679 49.79321) (xy 128.006787 49.793208)
(xy 126.33358 48.12) (xy 127.985907 48.12) (xy 128.098946 48.688285) (xy 128.420853 49.170054) (xy 128.902622 49.491961)
(xy 129.470907 49.605) (xy 129.529093 49.605) (xy 130.097378 49.491961) (xy 130.579147 49.170054) (xy 130.901054 48.688285)
(xy 131.014093 48.12) (xy 130.901054 47.551715) (xy 130.579147 47.069946) (xy 130.238447 46.842298) (xy 130.381358 46.775183)
(xy 130.771645 46.346924) (xy 130.941476 45.93689) (xy 130.820155 45.707) (xy 129.627 45.707) (xy 129.627 45.727)
(xy 129.373 45.727) (xy 129.373 45.707) (xy 128.179845 45.707) (xy 128.058524 45.93689) (xy 128.228355 46.346924)
(xy 128.618642 46.775183) (xy 128.761553 46.842298) (xy 128.420853 47.069946) (xy 128.098946 47.551715) (xy 127.985907 48.12)
(xy 126.33358 48.12) (xy 124.45079 46.23721) (xy 124.214736 46.079485) (xy 124.163675 46.045367) (xy 124.107484 46.03419)
(xy 123.825 45.977999) (xy 123.824995 45.978) (xy 122.358523 45.978) (xy 122.070564 45.689539) (xy 121.561702 45.478241)
(xy 121.010715 45.47776) (xy 120.501485 45.688169) (xy 120.111539 46.077436) (xy 119.900241 46.586298) (xy 119.89976 47.137285)
(xy 120.110169 47.646515) (xy 120.499436 48.036461) (xy 121.008298 48.247759) (xy 121.559285 48.24824) (xy 122.068515 48.037831)
(xy 122.358852 47.748) (xy 123.45842 47.748) (xy 123.97442 48.264) (xy 117.515 48.264) (xy 117.515 47.48575)
(xy 117.35625 47.327) (xy 116.707 47.327) (xy 116.707 47.347) (xy 116.453 47.347) (xy 116.453 47.327)
(xy 116.433 47.327) (xy 116.433 47.073) (xy 116.453 47.073) (xy 116.453 45.72375) (xy 116.707 45.72375)
(xy 116.707 47.073) (xy 117.35625 47.073) (xy 117.515 46.91425) (xy 117.515 46.073691) (xy 117.418327 45.840302)
(xy 117.239699 45.661673) (xy 117.00631 45.565) (xy 116.86575 45.565) (xy 116.707 45.72375) (xy 116.453 45.72375)
(xy 116.29425 45.565) (xy 116.15369 45.565) (xy 115.936878 45.654806) (xy 115.86189 45.603569) (xy 115.61 45.55256)
(xy 115.01 45.55256) (xy 114.925 45.568554) (xy 114.925 45.45758) (xy 115.047579 45.335) (xy 119.887995 45.335)
(xy 119.888 45.335001) (xy 120.170484 45.27881) (xy 120.226675 45.267633) (xy 120.51379 45.07579) (xy 120.513791 45.075789)
(xy 121.651579 43.938) (xy 126.053477 43.938) (xy 126.341436 44.226461) (xy 126.850298 44.437759) (xy 127.401285 44.43824)
(xy 127.910515 44.227831) (xy 128.271878 43.867097) (xy 128.420853 44.090054) (xy 128.761553 44.317702) (xy 128.618642 44.384817)
(xy 128.228355 44.813076) (xy 128.058524 45.22311) (xy 128.179845 45.453) (xy 129.373 45.453) (xy 129.373 45.433)
(xy 129.627 45.433) (xy 129.627 45.453) (xy 130.820155 45.453) (xy 130.941476 45.22311) (xy 130.771645 44.813076)
(xy 130.381358 44.384817) (xy 130.238447 44.317702) (xy 130.579147 44.090054) (xy 130.901054 43.608285) (xy 131.014093 43.04)
(xy 130.901054 42.471715) (xy 130.579147 41.989946) (xy 130.537548 41.96215) (xy 130.585317 41.953162) (xy 130.801441 41.81409)
(xy 130.946431 41.60189) (xy 130.99744 41.35) (xy 130.99744 39.65) (xy 130.953162 39.414683) (xy 130.81409 39.198559)
(xy 130.60189 39.053569) (xy 130.35 39.00256) (xy 128.65 39.00256) (xy 128.414683 39.046838) (xy 128.198559 39.18591)
(xy 128.053569 39.39811) (xy 128.00256 39.65) (xy 128.00256 41.35) (xy 128.046838 41.585317) (xy 128.18591 41.801441)
(xy 128.39811 41.946431) (xy 128.465541 41.960086) (xy 128.420853 41.989946) (xy 128.26124 42.228824) (xy 127.912564 41.879539)
(xy 127.403702 41.668241) (xy 126.852715 41.66776) (xy 126.343485 41.878169) (xy 126.053148 42.168) (xy 121.285 42.168)
(xy 120.946325 42.235367) (xy 120.65921 42.42721) (xy 120.659208 42.427213) (xy 119.52142 43.565) (xy 114.681005 43.565)
(xy 114.681 43.564999) (xy 114.398516 43.62119) (xy 114.342325 43.632367) (xy 114.05521 43.82421) (xy 114.055208 43.824213)
(xy 113.41421 44.46521) (xy 113.222367 44.752325) (xy 113.21119 44.808516) (xy 113.154999 45.091) (xy 113.155 45.091005)
(xy 113.155 45.569773) (xy 113.07 45.55256) (xy 112.47 45.55256) (xy 112.234683 45.596838) (xy 112.135472 45.660678)
(xy 112.05189 45.603569) (xy 111.8 45.55256) (xy 111.2 45.55256) (xy 110.964683 45.596838) (xy 110.865472 45.660678)
(xy 110.78189 45.603569) (xy 110.53 45.55256) (xy 109.93 45.55256) (xy 109.694683 45.596838) (xy 109.595472 45.660678)
(xy 109.51189 45.603569) (xy 109.26 45.55256) (xy 108.66 45.55256) (xy 108.424683 45.596838) (xy 108.325472 45.660678)
(xy 108.24189 45.603569) (xy 107.99 45.55256) (xy 107.39 45.55256) (xy 107.154683 45.596838) (xy 107.055472 45.660678)
(xy 106.97189 45.603569) (xy 106.72 45.55256) (xy 106.12 45.55256) (xy 105.884683 45.596838) (xy 105.668559 45.73591)
(xy 105.523569 45.94811) (xy 105.47256 46.2) (xy 105.47256 46.315) (xy 104.946005 46.315) (xy 104.946 46.314999)
(xy 104.663516 46.37119) (xy 104.607325 46.382367) (xy 104.32021 46.57421) (xy 104.320208 46.574213) (xy 100.59321 50.30121)
(xy 100.401367 50.588325) (xy 100.401367 50.588326) (xy 100.333999 50.927) (xy 96.21 50.927) (xy 96.21 40.406285)
(xy 96.53176 40.406285) (xy 96.742169 40.915515) (xy 97.131436 41.305461) (xy 97.640298 41.516759) (xy 98.191285 41.51724)
(xy 98.700515 41.306831) (xy 98.990852 41.017) (xy 100.653477 41.017) (xy 100.941436 41.305461) (xy 101.450298 41.516759)
(xy 101.860538 41.517117) (xy 102.239 41.895579) (xy 102.239 42.106477) (xy 101.950539 42.394436) (xy 101.739241 42.903298)
(xy 101.73876 43.454285) (xy 101.949169 43.963515) (xy 102.338436 44.353461) (xy 102.847298 44.564759) (xy 103.398285 44.56524)
(xy 103.907515 44.354831) (xy 104.297461 43.965564) (xy 104.508759 43.456702) (xy 104.50924 42.905715) (xy 104.298831 42.396485)
(xy 104.009 42.106148) (xy 104.009 41.529) (xy 103.941633 41.190325) (xy 103.74979 40.90321) (xy 103.749787 40.903208)
(xy 103.111884 40.265305) (xy 103.11224 39.857715) (xy 102.901831 39.348485) (xy 102.512564 38.958539) (xy 102.003702 38.747241)
(xy 101.452715 38.74676) (xy 100.943485 38.957169) (xy 100.653148 39.247) (xy 98.990523 39.247) (xy 98.702564 38.958539)
(xy 98.193702 38.747241) (xy 97.642715 38.74676) (xy 97.133485 38.957169) (xy 96.743539 39.346436) (xy 96.532241 39.855298)
(xy 96.53176 40.406285) (xy 96.21 40.406285) (xy 96.21 29.28575) (xy 97.3 29.28575) (xy 97.3 31.66631)
(xy 97.396673 31.899699) (xy 97.575302 32.078327) (xy 97.808691 32.175) (xy 98.28425 32.175) (xy 98.443 32.01625)
(xy 98.443 29.127) (xy 97.45875 29.127) (xy 97.3 29.28575) (xy 96.21 29.28575) (xy 96.21 26.71)
(xy 97.3 26.71)
(xy 124.45079 46.23721) (xy 124.214736 46.079485) (xy 124.163675 46.045367) (xy 124.107484 46.03419) (xy 123.825 45.977999)
(xy 123.824995 45.978) (xy 122.358523 45.978) (xy 122.317485 45.93689) (xy 128.058524 45.93689) (xy 128.228355 46.346924)
(xy 128.618642 46.775183) (xy 129.143108 47.021486) (xy 129.373 46.900819) (xy 129.373 45.707) (xy 129.627 45.707)
(xy 129.627 46.900819) (xy 129.856892 47.021486) (xy 130.381358 46.775183) (xy 130.771645 46.346924) (xy 130.941476 45.93689)
(xy 130.820155 45.707) (xy 129.627 45.707) (xy 129.373 45.707) (xy 128.179845 45.707) (xy 128.058524 45.93689)
(xy 122.317485 45.93689) (xy 122.070564 45.689539) (xy 121.561702 45.478241) (xy 121.010715 45.47776) (xy 120.501485 45.688169)
(xy 120.111539 46.077436) (xy 119.900241 46.586298) (xy 119.89976 47.137285) (xy 120.110169 47.646515) (xy 120.499436 48.036461)
(xy 121.008298 48.247759) (xy 121.559285 48.24824) (xy 122.068515 48.037831) (xy 122.358852 47.748) (xy 123.45842 47.748)
(xy 123.97442 48.264) (xy 117.515 48.264) (xy 117.515 47.48575) (xy 117.35625 47.327) (xy 116.707 47.327)
(xy 116.707 47.347) (xy 116.453 47.347) (xy 116.453 47.327) (xy 116.433 47.327) (xy 116.433 47.073)
(xy 116.453 47.073) (xy 116.453 45.72375) (xy 116.707 45.72375) (xy 116.707 47.073) (xy 117.35625 47.073)
(xy 117.515 46.91425) (xy 117.515 46.073691) (xy 117.418327 45.840302) (xy 117.239699 45.661673) (xy 117.00631 45.565)
(xy 116.86575 45.565) (xy 116.707 45.72375) (xy 116.453 45.72375) (xy 116.29425 45.565) (xy 116.15369 45.565)
(xy 115.936878 45.654806) (xy 115.86189 45.603569) (xy 115.61 45.55256) (xy 115.01 45.55256) (xy 114.925 45.568554)
(xy 114.925 45.45758) (xy 115.047579 45.335) (xy 119.887995 45.335) (xy 119.888 45.335001) (xy 120.170484 45.27881)
(xy 120.226675 45.267633) (xy 120.51379 45.07579) (xy 120.513791 45.075789) (xy 121.651579 43.938) (xy 126.053477 43.938)
(xy 126.341436 44.226461) (xy 126.850298 44.437759) (xy 127.401285 44.43824) (xy 127.910515 44.227831) (xy 128.271878 43.867097)
(xy 128.420853 44.090054) (xy 128.761553 44.317702) (xy 128.618642 44.384817) (xy 128.228355 44.813076) (xy 128.058524 45.22311)
(xy 128.179845 45.453) (xy 129.373 45.453) (xy 129.373 45.433) (xy 129.627 45.433) (xy 129.627 45.453)
(xy 130.820155 45.453) (xy 130.941476 45.22311) (xy 130.771645 44.813076) (xy 130.381358 44.384817) (xy 130.238447 44.317702)
(xy 130.579147 44.090054) (xy 130.901054 43.608285) (xy 131.014093 43.04) (xy 130.901054 42.471715) (xy 130.579147 41.989946)
(xy 130.537548 41.96215) (xy 130.585317 41.953162) (xy 130.801441 41.81409) (xy 130.946431 41.60189) (xy 130.99744 41.35)
(xy 130.99744 39.65) (xy 130.953162 39.414683) (xy 130.81409 39.198559) (xy 130.60189 39.053569) (xy 130.35 39.00256)
(xy 128.65 39.00256) (xy 128.414683 39.046838) (xy 128.198559 39.18591) (xy 128.053569 39.39811) (xy 128.00256 39.65)
(xy 128.00256 41.35) (xy 128.046838 41.585317) (xy 128.18591 41.801441) (xy 128.39811 41.946431) (xy 128.465541 41.960086)
(xy 128.420853 41.989946) (xy 128.26124 42.228824) (xy 127.912564 41.879539) (xy 127.403702 41.668241) (xy 126.852715 41.66776)
(xy 126.343485 41.878169) (xy 126.053148 42.168) (xy 121.285 42.168) (xy 120.946325 42.235367) (xy 120.65921 42.42721)
(xy 120.659208 42.427213) (xy 119.52142 43.565) (xy 114.681005 43.565) (xy 114.681 43.564999) (xy 114.398516 43.62119)
(xy 114.342325 43.632367) (xy 114.05521 43.82421) (xy 114.055208 43.824213) (xy 113.41421 44.46521) (xy 113.222367 44.752325)
(xy 113.21119 44.808516) (xy 113.154999 45.091) (xy 113.155 45.091005) (xy 113.155 45.569773) (xy 113.07 45.55256)
(xy 112.47 45.55256) (xy 112.234683 45.596838) (xy 112.135472 45.660678) (xy 112.05189 45.603569) (xy 111.8 45.55256)
(xy 111.2 45.55256) (xy 110.964683 45.596838) (xy 110.865472 45.660678) (xy 110.78189 45.603569) (xy 110.53 45.55256)
(xy 109.93 45.55256) (xy 109.694683 45.596838) (xy 109.595472 45.660678) (xy 109.51189 45.603569) (xy 109.26 45.55256)
(xy 108.66 45.55256) (xy 108.424683 45.596838) (xy 108.325472 45.660678) (xy 108.24189 45.603569) (xy 107.99 45.55256)
(xy 107.39 45.55256) (xy 107.154683 45.596838) (xy 107.055472 45.660678) (xy 106.97189 45.603569) (xy 106.72 45.55256)
(xy 106.12 45.55256) (xy 105.884683 45.596838) (xy 105.668559 45.73591) (xy 105.523569 45.94811) (xy 105.47256 46.2)
(xy 105.47256 46.315) (xy 104.946005 46.315) (xy 104.946 46.314999) (xy 104.663516 46.37119) (xy 104.607325 46.382367)
(xy 104.32021 46.57421) (xy 104.320208 46.574213) (xy 100.59321 50.30121) (xy 100.401367 50.588325) (xy 100.401367 50.588326)
(xy 100.333999 50.927) (xy 96.21 50.927) (xy 96.21 40.406285) (xy 96.53176 40.406285) (xy 96.742169 40.915515)
(xy 97.131436 41.305461) (xy 97.640298 41.516759) (xy 98.191285 41.51724) (xy 98.700515 41.306831) (xy 98.990852 41.017)
(xy 100.653477 41.017) (xy 100.941436 41.305461) (xy 101.450298 41.516759) (xy 101.860538 41.517117) (xy 102.239 41.895579)
(xy 102.239 42.106477) (xy 101.950539 42.394436) (xy 101.739241 42.903298) (xy 101.73876 43.454285) (xy 101.949169 43.963515)
(xy 102.338436 44.353461) (xy 102.847298 44.564759) (xy 103.398285 44.56524) (xy 103.907515 44.354831) (xy 104.297461 43.965564)
(xy 104.508759 43.456702) (xy 104.50924 42.905715) (xy 104.298831 42.396485) (xy 104.009 42.106148) (xy 104.009 41.529)
(xy 103.941633 41.190325) (xy 103.74979 40.90321) (xy 103.749787 40.903208) (xy 103.111884 40.265305) (xy 103.11224 39.857715)
(xy 102.901831 39.348485) (xy 102.512564 38.958539) (xy 102.003702 38.747241) (xy 101.452715 38.74676) (xy 100.943485 38.957169)
(xy 100.653148 39.247) (xy 98.990523 39.247) (xy 98.702564 38.958539) (xy 98.193702 38.747241) (xy 97.642715 38.74676)
(xy 97.133485 38.957169) (xy 96.743539 39.346436) (xy 96.532241 39.855298) (xy 96.53176 40.406285) (xy 96.21 40.406285)
(xy 96.21 29.28575) (xy 97.3 29.28575) (xy 97.3 31.66631) (xy 97.396673 31.899699) (xy 97.575302 32.078327)
(xy 97.808691 32.175) (xy 98.28425 32.175) (xy 98.443 32.01625) (xy 98.443 29.127) (xy 97.45875 29.127)
(xy 97.3 29.28575) (xy 96.21 29.28575) (xy 96.21 26.71) (xy 97.3 26.71)
)
)
(filled_polygon

View File

@ -1,8 +1,8 @@
(export (version D)
(design
(source /home/eddy/Docs/SAO/ELECTRONICS/SCORPIO/platform_module/stepper.sch)
(date "Пн 11 сен 2017 16:47:27")
(tool "Eeschema 4.0.6")
(source /home/eddy/Dropbox/Projects/scorpio/kicad/stm8_platform/stepper.sch)
(date "Пн 01 окт 2018 16:12:22")
(tool "Eeschema 4.0.7")
(sheet (number 1) (name /) (tstamps /)
(title_block
(title "2 steppers module")
@ -33,12 +33,6 @@
(libsource (lib stepper-cache) (part C-RESCUE-stepper))
(sheetpath (names /) (tstamps /))
(tstamp 52FB0426))
(comp (ref P2)
(value SWIM)
(footprint Pin_Headers.pretty:Pin_Header_Angled_1x04_Pitch2.54mm)
(libsource (lib conn) (part CONN_01X05))
(sheetpath (names /) (tstamps /))
(tstamp 52FB0A49))
(comp (ref D1)
(value LED)
(footprint LEDs.pretty:LED_0805)
@ -66,7 +60,7 @@
(comp (ref P1)
(value UART)
(footprint Pin_Headers.pretty:Pin_Header_Angled_1x04_Pitch2.54mm)
(libsource (lib conn) (part CONN_01X04))
(libsource (lib stepper-cache) (part CONN_01X04))
(sheetpath (names /) (tstamps /))
(tstamp 52FB4AA7))
(comp (ref U2)
@ -78,7 +72,7 @@
(comp (ref SW1)
(value SW_DIP_x03)
(footprint Housings_DIP.pretty:DIP-6_W7.62mm)
(libsource (lib switches) (part SW_DIP_x03))
(libsource (lib stepper-rescue) (part SW_DIP_x03-RESCUE-stepper))
(sheetpath (names /) (tstamps /))
(tstamp 59834FF2))
(comp (ref R3)
@ -120,7 +114,7 @@
(comp (ref U3)
(value LD1117S50CTR)
(footprint TO_SOT_Packages_SMD.pretty:SOT-223)
(libsource (lib stepper-rescue) (part LD1117S50CTR-RESCUE-stepper))
(libsource (lib stepper-cache) (part LD1117S50CTR-RESCUE-stepper))
(sheetpath (names /) (tstamps /))
(tstamp 598520BA))
(comp (ref C3)
@ -198,7 +192,7 @@
(comp (ref J1)
(value CONN_02X10)
(footprint modules:Pin_header_2x10_side)
(libsource (lib conn) (part CONN_02X10))
(libsource (lib stepper-cache) (part CONN_02X10))
(sheetpath (names /) (tstamps /))
(tstamp 5988822E))
(comp (ref Q1)
@ -218,7 +212,13 @@
(footprint modules:hole_3mm)
(libsource (lib my_elements) (part HOLE))
(sheetpath (names /) (tstamps /))
(tstamp 59B6D60D)))
(tstamp 59B6D60D))
(comp (ref P2)
(value SWIM)
(footprint Connector_PinHeader_2.54mm.pretty:PinHeader_1x03_P2.54mm_Horizontal)
(libsource (lib conn) (part Conn_01x03))
(sheetpath (names /) (tstamps /))
(tstamp 5BB234EF)))
(libparts
(libpart (lib stepper-cache) (part C-RESCUE-stepper)
(footprints
@ -231,8 +231,7 @@
(pins
(pin (num 1) (name ~) (type passive))
(pin (num 2) (name ~) (type passive))))
(libpart (lib conn) (part CONN_01X04)
(description "Connector, single row, 01x04, pin header")
(libpart (lib stepper-cache) (part CONN_01X04)
(footprints
(fp Pin_Header_Straight_1X*)
(fp Pin_Header_Angled_1X*)
@ -246,24 +245,7 @@
(pin (num 2) (name P2) (type passive))
(pin (num 3) (name P3) (type passive))
(pin (num 4) (name P4) (type passive))))
(libpart (lib conn) (part CONN_01X05)
(description "Connector, single row, 01x05, pin header")
(footprints
(fp Pin_Header_Straight_1X*)
(fp Pin_Header_Angled_1X*)
(fp Socket_Strip_Straight_1X*)
(fp Socket_Strip_Angled_1X*))
(fields
(field (name Reference) J)
(field (name Value) CONN_01X05))
(pins
(pin (num 1) (name P1) (type passive))
(pin (num 2) (name P2) (type passive))
(pin (num 3) (name P3) (type passive))
(pin (num 4) (name P4) (type passive))
(pin (num 5) (name P5) (type passive))))
(libpart (lib conn) (part CONN_02X10)
(description "Connector, double row, 02x10, pin header")
(libpart (lib stepper-cache) (part CONN_02X10)
(footprints
(fp Pin_Header_Straight_2X*)
(fp Pin_Header_Angled_2X*)
@ -304,13 +286,30 @@
(pins
(pin (num 1) (name ~) (type passive))
(pin (num 2) (name ~) (type passive))))
(libpart (lib conn) (part Conn_01x03)
(description "Generic connector, single row, 01x03")
(docs ~)
(footprints
(fp Connector*:*_??x*mm*)
(fp Connector*:*1x??x*mm*)
(fp Pin?Header?Straight?1X*)
(fp Pin?Header?Angled?1X*)
(fp Socket?Strip?Straight?1X*)
(fp Socket?Strip?Angled?1X*))
(fields
(field (name Reference) J)
(field (name Value) Conn_01x03))
(pins
(pin (num 1) (name Pin_1) (type passive))
(pin (num 2) (name Pin_2) (type passive))
(pin (num 3) (name Pin_3) (type passive))))
(libpart (lib my_elements) (part HOLE)
(footprints
(fp hole*))
(fields
(field (name Reference) HOLE)
(field (name Value) HOLE)))
(libpart (lib stepper-rescue) (part LD1117S50CTR-RESCUE-stepper)
(libpart (lib stepper-cache) (part LD1117S50CTR-RESCUE-stepper)
(footprints
(fp SOT223))
(fields
@ -363,7 +362,7 @@
(description "TVS Diode Array, 5.5V Standoff, 4 Channels, SOT-23-5 package")
(docs http://www.littelfuse.com/~/media/files/littelfuse/technical%20resources/documents/data%20sheets/sp05xxba.pdf)
(footprints
(fp SOT-23*))
(fp SOT?23*))
(fields
(field (name Reference) D)
(field (name Value) SP0504BAHT)
@ -415,13 +414,12 @@
(pin (num 30) (name PD5/UART2_TX) (type 3state))
(pin (num 31) (name PD6/UART2_RX) (type 3state))
(pin (num 32) (name PD7/TLI[TIM1_CH4]) (type 3state))))
(libpart (lib switches) (part SW_DIP_x03)
(description "3x DIP Switch, Single Pole Single Throw (SPST) switch, small symbol")
(libpart (lib stepper-rescue) (part SW_DIP_x03-RESCUE-stepper)
(footprints
(fp SW?DIP?x3*))
(fields
(field (name Reference) SW)
(field (name Value) SW_DIP_x03))
(field (name Value) SW_DIP_x03-RESCUE-stepper))
(pins
(pin (num 1) (name ~) (type input))
(pin (num 2) (name ~) (type input))
@ -463,218 +461,213 @@
(pin (num 17) (name O2) (type openCol))
(pin (num 18) (name O1) (type openCol)))))
(libraries
(library (logical stepper-rescue)
(uri stepper-rescue.lib))
(library (logical stm8s105k4t6c)
(uri stm8s105k4t6c.lib))
(library (logical my_elements)
(uri /home/eddy/kicad/my_elements.lib))
(library (logical switches)
(uri /usr/share/kicad/library/switches.lib))
(library (logical interface)
(uri /usr/share/kicad/library/interface.lib))
(library (logical ESD_Protection)
(uri /usr/share/kicad/library/ESD_Protection.lib))
(library (logical my_elements)
(uri /home/eddy/kicad/my_elements.lib))
(library (logical stepper-cache)
(uri /home/eddy/Docs/SAO/ELECTRONICS/SCORPIO/platform_module/stepper-cache.lib))
(library (logical conn)
(uri /usr/share/kicad/library/conn.lib))
(uri /home/eddy/Dropbox/Projects/scorpio/kicad/stm8_platform/stepper-cache.lib))
(library (logical device)
(uri /usr/share/kicad/library/device.lib))
(library (logical stepper-rescue)
(uri stepper-rescue.lib)))
(library (logical conn)
(uri /usr/share/kicad/library/conn.lib)))
(nets
(net (code 1) (name "Net-(Q1-Pad1)")
(node (ref R3) (pin 1))
(node (ref Q1) (pin 1)))
(node (ref Q1) (pin 1))
(node (ref R3) (pin 1)))
(net (code 2) (name /NRST)
(node (ref U1) (pin 1))
(node (ref P2) (pin 1))
(node (ref R12) (pin 1))
(node (ref C5) (pin 1)))
(node (ref U1) (pin 1))
(node (ref C5) (pin 1))
(node (ref R12) (pin 1)))
(net (code 3) (name GND)
(node (ref C4) (pin 2))
(node (ref C3) (pin 2))
(node (ref P2) (pin 3))
(node (ref U3) (pin 1))
(node (ref J1) (pin 1))
(node (ref D2) (pin 2))
(node (ref P1) (pin 4))
(node (ref C5) (pin 2))
(node (ref U1) (pin 10))
(node (ref U1) (pin 4))
(node (ref C2) (pin 1))
(node (ref C1) (pin 1))
(node (ref D2) (pin 2))
(node (ref U3) (pin 1))
(node (ref R15) (pin 1))
(node (ref J1) (pin 1))
(node (ref R14) (pin 1))
(node (ref U2) (pin 9))
(node (ref R13) (pin 1))
(node (ref C4) (pin 2))
(node (ref C3) (pin 2))
(node (ref R14) (pin 1)))
(node (ref R15) (pin 1))
(node (ref R13) (pin 1)))
(net (code 4) (name +12V)
(node (ref J1) (pin 19))
(node (ref C3) (pin 1))
(node (ref U2) (pin 10))
(node (ref U3) (pin 3)))
(net (code 5) (name /PD4)
(node (ref D2) (pin 3))
(node (ref R11) (pin 1))
(node (ref U1) (pin 29)))
(net (code 6) (name /PB4)
(node (ref R8) (pin 1))
(node (ref D2) (pin 4))
(node (ref U1) (pin 12)))
(net (code 7) (name "Net-(D1-Pad2)")
(node (ref U3) (pin 3))
(node (ref U2) (pin 10)))
(net (code 5) (name /PC4)
(node (ref U1) (pin 21))
(node (ref R2) (pin 2)))
(net (code 6) (name "Net-(D1-Pad2)")
(node (ref R2) (pin 1))
(node (ref D1) (pin 2)))
(net (code 8) (name "Net-(C1-Pad2)")
(node (ref U1) (pin 5))
(node (ref C1) (pin 2)))
(net (code 9) (name /S1P2)
(node (ref U2) (pin 17))
(node (ref J1) (pin 5)))
(net (code 10) (name /OUT1)
(node (ref Q2) (pin 3))
(node (ref J1) (pin 4)))
(net (code 11) (name /S1P1)
(node (ref U2) (pin 18))
(node (ref J1) (pin 3)))
(net (code 12) (name "Net-(J1-Pad2)")
(node (ref J1) (pin 2)))
(net (code 13) (name /PD7)
(node (ref D2) (pin 1))
(node (ref U1) (pin 32))
(node (ref R10) (pin 1)))
(net (code 14) (name /OUT2)
(net (code 7) (name "Net-(C1-Pad2)")
(node (ref C1) (pin 2))
(node (ref U1) (pin 5)))
(net (code 8) (name /OUT3)
(node (ref J1) (pin 8))
(node (ref Q3) (pin 3)))
(net (code 9) (name /S1P3)
(node (ref J1) (pin 7))
(node (ref U2) (pin 16)))
(net (code 10) (name /OUT2)
(node (ref J1) (pin 6))
(node (ref Q1) (pin 3)))
(net (code 15) (name "Net-(Q2-Pad1)")
(node (ref Q2) (pin 1))
(node (ref R6) (pin 1)))
(net (code 16) (name +5V)
(node (ref U1) (pin 6))
(node (ref C2) (pin 2))
(node (ref P1) (pin 1))
(node (ref R12) (pin 2))
(node (ref U1) (pin 9))
(node (ref U1) (pin 7))
(node (ref R1) (pin 1))
(node (ref C4) (pin 1))
(node (ref U3) (pin 4))
(node (ref U3) (pin 2))
(node (ref SW1) (pin 3))
(node (ref SW1) (pin 2))
(node (ref SW1) (pin 1))
(node (ref Q3) (pin 2))
(node (ref Q2) (pin 2))
(node (ref D1) (pin 1))
(node (ref R4) (pin 1))
(node (ref Q1) (pin 2))
(node (ref P2) (pin 5))
(node (ref R5) (pin 1)))
(net (code 11) (name /S1P2)
(node (ref U2) (pin 17))
(node (ref J1) (pin 5)))
(net (code 12) (name /OUT1)
(node (ref Q2) (pin 3))
(node (ref J1) (pin 4)))
(net (code 13) (name /S1P1)
(node (ref J1) (pin 3))
(node (ref U2) (pin 18)))
(net (code 14) (name "Net-(J1-Pad2)")
(node (ref J1) (pin 2)))
(net (code 15) (name /S1P4)
(node (ref U2) (pin 15))
(node (ref J1) (pin 9)))
(net (code 16) (name "Net-(Q2-Pad1)")
(node (ref R6) (pin 1))
(node (ref Q2) (pin 1)))
(net (code 17) (name /S2P4)
(node (ref U2) (pin 11))
(node (ref J1) (pin 17)))
(net (code 18) (name /PB5)
(node (ref R9) (pin 1))
(node (ref U1) (pin 11))
(node (ref D2) (pin 5)))
(net (code 19) (name /M2E2)
(node (ref R11) (pin 2))
(node (ref J1) (pin 16)))
(net (code 20) (name /S2P3)
(net (code 18) (name /M2E2)
(node (ref J1) (pin 16))
(node (ref R11) (pin 2)))
(net (code 19) (name /S2P3)
(node (ref J1) (pin 15))
(node (ref U2) (pin 12)))
(net (code 21) (name /M2E1)
(net (code 20) (name /M2E1)
(node (ref J1) (pin 14))
(node (ref R10) (pin 2)))
(net (code 22) (name /S2P2)
(node (ref J1) (pin 13))
(node (ref U2) (pin 13)))
(net (code 23) (name /M1E2)
(net (code 21) (name /S2P2)
(node (ref U2) (pin 13))
(node (ref J1) (pin 13)))
(net (code 22) (name /M1E2)
(node (ref R9) (pin 2))
(node (ref J1) (pin 12)))
(net (code 24) (name /S2P1)
(net (code 23) (name /S2P1)
(node (ref J1) (pin 11))
(node (ref U2) (pin 14)))
(net (code 25) (name /M1E1)
(node (ref R8) (pin 2))
(node (ref J1) (pin 10)))
(net (code 26) (name /S1P4)
(node (ref U2) (pin 15))
(node (ref J1) (pin 9)))
(net (code 27) (name /OUT3)
(node (ref Q3) (pin 3))
(node (ref J1) (pin 8)))
(net (code 28) (name /S1P3)
(node (ref J1) (pin 7))
(node (ref U2) (pin 16)))
(net (code 29) (name /PF4)
(node (ref U1) (pin 8)))
(net (code 30) (name /PE5)
(net (code 24) (name /M1E1)
(node (ref J1) (pin 10))
(node (ref R8) (pin 2)))
(net (code 25) (name /PC3)
(node (ref R7) (pin 2))
(node (ref U1) (pin 20))
(node (ref R5) (pin 2)))
(net (code 26) (name +5V)
(node (ref C4) (pin 1))
(node (ref P1) (pin 1))
(node (ref C2) (pin 2))
(node (ref SW1) (pin 3))
(node (ref SW1) (pin 1))
(node (ref SW1) (pin 2))
(node (ref R1) (pin 1))
(node (ref U3) (pin 4))
(node (ref U3) (pin 2))
(node (ref U1) (pin 6))
(node (ref U1) (pin 7))
(node (ref R12) (pin 2))
(node (ref U1) (pin 9))
(node (ref Q3) (pin 2))
(node (ref Q1) (pin 2))
(node (ref R5) (pin 1))
(node (ref Q2) (pin 2))
(node (ref R4) (pin 1))
(node (ref D1) (pin 1)))
(net (code 27) (name /PE5)
(node (ref U1) (pin 17)))
(net (code 31) (name /OSC1IN)
(net (code 28) (name /OSC1IN)
(node (ref U1) (pin 2)))
(net (code 32) (name /OSC2IN)
(net (code 29) (name /OSC2IN)
(node (ref U1) (pin 3)))
(net (code 33) (name /PC1)
(node (ref R6) (pin 2))
(net (code 30) (name /PF4)
(node (ref U1) (pin 8)))
(net (code 31) (name /PC1)
(node (ref U1) (pin 18))
(node (ref R4) (pin 2))
(node (ref U1) (pin 18)))
(net (code 34) (name "Net-(Q3-Pad1)")
(node (ref R6) (pin 2)))
(net (code 32) (name "Net-(Q3-Pad1)")
(node (ref Q3) (pin 1))
(node (ref R7) (pin 1)))
(net (code 35) (name /PC3)
(node (ref R7) (pin 2))
(node (ref R5) (pin 2))
(node (ref U1) (pin 20)))
(net (code 36) (name "Net-(P2-Pad4)")
(node (ref P2) (pin 4)))
(net (code 37) (name /PC4)
(node (ref U1) (pin 21))
(node (ref R2) (pin 2)))
(net (code 38) (name /SWIM/PD1)
(node (ref P2) (pin 2))
(node (ref U1) (pin 26))
(node (ref U2) (pin 7)))
(net (code 39) (name /PB0)
(net (code 33) (name /PB5)
(node (ref D2) (pin 5))
(node (ref R9) (pin 1))
(node (ref U1) (pin 11)))
(net (code 34) (name /PB0)
(node (ref U1) (pin 16))
(node (ref U2) (pin 1)))
(net (code 40) (name /PD0)
(net (code 35) (name /PD0)
(node (ref U2) (pin 8))
(node (ref U1) (pin 25)))
(net (code 41) (name /PB1)
(net (code 36) (name /PB1)
(node (ref U2) (pin 2))
(node (ref U1) (pin 15)))
(net (code 42) (name /PC7)
(node (ref SW1) (pin 4))
(net (code 37) (name /PC7)
(node (ref R13) (pin 2))
(node (ref U1) (pin 24)))
(net (code 43) (name /PB2)
(node (ref U1) (pin 24))
(node (ref SW1) (pin 4)))
(net (code 38) (name /PB2)
(node (ref U1) (pin 14))
(node (ref U2) (pin 3)))
(net (code 44) (name /PC6)
(net (code 39) (name /PC6)
(node (ref U1) (pin 23))
(node (ref R14) (pin 2))
(node (ref SW1) (pin 5)))
(net (code 45) (name /PB3)
(node (ref U1) (pin 13))
(node (ref U2) (pin 4)))
(net (code 46) (name /PC5)
(node (ref SW1) (pin 5))
(node (ref R14) (pin 2)))
(net (code 40) (name /PB3)
(node (ref U2) (pin 4))
(node (ref U1) (pin 13)))
(net (code 41) (name /PD7)
(node (ref U1) (pin 32))
(node (ref R10) (pin 1))
(node (ref D2) (pin 1)))
(net (code 42) (name /PC5)
(node (ref U1) (pin 22))
(node (ref SW1) (pin 6))
(node (ref R15) (pin 2)))
(net (code 47) (name /PD6)
(node (ref R15) (pin 2))
(node (ref SW1) (pin 6)))
(net (code 43) (name /PB4)
(node (ref D2) (pin 4))
(node (ref U1) (pin 12))
(node (ref R8) (pin 1)))
(net (code 44) (name /PD6)
(node (ref P1) (pin 2))
(node (ref U1) (pin 31))
(node (ref J1) (pin 20))
(node (ref P1) (pin 2)))
(net (code 48) (name /PD5)
(node (ref P1) (pin 3))
(node (ref J1) (pin 20)))
(net (code 45) (name /SWIM/PD1)
(node (ref P2) (pin 2))
(node (ref U2) (pin 7))
(node (ref U1) (pin 26)))
(net (code 46) (name /PD5)
(node (ref U1) (pin 30))
(node (ref P1) (pin 3))
(node (ref J1) (pin 18)))
(net (code 49) (name /PC2)
(node (ref U1) (pin 19))
(net (code 47) (name /PD4)
(node (ref U1) (pin 29))
(node (ref R11) (pin 1))
(node (ref D2) (pin 3)))
(net (code 48) (name /PC2)
(node (ref R3) (pin 2))
(node (ref U1) (pin 19))
(node (ref R1) (pin 2)))
(net (code 50) (name /PD3)
(node (ref U2) (pin 5))
(node (ref U1) (pin 28)))
(net (code 51) (name /PD2)
(node (ref U2) (pin 6))
(node (ref U1) (pin 27)))))
(net (code 49) (name /PD3)
(node (ref U1) (pin 28))
(node (ref U2) (pin 5)))
(net (code 50) (name /PD2)
(node (ref U1) (pin 27))
(node (ref U2) (pin 6)))))

View File

@ -1,4 +1,4 @@
update=Пн 11 сен 2017 16:44:46
update=Пн 01 окт 2018 16:08:45
last_client=kicad
[schematic_editor]
version=1

View File

@ -44,10 +44,10 @@ F 3 "~" H 3150 1850 60 0000 C CNN
1 0 0 -1
$EndComp
$Comp
L GND-RESCUE-stepper #PWR5
L GND-RESCUE-stepper #PWR01
U 1 1 52FB03EF
P 1500 1950
F 0 "#PWR5" H 1500 1950 30 0001 C CNN
F 0 "#PWR01" H 1500 1950 30 0001 C CNN
F 1 "GND" H 1500 1880 30 0001 C CNN
F 2 "" H 1500 1950 60 0000 C CNN
F 3 "" H 1500 1950 60 0000 C CNN
@ -55,10 +55,10 @@ F 3 "" H 1500 1950 60 0000 C CNN
1 0 0 -1
$EndComp
$Comp
L GND-RESCUE-stepper #PWR4
L GND-RESCUE-stepper #PWR02
U 1 1 52FB0400
P 1500 1350
F 0 "#PWR4" H 1500 1350 30 0001 C CNN
F 0 "#PWR02" H 1500 1350 30 0001 C CNN
F 1 "GND" H 1500 1280 30 0001 C CNN
F 2 "" H 1500 1350 60 0000 C CNN
F 3 "" H 1500 1350 60 0000 C CNN
@ -88,10 +88,10 @@ F 3 "" H 1000 1700 60 0000 C CNN
0 -1 -1 0
$EndComp
$Comp
L GND-RESCUE-stepper #PWR1
L GND-RESCUE-stepper #PWR03
U 1 1 52FB0453
P 800 1850
F 0 "#PWR1" H 800 1850 30 0001 C CNN
F 0 "#PWR03" H 800 1850 30 0001 C CNN
F 1 "GND" H 800 1780 30 0001 C CNN
F 2 "" H 800 1850 60 0000 C CNN
F 3 "" H 800 1850 60 0000 C CNN
@ -150,17 +150,6 @@ Text Label 4550 1100 0 60 ~ 0
PD6
Text Label 4550 1000 0 60 ~ 0
PD7
$Comp
L CONN_01X05 P2
U 1 1 52FB0A49
P 10900 1350
F 0 "P2" H 10900 1650 50 0000 C CNN
F 1 "SWIM" H 10900 1050 50 0000 C CNN
F 2 "Pin_Headers.pretty:Pin_Header_Angled_1x04_Pitch2.54mm" H 10900 1350 60 0001 C CNN
F 3 "" H 10900 1350 60 0000 C CNN
1 10900 1350
1 0 0 -1
$EndComp
Text Label 10700 1250 2 60 ~ 0
SWIM/PD1
Text Label 9850 1000 2 60 ~ 0
@ -201,10 +190,10 @@ F 3 "" H 9500 1150 60 0000 C CNN
0 1 1 0
$EndComp
$Comp
L GND-RESCUE-stepper #PWR22
L GND-RESCUE-stepper #PWR04
U 1 1 52FB0F03
P 9850 1650
F 0 "#PWR22" H 9850 1650 30 0001 C CNN
F 0 "#PWR04" H 9850 1650 30 0001 C CNN
F 1 "GND" H 9850 1580 30 0001 C CNN
F 2 "" H 9850 1650 60 0000 C CNN
F 3 "" H 9850 1650 60 0000 C CNN
@ -223,10 +212,10 @@ F 3 "" H 9850 1350 60 0000 C CNN
1 0 0 -1
$EndComp
$Comp
L GND-RESCUE-stepper #PWR23
L GND-RESCUE-stepper #PWR05
U 1 1 52FB287C
P 10150 1400
F 0 "#PWR23" H 10150 1400 30 0001 C CNN
F 0 "#PWR05" H 10150 1400 30 0001 C CNN
F 1 "GND" H 10150 1330 30 0001 C CNN
F 2 "" H 10150 1400 60 0000 C CNN
F 3 "" H 10150 1400 60 0000 C CNN
@ -251,10 +240,10 @@ RXD
Text Label 9650 2600 0 61 ~ 0
TXD
$Comp
L GND-RESCUE-stepper #PWR26
L GND-RESCUE-stepper #PWR06
U 1 1 52FB4CEF
P 10650 2500
F 0 "#PWR26" H 10650 2500 30 0001 C CNN
F 0 "#PWR06" H 10650 2500 30 0001 C CNN
F 1 "GND" H 10650 2430 30 0001 C CNN
F 2 "" H 10650 2500 60 0000 C CNN
F 3 "" H 10650 2500 60 0000 C CNN
@ -277,7 +266,7 @@ F 3 "" H 6650 1350 50 0001 C CNN
1 0 0 -1
$EndComp
$Comp
L SW_DIP_x03 SW1
L SW_DIP_x03-RESCUE-stepper SW1
U 1 1 59834FF2
P 9750 3950
F 0 "SW1" H 9750 4300 50 0000 C CNN
@ -310,10 +299,10 @@ F 3 "" H 8925 2725 50 0001 C CNN
0 -1 -1 0
$EndComp
$Comp
L +5V #PWR20
L +5V #PWR07
U 1 1 5984240F
P 9250 1050
F 0 "#PWR20" H 9250 900 50 0001 C CNN
F 0 "#PWR07" H 9250 900 50 0001 C CNN
F 1 "+5V" H 9250 1190 50 0000 C CNN
F 2 "" H 9250 1050 50 0001 C CNN
F 3 "" H 9250 1050 50 0001 C CNN
@ -321,21 +310,10 @@ F 3 "" H 9250 1050 50 0001 C CNN
1 0 0 -1
$EndComp
$Comp
L +5V #PWR25
U 1 1 59842472
P 10600 1600
F 0 "#PWR25" H 10600 1450 50 0001 C CNN
F 1 "+5V" H 10600 1740 50 0000 C CNN
F 2 "" H 10600 1600 50 0001 C CNN
F 3 "" H 10600 1600 50 0001 C CNN
1 10600 1600
-1 0 0 1
$EndComp
$Comp
L +5V #PWR2
L +5V #PWR08
U 1 1 598424AD
P 1350 1750
F 0 "#PWR2" H 1350 1600 50 0001 C CNN
F 0 "#PWR08" H 1350 1600 50 0001 C CNN
F 1 "+5V" H 1350 1890 50 0000 C CNN
F 2 "" H 1350 1750 50 0001 C CNN
F 3 "" H 1350 1750 50 0001 C CNN
@ -343,10 +321,10 @@ F 3 "" H 1350 1750 50 0001 C CNN
1 0 0 -1
$EndComp
$Comp
L +5V #PWR7
L +5V #PWR09
U 1 1 59842925
P 2500 3650
F 0 "#PWR7" H 2500 3500 50 0001 C CNN
F 0 "#PWR09" H 2500 3500 50 0001 C CNN
F 1 "+5V" H 2500 3790 50 0000 C CNN
F 2 "" H 2500 3650 50 0001 C CNN
F 3 "" H 2500 3650 50 0001 C CNN
@ -398,10 +376,10 @@ F 3 "" H 10100 3400 60 0000 C CNN
1 0 0 -1
$EndComp
$Comp
L +5V #PWR21
L +5V #PWR010
U 1 1 59844ACD
P 9400 3650
F 0 "#PWR21" H 9400 3500 50 0001 C CNN
F 0 "#PWR010" H 9400 3500 50 0001 C CNN
F 1 "+5V" H 9400 3790 50 0000 C CNN
F 2 "" H 9400 3650 50 0001 C CNN
F 3 "" H 9400 3650 50 0001 C CNN
@ -409,10 +387,10 @@ F 3 "" H 9400 3650 50 0001 C CNN
1 0 0 -1
$EndComp
$Comp
L GND-RESCUE-stepper #PWR27
L GND-RESCUE-stepper #PWR011
U 1 1 598456D9
P 10700 3200
F 0 "#PWR27" H 10700 3200 30 0001 C CNN
F 0 "#PWR011" H 10700 3200 30 0001 C CNN
F 1 "GND" H 10700 3130 30 0001 C CNN
F 2 "" H 10700 3200 60 0000 C CNN
F 3 "" H 10700 3200 60 0000 C CNN
@ -436,10 +414,10 @@ Text Notes 9450 3950 0 60 ~ 0
Text Notes 1550 3400 0 60 ~ 0
On-board LED
$Comp
L +5V #PWR3
L +5V #PWR012
U 1 1 59847EEF
P 1350 5100
F 0 "#PWR3" H 1350 4950 50 0001 C CNN
F 0 "#PWR012" H 1350 4950 50 0001 C CNN
F 1 "+5V" H 1350 5240 50 0000 C CNN
F 2 "" H 1350 5100 50 0001 C CNN
F 3 "" H 1350 5100 50 0001 C CNN
@ -447,10 +425,10 @@ F 3 "" H 1350 5100 50 0001 C CNN
1 0 0 -1
$EndComp
$Comp
L +5V #PWR6
L +5V #PWR013
U 1 1 59848624
P 2350 5350
F 0 "#PWR6" H 2350 5200 50 0001 C CNN
F 0 "#PWR013" H 2350 5200 50 0001 C CNN
F 1 "+5V" H 2350 5490 50 0000 C CNN
F 2 "" H 2350 5350 50 0001 C CNN
F 3 "" H 2350 5350 50 0001 C CNN
@ -463,16 +441,15 @@ Text Label 2800 5850 0 60 ~ 0
OUT2
Text Notes 1800 4300 0 60 ~ 0
PWM/power outputs
NoConn ~ 10700 1450
Text Notes 10050 850 0 60 ~ 0
SWIM
Text Label 9650 2700 0 61 ~ 0
5.0V
$Comp
L +5V #PWR24
L +5V #PWR014
U 1 1 598515D1
P 10250 2700
F 0 "#PWR24" H 10250 2550 50 0001 C CNN
F 0 "#PWR014" H 10250 2550 50 0001 C CNN
F 1 "+5V" H 10250 2840 50 0000 C CNN
F 2 "" H 10250 2700 50 0001 C CNN
F 3 "" H 10250 2700 50 0001 C CNN
@ -513,10 +490,10 @@ F 3 "" H 8600 1400 50 0001 C CNN
1 0 0 -1
$EndComp
$Comp
L GND-RESCUE-stepper #PWR16
L GND-RESCUE-stepper #PWR015
U 1 1 598534FD
P 8200 1600
F 0 "#PWR16" H 8200 1600 30 0001 C CNN
F 0 "#PWR015" H 8200 1600 30 0001 C CNN
F 1 "GND" H 8200 1530 30 0001 C CNN
F 2 "" H 8200 1600 60 0000 C CNN
F 3 "" H 8200 1600 60 0000 C CNN
@ -524,10 +501,10 @@ F 3 "" H 8200 1600 60 0000 C CNN
1 0 0 -1
$EndComp
$Comp
L +5V #PWR18
L +5V #PWR016
U 1 1 59853D62
P 8800 1100
F 0 "#PWR18" H 8800 950 50 0001 C CNN
F 0 "#PWR016" H 8800 950 50 0001 C CNN
F 1 "+5V" H 8800 1240 50 0000 C CNN
F 2 "" H 8800 1100 50 0001 C CNN
F 3 "" H 8800 1100 50 0001 C CNN
@ -535,10 +512,10 @@ F 3 "" H 8800 1100 50 0001 C CNN
1 0 0 -1
$EndComp
$Comp
L +12V #PWR14
L +12V #PWR017
U 1 1 59854294
P 7650 1100
F 0 "#PWR14" H 7650 950 50 0001 C CNN
F 0 "#PWR017" H 7650 950 50 0001 C CNN
F 1 "+12V" H 7650 1240 50 0000 C CNN
F 2 "" H 7650 1100 50 0001 C CNN
F 3 "" H 7650 1100 50 0001 C CNN
@ -550,10 +527,10 @@ Power
Text Notes 9800 2200 0 60 ~ 0
ext USART
$Comp
L GND-RESCUE-stepper #PWR19
L GND-RESCUE-stepper #PWR018
U 1 1 598572C2
P 9000 2650
F 0 "#PWR19" H 9000 2650 30 0001 C CNN
F 0 "#PWR018" H 9000 2650 30 0001 C CNN
F 1 "GND" H 9000 2580 30 0001 C CNN
F 2 "" H 9000 2650 60 0000 C CNN
F 3 "" H 9000 2650 60 0000 C CNN
@ -561,10 +538,10 @@ F 3 "" H 9000 2650 60 0000 C CNN
1 0 0 -1
$EndComp
$Comp
L GND-RESCUE-stepper #PWR12
L GND-RESCUE-stepper #PWR019
U 1 1 59857BB1
P 6550 2200
F 0 "#PWR12" H 6550 2200 30 0001 C CNN
F 0 "#PWR019" H 6550 2200 30 0001 C CNN
F 1 "GND" H 6550 2130 30 0001 C CNN
F 2 "" H 6550 2200 60 0000 C CNN
F 3 "" H 6550 2200 60 0000 C CNN
@ -572,10 +549,10 @@ F 3 "" H 6550 2200 60 0000 C CNN
1 0 0 -1
$EndComp
$Comp
L +12V #PWR13
L +12V #PWR020
U 1 1 59858729
P 7050 2050
F 0 "#PWR13" H 7050 1900 50 0001 C CNN
F 0 "#PWR020" H 7050 1900 50 0001 C CNN
F 1 "+12V" H 7050 2190 50 0000 C CNN
F 2 "" H 7050 2050 50 0001 C CNN
F 3 "" H 7050 2050 50 0001 C CNN
@ -695,10 +672,10 @@ M2E1
Text Label 9100 5300 0 60 ~ 0
M2E2
$Comp
L +12V #PWR17
L +12V #PWR021
U 1 1 59864EE6
P 8200 5500
F 0 "#PWR17" H 8200 5350 50 0001 C CNN
F 0 "#PWR021" H 8200 5350 50 0001 C CNN
F 1 "+12V" H 8200 5640 50 0000 C CNN
F 2 "" H 8200 5500 50 0001 C CNN
F 3 "" H 8200 5500 50 0001 C CNN
@ -706,10 +683,10 @@ F 3 "" H 8200 5500 50 0001 C CNN
1 0 0 -1
$EndComp
$Comp
L PWR_FLAG #FLG1
L PWR_FLAG #FLG022
U 1 1 598652F0
P 8100 5500
F 0 "#FLG1" H 8100 5575 50 0001 C CNN
F 0 "#FLG022" H 8100 5575 50 0001 C CNN
F 1 "PWR_FLAG" H 8100 5650 50 0001 C CNN
F 2 "" H 8100 5500 50 0001 C CNN
F 3 "" H 8100 5500 50 0001 C CNN
@ -717,10 +694,10 @@ F 3 "" H 8100 5500 50 0001 C CNN
-1 0 0 1
$EndComp
$Comp
L GND-RESCUE-stepper #PWR15
L GND-RESCUE-stepper #PWR023
U 1 1 598655A5
P 8050 4650
F 0 "#PWR15" H 8050 4650 30 0001 C CNN
F 0 "#PWR023" H 8050 4650 30 0001 C CNN
F 1 "GND" H 8050 4580 30 0001 C CNN
F 2 "" H 8050 4650 60 0000 C CNN
F 3 "" H 8050 4650 60 0000 C CNN
@ -728,10 +705,10 @@ F 3 "" H 8050 4650 60 0000 C CNN
1 0 0 -1
$EndComp
$Comp
L PWR_FLAG #FLG2
L PWR_FLAG #FLG024
U 1 1 5986564B
P 8200 4600
F 0 "#FLG2" H 8200 4675 50 0001 C CNN
F 0 "#FLG024" H 8200 4675 50 0001 C CNN
F 1 "PWR_FLAG" H 8200 4750 50 0001 C CNN
F 2 "" H 8200 4600 50 0001 C CNN
F 3 "" H 8200 4600 50 0001 C CNN
@ -832,10 +809,6 @@ Wire Wire Line
10150 1400 10150 1350
Wire Wire Line
10150 1350 10700 1350
Wire Wire Line
10700 1550 10600 1550
Wire Wire Line
10600 1550 10600 1600
Wire Wire Line
9250 1050 9250 1150
Wire Wire Line
@ -997,10 +970,10 @@ F 3 "" H 3600 5400 60 0000 C CNN
1 0 0 -1
$EndComp
$Comp
L +5V #PWR9
L +5V #PWR025
U 1 1 59875BF0
P 3600 5100
F 0 "#PWR9" H 3600 4950 50 0001 C CNN
F 0 "#PWR025" H 3600 4950 50 0001 C CNN
F 1 "+5V" H 3600 5240 50 0000 C CNN
F 2 "" H 3600 5100 50 0001 C CNN
F 3 "" H 3600 5100 50 0001 C CNN
@ -1008,10 +981,10 @@ F 3 "" H 3600 5100 50 0001 C CNN
1 0 0 -1
$EndComp
$Comp
L +5V #PWR11
L +5V #PWR026
U 1 1 59875BF6
P 4600 5350
F 0 "#PWR11" H 4600 5200 50 0001 C CNN
F 0 "#PWR026" H 4600 5200 50 0001 C CNN
F 1 "+5V" H 4600 5490 50 0000 C CNN
F 2 "" H 4600 5350 50 0001 C CNN
F 3 "" H 4600 5350 50 0001 C CNN
@ -1070,10 +1043,10 @@ F 3 "" H 3600 3850 60 0000 C CNN
1 0 0 -1
$EndComp
$Comp
L +5V #PWR8
L +5V #PWR027
U 1 1 59876770
P 3600 3550
F 0 "#PWR8" H 3600 3400 50 0001 C CNN
F 0 "#PWR027" H 3600 3400 50 0001 C CNN
F 1 "+5V" H 3600 3690 50 0000 C CNN
F 2 "" H 3600 3550 50 0001 C CNN
F 3 "" H 3600 3550 50 0001 C CNN
@ -1081,10 +1054,10 @@ F 3 "" H 3600 3550 50 0001 C CNN
1 0 0 -1
$EndComp
$Comp
L +5V #PWR10
L +5V #PWR028
U 1 1 59876776
P 4600 3800
F 0 "#PWR10" H 4600 3650 50 0001 C CNN
F 0 "#PWR028" H 4600 3650 50 0001 C CNN
F 1 "+5V" H 4600 3940 50 0000 C CNN
F 2 "" H 4600 3800 50 0001 C CNN
F 3 "" H 4600 3800 50 0001 C CNN
@ -1191,4 +1164,15 @@ F 3 "" H 5950 6900 60 0000 C CNN
1 5950 6900
1 0 0 -1
$EndComp
$Comp
L Conn_01x03 P2
U 1 1 5BB234EF
P 10900 1250
F 0 "P2" H 10900 1450 50 0000 C CNN
F 1 "SWIM" H 10900 1050 50 0000 C CNN
F 2 "Connector_PinHeader_2.54mm.pretty:PinHeader_1x03_P2.54mm_Horizontal" H 10900 1250 50 0001 C CNN
F 3 "" H 10900 1250 50 0001 C CNN
1 10900 1250
1 0 0 -1
$EndComp
$EndSCHEMATC