add quad encoder

This commit is contained in:
eddyem 2019-06-04 00:11:14 +03:00
parent ff4f2131a2
commit eb1b91cee5
10 changed files with 762 additions and 0 deletions

View File

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

View File

@ -0,0 +1,21 @@
Quadrature encoder
=============================
## GPIO
## UART
115200N1, not more than 100ms between data bytes in command.
To turn ON human terminal (without timeout) send "####".
## Protocol
All commands are in brackets: `[ command line ]`.
'[' clears earlier input; '\n', '\r', ' ', '\t' are ignored.
All messages are asynchronous!
## Commands
[D] - get rotation direction
[R] - reset
[T] - get encoder position
When you rotate encoder you will see speed of its rotation in quaters of pulses per 10ms.

BIN
F0-nolib/QuadEncoder/encoder.bin Executable file

Binary file not shown.

View File

@ -0,0 +1,73 @@
/*
* This file is part of the Chiller project.
* Copyright 2018 Edward V. Emelianov <edward.emelianoff@gmail.com>.
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#include "hardware.h"
#include "usart.h"
volatile uint8_t tim3upd = 0;
/**
* @brief gpio_setup - setup GPIOs for external IO
* GPIO pinout:
* PA4 - open drain - onboard LED (always ON when board works)
* PA6, PA7 - TIM3_CH1/CH2 - encoder input
*/
static inline void gpio_setup(){
// Enable clocks to the GPIO subsystems
RCC->AHBENR |= RCC_AHBENR_GPIOAEN | RCC_AHBENR_GPIOBEN | RCC_AHBENR_GPIOFEN;
// PA6/7 - AF; PB1 - AF
GPIOA->MODER = GPIO_MODER_MODER4_O | GPIO_MODER_MODER6_AF | GPIO_MODER_MODER7_AF;
GPIOA->OTYPER = GPIO_OTYPER_OT_4;
// alternate functions:
// PA6 - TIM3_CH1, PA7 - TIM3_CH2
GPIOA->AFR[0] = (GPIOA->AFR[0] &~ (GPIO_AFRL_AFRL6 | GPIO_AFRL_AFRL7)) \
| (1 << (6 * 4)) | (1 << (7 * 4));
}
static inline void timers_setup(){
RCC->APB1ENR |= RCC_APB1ENR_TIM3EN;
/* (1) Configure TI1FP1 on TI1 (CC1S = 01)
configure TI1FP2 on TI2 (CC2S = 01) */
/* (2) Configure TI1FP1 and TI1FP2 non inverted (CC1P = CC2P = 0, reset value) */
/* (3) Configure both inputs are active on both rising and falling edges
(SMS = 011), set external trigger filter to f_DTS/8, N=6 (ETF=1000) */
/* (4) Enable the counter by writing CEN=1 in the TIMx_CR1 register. */
TIM3->CCMR1 = TIM_CCMR1_CC1S_0 | TIM_CCMR1_CC2S_0; /* (1)*/
//TIMx->CCER &= (uint16_t)(~(TIM_CCER_CC21 | TIM_CCER_CC2P); /* (2) */
TIM3->SMCR = TIM_SMCR_ETF_3 | TIM_SMCR_SMS_0 | TIM_SMCR_SMS_1; /* (3) */
// enable update interrupt
TIM3->DIER = TIM_DIER_UIE;
// set ARR to 79 - generate interrupt each 80 counts (one revolution)
TIM3->ARR = 79;
// enable timer
TIM3->CR1 = TIM_CR1_CEN; /* (4) */
NVIC_EnableIRQ(TIM3_IRQn);
}
void hw_setup(){
sysreset();
gpio_setup();
timers_setup();
USART1_config();
}
void tim3_isr(){
if(TIM3->SR & TIM_SR_UIF){
tim3upd = 1;
}
TIM3->SR = 0;
}

View File

@ -0,0 +1,27 @@
/*
* This file is part of the Chiller project.
* Copyright 2018 Edward V. Emelianov <edward.emelianoff@gmail.com>.
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
#ifndef HARDWARE_H__
#define HARDWARE_H__
#include "stm32f0.h"
extern volatile uint8_t tim3upd;
extern volatile uint32_t Tms;
void hw_setup(void);
#endif // HARDWARE_H__

View File

@ -0,0 +1,67 @@
/*
* main.c
*
* Copyright 2018 Edward V. Emelianoff <eddy@sao.ru, edward.emelianoff@gmail.com>
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; if not, write to the Free Software
* Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston,
* MA 02110-1301, USA.
*/
#include "hardware.h"
#include "protocol.h"
#include "usart.h"
#include <stm32f0.h>
volatile uint32_t Tms = 0;
// Called when systick fires
void sys_tick_handler(void){
++Tms;
}
int main(void){
uint32_t T = 0;
uint32_t tim3cnt = 0;
char *txt;
hw_setup();
SysTick_Config(6000, 1);
SEND("Encoder controller v0.1\n");
while (1){
if(usart1_getline(&txt)){ // usart1 received command, process it
txt = process_command(txt);
}else txt = NULL;
if(txt){ // text waits for sending
while(ALL_OK != usart1_send(txt, 0));
}
if(Tms - T == 10){
T = Tms;
if(tim3cnt != TIM3->CNT){
int32_t diff = TIM3->CNT - tim3cnt;
if(tim3upd){
if(TIM3->CR1 & TIM_CR1_DIR) diff -= 80;
else diff += 80;
tim3upd = 0;
}
tim3cnt = TIM3->CNT;
put_string("Speed: ");
put_int(diff);
put_string(", pos: ");
put_uint(TIM3->CNT);
put_char('\n');
}
}
usart1_sendbuf();
}
}

View File

@ -0,0 +1,55 @@
/*
* This file is part of the Chiller project.
* Copyright 2018 Edward V. Emelianov <edward.emelianoff@gmail.com>.
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#include "hardware.h"
#include "protocol.h"
#include "usart.h"
/**
* @brief process_command - command parser
* @param command - command text (all inside [] without spaces)
* @return text to send over terminal or NULL
*/
char *process_command(const char *command){
char *ret = NULL;
usart1_sendbuf(); // send buffer (if it is already filled)
switch(*command){
case '?': // help
SEND_BLK(
"D - get rotation direction\n"
"R - reset\n"
"T - get timer value\n"
);
break;
case 'D':
if(TIM3->CR1 & TIM_CR1_DIR) SEND("negative\n");
else SEND("positive\n");
break;
case 'R': // reset MCU
NVIC_SystemReset();
break;
case 'T':
put_string("TIM3->CNT=");
put_uint(TIM3->CNT);
put_char('\n');
break;
}
usart1_sendbuf();
return ret;
}

View File

@ -0,0 +1,24 @@
/*
* This file is part of the Chiller project.
* Copyright 2018 Edward V. Emelianov <edward.emelianoff@gmail.com>.
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#ifndef PROTOCOL_H__
#define PROTOCOL_H__
#include <stm32f0.h>
char *process_command(const char *command);
#endif // PROTOCOL_H__

View File

@ -0,0 +1,302 @@
/*
* usart.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 "usart.h"
#include <string.h> // memcpy
extern volatile uint32_t Tms;
static int datalen[2] = {0,0}; // received data line length (including '\n')
uint8_t bufovr = 0; // input buffer overfull
static uint8_t linerdy = 0 // received data ready
,dlen = 0 // length of data in current buffer
,txrdy = 1 // transmission done
;
static int rbufno = 0; // current rbuf number
static char rbuf[2][UARTBUFSZ+1], tbuf[UARTBUFSZ]; // receive & transmit buffers
static char *recvdata = NULL;
static char trbuf[UARTBUFSZ+1]; // auxiliary buffer for data transmission
static int trbufidx = 0;
int put_char(char c){
if(trbufidx >= UARTBUFSZ - 1){
for(int i = 0; i < 72000000 && ALL_OK != usart1_sendbuf(); ++i)
if(i == 72000000) return 1;
}
trbuf[trbufidx++] = c;
return 0;
}
// write zero-terminated string
int put_string(const char *str){
while(*str){
if(put_char(*str++)) return 1; //error! shouldn't be!!!
}
return 0; // all OK
}
/**
* Fill trbuf with integer value
* @param N - integer value
* @return 1 if buffer overflow; oterwise return 0
*/
int put_int(int32_t N){
if(N < 0){
if(put_char('-')) return 1;
N = -N;
}
return put_uint((uint32_t) N);
}
int put_uint(uint32_t N){
char buf[10];
int L = 0;
if(N){
while(N){
buf[L++] = N % 10 + '0';
N /= 10;
}
while(L--) if(put_char(buf[L])) return 1;
}else if(put_char('0')) return 1;
return 0;
}
/**
* @brief usart1_sendbuf - send temporary transmission buffer (trbuf) over USART
* @return Tx status
*/
TXstatus usart1_sendbuf(){
int len = trbufidx;
if(len == 0) return ALL_OK;
else if(len > UARTBUFSZ) len = UARTBUFSZ;
TXstatus s = usart1_send(trbuf, len);
if(s == ALL_OK) trbufidx = 0;
return s;
}
void USART1_config(){
/* Enable the peripheral clock of GPIOA */
RCC->AHBENR |= RCC_AHBENR_GPIOAEN;
/* GPIO configuration for USART1 signals */
/* (1) Select AF mode (10) on PA9 and PA10 */
/* (2) AF1 for USART1 signals */
GPIOA->MODER = (GPIOA->MODER & ~(GPIO_MODER_MODER9|GPIO_MODER_MODER10))\
| (GPIO_MODER_MODER9_1 | GPIO_MODER_MODER10_1); /* (1) */
GPIOA->AFR[1] = (GPIOA->AFR[1] &~ (GPIO_AFRH_AFRH1 | GPIO_AFRH_AFRH2))\
| (1 << (1 * 4)) | (1 << (2 * 4)); /* (2) */
/* Enable the peripheral clock USART1 */
RCC->APB2ENR |= RCC_APB2ENR_USART1EN;
/* Configure USART1 */
/* (1) oversampling by 16, 115200 baud */
/* (2) 8 data bit, 1 start bit, 1 stop bit, no parity */
USART1->BRR = 480000 / 1152; /* (1) */
USART1->CR1 = USART_CR1_TE | USART_CR1_RE | USART_CR1_UE; /* (2) */
/* polling idle frame Transmission */
while(!(USART1->ISR & USART_ISR_TC)){}
USART1->ICR |= USART_ICR_TCCF; /* clear TC flag */
USART1->CR1 |= USART_CR1_RXNEIE; /* enable TC, TXE & RXNE interrupt */
RCC->AHBENR |= RCC_AHBENR_DMA1EN;
DMA1_Channel2->CPAR = (uint32_t) &(USART1->TDR); // periph
DMA1_Channel2->CMAR = (uint32_t) tbuf; // mem
DMA1_Channel2->CCR |= DMA_CCR_MINC | DMA_CCR_DIR | DMA_CCR_TCIE; // 8bit, mem++, mem->per, transcompl irq
USART1->CR3 = USART_CR3_DMAT;
NVIC_SetPriority(DMA1_Channel2_3_IRQn, 3);
NVIC_EnableIRQ(DMA1_Channel2_3_IRQn);
/* Configure IT */
/* (3) Set priority for USART1_IRQn */
/* (4) Enable USART1_IRQn */
NVIC_SetPriority(USART1_IRQn, 0); /* (3) */
NVIC_EnableIRQ(USART1_IRQn); /* (4) */
}
#ifdef EBUG
#define TMO 0
#else
#define TMO 1
#endif
void usart1_isr(){
static uint8_t timeout = TMO // == 0 for human interface without timeout
,nctr = 0 // counter of '#' received
,incmd = 0 // ==1 - inside command
;
static uint32_t tmout = 0;
if(USART1->ISR & USART_ISR_RXNE){ // RX not emty - receive next char
// read RDR clears flag
uint8_t rb = USART1->RDR;
if(timeout && rb == '#'){ // chek '#' without timeout
if(++nctr == 4){ // "####" received - turn off timeout
timeout = 0;
nctr = 0;
datalen[rbufno] = 0; // reset all incoming data
incmd = 0;
return;
}
}else nctr = 0;
if(!incmd){
if(rb == '['){ // open command or reset previoud input
datalen[rbufno] = 0;
incmd = 1;
}
return;
}
if(timeout){ // check timeout only inside commands
if(tmout && Tms >= tmout){ // set overflow flag
bufovr = 1;
datalen[rbufno] = 0;
}else{
tmout = Tms + TIMEOUT_MS;
if(!tmout) tmout = 1; // prevent 0
}
}
switch(rb){
case '[':
datalen[rbufno] = 0;
tmout = 0;
break;
case ']': // close command - line ready!
dlen = datalen[rbufno];
if(dlen){
linerdy = 1;
incmd = 0;
recvdata = rbuf[rbufno];
rbuf[rbufno][dlen] = 0;
rbufno = !rbufno;
datalen[rbufno] = 0;
}
tmout = 0;
break;
case '\r':
case '\n':
case ' ':
case '\t':
return;
break;
default:
break;
}
if(datalen[rbufno] < UARTBUFSZ){ // put next char into buf
rbuf[rbufno][datalen[rbufno]++] = rb;
}else{ // buffer overrun
bufovr = 1;
datalen[rbufno] = 0;
incmd = 0;
tmout = 0;
}
}
}
void dma1_channel2_3_isr(){
if(DMA1->ISR & DMA_ISR_TCIF2){ // Tx
DMA1->IFCR |= DMA_IFCR_CTCIF2; // clear TC flag
txrdy = 1;
}
}
/**
* return length of received data (without trailing zero)
*/
int usart1_getline(char **line){
if(!linerdy) return 0;
linerdy = 0;
if(bufovr){
bufovr = 0;
return 0;
}
*line = recvdata;
return dlen;
}
/**
* @brief usart1_send send buffer `str` adding trailing '\n'
* @param str - string to send (without '\n' at end)
* @param len - its length or 0 to auto count
* @return
*/
TXstatus usart1_send(const char *str, int len){
if(!txrdy) return LINE_BUSY;
if(len > UARTBUFSZ - 1) return STR_TOO_LONG;
txrdy = 0;
if(len == 0){
const char *ptr = str;
while(*ptr++) ++len;
}
if(len == 0) return ALL_OK;
DMA1_Channel2->CCR &= ~DMA_CCR_EN;
memcpy(tbuf, str, len);
// tbuf[len++] = '\n';
DMA1_Channel2->CNDTR = len;
DMA1_Channel2->CCR |= DMA_CCR_EN; // start transmission
return ALL_OK;
}
TXstatus usart1_send_blocking(const char *str, int len){
if(!txrdy) return LINE_BUSY;
if(len == 0){
const char *ptr = str;
while(*ptr++) ++len;
}
if(len == 0) return ALL_OK;
for(int i = 0; i < len; ++i){
USART1->TDR = *str++;
while(!(USART1->ISR & USART_ISR_TXE));
}
// USART1->TDR = '\n';
while(!(USART1->ISR & USART_ISR_TC));
txrdy = 1;
return ALL_OK;
}
// read `buf` and get first integer `N` in it
// @return pointer to first non-number if all OK or NULL if first symbol isn't a space or number
char *getnum(const char *buf, int32_t *N){
char c;
int positive = -1;
int32_t val = 0;
//usart1_send_blocking(buf, 0);
while((c = *buf++)){
if(c == '\t' || c == ' '){
if(positive < 0) continue; // beginning spaces
else break; // spaces after number
}
if(c == '-'){
if(positive < 0){
positive = 0;
continue;
}else break; // there already was `-` or number
}
if(c < '0' || c > '9') break;
if(positive < 0) positive = 1;
val = val * 10 + (int32_t)(c - '0');
}
if(positive != -1){
if(positive == 0){
if(val == 0) return NULL; // single '-'
val = -val;
}
*N = val;
}else return NULL;
/* usart1_sendbuf();
put_uint(val);
put_char('\n');*/
return (char*)buf-1;
}

View File

@ -0,0 +1,59 @@
/*
* usart.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 __USART_H__
#define __USART_H__
#include "stm32f0.h"
// input and output buffers size
#define UARTBUFSZ (64)
// timeout between data bytes
#define TIMEOUT_MS (100)
typedef enum{
ALL_OK,
LINE_BUSY,
STR_TOO_LONG
} TXstatus;
#define usart1ovr() (bufovr)
// send constant string
#define SEND_BLK(x) do{while(LINE_BUSY == usart1_send_blocking(x, sizeof(x)-1)) IWDG->KR = IWDG_REFRESH;}while(0)
#define SEND(x) do{while(LINE_BUSY == usart1_send(x, sizeof(x)-1)) IWDG->KR = IWDG_REFRESH;}while(0)
extern uint8_t bufovr;
void USART1_config();
int usart1_getline(char **line);
TXstatus usart1_send(const char *str, int len);
TXstatus usart1_send_blocking(const char *str, int len);
TXstatus usart1_sendbuf();
int put_char(char c);
int put_string(const char *str);
int put_int(int32_t N);
int put_uint(uint32_t N);
char *getnum(const char *buf, int32_t *N);
#endif // __USART_H__