mirror of
https://github.com/eddyem/tsys01.git
synced 2025-12-06 02:25:13 +03:00
Add code & schematic for 48-channel I2C multiplexer
This commit is contained in:
parent
49a2a231b7
commit
4e74e1121b
144
STM32/src4multiplexer/Makefile
Normal file
144
STM32/src4multiplexer/Makefile
Normal file
@ -0,0 +1,144 @@
|
||||
BINARY = tsys01
|
||||
BOOTPORT ?= /dev/ttyUSB0
|
||||
BOOTSPEED ?= 9600
|
||||
# MCU FAMILY
|
||||
FAMILY = F0
|
||||
# MCU code
|
||||
MCU = F042x6
|
||||
# hardware definitions
|
||||
#DEFS := -DUSARTNUM=2 -DI2CPINS=A9A10
|
||||
DEFS += -DEBUG
|
||||
# change this linking script depending on particular MCU model,
|
||||
# for example, if you have STM32F103VBT6, you should write:
|
||||
LDSCRIPT = ld/stm32f042k.ld
|
||||
|
||||
INDEPENDENT_HEADERS=
|
||||
|
||||
FP_FLAGS ?= -msoft-float
|
||||
ASM_FLAGS = -mthumb -mcpu=cortex-m0 -march=armv6-m -mtune=cortex-m0
|
||||
ARCH_FLAGS = $(ASM_FLAGS) $(FP_FLAGS)
|
||||
|
||||
###############################################################################
|
||||
# Executables
|
||||
OPREFIX ?= /opt/bin/arm-none-eabi
|
||||
#PREFIX ?= /usr/x86_64-pc-linux-gnu/arm-none-eabi/gcc-bin/7.3.0/arm-none-eabi
|
||||
PREFIX ?= $(OPREFIX)
|
||||
|
||||
RM := rm -f
|
||||
RMDIR := rmdir
|
||||
CC := $(PREFIX)-gcc
|
||||
LD := $(PREFIX)-gcc
|
||||
AR := $(PREFIX)-ar
|
||||
AS := $(PREFIX)-as
|
||||
OBJCOPY := $(OPREFIX)-objcopy
|
||||
OBJDUMP := $(OPREFIX)-objdump
|
||||
GDB := $(OPREFIX)-gdb
|
||||
STFLASH := $(shell which st-flash)
|
||||
STBOOT := $(shell which stm32flash)
|
||||
|
||||
###############################################################################
|
||||
# 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)/F0 -I$(INC_DIR)/cm
|
||||
LIB_DIR := $(INC_DIR)/ld
|
||||
|
||||
###############################################################################
|
||||
# C flags
|
||||
CFLAGS += -O2 -g -MD -D__thumb2__=1
|
||||
CFLAGS += -Wall -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 $<
|
||||
|
||||
#$(OBJDIR)/%.d: %.c $(OBJDIR)
|
||||
# $(CC) -MM -MG $< | sed -e 's,^\([^:]*\)\.o[ ]*:,$(@D)/\1.o $(@D)/\1.d:,' >$@
|
||||
|
||||
$(BIN): $(ELF)
|
||||
@echo " OBJCOPY $(BIN)"
|
||||
$(OBJCOPY) -Obinary $(ELF) $(BIN)
|
||||
|
||||
$(HEX): $(ELF)
|
||||
@echo " OBJCOPY $(HEX)"
|
||||
$(OBJCOPY) -Oihex $(ELF) $(HEX)
|
||||
|
||||
$(LIST): $(ELF)
|
||||
@echo " OBJDUMP $(LIST)"
|
||||
$(OBJDUMP) -S $(ELF) > $(LIST)
|
||||
|
||||
$(ELF): $(OBJDIR) $(OBJS)
|
||||
@echo " LD $(ELF)"
|
||||
$(LD) $(LDFLAGS) $(ARCH_FLAGS) $(OBJS) $(LDLIBS) -o $(ELF)
|
||||
|
||||
clean:
|
||||
@echo " CLEAN"
|
||||
$(RM) $(OBJS) $(DEPS) $(ELF) $(HEX) $(LIST) $(OBJDIR)/*.map
|
||||
@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)
|
||||
|
||||
gentags:
|
||||
CFLAGS="$(CFLAGS) $(DEFS)" geany -g $(BINARY).c.tags *[hc] 2>/dev/null
|
||||
|
||||
.PHONY: clean flash boot gentags
|
||||
18
STM32/src4multiplexer/Readme.md
Normal file
18
STM32/src4multiplexer/Readme.md
Normal file
@ -0,0 +1,18 @@
|
||||
# Check temperature on 16 sensors with different addresses and show values by USART.
|
||||
USART speed 115200. Code for NUCLEO-042
|
||||
|
||||
### Serial interface commands (ends with '\n'):
|
||||
|
||||
- **C** show coefficients for both thermosensors
|
||||
- **D** detect seosors (reseting them)
|
||||
- **H** switch I2C to high speed (100kHz)
|
||||
- **L** switch I2C to low speed (default, 10kHz)
|
||||
- **R** reset both sensors
|
||||
- **T** get temperature
|
||||
- **number** from 0 to 48 - set active multiplexer channel (PA3..PA8)
|
||||
|
||||
|
||||
### PINOUT
|
||||
- Multiplexer: PA3..PA8 (bits0..5)
|
||||
- I2C: PA9 (SCL) & PA10 (SDA)
|
||||
- USART2: PA2 (Tx) & PA15 (Rx)
|
||||
14
STM32/src4multiplexer/Readme.pinout
Normal file
14
STM32/src4multiplexer/Readme.pinout
Normal file
@ -0,0 +1,14 @@
|
||||
NAME NUCLEO-042 SENSORS board
|
||||
|
||||
USART USART2 USART1
|
||||
USART_TX PA2 PA9
|
||||
USART_RX PA15 PA10
|
||||
I2C
|
||||
SCL PA9 PB6
|
||||
SDA PA10 PB7
|
||||
Multiplexer
|
||||
~EN PA3 PB12
|
||||
ADDR0..3 PA4..7 PB0..2 (!!!)
|
||||
LEDS
|
||||
LED0 PB3 PB10
|
||||
LED1 --- PB11
|
||||
66
STM32/src4multiplexer/hardware.c
Normal file
66
STM32/src4multiplexer/hardware.c
Normal file
@ -0,0 +1,66 @@
|
||||
/*
|
||||
* geany_encoding=koi8-r
|
||||
* hardware.c - hardware-dependent macros & functions
|
||||
*
|
||||
* Copyright 2018 Edward V. Emelianov <eddy@sao.ru, edward.emelianoff@gmail.com>
|
||||
*
|
||||
* This program is free software; you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation; either version 2 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program; if not, write to the Free Software
|
||||
* Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston,
|
||||
* MA 02110-1301, USA.
|
||||
*
|
||||
*/
|
||||
|
||||
#include "hardware.h"
|
||||
|
||||
void gpio_setup(void){
|
||||
// Set green led (PB3) as output
|
||||
RCC->AHBENR |= RCC_AHBENR_GPIOBEN | RCC_AHBENR_GPIOAEN;
|
||||
GPIOB->MODER = GPIO_MODER_MODER3_O;
|
||||
// setup of multiplexer channel address bus: PA3..8
|
||||
GPIOA->MODER = GPIO_MODER_MODER3_O | GPIO_MODER_MODER4_O | GPIO_MODER_MODER5_O |
|
||||
GPIO_MODER_MODER6_O | GPIO_MODER_MODER7_O | GPIO_MODER_MODER8_O;
|
||||
}
|
||||
|
||||
void i2c_setup(I2C_SPEED speed){
|
||||
I2C1->CR1 = 0;
|
||||
#if I2CPINS == A9A10
|
||||
/*
|
||||
* GPIO Resources: I2C1_SCL - PA9, I2C1_SDA - PA10
|
||||
* GPIOA->AFR[1] AF4 -- GPIOA->AFR[1] &= ~0xff0, GPIOA->AFR[1] |= 0x440
|
||||
*/
|
||||
RCC->AHBENR |= RCC_AHBENR_GPIOAEN; // clock
|
||||
GPIOA->AFR[1] &= ~0xff0; // alternate function F4 for PA9/PA10
|
||||
GPIOA->AFR[1] |= 0x440;
|
||||
GPIOA->MODER &= ~(GPIO_MODER_MODER9 | GPIO_MODER_MODER10);
|
||||
GPIOA->MODER |= GPIO_MODER_MODER9_AF | GPIO_MODER_MODER10_AF; // alternate function
|
||||
GPIOA->OTYPER |= GPIO_OTYPER_OT_9 | GPIO_OTYPER_OT_10; // opendrain
|
||||
//GPIOA->OTYPER |= GPIO_OTYPER_OT_10; // opendrain
|
||||
#else // undefined
|
||||
#error "Not implemented"
|
||||
#endif
|
||||
// I2C
|
||||
RCC->APB1ENR |= RCC_APB1ENR_I2C1EN; // timing
|
||||
RCC->CFGR3 |= RCC_CFGR3_I2C1SW; // use sysclock for timing
|
||||
if(speed == LOW_SPEED){ // 10kHz
|
||||
// PRESC=B, SCLDEL=4, SDADEL=2, SCLH=0xC3, SCLL=0xC7
|
||||
//I2C1->TIMINGR = (0xB<<28) | (4<<20) | (2<<16) | (0xC3<<8) | (0xC7);
|
||||
I2C1->TIMINGR = (0xB<<28) | (4<<20) | (2<<16) | (0xC3<<8) | (0xB0);
|
||||
}else{ // 100kHz
|
||||
// Clock = 6MHz, 0.16(6)us, need 5us (*30)
|
||||
// PRESC=4 (f/5), SCLDEL=0 (t_SU=5/6us), SDADEL=0 (t_HD=5/6us), SCLL,SCLH=14 (2.(3)us)
|
||||
//I2C1->TIMINGR = (4<<28) | (14<<8) | (14); // 0x40000e0e
|
||||
I2C1->TIMINGR = (0xB<<28) | (4<<20) | (2<<16) | (0x12<<8) | (0x11);
|
||||
}
|
||||
I2C1->CR1 = I2C_CR1_PE;// | I2C_CR1_RXIE; // Enable I2C & (interrupt on receive - not supported yet)
|
||||
}
|
||||
61
STM32/src4multiplexer/hardware.h
Normal file
61
STM32/src4multiplexer/hardware.h
Normal file
@ -0,0 +1,61 @@
|
||||
/*
|
||||
* geany_encoding=koi8-r
|
||||
* hardware.h
|
||||
*
|
||||
* Copyright 2018 Edward V. Emelianov <eddy@sao.ru, edward.emelianoff@gmail.com>
|
||||
*
|
||||
* This program is free software; you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation; either version 2 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program; if not, write to the Free Software
|
||||
* Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston,
|
||||
* MA 02110-1301, USA.
|
||||
*
|
||||
*/
|
||||
|
||||
#include "stm32f0.h"
|
||||
|
||||
#define LED0_port GPIOB
|
||||
#define LED0_pin (1<<3)
|
||||
|
||||
#ifndef USARTNUM
|
||||
#define USARTNUM 2
|
||||
#endif
|
||||
|
||||
#define CONCAT(a,b) a ## b
|
||||
#define STR_HELPER(s) #s
|
||||
#define STR(s) STR_HELPER(s)
|
||||
|
||||
#define FORMUSART(X) CONCAT(USART, X)
|
||||
#define USARTX FORMUSART(USARTNUM)
|
||||
|
||||
#ifndef I2CPINS
|
||||
#define I2CPINS A9A10
|
||||
#endif
|
||||
|
||||
#ifndef LED1_port
|
||||
#define LED1_port LED0_port
|
||||
#endif
|
||||
#ifndef LED1_pin
|
||||
#define LED1_pin LED0_pin
|
||||
#endif
|
||||
#define LED_blink(x) pin_toggle(x ## _port, x ## _pin)
|
||||
|
||||
// set active channel number
|
||||
#define MUL_ADDRESS(x) do{GPIOA->BSRR = (0x1F8 << 16) | (x << 3);}while(0)
|
||||
|
||||
typedef enum{
|
||||
LOW_SPEED,
|
||||
HIGH_SPEED
|
||||
} I2C_SPEED;
|
||||
|
||||
void gpio_setup(void);
|
||||
void i2c_setup(I2C_SPEED speed);
|
||||
99
STM32/src4multiplexer/i2c.c
Normal file
99
STM32/src4multiplexer/i2c.c
Normal file
@ -0,0 +1,99 @@
|
||||
/*
|
||||
* geany_encoding=koi8-r
|
||||
* i2c.c
|
||||
*
|
||||
* Copyright 2017 Edward V. Emelianov <eddy@sao.ru, edward.emelianoff@gmail.com>
|
||||
*
|
||||
* This program is free software; you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation; either version 2 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program; if not, write to the Free Software
|
||||
* Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston,
|
||||
* MA 02110-1301, USA.
|
||||
*
|
||||
*/
|
||||
#include "stm32f0.h"
|
||||
#include "hardware.h"
|
||||
#include "i2c.h"
|
||||
|
||||
/**
|
||||
* I2C for TSYS01
|
||||
* Speed <= 400kHz (200)
|
||||
* t_SCLH > 21ns
|
||||
* t_SCLL > 21ns
|
||||
* while reading, sends NACK
|
||||
* after reading get 24bits of T value, we need upper 2 bytes: ADC16 = ADC>>8
|
||||
* T = (-2) * k4 * 10^{-21} * ADC16^4
|
||||
* + 4 * k3 * 10^{-16} * ADC16^3
|
||||
* + (-2) * k2 * 10^{-11} * ADC16^2
|
||||
* + 1 * k1 * 10^{-6} * ADC16
|
||||
* +(-1.5)* k0 * 10^{-2}
|
||||
* All coefficiens are in registers:
|
||||
* k4 - 0xA2, k3 - 0xA4, k2 - 0xA6, k1 - 0xA8, k0 - 0xAA
|
||||
*/
|
||||
|
||||
extern volatile uint32_t Tms;
|
||||
static uint32_t cntr;
|
||||
|
||||
/**
|
||||
* write command byte to I2C
|
||||
* @param addr - device address (TSYS01_ADDR0 or TSYS01_ADDR1)
|
||||
* @param data - byte to write
|
||||
* @return 0 if error
|
||||
*/
|
||||
uint8_t write_i2c(uint8_t addr, uint8_t data){
|
||||
cntr = Tms;
|
||||
while(I2C1->ISR & I2C_ISR_BUSY) if(Tms - cntr > I2C_TIMEOUT) return 0; // check busy
|
||||
cntr = Tms;
|
||||
while(I2C1->CR2 & I2C_CR2_START) if(Tms - cntr > I2C_TIMEOUT) return 0; // check start
|
||||
I2C1->CR2 = 1<<16 | addr | I2C_CR2_AUTOEND; // 1 byte, autoend
|
||||
// now start transfer
|
||||
I2C1->CR2 |= I2C_CR2_START;
|
||||
cntr = Tms;
|
||||
while(!(I2C1->ISR & I2C_ISR_TXIS)){ // ready to transmit
|
||||
if(I2C1->ISR & I2C_ISR_NACKF){
|
||||
I2C1->ICR |= I2C_ICR_NACKCF;
|
||||
return 0;
|
||||
}
|
||||
if(Tms - cntr > I2C_TIMEOUT) return 0;
|
||||
}
|
||||
I2C1->TXDR = data; // send data
|
||||
return 1;
|
||||
}
|
||||
|
||||
/**
|
||||
* read nbytes (2 or 3) of data from I2C line
|
||||
* @return 1 if all OK, 0 if NACK or no device found
|
||||
*/
|
||||
uint8_t read_i2c(uint8_t addr, uint32_t *data, uint8_t nbytes){
|
||||
uint32_t result = 0;
|
||||
cntr = Tms;
|
||||
while(I2C1->ISR & I2C_ISR_BUSY) if(Tms - cntr > 5) return 0; // check busy
|
||||
cntr = Tms;
|
||||
while(I2C1->CR2 & I2C_CR2_START) if(Tms - cntr > 5) return 0; // check start
|
||||
// read N bytes
|
||||
I2C1->CR2 = (nbytes<<16) | addr | 1 | I2C_CR2_AUTOEND | I2C_CR2_RD_WRN;
|
||||
I2C1->CR2 |= I2C_CR2_START;
|
||||
uint8_t i;
|
||||
cntr = Tms;
|
||||
for(i = 0; i < nbytes; ++i){
|
||||
while(!(I2C1->ISR & I2C_ISR_RXNE)){ // wait for data
|
||||
if(I2C1->ISR & I2C_ISR_NACKF){
|
||||
I2C1->ICR |= I2C_ICR_NACKCF;
|
||||
return 0;
|
||||
}
|
||||
if(Tms - cntr > 5) return 0;
|
||||
}
|
||||
result = (result << 8) | I2C1->RXDR;
|
||||
}
|
||||
*data = result;
|
||||
return 1;
|
||||
}
|
||||
39
STM32/src4multiplexer/i2c.h
Normal file
39
STM32/src4multiplexer/i2c.h
Normal file
@ -0,0 +1,39 @@
|
||||
/*
|
||||
* geany_encoding=koi8-r
|
||||
* i2c.h
|
||||
*
|
||||
* Copyright 2017 Edward V. Emelianov <eddy@sao.ru, edward.emelianoff@gmail.com>
|
||||
*
|
||||
* This program is free software; you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation; either version 2 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program; if not, write to the Free Software
|
||||
* Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston,
|
||||
* MA 02110-1301, USA.
|
||||
*
|
||||
*/
|
||||
|
||||
// timeout in ms
|
||||
#define I2C_TIMEOUT (15)
|
||||
// CSB=1, address 1110110
|
||||
#define TSYS01_ADDR0 (0x76 << 1)
|
||||
// CSB=0, address 1110111
|
||||
#define TSYS01_ADDR1 (0x77 << 1)
|
||||
// registers: reset, read ADC value, start converstion, sart of PROM
|
||||
#define TSYS01_RESET (0x1E)
|
||||
#define TSYS01_ADC_READ (0x00)
|
||||
#define TSYS01_START_CONV (0x48)
|
||||
#define TSYS01_PROM_ADDR0 (0xA0)
|
||||
// conversion time = 10ms
|
||||
#define CONV_TIME (10)
|
||||
|
||||
uint8_t read_i2c(uint8_t addr, uint32_t *data, uint8_t nbytes);
|
||||
uint8_t write_i2c(uint8_t addr, uint8_t data);
|
||||
12
STM32/src4multiplexer/ld/stm32f042k.ld
Normal file
12
STM32/src4multiplexer/ld/stm32f042k.ld
Normal file
@ -0,0 +1,12 @@
|
||||
/* Linker script for STM32F042x6, 32K flash, 6K RAM. */
|
||||
|
||||
/* Define memory regions. */
|
||||
MEMORY
|
||||
{
|
||||
rom (rx) : ORIGIN = 0x08000000, LENGTH = 32K
|
||||
ram (rwx) : ORIGIN = 0x20000000, LENGTH = 6K
|
||||
}
|
||||
|
||||
/* Include the common ld script. */
|
||||
INCLUDE stm32f0.ld
|
||||
|
||||
198
STM32/src4multiplexer/main.c
Normal file
198
STM32/src4multiplexer/main.c
Normal file
@ -0,0 +1,198 @@
|
||||
/*
|
||||
* main.c
|
||||
*
|
||||
* Copyright 2017 Edward V. Emelianoff <eddy@sao.ru, edward.emelianoff@gmail.com>
|
||||
*
|
||||
* This program is free software; you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation; either version 2 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program; if not, write to the Free Software
|
||||
* Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston,
|
||||
* MA 02110-1301, USA.
|
||||
*/
|
||||
|
||||
#include "hardware.h"
|
||||
#include "usart.h"
|
||||
#include "i2c.h"
|
||||
|
||||
volatile uint32_t Tms = 0;
|
||||
|
||||
/* Called when systick fires */
|
||||
void sys_tick_handler(void){
|
||||
++Tms;
|
||||
}
|
||||
|
||||
// print 32bit unsigned int
|
||||
void printu(uint32_t val){
|
||||
char buf[11], rbuf[10];
|
||||
int l = 0, bpos = 0;
|
||||
if(!val){
|
||||
buf[0] = '0';
|
||||
l = 1;
|
||||
}else{
|
||||
while(val){
|
||||
rbuf[l++] = val % 10 + '0';
|
||||
val /= 10;
|
||||
}
|
||||
int i;
|
||||
bpos += l;
|
||||
for(i = 0; i < l; ++i){
|
||||
buf[--bpos] = rbuf[i];
|
||||
}
|
||||
}
|
||||
while(LINE_BUSY == usart_send_blocking(buf, l+bpos));
|
||||
}
|
||||
|
||||
void showcoeffs(uint8_t addr){ // show norm coefficiens
|
||||
int i;
|
||||
const uint8_t regs[5] = {0xAA, 0xA8, 0xA6, 0xA4, 0xA2}; // commands for coefficients
|
||||
uint32_t K;
|
||||
char numbr = (addr == TSYS01_ADDR0) ? '0' : '1';
|
||||
for(i = 0; i < 5; ++i){
|
||||
if(write_i2c(addr, regs[i])){
|
||||
if(read_i2c(addr, &K, 2)){
|
||||
char b[4] = {'K', numbr, i+'0', '='};
|
||||
while(ALL_OK != usart_send_blocking(b, 4));
|
||||
printu(K);
|
||||
while(ALL_OK != usart_send_blocking("\n", 1));
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void ch_addr(char *str){
|
||||
char ch;
|
||||
uint32_t L = 0;
|
||||
for(ch = *str++; ch && ch > '/' && ch < ':'; ch = *str++){
|
||||
L = L * 10 + ch - '0';
|
||||
if(L > 47){
|
||||
SEND("Bad address!\n");
|
||||
return;
|
||||
}
|
||||
}
|
||||
MUL_ADDRESS(L);
|
||||
printu(L);
|
||||
SEND(" channel active\n");
|
||||
}
|
||||
|
||||
int main(void){
|
||||
uint32_t lastT = 0;
|
||||
int16_t L = 0;
|
||||
uint32_t started0=0, started1=0; // time of measurements for given sensor started
|
||||
char *txt;
|
||||
sysreset();
|
||||
SysTick_Config(6000, 1);
|
||||
gpio_setup();
|
||||
usart_setup();
|
||||
i2c_setup(LOW_SPEED);
|
||||
// reset on start
|
||||
write_i2c(TSYS01_ADDR0, TSYS01_RESET);
|
||||
write_i2c(TSYS01_ADDR1, TSYS01_RESET);
|
||||
|
||||
while (1){
|
||||
if(lastT > Tms || Tms - lastT > 499){
|
||||
LED_blink(LED0);
|
||||
lastT = Tms;
|
||||
}
|
||||
if(started0 && Tms - started0 > CONV_TIME){ // poll sensor0
|
||||
if(write_i2c(TSYS01_ADDR0, TSYS01_ADC_READ)){
|
||||
uint32_t t;
|
||||
if(read_i2c(TSYS01_ADDR0, &t, 3)){
|
||||
while(ALL_OK != usart_send_blocking("T0=", 3));
|
||||
printu(t);
|
||||
while(ALL_OK != usart_send_blocking("\n", 1));
|
||||
started0 = 0;
|
||||
}
|
||||
}
|
||||
}
|
||||
if(started1 && Tms - started1 > CONV_TIME){ // poll sensor1
|
||||
if(write_i2c(TSYS01_ADDR1, TSYS01_ADC_READ)){
|
||||
uint32_t t;
|
||||
if(read_i2c(TSYS01_ADDR1, &t, 3)){
|
||||
while(ALL_OK != usart_send_blocking("T1=", 3));
|
||||
printu(t);
|
||||
while(ALL_OK != usart_send_blocking("\n", 1));
|
||||
started1 = 0;
|
||||
}
|
||||
}
|
||||
}
|
||||
if(usartrx()){ // usart1 received data, store in in buffer
|
||||
L = usart_getline(&txt);
|
||||
char _1st = txt[0];
|
||||
if(_1st > '/' && _1st < ':'){
|
||||
ch_addr(txt);
|
||||
L = 0;
|
||||
}else if(L == 2 && txt[1] == '\n'){
|
||||
L = 0;
|
||||
uint32_t tstart = Tms;
|
||||
switch(_1st){
|
||||
case 'C': // 'C' - show coefficients
|
||||
showcoeffs(TSYS01_ADDR0);
|
||||
showcoeffs(TSYS01_ADDR1);
|
||||
break;
|
||||
case 'R': // 'R' - reset both
|
||||
SEND("Reset\n");
|
||||
write_i2c(TSYS01_ADDR0, TSYS01_RESET);//) SEND("0 - err\n");
|
||||
write_i2c(TSYS01_ADDR1, TSYS01_RESET);//) SEND("1 - err\n");
|
||||
break;
|
||||
case 'D':
|
||||
if(write_i2c(TSYS01_ADDR0, TSYS01_RESET)) SEND("0");
|
||||
if(write_i2c(TSYS01_ADDR1, TSYS01_RESET)) SEND("1");
|
||||
SEND("\n");
|
||||
break;
|
||||
case 't':
|
||||
SEND("USART");
|
||||
SEND(" test ");
|
||||
printu(111);
|
||||
SEND(" got number 111?\n");
|
||||
break;
|
||||
case 'T': // 'T' - get temperature
|
||||
if(tstart == 0) tstart = 1;
|
||||
if(write_i2c(TSYS01_ADDR0, TSYS01_START_CONV)) started0 = tstart;
|
||||
else{
|
||||
//SEND("0 BAD\n");
|
||||
started0 = 0;
|
||||
}
|
||||
if(write_i2c(TSYS01_ADDR1, TSYS01_START_CONV)) started1 = tstart;
|
||||
else{
|
||||
//SEND("1 BAD\n");
|
||||
started1 = 0;
|
||||
}
|
||||
break;
|
||||
case 'L':
|
||||
i2c_setup(LOW_SPEED);
|
||||
SEND("Low speed\n");
|
||||
break;
|
||||
case 'H':
|
||||
i2c_setup(HIGH_SPEED);
|
||||
SEND("High speed\n");
|
||||
break;
|
||||
default: // help
|
||||
SEND("'C' - show coefficients\n"
|
||||
"'D' - slave discovery\n"
|
||||
"'R' - reset both\n"
|
||||
"'T' - get temperature\n"
|
||||
"'t' - USART test\n"
|
||||
"number - set active channel\n"
|
||||
"'L' - low speed\n"
|
||||
"'H' - high speed\n");
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
if(L){ // text waits for sending
|
||||
while(LINE_BUSY == usart_send(txt, L));
|
||||
L = 0;
|
||||
}
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
BIN
STM32/src4multiplexer/tsys01.bin
Executable file
BIN
STM32/src4multiplexer/tsys01.bin
Executable file
Binary file not shown.
4370
STM32/src4multiplexer/tsys01.c.tags
Normal file
4370
STM32/src4multiplexer/tsys01.c.tags
Normal file
File diff suppressed because it is too large
Load Diff
32
STM32/src4multiplexer/tsys01.geany
Normal file
32
STM32/src4multiplexer/tsys01.geany
Normal file
@ -0,0 +1,32 @@
|
||||
[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=tsys01
|
||||
base_path=/home/eddy/Docs/SAO/BTA/Зеркало_контроль/Project/STM32src/src
|
||||
|
||||
[long line marker]
|
||||
long_line_behaviour=1
|
||||
long_line_column=100
|
||||
|
||||
[files]
|
||||
current_page=-1
|
||||
|
||||
[VTE]
|
||||
last_dir=/home/eddy
|
||||
167
STM32/src4multiplexer/usart.c
Normal file
167
STM32/src4multiplexer/usart.c
Normal file
@ -0,0 +1,167 @@
|
||||
/*us
|
||||
* usart.c
|
||||
*
|
||||
* Copyright 2017 Edward V. Emelianoff <eddy@sao.ru, edward.emelianoff@gmail.com>
|
||||
*
|
||||
* This program is free software; you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation; either version 2 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program; if not, write to the Free Software
|
||||
* Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston,
|
||||
* MA 02110-1301, USA.
|
||||
*/
|
||||
#include "stm32f0.h"
|
||||
#include "hardware.h"
|
||||
#include "usart.h"
|
||||
#include <string.h>
|
||||
|
||||
extern volatile uint32_t Tms;
|
||||
static int datalen[2] = {0,0}; // received data line length (including '\n')
|
||||
|
||||
int linerdy = 0, // received data ready
|
||||
dlen = 0, // length of data (including '\n') in current buffer
|
||||
bufovr = 0, // input buffer overfull
|
||||
txrdy = 1 // transmission done
|
||||
;
|
||||
|
||||
|
||||
int rbufno = 0; // current rbuf number
|
||||
static char rbuf[UARTBUFSZ][2], tbuf[UARTBUFSZ]; // receive & transmit buffers
|
||||
static char *recvdata = NULL;
|
||||
|
||||
/**
|
||||
* return length of received data (without trailing zero
|
||||
*/
|
||||
int usart_getline(char **line){
|
||||
if(bufovr){
|
||||
bufovr = 0;
|
||||
linerdy = 0;
|
||||
return 0;
|
||||
}
|
||||
*line = recvdata;
|
||||
linerdy = 0;
|
||||
return dlen;
|
||||
}
|
||||
|
||||
TXstatus usart_send(const char *str, int len){
|
||||
if(!txrdy) return LINE_BUSY;
|
||||
if(len > UARTBUFSZ) return STR_TOO_LONG;
|
||||
txrdy = 0;
|
||||
memcpy(tbuf, str, len);
|
||||
#if USARTNUM == 2
|
||||
DMA1_Channel4->CCR &= ~DMA_CCR_EN;
|
||||
DMA1_Channel4->CNDTR = len;
|
||||
DMA1_Channel4->CCR |= DMA_CCR_EN; // start transmission
|
||||
#else // USART1
|
||||
#error "Not implemented"
|
||||
#endif
|
||||
return ALL_OK;
|
||||
}
|
||||
|
||||
TXstatus usart_send_blocking(const char *str, int len){
|
||||
if(!txrdy) return LINE_BUSY;
|
||||
int i;
|
||||
bufovr = 0;
|
||||
for(i = 0; i < len; ++i){
|
||||
USARTX -> TDR = *str++;
|
||||
while(!(USARTX->ISR & USART_ISR_TXE));
|
||||
}
|
||||
return ALL_OK;
|
||||
}
|
||||
|
||||
|
||||
// Nucleo's USART2 connected to VCP proxy of st-link
|
||||
void usart_setup(){
|
||||
#if USARTNUM == 2
|
||||
// setup pins: PA2 (Tx - AF1), PA15 (Rx - AF1)
|
||||
RCC->AHBENR |= RCC_AHBENR_GPIOAEN | RCC_AHBENR_DMAEN;
|
||||
// AF mode (AF1)
|
||||
GPIOA->MODER = (GPIOA->MODER & ~(GPIO_MODER_MODER2|GPIO_MODER_MODER15))\
|
||||
| (GPIO_MODER_MODER2_1 | GPIO_MODER_MODER15_1);
|
||||
GPIOA->AFR[0] = (GPIOA->AFR[0] &~GPIO_AFRH_AFRH2) | 1 << (2 * 4); // PA2
|
||||
GPIOA->AFR[1] = (GPIOA->AFR[1] &~GPIO_AFRH_AFRH7) | 1 << (7 * 4); // PA15
|
||||
// DMA: Tx - Ch4
|
||||
DMA1_Channel4->CPAR = (uint32_t) &USART2->TDR; // periph
|
||||
DMA1_Channel4->CMAR = (uint32_t) tbuf; // mem
|
||||
DMA1_Channel4->CCR |= DMA_CCR_MINC | DMA_CCR_DIR | DMA_CCR_TCIE; // 8bit, mem++, mem->per, transcompl irq
|
||||
// Tx CNDTR set @ each transmission due to data size
|
||||
NVIC_SetPriority(DMA1_Channel4_5_IRQn, 3);
|
||||
NVIC_EnableIRQ(DMA1_Channel4_5_IRQn);
|
||||
NVIC_SetPriority(USART2_IRQn, 0);
|
||||
// setup usart2
|
||||
RCC->APB1ENR |= RCC_APB1ENR_USART2EN; // clock
|
||||
// oversampling by16, 115200bps (fck=48mHz)
|
||||
//USART2_BRR = 0x1a1; // 48000000 / 115200
|
||||
USART2->BRR = 480000 / 1152;
|
||||
USART2->CR3 = USART_CR3_DMAT; // enable DMA Tx
|
||||
USART2->CR1 = USART_CR1_TE | USART_CR1_RE | USART_CR1_UE; // 1start,8data,nstop; enable Rx,Tx,USART
|
||||
while(!(USART2->ISR & USART_ISR_TC)); // polling idle frame Transmission
|
||||
USART2->ICR |= USART_ICR_TCCF; // clear TC flag
|
||||
USART2->CR1 |= USART_CR1_RXNEIE;
|
||||
NVIC_EnableIRQ(USART2_IRQn);
|
||||
#else // USART1
|
||||
#error "Not implemented"
|
||||
#endif
|
||||
}
|
||||
|
||||
#if USARTNUM == 2
|
||||
void usart2_isr(){
|
||||
#else // USART1
|
||||
#error "Not implemented"
|
||||
#endif
|
||||
#ifdef CHECK_TMOUT
|
||||
static uint32_t tmout = 0;
|
||||
#endif
|
||||
if(USARTX->ISR & USART_ISR_RXNE){ // RX not emty - receive next char
|
||||
#ifdef CHECK_TMOUT
|
||||
if(tmout && Tms >= tmout){ // set overflow flag
|
||||
bufovr = 1;
|
||||
datalen[rbufno] = 0;
|
||||
}
|
||||
tmout = Tms + TIMEOUT_MS;
|
||||
if(!tmout) tmout = 1; // prevent 0
|
||||
#endif
|
||||
// read RDR clears flag
|
||||
uint8_t rb = USARTX->RDR;
|
||||
if(datalen[rbufno] < UARTBUFSZ){ // put next char into buf
|
||||
rbuf[rbufno][datalen[rbufno]++] = rb;
|
||||
if(rb == '\n'){ // got newline - line ready
|
||||
linerdy = 1;
|
||||
dlen = datalen[rbufno];
|
||||
recvdata = rbuf[rbufno];
|
||||
// prepare other buffer
|
||||
rbufno = !rbufno;
|
||||
datalen[rbufno] = 0;
|
||||
#ifdef CHECK_TMOUT
|
||||
// clear timeout at line end
|
||||
tmout = 0;
|
||||
#endif
|
||||
}
|
||||
}else{ // buffer overrun
|
||||
bufovr = 1;
|
||||
datalen[rbufno] = 0;
|
||||
#ifdef CHECK_TMOUT
|
||||
tmout = 0;
|
||||
#endif
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
#if USARTNUM == 2
|
||||
void dma1_channel4_5_isr(){
|
||||
if(DMA1->ISR & DMA_ISR_TCIF4){ // Tx
|
||||
DMA1->IFCR |= DMA_IFCR_CTCIF4; // clear TC flag
|
||||
txrdy = 1;
|
||||
}
|
||||
}
|
||||
#else // USART1
|
||||
#error "Not implemented"
|
||||
#endif
|
||||
51
STM32/src4multiplexer/usart.h
Normal file
51
STM32/src4multiplexer/usart.h
Normal file
@ -0,0 +1,51 @@
|
||||
/*
|
||||
* usart.h
|
||||
*
|
||||
* Copyright 2017 Edward V. Emelianoff <eddy@sao.ru, edward.emelianoff@gmail.com>
|
||||
*
|
||||
* This program is free software; you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation; either version 2 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program; if not, write to the Free Software
|
||||
* Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston,
|
||||
* MA 02110-1301, USA.
|
||||
*/
|
||||
#pragma once
|
||||
#ifndef __USART_H__
|
||||
#define __USART_H__
|
||||
|
||||
// input and output buffers size
|
||||
#define UARTBUFSZ (64)
|
||||
// timeout between data bytes
|
||||
#ifndef TIMEOUT_MS
|
||||
#define TIMEOUT_MS (1500)
|
||||
#endif
|
||||
|
||||
// macro for static strings
|
||||
#define SEND(str) do{}while(LINE_BUSY == usart_send_blocking(str, sizeof(str)-1))
|
||||
|
||||
typedef enum{
|
||||
ALL_OK,
|
||||
LINE_BUSY,
|
||||
STR_TOO_LONG
|
||||
} TXstatus;
|
||||
|
||||
#define usartrx() (linerdy)
|
||||
#define usartovr() (bufovr)
|
||||
|
||||
extern int linerdy, bufovr, txrdy;
|
||||
|
||||
void usart_setup();
|
||||
int usart_getline(char **line);
|
||||
TXstatus usart_send(const char *str, int len);
|
||||
TXstatus usart_send_blocking(const char *str, int len);
|
||||
|
||||
#endif // __USART_H__
|
||||
@ -1,15 +1,11 @@
|
||||
tsys_daemon - simple data logger
|
||||
================================
|
||||
|
||||
Usage: tsys_daemon [args]
|
||||
|
||||
Where args are:
|
||||
|
||||
- -b, --baudrate=arg connect at given baudrate (115200 by default)
|
||||
- -h, --help show this help
|
||||
- -i, --device=arg serial device name (default: /dev/ttyUSB0)
|
||||
- -o, --output=arg output file name
|
||||
- -r, --rewrite rewrite existing log file
|
||||
- -t, --poll-time=arg pause between subsequent readings (default: 5sec)
|
||||
|
||||
## Arguments:
|
||||
|
||||
-b, --baudrate=arg connect at given baudrate (115200 by default)
|
||||
-h, --help show this help
|
||||
-i, --device=arg serial device name (default: /dev/ttyUSB0)
|
||||
-o, --output=arg output file name
|
||||
-r, --rewrite rewrite existing log file
|
||||
-t, --poll-time=arg pause between subsequent readings (default: 5sec)
|
||||
|
||||
49
src/readtemp.m
Normal file
49
src/readtemp.m
Normal file
@ -0,0 +1,49 @@
|
||||
function [tm T goodrecs diffs] = readtemp(name)
|
||||
% return arrays of unix time & temperatures from file `name`
|
||||
% substitute missed values by interpolation
|
||||
T = dlmread(name);
|
||||
nrecs = size(T, 1);
|
||||
nsensors = size(T, 2) - 1;
|
||||
if(nrecs < 2 || nsensors < 2) return; endif
|
||||
tm = T(:, 1);
|
||||
tm -= tm(1);
|
||||
T(:,1) = [];
|
||||
goodrecs = [];
|
||||
% interpolate missing values
|
||||
for N = 1:nsensors
|
||||
term = T(:, N);
|
||||
badidxs = find(term < -275.);
|
||||
bads = size(badidxs, 1);
|
||||
if(bads == nrecs)
|
||||
printf("%d: all data records are bad\n", N);
|
||||
continue;
|
||||
elseif(bads) % some records are bad, try to make interpolation
|
||||
printf("%d: %d bad records\n", N, bads);
|
||||
tmx = tm; Tx = term;
|
||||
tmx(badidxs) = [];
|
||||
Tx(badidxs) = [];
|
||||
T(:, N) = interp1(tmx, Tx, tm);
|
||||
endif
|
||||
goodrecs = [goodrecs N];
|
||||
endfor
|
||||
% remove strings with NANs
|
||||
ii = find(isnan(T));
|
||||
s = size(T, 1);
|
||||
idxs = ii - s*floor((ii-1)/s);
|
||||
T(idxs, :) = [];
|
||||
tm(idxs) = [];
|
||||
diffs = T - median(T,2);
|
||||
% now remove bad records
|
||||
for N = goodrecs
|
||||
term = abs(diffs(:, N));
|
||||
badidxs = find(term > 3.);
|
||||
bads = size(badidxs, 1);
|
||||
if(bads)
|
||||
tmx = tm; Tx = T(:, N);
|
||||
tmx(badidxs) = [];
|
||||
Tx(badidxs) = [];
|
||||
T(:, N) = interp1(tmx, Tx, tm);
|
||||
endif
|
||||
endfor
|
||||
diffs = T - median(T,2);
|
||||
endfunction
|
||||
294
src/term.c
294
src/term.c
@ -18,15 +18,13 @@
|
||||
* Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston,
|
||||
* MA 02110-1301, USA.
|
||||
*/
|
||||
#ifndef CLIENT
|
||||
|
||||
#include "usefull_macros.h"
|
||||
#include "term.h"
|
||||
#include <strings.h> // strncasecmp
|
||||
#include <time.h> // time(NULL)
|
||||
|
||||
#define BUFLEN 1024
|
||||
uint8_t buf[BUFLEN+1]; // buffer for tty data
|
||||
char buf[BUFLEN+1]; // buffer for tty data
|
||||
|
||||
typedef struct {
|
||||
int speed; // communication speed in bauds/s
|
||||
@ -67,7 +65,98 @@ static spdtbl speeds[] = {
|
||||
{0,0}
|
||||
};
|
||||
|
||||
static uint16_t coefficients[2][5] = {{0,0,0,0,0}, {0,0,0,0,0}}; // polinome coefficients for both termometers
|
||||
static uint16_t coefficients[NSENSORS][2][5]; // polinome coefficients for all 48 pairs of termometers
|
||||
static uint8_t present[NSENSORS][2]; // == 1 if sensor presents
|
||||
|
||||
|
||||
/**
|
||||
* read string from terminal (with timeout) into buf
|
||||
* @return number of characters read
|
||||
*/
|
||||
static size_t read_string(){
|
||||
size_t r = 0, l, L = BUFLEN;
|
||||
char *ptr = buf;
|
||||
double d0 = dtime();
|
||||
do{
|
||||
if((l = read_tty(ptr, L))){
|
||||
r += l; L -= l; ptr += l;
|
||||
d0 = dtime();
|
||||
}
|
||||
}while(dtime() - d0 < WAIT_TMOUT);
|
||||
*ptr = 0;
|
||||
DBG("GOT string: %s, len: %zd\n", buf, r);
|
||||
return r;
|
||||
}
|
||||
|
||||
/*
|
||||
* send command to controller
|
||||
* @return 1 if OK
|
||||
* @arg cmd - zero-terminated command
|
||||
* @arg chk - ==0 if there's no need to omit answer
|
||||
*/
|
||||
static int send_command(char *cmd, int chk){
|
||||
DBG("Send %s", cmd);
|
||||
size_t L = strlen(cmd);
|
||||
if(write_tty(cmd, L)){
|
||||
DBG("Bad write");
|
||||
return 0;
|
||||
}
|
||||
if(chk){
|
||||
size_t L = read_string();
|
||||
if(L == 0){
|
||||
DBG("Bad answer");
|
||||
return 0;
|
||||
}}
|
||||
return 1;
|
||||
}
|
||||
|
||||
/*
|
||||
* run procedure of sensors discovery
|
||||
*/
|
||||
static int detect_sensors(){
|
||||
int i, amount = 0;
|
||||
green("Find sensors\n");
|
||||
for(i = 0; i < NSENSORS; ++i){
|
||||
int j;
|
||||
present[i][0] = 0; present[i][1] = 0;
|
||||
for(j = 0; j < NTRY; ++j){
|
||||
char obuf[5] = {0};
|
||||
int found = 0;
|
||||
snprintf(obuf, 4, "%d\n", i);
|
||||
int bad = 0;
|
||||
if(!send_command(obuf, 1)) bad = 1; // change line number
|
||||
else if(!send_command(CMD_DISCOVERY, 0)) bad = 1; // discovery sensors
|
||||
if(bad){ send_command(CMD_RESET,1); continue;}
|
||||
size_t L = read_string();
|
||||
DBG("sensors pair %d, got answer: %s", i, buf);
|
||||
if(L == 0 || buf[0] == '\n') continue; // no sensors? Make another try
|
||||
if(strchr(buf, '0')){
|
||||
present[i][0] = 1;
|
||||
DBG("found %d_0", i);
|
||||
++found;
|
||||
}
|
||||
if(strchr(buf, '1')){
|
||||
present[i][1] = 1;
|
||||
DBG("found %d_1", i);
|
||||
++found;
|
||||
}
|
||||
if(found == 2) break;
|
||||
}
|
||||
}
|
||||
printf("\n");
|
||||
for(i = 0; i < NSENSORS; ++i){
|
||||
uint8_t p1 = present[i][1], p0 = present[i][0];
|
||||
if(p1 || p0){
|
||||
++amount;
|
||||
green("%d[", i);
|
||||
if(p0) green("0");
|
||||
if(p1) green("1");
|
||||
green("] ");
|
||||
}else red("%d ", i);
|
||||
}
|
||||
printf("\n");
|
||||
return amount;
|
||||
}
|
||||
|
||||
/**
|
||||
* test if `speed` is in .speed of `speeds` array
|
||||
@ -107,52 +196,17 @@ int create_log(char *name, int r){
|
||||
return fd;
|
||||
}
|
||||
|
||||
/**
|
||||
* read string from terminal (with timeout) into buf
|
||||
* @return number of characters read
|
||||
*/
|
||||
static size_t read_string(){
|
||||
size_t r = 0, l, L = BUFLEN;
|
||||
uint8_t *ptr = buf;
|
||||
double d0 = dtime();
|
||||
do{
|
||||
if((l = read_tty(ptr, L))){
|
||||
r += l; L -= l; ptr += l;
|
||||
d0 = dtime();
|
||||
}
|
||||
}while(dtime() - d0 < WAIT_TMOUT);
|
||||
*ptr = 0;
|
||||
DBG("GOT string: %s, len: %zd\n", buf, r);
|
||||
return r;
|
||||
}
|
||||
|
||||
// send command. Return 1 if OK
|
||||
static int send_command(char *cmd, int chk){
|
||||
DBG("Send %s", cmd);
|
||||
if(write_tty((uint8_t*)cmd, 2)){
|
||||
DBG("Bad write");
|
||||
return 0;
|
||||
}
|
||||
if(chk){
|
||||
size_t L = read_string();
|
||||
if(L != 2 || buf[0] != cmd[0]){
|
||||
DBG("Bad answer");
|
||||
return 0;
|
||||
}}
|
||||
return 1;
|
||||
}
|
||||
|
||||
// try to read coefficitents @return amount of sensors if all OK
|
||||
static int get_coefficients(){
|
||||
static int get_coefficients(int pairnum){
|
||||
send_command(CMD_CONSTANTS,0);
|
||||
size_t L = read_string();
|
||||
DBG("%zd", L);
|
||||
if(!L) return 0;
|
||||
uint8_t *ptr = buf, *estr = NULL;
|
||||
char *ptr = buf, *estr = NULL;
|
||||
do{
|
||||
char N, n; // number of sensor & coefficient
|
||||
int C;
|
||||
estr = (uint8_t*)strchr((char*)ptr, '\n');
|
||||
estr = strchr((char*)ptr, '\n');
|
||||
if(estr){*estr = 0; ++estr;}
|
||||
size_t amount = sscanf((char*)ptr, "K%c%c=%d", &N, &n, &C);
|
||||
DBG("in str\"%s\" got %zd values", ptr, amount);
|
||||
@ -160,7 +214,7 @@ static int get_coefficients(){
|
||||
N -= '0'; n -= '0';
|
||||
if((N==0 || N==1) && n < 5){
|
||||
DBG("K[%d][%d] = %d", N, n, C);
|
||||
coefficients[(int)N][(int)n] = (uint16_t)C;
|
||||
coefficients[pairnum][(int)N][(int)n] = (uint16_t)C;
|
||||
}
|
||||
}
|
||||
ptr = estr;
|
||||
@ -170,13 +224,13 @@ static int get_coefficients(){
|
||||
for(i = 0; i < 2; ++i){ // sensor's number
|
||||
int j, k = 0;
|
||||
for(j = 0; j < 5; ++j){ // coeff.
|
||||
if(coefficients[i][j]) ++k;
|
||||
if(coefficients[pairnum][i][j]) ++k;
|
||||
}
|
||||
if(k == 5){
|
||||
green(_("Found sensor number %d\n"), i);
|
||||
if(k == 5){ // check coefficients
|
||||
++found;
|
||||
}
|
||||
}
|
||||
DBG("%d sensors found for pair %d", found, pairnum);
|
||||
return found;
|
||||
}
|
||||
|
||||
@ -187,19 +241,34 @@ static int get_coefficients(){
|
||||
void try_connect(char *device, int speed){
|
||||
if(!device) return;
|
||||
tty_init(device, speed);
|
||||
green(_("Connected to %s, try to get coefficients\n"), device);
|
||||
if(!send_command(CMD_REINIT,1) || !send_command(CMD_RESET,1))
|
||||
ERRX(_("Can't do communications!"));
|
||||
int i; // 10 tries to get constants
|
||||
for(i = 0; i < 10; ++i){
|
||||
green("Try %d\n", i);
|
||||
if(get_coefficients()) return;
|
||||
sleep(1);
|
||||
green(_("Connected to %s, try to discovery sensors\n"), device);
|
||||
if(!detect_sensors()) ERRX("No sensors detected!");
|
||||
//if(!send_command(CMD_REINIT,1) || !send_command(CMD_RESET,1))
|
||||
// ERRX(_("Can't do communications!"));
|
||||
int n, i;
|
||||
green("OK, read coefficients\n");
|
||||
for(n = 0; n < NSENSORS; ++n){
|
||||
char obuf[5] = {0};
|
||||
snprintf(obuf, 4, "%d\n", n);
|
||||
int amount = 0;
|
||||
if(present[n][0]) ++amount;
|
||||
if(present[n][1]) ++amount;
|
||||
if(!amount) continue;
|
||||
DBG("get coeffs for pair %d", n);
|
||||
for(i = 0; i < NTRY; ++i){
|
||||
int bad = 0;
|
||||
if(!send_command(obuf, 1)) bad = 1; // change line number
|
||||
else if(get_coefficients(n) != amount) bad = 1;
|
||||
if(bad) send_command(CMD_RESET,1);
|
||||
else{
|
||||
green("pair %d, got %d\n", n, amount);
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
ERRX(_("No sensors found!"));
|
||||
}
|
||||
|
||||
void write_log(int fd, char *str){ // write string to log file
|
||||
static void write_log(int fd, char *str){ // write string to log file
|
||||
if(fd < 1) return;
|
||||
size_t x = strlen(str);
|
||||
if(write(fd, str, x))return;
|
||||
@ -216,7 +285,7 @@ void write_log(int fd, char *str){ // write string to log file
|
||||
*/
|
||||
static void gettemp(int fd, size_t L){
|
||||
if(!L) return;
|
||||
char *ptr = (char*)buf, *estr = NULL;
|
||||
char *ptr = buf, *estr = NULL;
|
||||
int32_t Ti[2] = {0,0}; // array for raw temp values
|
||||
do{
|
||||
char N; // number of sensor
|
||||
@ -237,26 +306,25 @@ static void gettemp(int fd, size_t L){
|
||||
if(!Ti[i]) continue;
|
||||
// check coefficients & try to get them again if absent
|
||||
int C=0, j;
|
||||
for(j = 0; j < 5; ++j) if(coefficients[i][j]) ++C;
|
||||
if(C != 5 && !get_coefficients()) continue;
|
||||
for(j = 0; j < 5; ++j) if(coefficients[0][i][j]) ++C;
|
||||
if(C != 5 && !get_coefficients(0)) continue;
|
||||
double d = (double)Ti[i]/256., tmp = 0.;
|
||||
DBG("val256=%g", d);
|
||||
// k0*(-1.5e-2) + 0.1*1e-5*val*(1*k1 + 1e-5*val*(-2.*k2 + 1e-5*val*(4*k3 + 1e-5*val*(-2*k4))))
|
||||
double mul[5] = {-1.5e-2, 1., -2., 4., -2.};
|
||||
for(j = 4; j > 0; --j){
|
||||
tmp += mul[j] * (double)coefficients[i][j];
|
||||
tmp += mul[j] * (double)coefficients[0][i][j];
|
||||
tmp *= 1e-5*d;
|
||||
DBG("tmp=%g, K=%d, mul=%g", tmp, coefficients[i][j], mul[j]);
|
||||
DBG("tmp=%g, K=%d, mul=%g", tmp, coefficients[0][i][j], mul[j]);
|
||||
}
|
||||
DBG("tmp: %g, mul[0]=%g, c0=%d", tmp, mul[0], coefficients[i][0]);
|
||||
tmp = tmp/10. + mul[0]*coefficients[i][0];
|
||||
DBG("tmp: %g, mul[0]=%g, c0=%d", tmp, mul[0], coefficients[0][i][0]);
|
||||
tmp = tmp/10. + mul[0]*coefficients[0][i][0];
|
||||
Td[i] = tmp;
|
||||
DBG("Got temp: %g", tmp);
|
||||
}
|
||||
time_t utm = time(NULL);
|
||||
snprintf((char*)buf, BUFLEN, "%zd\t%.4f\t%.4f\n", utm, Td[0], Td[1]);
|
||||
snprintf(buf, BUFLEN, "%.4f\t%.4f\t", Td[0], Td[1]);
|
||||
printf("%s", buf);
|
||||
write_log(fd, (char*)buf);
|
||||
write_log(fd, buf);
|
||||
}
|
||||
|
||||
/**
|
||||
@ -265,62 +333,54 @@ static void gettemp(int fd, size_t L){
|
||||
* if thermometer N is absent, T=-300
|
||||
*/
|
||||
void begin_logging(int fd, double pause){
|
||||
int ntry;
|
||||
void emptyrec(){
|
||||
snprintf(buf, BUFLEN, "%.4f\t%.4f\t", -300., -300.);
|
||||
printf("%s", buf);
|
||||
write_log(fd, buf);
|
||||
}
|
||||
while(1){
|
||||
double tcmd = dtime();
|
||||
if(!send_command(CMD_GETTEMP,0)) continue;
|
||||
size_t L = read_string();
|
||||
if(!L){
|
||||
WARNX(_("No answer, reinit"));
|
||||
if(!send_command(CMD_REINIT,1) || !send_command(CMD_RESET,1)){
|
||||
write_log(fd, "\nExit on communication error\n");
|
||||
ERRX(_("Communications problem!"));
|
||||
int n;
|
||||
time_t utm = time(NULL);
|
||||
snprintf(buf, BUFLEN, "%zd\t", utm);
|
||||
printf("%s", buf);
|
||||
write_log(fd, buf);
|
||||
for(n = 0; n < NSENSORS; ++n){
|
||||
char obuf[5] = {0};
|
||||
snprintf(obuf, 4, "%d\n", n);
|
||||
int amount = 0;
|
||||
if(present[n][0]) ++amount;
|
||||
if(present[n][1]) ++amount;
|
||||
if(!amount){
|
||||
emptyrec();
|
||||
continue;
|
||||
}
|
||||
if(++ntry > 10){
|
||||
write_log(fd, "\nNo sensors!\n");
|
||||
ERRX(_("No sensors!"));
|
||||
DBG("get temperature for pair %d", n);
|
||||
int i;
|
||||
for(i = 0; i < NTRY; ++i){
|
||||
int bad = 0;
|
||||
if(!send_command(obuf, 1)) bad = 1; // change line number
|
||||
else if(!send_command(CMD_GETTEMP,0)) bad = 1;
|
||||
if(bad){
|
||||
send_command(CMD_RESET,1);
|
||||
continue;
|
||||
}
|
||||
size_t L = read_string();
|
||||
if(!L){
|
||||
WARNX(_("No answer, reinit"));
|
||||
if(!send_command(CMD_REINIT,1) || !send_command(CMD_RESET,1)){
|
||||
write_log(fd, "\nCommunication error\n");
|
||||
WARNX(_("Communications problem!"));
|
||||
}
|
||||
}
|
||||
// try to convert temperature
|
||||
gettemp(fd, L);
|
||||
break;
|
||||
}
|
||||
if(i == NTRY) emptyrec();
|
||||
}
|
||||
ntry = 0;
|
||||
// try to convert temperature
|
||||
gettemp(fd, L);
|
||||
printf("\n");
|
||||
write_log(fd, "\n");
|
||||
while(dtime() - tcmd < pause);
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* run terminal emulation: send user's commands with checksum and show answers
|
||||
*
|
||||
void run_terminal(){
|
||||
green(_("Work in terminal mode without echo\n"));
|
||||
int rb;
|
||||
uint8_t buf[BUFLEN];
|
||||
size_t L;
|
||||
setup_con();
|
||||
while(1){
|
||||
if((L = read_tty(buf, BUFLEN))){
|
||||
printf(_("Get %zd bytes: "), L);
|
||||
uint8_t *ptr = buf;
|
||||
while(L--){
|
||||
uint8_t c = *ptr++;
|
||||
printf("0x%02x", c);
|
||||
if(c > 31) printf("(%c)", (char)c);
|
||||
printf(" ");
|
||||
}
|
||||
printf("\n");
|
||||
}
|
||||
if((rb = read_console())){
|
||||
if(rb > 31){
|
||||
printf("Send command: %c ... ", (char)rb);
|
||||
send_cmd((uint8_t)rb);
|
||||
if(TRANS_SUCCEED != wait_checksum()) printf(_("Error.\n"));
|
||||
else printf(_("Done.\n"));
|
||||
}
|
||||
}
|
||||
}
|
||||
}*/
|
||||
|
||||
|
||||
|
||||
|
||||
#endif // CLIENT
|
||||
|
||||
@ -23,13 +23,18 @@
|
||||
#define __TERM_H__
|
||||
|
||||
// terminal timeout (seconds)
|
||||
#define WAIT_TMOUT (0.5)
|
||||
#define WAIT_TMOUT (0.06)
|
||||
// sensors pairs amount
|
||||
#define NSENSORS (48)
|
||||
// amount of communication tries
|
||||
#define NTRY (5)
|
||||
|
||||
/******************************** Commands definition ********************************/
|
||||
#define CMD_CONSTANTS "C\n"
|
||||
#define CMD_RESET "R\n"
|
||||
#define CMD_RESET "L\n"
|
||||
#define CMD_REINIT "I\n"
|
||||
#define CMD_GETTEMP "T\n"
|
||||
#define CMD_DISCOVERY "D\n"
|
||||
|
||||
void try_connect(char *device, int speed);
|
||||
int create_log(char *name, int r);
|
||||
|
||||
BIN
src/tsys_daemon
BIN
src/tsys_daemon
Binary file not shown.
@ -283,7 +283,7 @@ void restore_tty(){
|
||||
comfd = -1;
|
||||
}
|
||||
|
||||
// init: (speed = B9600 etc)
|
||||
// init:
|
||||
void tty_init(char *comdev, int speed){
|
||||
if(comfd == -1){ // not opened
|
||||
if(!comdev){
|
||||
@ -331,7 +331,7 @@ void tty_init(char *comdev, int speed){
|
||||
* @param length - buffer len
|
||||
* @return amount of readed bytes
|
||||
*/
|
||||
size_t read_tty(uint8_t *buff, size_t length){
|
||||
size_t read_tty(char *buff, size_t length){
|
||||
if(comfd < 0) return 0;
|
||||
ssize_t L = 0;
|
||||
fd_set rfds;
|
||||
@ -348,7 +348,7 @@ size_t read_tty(uint8_t *buff, size_t length){
|
||||
return (size_t)L;
|
||||
}
|
||||
|
||||
int write_tty(const uint8_t *buff, size_t length){
|
||||
int write_tty(const char *buff, size_t length){
|
||||
if(comfd < 0) return 1;
|
||||
ssize_t L = write(comfd, buff, length);
|
||||
if((size_t)L != length){
|
||||
|
||||
@ -132,8 +132,8 @@ int mygetchar();
|
||||
|
||||
void restore_tty();
|
||||
void tty_init(char *comdev, int speed);
|
||||
size_t read_tty(uint8_t *buff, size_t length);
|
||||
int write_tty(const uint8_t *buff, size_t length);
|
||||
size_t read_tty(char *buff, size_t length);
|
||||
int write_tty(const char *buff, size_t length);
|
||||
|
||||
int str2double(double *num, const char *str);
|
||||
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user