testing CAN bus network version (without USB)

This commit is contained in:
eddyem 2018-07-25 20:27:25 +03:00
parent b318da7884
commit 9fc1fd7ad6
18 changed files with 914 additions and 143 deletions

View File

@ -1,6 +1,6 @@
2sensors_logging - source for loggint temperature of 2 sensors - 2sensors_logging - source for loggint temperature of 2 sensors
inc - system include files - inc - system include files
src4multiplexer - source code for I2C multiplexer (48 channels * 2 sensors) - src4multiplexer - source code for I2C multiplexer (48 channels * 2 sensors)
Tcalc - test code for temperature calculation inside MCU - Tcalc - test code for temperature calculation inside MCU
Tcalc_screen - Tcalc displaying T on OLED screen - Tcalc_screen - Tcalc displaying T on OLED screen
TSYS_controller - MAIN controller code (USB, CAN, UART1) - TSYS_controller - MAIN controller code (USB, CAN, UART1)

View File

@ -1,4 +1,3 @@
- CAN bus: PB8 (Rx), PB9 (Tx)
- USB bus: PA11 (DM), PA12 (DP) - USB bus: PA11 (DM), PA12 (DP)
- ADC inputs: PA0 (V12/4.93), PA1 (V5/2), PA3 (I12 - 1V/A), PA6 (V3.3/2) - ADC inputs: PA0 (V12/4.93), PA1 (V5/2), PA3 (I12 - 1V/A), PA6 (V3.3/2)

View File

@ -36,6 +36,7 @@ OBJDUMP := $(OPREFIX)-objdump
GDB := $(OPREFIX)-gdb GDB := $(OPREFIX)-gdb
STFLASH := $(shell which st-flash) STFLASH := $(shell which st-flash)
STBOOT := $(shell which stm32flash) STBOOT := $(shell which stm32flash)
DFUUTIL := $(shell which dfu-util)
############################################################################### ###############################################################################
# Source files # Source files
@ -54,7 +55,7 @@ LIB_DIR := $(INC_DIR)/ld
############################################################################### ###############################################################################
# C flags # C flags
CFLAGS += -O2 -g -MD -D__thumb2__=1 CFLAGS += -O2 -g -D__thumb2__=1
CFLAGS += -Wall -Wextra -Wshadow -Wimplicit-function-declaration CFLAGS += -Wall -Wextra -Wshadow -Wimplicit-function-declaration
CFLAGS += -Wredundant-decls $(INCLUDE) CFLAGS += -Wredundant-decls $(INCLUDE)
# -Wmissing-prototypes -Wstrict-prototypes # -Wmissing-prototypes -Wstrict-prototypes
@ -104,7 +105,7 @@ $(STARTUP): $(INC_DIR)/startup/vector.c
$(OBJDIR)/%.o: %.c $(OBJDIR)/%.o: %.c
@echo " CC $<" @echo " CC $<"
$(CC) $(CFLAGS) $(DEFS) $(INCLUDE) $(ARCH_FLAGS) -o $@ -c $< $(CC) $(CFLAGS) -MD $(DEFS) $(INCLUDE) $(ARCH_FLAGS) -o $@ -c $<
#$(OBJDIR)/%.d: %.c $(OBJDIR) #$(OBJDIR)/%.d: %.c $(OBJDIR)
# $(CC) -MM -MG $< | sed -e 's,^\([^:]*\)\.o[ ]*:,$(@D)/\1.o $(@D)/\1.d:,' >$@ # $(CC) -MM -MG $< | sed -e 's,^\([^:]*\)\.o[ ]*:,$(@D)/\1.o $(@D)/\1.d:,' >$@
@ -130,6 +131,9 @@ clean:
$(RM) $(OBJS) $(DEPS) $(ELF) $(HEX) $(LIST) $(OBJDIR)/*.map *.d $(RM) $(OBJS) $(DEPS) $(ELF) $(HEX) $(LIST) $(OBJDIR)/*.map *.d
@rmdir $(OBJDIR) 2>/dev/null || true @rmdir $(OBJDIR) 2>/dev/null || true
dfuboot: $(BIN)
@echo " LOAD $(BIN) THROUGH DFU"
$(DFUUTIL) -a0 -D $(BIN) -s 0x08000000
flash: $(BIN) flash: $(BIN)
@echo " FLASH $(BIN)" @echo " FLASH $(BIN)"
@ -142,4 +146,4 @@ boot: $(BIN)
gentags: gentags:
CFLAGS="$(CFLAGS) $(DEFS)" geany -g $(BINARY).c.tags *[hc] 2>/dev/null CFLAGS="$(CFLAGS) $(DEFS)" geany -g $(BINARY).c.tags *[hc] 2>/dev/null
.PHONY: clean flash boot gentags .PHONY: clean flash boot dfuboot gentags

View File

@ -4,12 +4,24 @@ Make regular scan of 8 sensors' pairs.
USART speed 115200. Code for ../../kicad/stm32 USART speed 115200. Code for ../../kicad/stm32
### Serial interface commands (ends with '\n'): ### Serial interface commands (ends with '\n'):
- **0...9** - wait measurements of T from Nth controller (0==T for master)
- **A** send everybody to start T measurement
- **B** send dummy CAN messages to broadcast address
- **C** show coefficients for all thermosensors - **C** show coefficients for all thermosensors
- **D** detect seosors (reseting them) - **D** send dummy CAN messages to master (0) address
- **E** end temperature scan
- **F** turn sensors off
- **G** get CAN address
- **H** switch I2C to high speed (100kHz) - **H** switch I2C to high speed (100kHz)
- **I** reinit CAN
- **L** switch I2C to low speed (default, 10kHz) - **L** switch I2C to low speed (default, 10kHz)
- **R** reset both sensors - **O** turn sensors on
- **T** get temperature in degrC - **P** ping everyone over CAN
- **R** reinit I2C
- **S** start temperature scan
- **T** start single temperature measurement
- **V** very low speed
- **Z** get sensors state over CAN
### PINOUT ### PINOUT
- I2C: PB6 (SCL) & PB7 (SDA) - I2C: PB6 (SCL) & PB7 (SDA)
@ -22,3 +34,27 @@ USART speed 115200. Code for ../../kicad/stm32
- ADC inputs: PA0 (V12/4.93), PA1 (V5/2), PA3 (I12 - 1V/A), PA6 (V3.3/2) - ADC inputs: PA0 (V12/4.93), PA1 (V5/2), PA3 (I12 - 1V/A), PA6 (V3.3/2)
- controller CAN address: PA13..PA15 (0..2 bits); 0 - master, other address - slave - controller CAN address: PA13..PA15 (0..2 bits); 0 - master, other address - slave
### LEDS
- LED0 (nearest to sensors' connectors) - heartbeat
- LED1 (above LED0) - CAN bus OK
### CAN protocol
Variable data length: from 1 to 7 bytes.
First byte of every sequence is command mark (0xA5) or data mark (0x5A).
Commands:
- CMD_PING - send from master to receive answer in data packet if target alive.
- CMD_START_MEASUREMENT - start single temperature measurement.
- CMD_SENSORS_STATE - state of sensors.
Data format:
- 1 byte - Controller number
- 2 byte - Command received
- 3..7 bytes - data
Thermal data format:
- 3 byte - Sensor number (10*N + M, where N is multiplexer number, M - number of sensor in pair, i.e. 0,1,10,11,20,21...70,71)
- 4 byte - thermal data H
- 5 byte - thermal data L

View File

@ -20,16 +20,284 @@
* MA 02110-1301, USA. * MA 02110-1301, USA.
* *
*/ */
#include <string.h> // memcpy
#include "can.h" #include "can.h"
#include "hardware.h"
#include "usart.h"
static uint8_t CAN_addr = 0; // incoming message buffer size
#define CAN_INMESSAGE_SIZE (6)
extern volatile uint32_t Tms;
// circular buffer for received messages
static CAN_message messages[CAN_INMESSAGE_SIZE];
static uint8_t first_free_idx = 0; // index of first empty cell
static int8_t first_nonfree_idx = -1; // index of first data cell
static uint16_t CANID = 0xFFFF;
uint8_t Controller_address = 0;
static CAN_status can_status = CAN_STOP;
static void can_process_fifo(uint8_t fifo_num);
CAN_status CAN_get_status(){
CAN_status st = can_status;
// give overrun message only once
if(st == CAN_FIFO_OVERRUN) can_status = CAN_READY;
return st;
}
// push next message into buffer; return 1 if buffer overfull
static int CAN_messagebuf_push(CAN_message *msg){
MSG("Try to push\n");
if(first_free_idx == first_nonfree_idx) return 1; // no free space
if(first_nonfree_idx < 0) first_nonfree_idx = 0; // first message in empty buffer
memcpy(&messages[first_free_idx++], msg, sizeof(CAN_message));
// need to roll?
if(first_free_idx == CAN_INMESSAGE_SIZE) first_free_idx = 0;
#ifdef EBUG
MSG("1st free: "); usart_putchar('0' + first_free_idx); newline();
#endif
return 0;
}
// pop message from buffer
CAN_message *CAN_messagebuf_pop(){
if(first_nonfree_idx < 0) return NULL;
#ifdef EBUG
MSG("read from idx "); usart_putchar('0' + first_nonfree_idx); newline();
#endif
CAN_message *msg = &messages[first_nonfree_idx++];
if(first_nonfree_idx == CAN_INMESSAGE_SIZE) first_nonfree_idx = 0;
if(first_nonfree_idx == first_free_idx){ // buffer is empty - refresh it
first_nonfree_idx = -1;
first_free_idx = 0;
MSG("refresh buffer\n");
}
return msg;
}
// get CAN address data from GPIO pins // get CAN address data from GPIO pins
void readCANaddr(){ void readCANID(){
CAN_addr = READ_CAN_INV_ADDR(); uint8_t CAN_addr = READ_CAN_INV_ADDR();
CAN_addr = ~CAN_addr & 0x7; Controller_address = ~CAN_addr & 0x7;
CANID = (CAN_ID_PREFIX & CAN_ID_MASK) | Controller_address;
} }
uint8_t getCANaddr(){ uint16_t getCANID(){
return CAN_addr; return CANID;
}
void CAN_reinit(){
readCANID();
CAN->TSR |= CAN_TSR_ABRQ0 | CAN_TSR_ABRQ1 | CAN_TSR_ABRQ2;
RCC->APB1RSTR |= RCC_APB1RSTR_CANRST;
RCC->APB1RSTR &= ~RCC_APB1RSTR_CANRST;
CAN_setup();
}
void CAN_setup(){
if(CANID == 0xFFFF) readCANID();
// Configure GPIO: PB8 - CAN_Rx, PB9 - CAN_Tx
/* (1) Select AF mode (10) on PB8 and PB9 */
/* (2) AF4 for CAN signals */
GPIOB->MODER = (GPIOB->MODER & ~(GPIO_MODER_MODER8 | GPIO_MODER_MODER9))
| (GPIO_MODER_MODER8_AF | GPIO_MODER_MODER9_AF); /* (1) */
GPIOB->AFR[1] = (GPIOB->AFR[1] &~ (GPIO_AFRH_AFRH0 | GPIO_AFRH_AFRH1))\
| (4 << (0 * 4)) | (4 << (1 * 4)); /* (2) */
/* Enable the peripheral clock CAN */
RCC->APB1ENR |= RCC_APB1ENR_CANEN;
/* Configure CAN */
/* (1) Enter CAN init mode to write the configuration */
/* (2) Wait the init mode entering */
/* (3) Exit sleep mode */
/* (4) Loopback mode, set timing to 100kb/s: BS1 = 4, BS2 = 3, prescaler = 60 */
/* (5) Leave init mode */
/* (6) Wait the init mode leaving */
/* (7) Enter filter init mode, (16-bit + mask, filter 0 for FIFO 0) */
/* (8) Acivate filter 0 */
/* (9) Identifier list mode */
/* (10) Set the Id list */
/* (12) Leave filter init */
/* (13) Set error interrupts enable */
CAN->MCR |= CAN_MCR_INRQ; /* (1) */
while((CAN->MSR & CAN_MSR_INAK)!=CAN_MSR_INAK) /* (2) */
{
/* add time out here for a robust application */
}
CAN->MCR &=~ CAN_MCR_SLEEP; /* (3) */
CAN->MCR |= CAN_MCR_ABOM;
CAN->BTR |= 2 << 20 | 3 << 16 | 59 << 0; /* (4) */
CAN->MCR &=~ CAN_MCR_INRQ; /* (5) */
while((CAN->MSR & CAN_MSR_INAK)==CAN_MSR_INAK) /* (6) */
{
/* add time out here for a robust application */
}
CAN->FMR = CAN_FMR_FINIT; /* (7) */
CAN->FA1R = CAN_FA1R_FACT0; /* (8) */
CAN->FM1R = CAN_FM1R_FBM0; /* (9) */
CAN->sFilterRegister[0].FR1 = CANID << 5 | ((BCAST_ID << 5) << 16); /* (10) */
CAN->FMR &=~ CAN_FMR_FINIT; /* (12) */
CAN->IER |= CAN_IER_ERRIE | CAN_IER_FOVIE0 | CAN_IER_FOVIE1; /* (13) */
/* Configure IT */
/* (14) Set priority for CAN_IRQn */
/* (15) Enable CAN_IRQn */
NVIC_SetPriority(CEC_CAN_IRQn, 0); /* (14) */
NVIC_EnableIRQ(CEC_CAN_IRQn); /* (15) */
can_status = CAN_READY;
}
void can_proc(){
// check for messages in FIFO0 & FIFO1
if(CAN->RF0R & CAN_RF0R_FMP0){
can_process_fifo(0);
}
if(CAN->RF1R & CAN_RF1R_FMP1){
can_process_fifo(1);
}
if(CAN->ESR & (CAN_ESR_BOFF | CAN_ESR_EPVF | CAN_ESR_EWGF)){ // much errors - restart CAN BUS
LED_off(LED1);
MSG("bus-off, restarting\n");
#pragma message "TODO: let 2 know main() about problems in CANbus"
// request abort for all mailboxes
CAN->TSR |= CAN_TSR_ABRQ0 | CAN_TSR_ABRQ1 | CAN_TSR_ABRQ2;
// reset CAN bus
RCC->APB1RSTR |= RCC_APB1RSTR_CANRST;
RCC->APB1RSTR &= ~RCC_APB1RSTR_CANRST;
CAN_setup();
}
#ifdef EBUG
static uint32_t esr, msr, tsr;
uint32_t msr_now = CAN->MSR & 0xf;
if(esr != CAN->ESR || msr != msr_now || tsr != CAN->TSR){
MSG("Timestamp: ");
printu(Tms);
newline();
}
if((CAN->ESR) != esr){
usart_putchar(((CAN->ESR & CAN_ESR_BOFF) != 0) + '0');
esr = CAN->ESR;
MSG("CAN->ESR: ");
printuhex(esr); newline();
}
if(msr_now != msr){
msr = msr_now;
MSG("CAN->MSR & 0xf: ");
printuhex(msr); newline();
}
if(CAN->TSR != tsr){
tsr = CAN->TSR;
MSG("CAN->TSR: ");
printuhex(tsr); newline();
}
#endif
}
CAN_status can_send(uint8_t *msg, uint8_t len, uint16_t target_id){
LED_on(LED1); // turn ON LED1 at first data sent/receive
uint8_t mailbox = 0;
// check first free mailbox
if(CAN->TSR & (CAN_TSR_TME)){
mailbox = (CAN->TSR & CAN_TSR_CODE) >> 24;
#ifdef EBUG
MSG("select "); usart_putchar('0'+mailbox); SEND(" mailbox\n");
#endif
}else{ // no free mailboxes
return CAN_BUSY;
}
CAN_TxMailBox_TypeDef *box = &CAN->sTxMailBox[mailbox];
uint32_t lb = 0, hb = 0;
switch(len){
case 8:
hb |= (uint32_t)msg[7] << 24;
case 7:
hb |= (uint32_t)msg[6] << 16;
case 6:
hb |= (uint32_t)msg[5] << 8;
case 5:
hb |= (uint32_t)msg[4];
case 4:
lb |= (uint32_t)msg[3] << 24;
case 3:
lb |= (uint32_t)msg[2] << 16;
case 2:
lb |= (uint32_t)msg[1] << 8;
default:
lb |= (uint32_t)msg[0];
}
box->TDLR = lb;
box->TDHR = hb;
box->TDTR = len;
box->TIR = (target_id & 0x7FF) << 21 | CAN_TI0R_TXRQ;
return CAN_OK;
}
static void can_process_fifo(uint8_t fifo_num){
if(fifo_num > 1) return;
CAN_FIFOMailBox_TypeDef *box = &CAN->sFIFOMailBox[fifo_num];
volatile uint32_t *RFxR = (fifo_num) ? &CAN->RF1R : &CAN->RF0R;
LED_on(LED1); // turn ON LED1 at first data sent/receive
MSG("Receive, RDTR=");
#ifdef EBUG
printuhex(box->RDTR);
newline();
#endif
// read all
while(*RFxR & CAN_RF0R_FMP0){ // amount of messages pending
// CAN_RDTxR: (16-31) - timestamp, (8-15) - filter match index, (0-3) - data length
/* TODO: check filter match index if more than one ID can receive */
CAN_message msg;
uint8_t *dat = msg.data;
uint8_t len = box->RDTR & 0x7;
msg.length = len;
if(len){ // message can be without data
uint32_t hb = box->RDHR, lb = box->RDLR;
switch(len){
case 8:
dat[7] = hb>>24;
case 7:
dat[6] = (hb>>16) & 0xff;
case 6:
dat[5] = (hb>>8) & 0xff;
case 5:
dat[4] = hb & 0xff;
case 4:
dat[3] = lb>>24;
case 3:
dat[2] = (lb>>16) & 0xff;
case 2:
dat[1] = (lb>>8) & 0xff;
case 1:
dat[0] = lb & 0xff;
}
}
if(CAN_messagebuf_push(&msg)) return; // error: buffer is full, try later
*RFxR |= CAN_RF0R_RFOM0; // release fifo for access to next message
}
if(*RFxR & CAN_RF0R_FULL0) *RFxR &= ~CAN_RF0R_FULL0;
}
void cec_can_isr(){
if(CAN->RF0R & CAN_RF0R_FOVR0){ // FIFO overrun
CAN->RF0R &= ~CAN_RF0R_FOVR0;
can_status = CAN_FIFO_OVERRUN;
}
if(CAN->RF1R & CAN_RF1R_FOVR1){
CAN->RF1R &= ~CAN_RF1R_FOVR1;
can_status = CAN_FIFO_OVERRUN;
}
#ifdef EBUG
if(can_status == CAN_FIFO_OVERRUN) MSG("fifo 0 overrun\n");
#endif
if(CAN->MSR & CAN_MSR_ERRI){ // Error
CAN->MSR &= ~CAN_MSR_ERRI;
// request abort for problem mailbox
if(CAN->TSR & CAN_TSR_TERR0) CAN->TSR |= CAN_TSR_ABRQ0;
if(CAN->TSR & CAN_TSR_TERR1) CAN->TSR |= CAN_TSR_ABRQ1;
if(CAN->TSR & CAN_TSR_TERR2) CAN->TSR |= CAN_TSR_ABRQ2;
}
} }

View File

@ -26,7 +26,41 @@
#include "hardware.h" #include "hardware.h"
void readCANaddr(); // identifier mask (for ORing with Controller_address
uint8_t getCANaddr(); #define CAN_ID_MASK ((uint16_t)0x7F8)
// prefix of identifiers
#define CAN_ID_PREFIX ((uint16_t)0xAAA)
// this is master - Controller_address==0
#define MASTER_ID (CAN_ID_PREFIX & CAN_ID_MASK)
// broadcasting to every slave
#define BCAST_ID ((uint16_t)0x7F7)
// send dummy message to this ID for testing CAN bus status
#define NOONE_ID ((uint16_t)0x7FF)
typedef struct{
uint8_t data[8];
uint8_t length;
} CAN_message;
typedef enum{
CAN_STOP,
CAN_READY,
CAN_BUSY,
CAN_OK,
CAN_FIFO_OVERRUN
} CAN_status;
CAN_status CAN_get_status();
void readCANID();
uint16_t getCANID();
void CAN_reinit();
void CAN_setup();
void can_proc();
CAN_status can_send(uint8_t *msg, uint8_t len, uint16_t target_id);
CAN_message *CAN_messagebuf_pop();
#endif // __CAN_H__ #endif // __CAN_H__

View File

@ -0,0 +1,172 @@
/*
* geany_encoding=koi8-r
* can_process.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 "can_process.h"
#include "sensors_manage.h"
#include "can.h"
#include "usart.h"
extern volatile uint32_t Tms; // timestamp data
void can_messages_proc(){
CAN_message *can_mesg = CAN_messagebuf_pop();
if(!can_mesg) return; // no data in buffer
uint8_t len = can_mesg->length;
#ifdef EBUG
SEND("got message, len: "); usart_putchar('0' + len);
SEND(", data: ");
uint8_t ctr;
for(ctr = 0; ctr < len; ++ctr){
printuhex(can_mesg->data[ctr]);
usart_putchar(' ');
}
newline();
#endif
uint8_t *data = can_mesg->data, b[2];
b[0] = data[1];
if(data[0] == COMMAND_MARK){ // process commands
if(len < 2) return;
switch(data[1]){
case CMD_DUMMY0:
case CMD_DUMMY1:
SEND("DUMMY");
usart_putchar('0' + (data[1]==CMD_DUMMY0 ? 0 : 1));
newline();
break;
case CMD_PING: // pong
can_send_data(b, 1);
break;
case CMD_SENSORS_STATE:
b[1] = sensors_get_state();
can_send_data(b, 2);
break;
case CMD_START_MEASUREMENT:
sensors_start();
break;
}
}else if(data[0] == DATA_MARK){ // process received data
if(len < 3) return;
switch(data[2]){
case CMD_PING:
SEND("PONG");
usart_putchar('0' + data[1]);
break;
case CMD_SENSORS_STATE:
SEND("SSTATE");
usart_putchar('0' + data[1]);
usart_putchar('=');
printu(data[3]);
break;
case CMD_START_MEASUREMENT: // temperature
if(len != 6) return;
usart_putchar('T');
usart_putchar('0' + data[1]);
usart_putchar('_');
printu(data[3]);
usart_putchar('=');
int16_t t = data[4]<<8 | data[5];
if(t < 0){
t = -t;
usart_putchar('-');
}
printu(t);
#pragma message("TODO: process received T over USB!")
break;
default:
SEND("Unknown data received");
}
newline();
}
}
// try to send messages, wait no more than 100ms
static CAN_status try2send(uint8_t *buf, uint8_t len, uint16_t id){
uint32_t Tstart = Tms;
while(Tms - Tstart < SEND_TIMEOUT_MS){
if(CAN_OK == can_send(buf, len, id)) return CAN_OK;
}
SEND("Bus busy!\n");
return CAN_BUSY;
}
/**
* Send command over CAN bus (works only if controller number is 0 - master mode)
* @param targetID - target identifier
* @param cmd - command to send
*/
CAN_status can_send_cmd(uint16_t targetID, uint8_t cmd){
if(Controller_address != 0 && cmd != CMD_DUMMY0 && cmd != CMD_DUMMY1) return CAN_OK;
uint8_t buf[2];
buf[0] = COMMAND_MARK;
buf[1] = cmd;
return try2send(buf, 2, targetID);
}
// send data over CAN bus to MASTER_ID (not more than 6 bytes)
CAN_status can_send_data(uint8_t *data, uint8_t len){
if(len > 6) return CAN_OK;
uint8_t buf[8];
buf[0] = DATA_MARK;
buf[1] = Controller_address;
int i;
for(i = 0; i < len; ++i) buf[i+2] = *data++;
return try2send(buf, len+2, MASTER_ID);
}
/**
* send temperature data over CAN bus once per call
* @return next number or -1 if all data sent
*/
int8_t send_temperatures(int8_t N){
if(N < 0 || Controller_address == 0) return -1;
int a, p;
uint8_t can_data[4];
int8_t retn = N;
can_data[0] = CMD_START_MEASUREMENT;
a = N / 10;
p = N - a*10;
if(p == 2){ // next sensor
if(++a > MUL_MAX_ADDRESS) return -1;
p = 0;
}
do{
if(!(sens_present[p] & (1<<a))){
if(p == 0) p = 1;
else{
p = 0;
++a;
}
} else break;
}while(a <= MUL_MAX_ADDRESS);
if(a > MUL_MAX_ADDRESS) return -1; // done
retn = a*10 + p; // current temperature sensor number
can_data[1] = a*10 + p;
//char b[] = {'T', a+'0', p+'0', '=', '+'};
int16_t t = Temperatures[a][p];
can_data[2] = t>>8; // H byte
can_data[3] = t&0xff; // L byte
if(CAN_OK == can_send_data(can_data, 4)){ // OK, calculate next address
++retn;
}
return retn;
}

View File

@ -0,0 +1,45 @@
/*
* geany_encoding=koi8-r
* can_process.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 "can.h"
// timeout for trying to send data
#define SEND_TIMEOUT_MS (10)
// mark first byte if command sent
#define COMMAND_MARK (0xA5)
// mark first byte if data sent
#define DATA_MARK (0x5A)
// 8-bit commands sent by master
typedef enum{
CMD_PING, // request for PONG cmd
CMD_START_MEASUREMENT, // start thermal measurement
CMD_SENSORS_STATE, // reply data with sensors state
// dummy commands for test purposes
CMD_DUMMY0 = 0xDA,
CMD_DUMMY1 = 0xAD
} CAN_commands;
void can_messages_proc();
CAN_status can_send_cmd(uint16_t targetID, uint8_t cmd);
CAN_status can_send_data(uint8_t *data, uint8_t len);
int8_t send_temperatures(int8_t N);

View File

@ -55,12 +55,14 @@
#define LED1_pin LED0_pin #define LED1_pin LED0_pin
#endif #endif
#define LED_blink(x) pin_toggle(x ## _port, x ## _pin) #define LED_blink(x) pin_toggle(x ## _port, x ## _pin)
#define LED_on(x) pin_clear(x ## _port, x ## _pin)
#define LED_off(x) pin_set(x ## _port, x ## _pin)
// set active channel number // set active channel number
#define MUL_ADDRESS(x) do{GPIOB->BSRR = (0x7 << 16) | (x);}while(0) #define MUL_ADDRESS(x) do{GPIOB->BSRR = (0x7 << 16) | (x);}while(0)
// address from 0 to 7 // address from 0 to 7
// WARNING!!! In current case all variables for sensors counting are uint8_t, so if // WARNING!!! In current case all variables for sensors counting are uint8_t, so if
// MUL_MAX_ADDRESS would be greater than 7 you need to edit sensors_manage.c // MUL_MAX_ADDRESS would be greater than 7 you need to edit all codes!!!11111111111111111111
#define MUL_MAX_ADDRESS (7) #define MUL_MAX_ADDRESS (7)
// turn multiplexer on/off (PB12 -> 1/0) // turn multiplexer on/off (PB12 -> 1/0)
#define MUL_ON() pin_clear(GPIOB, (1<<12)) #define MUL_ON() pin_clear(GPIOB, (1<<12))
@ -74,6 +76,7 @@
// CAN address - PA13..PA15 // CAN address - PA13..PA15
#define READ_CAN_INV_ADDR() ((GPIOA->IDR & (0x7<<13))>>13) #define READ_CAN_INV_ADDR() ((GPIOA->IDR & (0x7<<13))>>13)
extern uint8_t Controller_address;
typedef enum{ typedef enum{
VERYLOW_SPEED, VERYLOW_SPEED,

View File

@ -54,12 +54,12 @@ uint8_t write_i2c(uint8_t addr, uint8_t data){
cntr = Tms; cntr = Tms;
I2C1->ICR = 0x3f38; // clear all errors I2C1->ICR = 0x3f38; // clear all errors
while(I2C1->ISR & I2C_ISR_BUSY) if(Tms - cntr > I2C_TIMEOUT){ while(I2C1->ISR & I2C_ISR_BUSY) if(Tms - cntr > I2C_TIMEOUT){
MSG("always busy\n"); //MSG("always busy\n");
return 0; // check busy return 0; // check busy
} }
cntr = Tms; cntr = Tms;
while(I2C1->CR2 & I2C_CR2_START) if(Tms - cntr > I2C_TIMEOUT){ while(I2C1->CR2 & I2C_CR2_START) if(Tms - cntr > I2C_TIMEOUT){
MSG("always start\n"); //MSG("always start\n");
return 0; // check start return 0; // check start
} }
//I2C1->ICR = 0x3f38; // clear all errors //I2C1->ICR = 0x3f38; // clear all errors
@ -71,12 +71,12 @@ uint8_t write_i2c(uint8_t addr, uint8_t data){
if(I2C1->ISR & I2C_ISR_NACKF){ if(I2C1->ISR & I2C_ISR_NACKF){
I2C1->ICR |= I2C_ICR_NACKCF; I2C1->ICR |= I2C_ICR_NACKCF;
//I2C1->ICR = 0x3f38; //I2C1->ICR = 0x3f38;
MSG("NACK\n"); //MSG("NACK\n");
return 0; return 0;
} }
if(Tms - cntr > I2C_TIMEOUT){ if(Tms - cntr > I2C_TIMEOUT){
//I2C1->ICR = 0x3f38; //I2C1->ICR = 0x3f38;
MSG("Timeout\n"); //MSG("Timeout\n");
return 0; return 0;
} }
} }
@ -93,14 +93,14 @@ uint8_t write_i2c(uint8_t addr, uint8_t data){
uint8_t read_i2c(uint8_t addr, uint32_t *data, uint8_t nbytes){ uint8_t read_i2c(uint8_t addr, uint32_t *data, uint8_t nbytes){
uint32_t result = 0; uint32_t result = 0;
cntr = Tms; cntr = Tms;
MSG("read_i2c\n"); //MSG("read_i2c\n");
while(I2C1->ISR & I2C_ISR_BUSY) if(Tms - cntr > I2C_TIMEOUT){ while(I2C1->ISR & I2C_ISR_BUSY) if(Tms - cntr > I2C_TIMEOUT){
MSG("always busy\n"); //MSG("always busy\n");
return 0; // check busy return 0; // check busy
} }
cntr = Tms; cntr = Tms;
while(I2C1->CR2 & I2C_CR2_START) if(Tms - cntr > I2C_TIMEOUT){ while(I2C1->CR2 & I2C_CR2_START) if(Tms - cntr > I2C_TIMEOUT){
MSG("always start\n"); //MSG("always start\n");
return 0; // check start return 0; // check start
} }
// I2C1->ICR = 0x3f38; // clear all errors // I2C1->ICR = 0x3f38; // clear all errors
@ -114,12 +114,12 @@ uint8_t read_i2c(uint8_t addr, uint32_t *data, uint8_t nbytes){
if(I2C1->ISR & I2C_ISR_NACKF){ if(I2C1->ISR & I2C_ISR_NACKF){
I2C1->ICR |= I2C_ICR_NACKCF; I2C1->ICR |= I2C_ICR_NACKCF;
//I2C1->ICR = 0x3f38; //I2C1->ICR = 0x3f38;
MSG("NACK\n"); //MSG("NACK\n");
return 0; return 0;
} }
if(Tms - cntr > I2C_TIMEOUT){ if(Tms - cntr > I2C_TIMEOUT){
//I2C1->ICR = 0x3f38; //I2C1->ICR = 0x3f38;
MSG("Timeout\n"); //MSG("Timeout\n");
return 0; return 0;
} }
} }

View File

@ -24,6 +24,7 @@
#include "i2c.h" #include "i2c.h"
#include "sensors_manage.h" #include "sensors_manage.h"
#include "can.h" #include "can.h"
#include "can_process.h"
#pragma message("USARTNUM=" STR(USARTNUM)) #pragma message("USARTNUM=" STR(USARTNUM))
#pragma message("I2CPINS=" STR(I2CPINS)) #pragma message("I2CPINS=" STR(I2CPINS))
@ -61,10 +62,17 @@ void iwdg_setup(){
IWDG->KR = IWDG_REFRESH; /* (6) */ IWDG->KR = IWDG_REFRESH; /* (6) */
} }
void CANsend(uint16_t targetID, uint8_t cmd, char echo){
if(CAN_OK == can_send_cmd(targetID, cmd)){
usart_putchar(echo);
newline();
}
}
int main(void){ int main(void){
uint32_t lastT = 0, lastS = 0; uint32_t lastT = 0, lastS = 0;
int16_t L = 0; int16_t L = 0, ID;
uint8_t scan = 0, gotmeasurement = 0; uint8_t gotmeasurement = 0;
char *txt; char *txt;
sysreset(); sysreset();
SysTick_Config(6000, 1); SysTick_Config(6000, 1);
@ -72,28 +80,43 @@ int main(void){
usart_setup(); usart_setup();
i2c_setup(LOW_SPEED); i2c_setup(LOW_SPEED);
iwdg_setup(); iwdg_setup();
readCANaddr(); CAN_setup();
SEND("Greetings! My address is "); SEND("Greetings! My address is ");
printu(getCANaddr()); printuhex(getCANID());
newline(); newline();
if(RCC->CSR & RCC_CSR_IWDGRSTF){ // watchdog reset occured
SEND("WDGRESET=1\n");
}
if(RCC->CSR & RCC_CSR_SFTRSTF){ // software reset occured
SEND("SOFTRESET=1\n");
}
RCC->CSR |= RCC_CSR_RMVF; // remove reset flags
while (1){ while (1){
IWDG->KR = IWDG_REFRESH; // refresh watchdog IWDG->KR = IWDG_REFRESH; // refresh watchdog
if(lastT > Tms || Tms - lastT > 499){ if(lastT > Tms || Tms - lastT > 499){
LED_blink(LED0); LED_blink(LED0);
lastT = Tms; lastT = Tms;
// send dummy command to noone to test CAN bus
can_send_cmd(NOONE_ID, CMD_DUMMY0);
} }
if(lastS > Tms || Tms - lastS > 5){ // run sensors proc. once per 5ms if(lastS > Tms || Tms - lastS > 5){ // run sensors proc. once per 5ms
sensors_process(); sensors_process();
lastS = Tms; lastS = Tms;
} }
if(scan){ can_proc();
if(CAN_get_status() == CAN_FIFO_OVERRUN){
SEND("CAN bus fifo overrun occured!\n");
}
can_messages_proc();
//if(sensors_scan_mode){
if(SENS_SLEEPING == sensors_get_state()){ // show temperature @ each sleeping occurence if(SENS_SLEEPING == sensors_get_state()){ // show temperature @ each sleeping occurence
if(!gotmeasurement){ if(!gotmeasurement){
//SEND("\nTIME="); //SEND("\nTIME=");
printu(Tms); //printu(Tms);
usart_putchar('\t'); //usart_putchar('\t');
//newline(); //newline();
gotmeasurement = 1; gotmeasurement = 1;
showtemperature(); showtemperature();
@ -101,55 +124,81 @@ int main(void){
}else{ }else{
gotmeasurement = 0; gotmeasurement = 0;
} }
} //}
if(usartrx()){ // usart1 received data, store in in buffer if(usartrx()){ // usart1 received data, store in in buffer
L = usart_getline(&txt); L = usart_getline(&txt);
char _1st = txt[0]; char _1st = txt[0];
if(L == 2 && txt[1] == '\n'){ if(L == 2 && txt[1] == '\n'){
L = 0; L = 0;
switch(_1st){ if(_1st > '0' && _1st < '8'){
ID = (CAN_ID_PREFIX & CAN_ID_MASK) | (_1st - '0');
CANsend(ID, CMD_START_MEASUREMENT, _1st);
}else switch(_1st){
case 'A':
CANsend(BCAST_ID, CMD_START_MEASUREMENT, _1st);
if(!sensors_scan_mode) sensors_start();
break;
case 'B':
CANsend(BCAST_ID, CMD_DUMMY0, _1st);
break;
case 'C': // 'C' - show coefficients case 'C': // 'C' - show coefficients
showcoeffs(); showcoeffs();
break; break;
case 'O': case 'D':
sensors_on(); CANsend(MASTER_ID, CMD_DUMMY1, _1st);
break;
case 'E':
SEND("End scan mode\n");
sensors_scan_mode = 0;
break; break;
case 'F': case 'F':
sensors_off(); sensors_off();
break; break;
case 'T': // 'T' - get temperature case 'G':
showtemperature(); SEND("Can address: ");
break; printuhex(getCANID());
case 'R': newline();
i2c_setup(CURRENT_SPEED);
SEND("Reinit I2C\n");
break;
case 'V':
i2c_setup(VERYLOW_SPEED);
SEND("Very low speed\n");
break;
case 'L':
i2c_setup(LOW_SPEED);
SEND("Low speed\n");
break; break;
case 'H': case 'H':
i2c_setup(HIGH_SPEED); i2c_setup(HIGH_SPEED);
SEND("High speed\n"); SEND("High speed\n");
break; break;
case 'G': case 'I':
CAN_reinit();
SEND("Can address: "); SEND("Can address: ");
printu(getCANaddr()); printuhex(getCANID());
newline(); newline();
break; break;
case 'L':
i2c_setup(LOW_SPEED);
SEND("Low speed\n");
break;
case 'O':
sensors_on();
break;
case 'P':
CANsend(BCAST_ID, CMD_PING, _1st);
break;
case 'R':
i2c_setup(CURRENT_SPEED);
SEND("Reinit I2C\n");
break;
case 'S': case 'S':
SEND("Start scan mode\n"); SEND("Start scan mode\n");
scan = 1; sensors_scan_mode = 1;
break; break;
case 'P': case '0':
SEND("End scan mode\n"); case 'T': // 'T' - get temperature
scan = 0; if(!sensors_scan_mode) sensors_start();
break; break;
#ifdef EBUG case 'V':
i2c_setup(VERYLOW_SPEED);
SEND("Very low speed\n");
break;
case 'Z':
CANsend(BCAST_ID, CMD_SENSORS_STATE, _1st);
break;
#if 0
case 'd': case 'd':
case 'g': case 'g':
case 't': case 't':
@ -161,24 +210,32 @@ int main(void){
break; break;
#endif #endif
default: // help default: // help
SEND("'C' - show coefficients\n" SEND(
"'G' - get CAN address\n" "0..7 - start measurement on given controller\n"
"'F' - turn oFf sensors\n" "A - start measurement on all controllers\n"
"'H' - high speed\n" "B - send broadcast CAN dummy message\n"
"'L' - low speed\n" "C - show coefficients\n"
"'O' - turn On sensors\n" "D - send CAN dummy message to master\n"
"'P' - stoP themperature scan\n" "E - end themperature scan\n"
"'R' - reinit I2C\n" "F - turn oFf sensors\n"
"'S' - Start themperature scan\n" "G - get CAN address\n"
"'T' - get raw temperature\n" "H - high speed\n"
"'V' - very low speed\n" "I - reinit CAN\n"
#ifdef EBUG "L - low speed\n"
"O - turn On sensors\n"
"P - ping everyone over CAN\n"
"R - reinit I2C\n"
"S - Start themperature scan\n"
"T - start temperature measurement\n"
"V - very low speed\n"
"Z - get sensors state over CAN\n"
#if 0
"\t\tTEST OPTIONS\n" "\t\tTEST OPTIONS\n"
"'d' - discovery\n" "d - discovery\n"
"'g' - get coeff\n" "g - get coeff\n"
"'t' - measure temper\n" "t - measure temper\n"
"'s' - show temper measured\n" "s - show temper measured\n"
"'p' - sensors_process()\n" "p - sensors_process()\n"
#endif #endif
); );
break; break;

View File

@ -21,22 +21,24 @@
* *
*/ */
#include "sensors_manage.h" #include "sensors_manage.h"
#include "can_process.h"
#include "i2c.h" #include "i2c.h"
#include "usart.h" #include "usart.h"
extern volatile uint32_t Tms; extern volatile uint32_t Tms;
uint8_t sensors_scan_mode = 0; // infinite scan mode
static uint32_t lastSensT = 0; static uint32_t lastSensT = 0;
static SensorsState Sstate = SENS_OFF; // turn on sensors only by request static SensorsState Sstate = SENS_OFF; // turn on sensors only by request
static uint8_t curr_mul_addr = 0; // current sensors pair address @ multiplexer static uint8_t curr_mul_addr = 0; // current sensors pair address @ multiplexer
static uint8_t overcurnt_ctr = 0; // if this counter > 32 go to OFF state static uint8_t overcurnt_ctr = 0; // if this counter > 32 go to OFF state
static uint8_t sens_present[2] = {0,0}; // bit flag: Nth bit == 1 if sensor[s] on given channel found uint8_t sens_present[2] = {0,0}; // bit flag: Nth bit == 1 if sensor[s] on given channel found
static uint8_t Nsens_present = 0; // total amount of sensors found static uint8_t Nsens_present = 0; // total amount of sensors found
static uint8_t Ntemp_measured = 0; // total amount of themperatures measured static uint8_t Ntemp_measured = 0; // total amount of themperatures measured
// 8 - amount of pairs, 2 - amount in pair, 5 - amount of Coef. // 8 - amount of pairs, 2 - amount in pair, 5 - amount of Coef.
static uint16_t coefficients[MUL_MAX_ADDRESS+1][2][5]; // Coefficients for given sensors static uint16_t coefficients[MUL_MAX_ADDRESS+1][2][5]; // Coefficients for given sensors
// measured temperatures * 100 // measured temperatures * 100
static int16_t Temperatures[MUL_MAX_ADDRESS+1][2]; int16_t Temperatures[MUL_MAX_ADDRESS+1][2];
// pair addresses // pair addresses
static const uint8_t Taddr[2] = {TSYS01_ADDR0, TSYS01_ADDR1}; static const uint8_t Taddr[2] = {TSYS01_ADDR0, TSYS01_ADDR1};
@ -96,6 +98,25 @@ void sensors_on(){
} }
} }
/**
* start measurement if sensors are sleeping,
* turn ON if they were OFF
* do nothing if measurement processing
*/
void sensors_start(){
if(sensors_scan_mode) return;
switch(Sstate){
case SENS_SLEEPING:
Sstate = SENS_START_MSRMNT;
break;
case SENS_OFF:
sensors_on();
break;
default:
break;
}
}
/* / count bits in byte /* / count bits in byte
static uint8_t bitCount(uint8_t B){ static uint8_t bitCount(uint8_t B){
uint8_t ctr = 0; uint8_t ctr = 0;
@ -146,7 +167,7 @@ static uint8_t resetproc(){
static uint8_t getcoefsproc(){ static uint8_t getcoefsproc(){
uint8_t i, j; uint8_t i, j;
const uint8_t regs[5] = {0xAA, 0xA8, 0xA6, 0xA4, 0xA2}; // commands for coefficients const uint8_t regs[5] = {0xAA, 0xA8, 0xA6, 0xA4, 0xA2}; // commands for coefficients
#ifdef EBUG #if 0
MSG("sens_present[0]="); MSG("sens_present[0]=");
printu(sens_present[0]); printu(sens_present[0]);
SEND(", sens_present[1]="); SEND(", sens_present[1]=");
@ -157,7 +178,7 @@ newline();
if(!(sens_present[i] & (1<<curr_mul_addr))) continue; // no sensors @ given line if(!(sens_present[i] & (1<<curr_mul_addr))) continue; // no sensors @ given line
uint8_t err = 5; uint8_t err = 5;
uint16_t *coef = coefficients[curr_mul_addr][i]; uint16_t *coef = coefficients[curr_mul_addr][i];
#ifdef EBUG #if 0
SEND("muladdr: "); SEND("muladdr: ");
usart_putchar('0'+curr_mul_addr); usart_putchar('0'+curr_mul_addr);
SEND(", i: "); SEND(", i: ");
@ -167,15 +188,15 @@ newline();
for(j = 0; j < 5; ++j){ for(j = 0; j < 5; ++j){
uint32_t K; uint32_t K;
MSG("N="); MSG("N=");
#ifdef EBUG #if 0
usart_putchar('0'+j); usart_putchar('0'+j);
newline(); newline();
#endif #endif
if(write_i2c(Taddr[i], regs[j])){ if(write_i2c(Taddr[i], regs[j])){
MSG("write\n"); //MSG("write\n");
if(read_i2c(Taddr[i], &K, 2)){ if(read_i2c(Taddr[i], &K, 2)){
MSG("read: "); //MSG("read: ");
#ifdef EBUG #if 0
printu(K); printu(K);
newline(); newline();
#endif #endif
@ -185,7 +206,7 @@ newline();
}else break; }else break;
} }
if(err){ // restart all procedures if we can't get coeffs of present sensor if(err){ // restart all procedures if we can't get coeffs of present sensor
MSG("Error: can't get all coefficients!\n"); //MSG("Error: can't get all coefficients!\n");
sensors_on(); sensors_on();
return 1; return 1;
} }
@ -198,8 +219,8 @@ static uint8_t msrtempproc(){
uint8_t i, j; uint8_t i, j;
for(i = 0; i < 2; ++i){ for(i = 0; i < 2; ++i){
if(!(sens_present[i] & (1<<curr_mul_addr))) continue; // no sensors @ given line if(!(sens_present[i] & (1<<curr_mul_addr))) continue; // no sensors @ given line
MSG("Start measurement for #"); //MSG("Start measurement for #");
#ifdef EBUG #if 0
usart_putchar('0'+curr_mul_addr); usart_putchar('0'+curr_mul_addr);
usart_putchar('_'); usart_putchar('_');
usart_putchar('0'+i); usart_putchar('0'+i);
@ -207,7 +228,7 @@ newline();
#endif #endif
for(j = 0; j < 5; ++j){ for(j = 0; j < 5; ++j){
if(write_i2c(Taddr[i], TSYS01_START_CONV)) break; if(write_i2c(Taddr[i], TSYS01_START_CONV)) break;
MSG("try more\n"); // MSG("try more\n");
if(!write_i2c(Taddr[i], TSYS01_RESET)) i2c_setup(CURRENT_SPEED); // maybe I2C restart will solve the problem? if(!write_i2c(Taddr[i], TSYS01_RESET)) i2c_setup(CURRENT_SPEED); // maybe I2C restart will solve the problem?
} }
/*if(j == 5){ /*if(j == 5){
@ -226,8 +247,8 @@ static uint8_t gettempproc(){
if(!(sens_present[i] & (1<<curr_mul_addr))) continue; // no sensors @ given line if(!(sens_present[i] & (1<<curr_mul_addr))) continue; // no sensors @ given line
Temperatures[curr_mul_addr][i] = NO_SENSOR; Temperatures[curr_mul_addr][i] = NO_SENSOR;
uint8_t err = 1; uint8_t err = 1;
#if 0
MSG("Sensor #"); MSG("Sensor #");
#ifdef EBUG
usart_putchar('0'+curr_mul_addr); usart_putchar('0'+curr_mul_addr);
usart_putchar('_'); usart_putchar('_');
usart_putchar('0'+i); usart_putchar('0'+i);
@ -235,9 +256,9 @@ newline();
#endif #endif
if(write_i2c(Taddr[i], TSYS01_ADC_READ)){ if(write_i2c(Taddr[i], TSYS01_ADC_READ)){
uint32_t t; uint32_t t;
MSG("Read\n"); //MSG("Read\n");
if(read_i2c(Taddr[i], &t, 3) && t){ if(read_i2c(Taddr[i], &t, 3) && t){
#ifdef EBUG #if 0
SEND("Calc from "); SEND("Calc from ");
printu(t); printu(t);
newline(); newline();
@ -249,7 +270,7 @@ newline();
} }
} }
if(err){ if(err){
MSG("Can't read temperature\n"); //MSG("Can't read temperature\n");
write_i2c(Taddr[i], TSYS01_RESET); write_i2c(Taddr[i], TSYS01_RESET);
} }
} }
@ -303,7 +324,7 @@ void showcoeffs(){
} }
} }
// print temperature @debug console // print temperatures @debug console
void showtemperature(){ void showtemperature(){
int a, p; int a, p;
if(Nsens_present == 0){ if(Nsens_present == 0){
@ -317,27 +338,27 @@ void showtemperature(){
for(a = 0; a <= MUL_MAX_ADDRESS; ++a){ for(a = 0; a <= MUL_MAX_ADDRESS; ++a){
for(p = 0; p < 2; ++p){ for(p = 0; p < 2; ++p){
if(!(sens_present[p] & (1<<a))){ if(!(sens_present[p] & (1<<a))){
SEND("-31000\t"); // NO_SENSOR
continue; // no sensor continue; // no sensor
} }
//char b[] = {'T', a+'0', p+'0', '=', '+'}; usart_putchar('T');
usart_putchar('0' + Controller_address);
usart_putchar('_');
printu(a*10+p);
usart_putchar('=');
int16_t t = Temperatures[a][p]; int16_t t = Temperatures[a][p];
if(t < 0){ if(t < 0){
//b[4] = '-';
t = -t; t = -t;
usart_putchar('-'); usart_putchar('-');
} }
//while(ALL_OK != usart_send_blocking(b, 5));
printu(t); printu(t);
usart_putchar('\t'); newline();
//newline();
} }
} }
newline();
} }
// finite state machine for sensors switching & checking // finite state machine for sensors switching & checking
void sensors_process(){ void sensors_process(){
static int8_t NsentOverCAN = -1; // number of T (N*10+p) sent over CAN bus; -1 - nothing to send
if(SENSORS_OVERCURNT()){ if(SENSORS_OVERCURNT()){
MUL_OFF(); MUL_OFF();
SENSORS_OFF(); SENSORS_OFF();
@ -346,7 +367,7 @@ void sensors_process(){
} }
switch (Sstate){ switch (Sstate){
case SENS_INITING: // initialisation (restart I2C) case SENS_INITING: // initialisation (restart I2C)
MSG("init->reset\n"); //MSG("init->reset\n");
i2c_setup(CURRENT_SPEED); i2c_setup(CURRENT_SPEED);
Sstate = SENS_RESETING; Sstate = SENS_RESETING;
lastSensT = Tms; lastSensT = Tms;
@ -358,10 +379,10 @@ MSG("init->reset\n");
if(sensors_scan(resetproc)){ if(sensors_scan(resetproc)){
count_sensors(); // get total amount of sensors count_sensors(); // get total amount of sensors
if(Nsens_present){ if(Nsens_present){
MSG("reset->getcoeff\n"); //MSG("reset->getcoeff\n");
Sstate = SENS_GET_COEFFS; Sstate = SENS_GET_COEFFS;
}else{ // no sensors found }else{ // no sensors found
MSG("reset->off\n"); //MSG("reset->off\n");
sensors_off(); sensors_off();
} }
} }
@ -369,8 +390,8 @@ MSG("reset->off\n");
break; break;
case SENS_GET_COEFFS: // get coefficients case SENS_GET_COEFFS: // get coefficients
if(sensors_scan(getcoefsproc)){ if(sensors_scan(getcoefsproc)){
MSG("got coeffs for "); //MSG("got coeffs for ");
#ifdef EBUG #if 0
printu(Nsens_present); printu(Nsens_present);
SEND(" sensors ->start\n"); SEND(" sensors ->start\n");
#endif #endif
@ -380,23 +401,29 @@ SEND(" sensors ->start\n");
case SENS_START_MSRMNT: // send all sensors command to start measurements case SENS_START_MSRMNT: // send all sensors command to start measurements
if(sensors_scan(msrtempproc)){ if(sensors_scan(msrtempproc)){
lastSensT = Tms; lastSensT = Tms;
MSG("->wait\n"); //MSG("->wait\n");
Sstate = SENS_WAITING; Sstate = SENS_WAITING;
Ntemp_measured = 0; // reset value of good measurements Ntemp_measured = 0; // reset value of good measurements
} }
break; break;
case SENS_WAITING: // wait for end of conversion case SENS_WAITING: // wait for end of conversion
if(Tms - lastSensT > CONV_TIME){ if(Tms - lastSensT > CONV_TIME){
MSG("->gather\n"); //MSG("->gather\n");
Sstate = SENS_GATHERING; Sstate = SENS_GATHERING;
} }
break; break;
case SENS_GATHERING: // scan all sensors, get thermal data & calculate temperature case SENS_GATHERING: // scan all sensors, get thermal data & calculate temperature
if(sensors_scan(gettempproc)){ if(sensors_scan(gettempproc)){
lastSensT = Tms; lastSensT = Tms;
if(Nsens_present != Ntemp_measured) i2c_setup(CURRENT_SPEED); if(Nsens_present != Ntemp_measured){
Sstate = SENS_SLEEPING; i2c_setup(CURRENT_SPEED);
MSG("->sleep\n"); sensors_on();
}
else{
NsentOverCAN = 0;
Sstate = SENS_SLEEPING;
}
//MSG("->sleep\n");
/* /*
if(Nsens_present == Ntemp_measured){ // All OK, amount of T == amount of sensors if(Nsens_present == Ntemp_measured){ // All OK, amount of T == amount of sensors
MSG("->sleep\n"); MSG("->sleep\n");
@ -409,13 +436,16 @@ MSG("gather error ->start\n");
} }
break; break;
case SENS_SLEEPING: // wait for `SLEEP_TIME` till next measurements case SENS_SLEEPING: // wait for `SLEEP_TIME` till next measurements
if(Tms - lastSensT > SLEEP_TIME){ NsentOverCAN = send_temperatures(NsentOverCAN); // call sending T process
MSG("sleep->start\n"); if(sensors_scan_mode){ // sleep until next measurement start
Sstate = SENS_START_MSRMNT; if(Tms - lastSensT > SLEEP_TIME){
//MSG("sleep->start\n");
Sstate = SENS_START_MSRMNT;
}
} }
break; break;
case SENS_OVERCURNT: // try to reinit all after overcurrent case SENS_OVERCURNT: // try to reinit all after overcurrent
MSG("try to turn on after overcurrent\n"); //MSG("try to turn on after overcurrent\n");
sensors_on(); sensors_on();
break; break;
default: // do nothing default: // do nothing
@ -423,7 +453,7 @@ MSG("try to turn on after overcurrent\n");
} }
} }
#ifdef EBUG #if 0
void senstest(char cmd){ void senstest(char cmd){
MUL_OFF(); MUL_OFF();
SENSORS_ON(); SENSORS_ON();

View File

@ -35,6 +35,10 @@
// no sensor on given channel // no sensor on given channel
#define NO_SENSOR (-31000) #define NO_SENSOR (-31000)
extern uint8_t sensors_scan_mode;
extern int16_t Temperatures[MUL_MAX_ADDRESS+1][2];
extern uint8_t sens_present[2];
typedef enum{ typedef enum{
SENS_INITING // power on SENS_INITING // power on
,SENS_RESETING // discovery sensors resetting them ,SENS_RESETING // discovery sensors resetting them
@ -53,6 +57,7 @@ void sensors_process();
void sensors_off(); void sensors_off();
void sensors_on(); void sensors_on();
void sensors_start();
void showcoeffs(); void showcoeffs();
void showtemperature(); void showtemperature();

Binary file not shown.

View File

@ -94,10 +94,12 @@ ADC_TR_HT
ADC_TR_LTÌ65536Ö0 ADC_TR_LTÌ65536Ö0
AHB2PERIPH_BASEÌ65536Ö0 AHB2PERIPH_BASEÌ65536Ö0
AHBPERIPH_BASEÌ65536Ö0 AHBPERIPH_BASEÌ65536Ö0
ALL_OKÌ4Îanon_enum_1Ö0 ALL_OKÌ4Îanon_enum_5Ö0
APBPERIPH_BASEÌ65536Ö0 APBPERIPH_BASEÌ65536Ö0
BAD_TEMPERATUREÌ65536Ö0 BAD_TEMPERATUREÌ65536Ö0
BCAST_IDÌ65536Ö0
CANÌ65536Ö0 CANÌ65536Ö0
CANIDÌ16384Ö0Ïuint16_t
CAN_BASEÌ65536Ö0 CAN_BASEÌ65536Ö0
CAN_BTR_BRPÌ65536Ö0 CAN_BTR_BRPÌ65536Ö0
CAN_BTR_LBKMÌ65536Ö0 CAN_BTR_LBKMÌ65536Ö0
@ -114,6 +116,7 @@ CAN_BTR_TS2
CAN_BTR_TS2_0Ì65536Ö0 CAN_BTR_TS2_0Ì65536Ö0
CAN_BTR_TS2_1Ì65536Ö0 CAN_BTR_TS2_1Ì65536Ö0
CAN_BTR_TS2_2Ì65536Ö0 CAN_BTR_TS2_2Ì65536Ö0
CAN_BUSYÌ4Îanon_enum_2Ö0
CAN_ESR_BOFFÌ65536Ö0 CAN_ESR_BOFFÌ65536Ö0
CAN_ESR_EPVFÌ65536Ö0 CAN_ESR_EPVFÌ65536Ö0
CAN_ESR_EWGFÌ65536Ö0 CAN_ESR_EWGFÌ65536Ö0
@ -1049,6 +1052,7 @@ CAN_FFA1R_FFA6
CAN_FFA1R_FFA7Ì65536Ö0 CAN_FFA1R_FFA7Ì65536Ö0
CAN_FFA1R_FFA8Ì65536Ö0 CAN_FFA1R_FFA8Ì65536Ö0
CAN_FFA1R_FFA9Ì65536Ö0 CAN_FFA1R_FFA9Ì65536Ö0
CAN_FIFO_OVERRUNÌ4Îanon_enum_2Ö0
CAN_FM1R_FBMÌ65536Ö0 CAN_FM1R_FBMÌ65536Ö0
CAN_FM1R_FBM0Ì65536Ö0 CAN_FM1R_FBM0Ì65536Ö0
CAN_FM1R_FBM1Ì65536Ö0 CAN_FM1R_FBM1Ì65536Ö0
@ -1080,6 +1084,8 @@ CAN_FS1R_FSC6
CAN_FS1R_FSC7Ì65536Ö0 CAN_FS1R_FSC7Ì65536Ö0
CAN_FS1R_FSC8Ì65536Ö0 CAN_FS1R_FSC8Ì65536Ö0
CAN_FS1R_FSC9Ì65536Ö0 CAN_FS1R_FSC9Ì65536Ö0
CAN_ID_MASKÌ65536Ö0
CAN_ID_PREFIXÌ65536Ö0
CAN_IER_BOFIEÌ65536Ö0 CAN_IER_BOFIEÌ65536Ö0
CAN_IER_EPVIEÌ65536Ö0 CAN_IER_EPVIEÌ65536Ö0
CAN_IER_ERRIEÌ65536Ö0 CAN_IER_ERRIEÌ65536Ö0
@ -1094,6 +1100,7 @@ CAN_IER_LECIE
CAN_IER_SLKIEÌ65536Ö0 CAN_IER_SLKIEÌ65536Ö0
CAN_IER_TMEIEÌ65536Ö0 CAN_IER_TMEIEÌ65536Ö0
CAN_IER_WKUIEÌ65536Ö0 CAN_IER_WKUIEÌ65536Ö0
CAN_INMESSAGE_SIZEÌ65536Ö0
CAN_MCR_ABOMÌ65536Ö0 CAN_MCR_ABOMÌ65536Ö0
CAN_MCR_AWUMÌ65536Ö0 CAN_MCR_AWUMÌ65536Ö0
CAN_MCR_INRQÌ65536Ö0 CAN_MCR_INRQÌ65536Ö0
@ -1112,6 +1119,7 @@ CAN_MSR_SLAK
CAN_MSR_SLAKIÌ65536Ö0 CAN_MSR_SLAKIÌ65536Ö0
CAN_MSR_TXMÌ65536Ö0 CAN_MSR_TXMÌ65536Ö0
CAN_MSR_WKUIÌ65536Ö0 CAN_MSR_WKUIÌ65536Ö0
CAN_OKÌ4Îanon_enum_2Ö0
CAN_RDH0R_DATA4Ì65536Ö0 CAN_RDH0R_DATA4Ì65536Ö0
CAN_RDH0R_DATA5Ì65536Ö0 CAN_RDH0R_DATA5Ì65536Ö0
CAN_RDH0R_DATA6Ì65536Ö0 CAN_RDH0R_DATA6Ì65536Ö0
@ -1134,6 +1142,7 @@ CAN_RDT0R_TIME
CAN_RDT1R_DLCÌ65536Ö0 CAN_RDT1R_DLCÌ65536Ö0
CAN_RDT1R_FMIÌ65536Ö0 CAN_RDT1R_FMIÌ65536Ö0
CAN_RDT1R_TIMEÌ65536Ö0 CAN_RDT1R_TIMEÌ65536Ö0
CAN_READYÌ4Îanon_enum_2Ö0
CAN_RF0R_FMP0Ì65536Ö0 CAN_RF0R_FMP0Ì65536Ö0
CAN_RF0R_FOVR0Ì65536Ö0 CAN_RF0R_FOVR0Ì65536Ö0
CAN_RF0R_FULL0Ì65536Ö0 CAN_RF0R_FULL0Ì65536Ö0
@ -1150,6 +1159,7 @@ CAN_RI1R_EXID
CAN_RI1R_IDEÌ65536Ö0 CAN_RI1R_IDEÌ65536Ö0
CAN_RI1R_RTRÌ65536Ö0 CAN_RI1R_RTRÌ65536Ö0
CAN_RI1R_STIDÌ65536Ö0 CAN_RI1R_STIDÌ65536Ö0
CAN_STOPÌ4Îanon_enum_2Ö0
CAN_TDH0R_DATA4Ì65536Ö0 CAN_TDH0R_DATA4Ì65536Ö0
CAN_TDH0R_DATA5Ì65536Ö0 CAN_TDH0R_DATA5Ì65536Ö0
CAN_TDH0R_DATA6Ì65536Ö0 CAN_TDH0R_DATA6Ì65536Ö0
@ -1222,6 +1232,19 @@ CAN_TSR_TME2
CAN_TSR_TXOK0Ì65536Ö0 CAN_TSR_TXOK0Ì65536Ö0
CAN_TSR_TXOK1Ì65536Ö0 CAN_TSR_TXOK1Ì65536Ö0
CAN_TSR_TXOK2Ì65536Ö0 CAN_TSR_TXOK2Ì65536Ö0
CAN_commandsÌ4096Ö0Ïanon_enum_8
CAN_get_statusÌ16Í()Ö0ÏCAN_status
CAN_get_statusÌ1024Í()Ö0ÏCAN_status
CAN_messageÌ4096Ö0Ïanon_struct_1
CAN_messagebuf_popÌ16Í()Ö0ÏCAN_message *
CAN_messagebuf_popÌ1024Í()Ö0ÏCAN_message *
CAN_messagebuf_pushÌ16Í(CAN_message *msg)Ö0Ïint
CAN_reinitÌ16Í()Ö0Ïvoid
CAN_reinitÌ1024Í()Ö0Ïvoid
CAN_setupÌ16Í()Ö0Ïvoid
CAN_setupÌ1024Í()Ö0Ïvoid
CAN_statusÌ4096Ö0Ïanon_enum_2
CANsendÌ16Í(uint16_t targetID, uint8_t cmd, char echo)Ö0Ïvoid
CECÌ65536Ö0 CECÌ65536Ö0
CEC_BASEÌ65536Ö0 CEC_BASEÌ65536Ö0
CEC_CFGR_BRDNOGENÌ65536Ö0 CEC_CFGR_BRDNOGENÌ65536Ö0
@ -1266,6 +1289,27 @@ CEC_TXDR_RXD
CEC_TXDR_TXDÌ65536Ö0 CEC_TXDR_TXDÌ65536Ö0
CLEAR_BITÌ131072Í(REG,BIT)Ö0 CLEAR_BITÌ131072Í(REG,BIT)Ö0
CLEAR_REGÌ131072Í(REG)Ö0 CLEAR_REGÌ131072Í(REG)Ö0
CMD_DUMMY0Ì4Îanon_enum_3Ö0
CMD_DUMMY0Ì4Îanon_enum_6Ö0
CMD_DUMMY0Ì4Îanon_enum_7Ö0
CMD_DUMMY0Ì4Îanon_enum_8Ö0
CMD_DUMMY1Ì4Îanon_enum_3Ö0
CMD_DUMMY1Ì4Îanon_enum_6Ö0
CMD_DUMMY1Ì4Îanon_enum_7Ö0
CMD_DUMMY1Ì4Îanon_enum_8Ö0
CMD_PINGÌ4Îanon_enum_3Ö0
CMD_PINGÌ4Îanon_enum_6Ö0
CMD_PINGÌ4Îanon_enum_7Ö0
CMD_PINGÌ4Îanon_enum_8Ö0
CMD_SENSORS_STATEÌ4Îanon_enum_3Ö0
CMD_SENSORS_STATEÌ4Îanon_enum_6Ö0
CMD_SENSORS_STATEÌ4Îanon_enum_7Ö0
CMD_SENSORS_STATEÌ4Îanon_enum_8Ö0
CMD_START_MEASUREMENTÌ4Îanon_enum_3Ö0
CMD_START_MEASUREMENTÌ4Îanon_enum_6Ö0
CMD_START_MEASUREMENTÌ4Îanon_enum_7Ö0
CMD_START_MEASUREMENTÌ4Îanon_enum_8Ö0
COMMAND_MARKÌ65536Ö0
CONCATÌ131072Í(a,b)Ö0 CONCATÌ131072Í(a,b)Ö0
CONV_TIMEÌ65536Ö0 CONV_TIMEÌ65536Ö0
CRCÌ65536Ö0 CRCÌ65536Ö0
@ -1312,6 +1356,9 @@ CRS_ISR_SYNCOKF
CRS_ISR_SYNCWARNFÌ65536Ö0 CRS_ISR_SYNCWARNFÌ65536Ö0
CRS_ISR_TRIMOVFÌ65536Ö0 CRS_ISR_TRIMOVFÌ65536Ö0
CURRENT_SPEEDÌ4Îanon_enum_0Ö0 CURRENT_SPEEDÌ4Îanon_enum_0Ö0
Controller_addressÌ16384Ö0Ïuint8_t
Controller_addressÌ32768Ö0Ïuint8_t
DATA_MARKÌ65536Ö0
DBGMCUÌ65536Ö0 DBGMCUÌ65536Ö0
DBGMCU_APB1_FZ_DBG_CAN_STOPÌ65536Ö0 DBGMCU_APB1_FZ_DBG_CAN_STOPÌ65536Ö0
DBGMCU_APB1_FZ_DBG_I2C1_SMBUS_TIMEOUTÌ65536Ö0 DBGMCU_APB1_FZ_DBG_I2C1_SMBUS_TIMEOUTÌ65536Ö0
@ -1440,7 +1487,6 @@ DMA_ISR_TEIF4
DMA_ISR_TEIF5Ì65536Ö0 DMA_ISR_TEIF5Ì65536Ö0
DMA_ISR_TEIF6Ì65536Ö0 DMA_ISR_TEIF6Ì65536Ö0
DMA_ISR_TEIF7Ì65536Ö0 DMA_ISR_TEIF7Ì65536Ö0
EBUGÌ65536Ö0
EXTIÌ65536Ö0 EXTIÌ65536Ö0
EXTI_BASEÌ65536Ö0 EXTI_BASEÌ65536Ö0
EXTI_EMR_MR0Ì65536Ö0 EXTI_EMR_MR0Ì65536Ö0
@ -2199,15 +2245,19 @@ LED0_port
LED1_pinÌ65536Ö0 LED1_pinÌ65536Ö0
LED1_portÌ65536Ö0 LED1_portÌ65536Ö0
LED_blinkÌ131072Í(x)Ö0 LED_blinkÌ131072Í(x)Ö0
LINE_BUSYÌ4Îanon_enum_1Ö0 LED_offÌ131072Í(x)Ö0
LED_onÌ131072Í(x)Ö0
LINE_BUSYÌ4Îanon_enum_5Ö0
LOW_SPEEDÌ4Îanon_enum_0Ö0 LOW_SPEEDÌ4Îanon_enum_0Ö0
MASTER_IDÌ65536Ö0
MODIFY_REGÌ131072Í(REG,CLEARMASK,SETMASK)Ö0 MODIFY_REGÌ131072Í(REG,CLEARMASK,SETMASK)Ö0
MSGÌ131072Í(str)Ö0 MSGÌ131072Í(str)Ö0
MUL_ADDRESSÌ131072Í(x)Ö0 MUL_ADDRESSÌ131072Í(x)Ö0
MUL_MAX_ADDRESSÌ65536Ö0 MUL_MAX_ADDRESSÌ65536Ö0
MUL_OFFÌ131072Í()Ö0 MUL_OFFÌ131072Í()Ö0
MUL_ONÌ131072Í()Ö0 MUL_ONÌ131072Í()Ö0
NEWLINEÌ131072Í()Ö0 NOONE_IDÌ65536Ö0
NO_SENSORÌ65536Ö0
NULLÌ65536Ö0 NULLÌ65536Ö0
NVICÌ65536Ö0 NVICÌ65536Ö0
NVIC_BASEÌ65536Ö0 NVIC_BASEÌ65536Ö0
@ -2228,6 +2278,7 @@ OB_WRP2_nWRP2
OB_WRP3_WRP3Ì65536Ö0 OB_WRP3_WRP3Ì65536Ö0
OB_WRP3_nWRP3Ì65536Ö0 OB_WRP3_nWRP3Ì65536Ö0
PERIPH_BASEÌ65536Ö0 PERIPH_BASEÌ65536Ö0
POWERUP_TIMEÌ65536Ö0
PTRDIFF_MAXÌ65536Ö0 PTRDIFF_MAXÌ65536Ö0
PTRDIFF_MINÌ65536Ö0 PTRDIFF_MINÌ65536Ö0
PTRDIFF_WIDTHÌ65536Ö0 PTRDIFF_WIDTHÌ65536Ö0
@ -2556,6 +2607,7 @@ RCC_CSR_WWDGRSTF
RCC_IRQHandlerÌ65536Ö0 RCC_IRQHandlerÌ65536Ö0
RCC_IRQnÌ65536Ö0 RCC_IRQnÌ65536Ö0
READ_BITÌ131072Í(REG,BIT)Ö0 READ_BITÌ131072Í(REG,BIT)Ö0
READ_CAN_INV_ADDRÌ131072Í()Ö0
READ_REGÌ131072Í(REG)Ö0 READ_REGÌ131072Í(REG)Ö0
RTCÌ65536Ö0 RTCÌ65536Ö0
RTC_ALRMAR_DTÌ65536Ö0 RTC_ALRMAR_DTÌ65536Ö0
@ -2832,19 +2884,20 @@ SCB_SHCSR_SVCALLPENDED_Msk
SCB_SHCSR_SVCALLPENDED_PosÌ65536Ö0 SCB_SHCSR_SVCALLPENDED_PosÌ65536Ö0
SCS_BASEÌ65536Ö0 SCS_BASEÌ65536Ö0
SENDÌ131072Í(str)Ö0 SENDÌ131072Í(str)Ö0
SEND_TIMEOUT_MSÌ65536Ö0
SENSORS_OFFÌ131072Í()Ö0 SENSORS_OFFÌ131072Í()Ö0
SENSORS_ONÌ131072Í()Ö0 SENSORS_ONÌ131072Í()Ö0
SENSORS_OVERCURNTÌ131072Í()Ö0 SENSORS_OVERCURNTÌ131072Í()Ö0
SENS_GATHERINGÌ4Îanon_enum_2Ö0 SENS_GATHERINGÌ4Îanon_enum_4Ö0
SENS_GET_COEFFSÌ4Îanon_enum_2Ö0 SENS_GET_COEFFSÌ4Îanon_enum_4Ö0
SENS_INITINGÌ4Îanon_enum_2Ö0 SENS_INITINGÌ4Îanon_enum_4Ö0
SENS_OFFÌ4Îanon_enum_2Ö0 SENS_OFFÌ4Îanon_enum_4Ö0
SENS_OVERCURNTÌ4Îanon_enum_2Ö0 SENS_OVERCURNTÌ4Îanon_enum_4Ö0
SENS_OVERCURNT_OFFÌ4Îanon_enum_2Ö0 SENS_OVERCURNT_OFFÌ4Îanon_enum_4Ö0
SENS_RESETINGÌ4Îanon_enum_2Ö0 SENS_RESETINGÌ4Îanon_enum_4Ö0
SENS_SLEEPINGÌ4Îanon_enum_2Ö0 SENS_SLEEPINGÌ4Îanon_enum_4Ö0
SENS_START_MSRMNTÌ4Îanon_enum_2Ö0 SENS_START_MSRMNTÌ4Îanon_enum_4Ö0
SENS_WAITINGÌ4Îanon_enum_2Ö0 SENS_WAITINGÌ4Îanon_enum_4Ö0
SET_BITÌ131072Í(REG,BIT)Ö0 SET_BITÌ131072Í(REG,BIT)Ö0
SIG_ATOMIC_MAXÌ65536Ö0 SIG_ATOMIC_MAXÌ65536Ö0
SIG_ATOMIC_MINÌ65536Ö0 SIG_ATOMIC_MINÌ65536Ö0
@ -2930,7 +2983,7 @@ STM32F0
STM32F042x6Ì65536Ö0 STM32F042x6Ì65536Ö0
STRÌ131072Í(s)Ö0 STRÌ131072Í(s)Ö0
STR_HELPERÌ131072Í(s)Ö0 STR_HELPERÌ131072Í(s)Ö0
STR_TOO_LONGÌ4Îanon_enum_1Ö0 STR_TOO_LONGÌ4Îanon_enum_5Ö0
SYSCFGÌ65536Ö0 SYSCFGÌ65536Ö0
SYSCFG_BASEÌ65536Ö0 SYSCFG_BASEÌ65536Ö0
SYSCFG_CFGR1_ADC_DMA_RMPÌ65536Ö0 SYSCFG_CFGR1_ADC_DMA_RMPÌ65536Ö0
@ -3062,7 +3115,7 @@ SYSCFG_EXTICR4_EXTI15_PB
SYSCFG_EXTICR4_EXTI15_PCÌ65536Ö0 SYSCFG_EXTICR4_EXTI15_PCÌ65536Ö0
SYSCFG_EXTICR4_EXTI15_PDÌ65536Ö0 SYSCFG_EXTICR4_EXTI15_PDÌ65536Ö0
SYSCFG_EXTICR4_EXTI15_PEÌ65536Ö0 SYSCFG_EXTICR4_EXTI15_PEÌ65536Ö0
SensorsStateÌ4096Ö0Ïanon_enum_2 SensorsStateÌ4096Ö0Ïanon_enum_4
SstateÌ16384Ö0ÏSensorsState SstateÌ16384Ö0ÏSensorsState
StartHSEÌ16Í()Ö0Ïinline void StartHSEÌ16Í()Ö0Ïinline void
StartHSI48Ì16Í()Ö0Ïinline void StartHSI48Ì16Í()Ö0Ïinline void
@ -3505,9 +3558,10 @@ TSYS01_ADDR1
TSYS01_PROM_ADDR0Ì65536Ö0 TSYS01_PROM_ADDR0Ì65536Ö0
TSYS01_RESETÌ65536Ö0 TSYS01_RESETÌ65536Ö0
TSYS01_START_CONVÌ65536Ö0 TSYS01_START_CONVÌ65536Ö0
TXstatusÌ4096Ö0Ïanon_enum_1 TXstatusÌ4096Ö0Ïanon_enum_5
TaddrÌ16384Ö0Ïconst uint8_t TaddrÌ16384Ö0Ïconst uint8_t
TemperaturesÌ16384Ö0Ïint16_t TemperaturesÌ16384Ö0Ïint16_t
TemperaturesÌ32768Ö0Ïint16_t
TmsÌ16384Ö0Ïvolatile uint32_t TmsÌ16384Ö0Ïvolatile uint32_t
TmsÌ32768Ö0Ïvolatile uint32_t TmsÌ32768Ö0Ïvolatile uint32_t
UARTBUFSZÌ65536Ö0 UARTBUFSZÌ65536Ö0
@ -3880,6 +3934,7 @@ __BLKCNT64_T_TYPE
__BLKCNT_T_TYPEÌ65536Ö0 __BLKCNT_T_TYPEÌ65536Ö0
__BLKSIZE_T_TYPEÌ65536Ö0 __BLKSIZE_T_TYPEÌ65536Ö0
__BYTE_ORDER__Ì65536Ö0 __BYTE_ORDER__Ì65536Ö0
__CAN_H__Ì65536Ö0
__CHAR16_TYPE__Ì65536Ö0 __CHAR16_TYPE__Ì65536Ö0
__CHAR32_TYPE__Ì65536Ö0 __CHAR32_TYPE__Ì65536Ö0
__CHAR_BIT__Ì65536Ö0 __CHAR_BIT__Ì65536Ö0
@ -4278,6 +4333,7 @@ __attribute_format_arg__
__attribute_format_strfmon__Ì131072Í(a,b)Ö0 __attribute_format_strfmon__Ì131072Í(a,b)Ö0
__attribute_malloc__Ì65536Ö0 __attribute_malloc__Ì65536Ö0
__attribute_noinline__Ì65536Ö0 __attribute_noinline__Ì65536Ö0
__attribute_nonstring__Ì65536Ö0
__attribute_pure__Ì65536Ö0 __attribute_pure__Ì65536Ö0
__attribute_used__Ì65536Ö0 __attribute_used__Ì65536Ö0
__attribute_warn_unused_result__Ì65536Ö0 __attribute_warn_unused_result__Ì65536Ö0
@ -4337,7 +4393,6 @@ __k8
__k8__Ì65536Ö0 __k8__Ì65536Ö0
__linuxÌ65536Ö0 __linuxÌ65536Ö0
__linux__Ì65536Ö0 __linux__Ì65536Ö0
__long_double_tÌ65536Ö0
__need_NULLÌ65536Ö0 __need_NULLÌ65536Ö0
__need_size_tÌ65536Ö0 __need_size_tÌ65536Ö0
__nonnullÌ131072Í(params)Ö0 __nonnullÌ131072Í(params)Ö0
@ -4372,20 +4427,45 @@ __wur
__x86_64Ì65536Ö0 __x86_64Ì65536Ö0
__x86_64__Ì65536Ö0 __x86_64__Ì65536Ö0
anon_enum_0Ì2Ö0 anon_enum_0Ì2Ö0
anon_enum_1Ì2Ö0
anon_enum_2Ì2Ö0 anon_enum_2Ì2Ö0
anon_enum_3Ì2Ö0
anon_enum_4Ì2Ö0
anon_enum_5Ì2Ö0
anon_enum_6Ì2Ö0
anon_enum_7Ì2Ö0
anon_enum_8Ì2Ö0
anon_struct_1Ì2048Ö0
bufovrÌ16384Ö0Ïint bufovrÌ16384Ö0Ïint
bufovrÌ32768Ö0Ïint bufovrÌ32768Ö0Ïint
calc_tÌ16Í(uint32_t t, int i)Ö0Ïuint16_t calc_tÌ16Í(uint32_t t, int i)Ö0Ïuint16_t
can_messages_procÌ16Í()Ö0Ïvoid
can_messages_procÌ1024Í()Ö0Ïvoid
can_procÌ16Í()Ö0Ïvoid
can_procÌ1024Í()Ö0Ïvoid
can_process_fifoÌ16Í(uint8_t fifo_num)Ö0Ïvoid
can_process_fifoÌ1024Í(uint8_t fifo_num)Ö0Ïvoid
can_sendÌ16Í(uint8_t *msg, uint8_t len, uint16_t target_id)Ö0ÏCAN_status
can_sendÌ1024Í(uint8_t *msg, uint8_t len, uint16_t target_id)Ö0ÏCAN_status
can_send_cmdÌ16Í(uint16_t targetID, uint8_t cmd)Ö0ÏCAN_status
can_send_cmdÌ1024Í(uint16_t targetID, uint8_t cmd)Ö0ÏCAN_status
can_send_dataÌ16Í(uint8_t *data, uint8_t len)Ö0ÏCAN_status
can_send_dataÌ1024Í(uint8_t *data, uint8_t len)Ö0ÏCAN_status
can_statusÌ16384Ö0ÏCAN_status
cec_can_isrÌ16Í()Ö0Ïvoid
cntrÌ16384Ö0Ïuint32_t cntrÌ16384Ö0Ïuint32_t
coefficientsÌ16384Ö0Ïuint16_t coefficientsÌ16384Ö0Ïuint16_t
count_sensorsÌ16Í()Ö0Ïvoid count_sensorsÌ16Í()Ö0Ïvoid
curI2CspeedÌ16384Ö0ÏI2C_SPEED curI2CspeedÌ16384Ö0ÏI2C_SPEED
curI2CspeedÌ32768Ö0ÏI2C_SPEED curI2CspeedÌ32768Ö0ÏI2C_SPEED
curr_mul_addrÌ16384Ö0Ïuint8_t curr_mul_addrÌ16384Ö0Ïuint8_t
dataÌ64Îanon_struct_1Ö0Ïuint8_t
datalenÌ16384Ö0Ïint datalenÌ16384Ö0Ïint
dlenÌ16384Ö0Ïint dlenÌ16384Ö0Ïint
dma1_channel2_3_isrÌ16Í()Ö0Ïvoid dma1_channel2_3_isrÌ16Í()Ö0Ïvoid
first_free_idxÌ16384Ö0Ïuint8_t
first_nonfree_idxÌ16384Ö0Ïint8_t
getCANIDÌ16Í()Ö0Ïuint16_t
getCANIDÌ1024Í()Ö0Ïuint16_t
getcoefsprocÌ16Í()Ö0Ïuint8_t getcoefsprocÌ16Í()Ö0Ïuint8_t
gettempprocÌ16Í()Ö0Ïuint8_t gettempprocÌ16Í()Ö0Ïuint8_t
gpio_setupÌ16Í(void)Ö0Ïvoid gpio_setupÌ16Í(void)Ö0Ïvoid
@ -4394,10 +4474,12 @@ i2c_setup
i2c_setupÌ1024Í(I2C_SPEED speed)Ö0Ïvoid i2c_setupÌ1024Í(I2C_SPEED speed)Ö0Ïvoid
iwdg_setupÌ16Í()Ö0Ïvoid iwdg_setupÌ16Í()Ö0Ïvoid
lastSensTÌ16384Ö0Ïuint32_t lastSensTÌ16384Ö0Ïuint32_t
linerdyÌ16384Ö0Ïint lengthÌ64Îanon_struct_1Ö0Ïuint8_t
linerdyÌ32768Ö0Ïint linerdyÌ16384Ö0Ïvolatile int
linerdyÌ32768Ö0Ïvolatile int
linuxÌ65536Ö0 linuxÌ65536Ö0
mainÌ16Í(void)Ö0Ïint mainÌ16Í(void)Ö0Ïint
messagesÌ16384Ö0ÏCAN_message
msrtempprocÌ16Í()Ö0Ïuint8_t msrtempprocÌ16Í()Ö0Ïuint8_t
newlineÌ16Í()Ö0Ïvoid newlineÌ16Í()Ö0Ïvoid
newlineÌ1024Í()Ö0Ïvoid newlineÌ1024Í()Ö0Ïvoid
@ -4410,13 +4492,20 @@ pin_toggle
pin_writeÌ131072Í(gpioport,gpios)Ö0 pin_writeÌ131072Í(gpioport,gpios)Ö0
printuÌ16Í(uint32_t val)Ö0Ïvoid printuÌ16Í(uint32_t val)Ö0Ïvoid
printuÌ1024Í(uint32_t val)Ö0Ïvoid printuÌ1024Í(uint32_t val)Ö0Ïvoid
printuhexÌ16Í(uint32_t val)Ö0Ïvoid
printuhexÌ1024Í(uint32_t val)Ö0Ïvoid
rbufÌ16384Ö0Ïchar rbufÌ16384Ö0Ïchar
rbufnoÌ16384Ö0Ïint rbufnoÌ16384Ö0Ïint
readCANIDÌ16Í()Ö0Ïvoid
readCANIDÌ1024Í()Ö0Ïvoid
read_i2cÌ16Í(uint8_t addr, uint32_t *data, uint8_t nbytes)Ö0Ïuint8_t read_i2cÌ16Í(uint8_t addr, uint32_t *data, uint8_t nbytes)Ö0Ïuint8_t
read_i2cÌ1024Í(uint8_t addr, uint32_t *data, uint8_t nbytes)Ö0Ïuint8_t read_i2cÌ1024Í(uint8_t addr, uint32_t *data, uint8_t nbytes)Ö0Ïuint8_t
recvdataÌ16384Ö0Ïchar * recvdataÌ16384Ö0Ïchar *
resetprocÌ16Í()Ö0Ïuint8_t resetprocÌ16Í()Ö0Ïuint8_t
send_temperaturesÌ16Í(int8_t N)Ö0Ïint8_t
send_temperaturesÌ1024Í(int8_t N)Ö0Ïint8_t
sens_presentÌ16384Ö0Ïuint8_t sens_presentÌ16384Ö0Ïuint8_t
sens_presentÌ32768Ö0Ïuint8_t
sensors_get_stateÌ16Í()Ö0ÏSensorsState sensors_get_stateÌ16Í()Ö0ÏSensorsState
sensors_get_stateÌ1024Í()Ö0ÏSensorsState sensors_get_stateÌ1024Í()Ö0ÏSensorsState
sensors_offÌ16Í()Ö0Ïvoid sensors_offÌ16Í()Ö0Ïvoid
@ -4426,6 +4515,10 @@ sensors_on
sensors_processÌ16Í()Ö0Ïvoid sensors_processÌ16Í()Ö0Ïvoid
sensors_processÌ1024Í()Ö0Ïvoid sensors_processÌ1024Í()Ö0Ïvoid
sensors_scanÌ16Í(uint8_t (* procfn)())Ö0Ïuint8_t sensors_scanÌ16Í(uint8_t (* procfn)())Ö0Ïuint8_t
sensors_scan_modeÌ16384Ö0Ïuint8_t
sensors_scan_modeÌ32768Ö0Ïuint8_t
sensors_startÌ16Í()Ö0Ïvoid
sensors_startÌ1024Í()Ö0Ïvoid
showcoeffsÌ16Í()Ö0Ïvoid showcoeffsÌ16Í()Ö0Ïvoid
showcoeffsÌ1024Í()Ö0Ïvoid showcoeffsÌ1024Í()Ö0Ïvoid
showtemperatureÌ16Í()Ö0Ïvoid showtemperatureÌ16Í()Ö0Ïvoid
@ -4435,6 +4528,7 @@ strndupa
sys_tick_handlerÌ16Í(void)Ö0Ïvoid sys_tick_handlerÌ16Í(void)Ö0Ïvoid
sysresetÌ16Í(void)Ö0Ïinline void sysresetÌ16Í(void)Ö0Ïinline void
tbufÌ16384Ö0Ïchar tbufÌ16384Ö0Ïchar
try2sendÌ16Í(uint8_t *buf, uint8_t len, uint16_t id)Ö0ÏCAN_status
txrdyÌ16384Ö0Ïint txrdyÌ16384Ö0Ïint
txrdyÌ32768Ö0Ïint txrdyÌ32768Ö0Ïint
unixÌ65536Ö0 unixÌ65536Ö0

View File

@ -27,7 +27,16 @@ long_line_behaviour=1
long_line_column=100 long_line_column=100
[files] [files]
current_page=-1 current_page=8
FILE_NAME_0=6740;C;0;EKOI8-R;0;1;0;%2Fhome%2Feddy%2FDocs%2FSAO%2FBTA%2FMIRROR_CONTROL_termo%2FProject%2FSTM32src%2FTSYS_controller%2Fcan.c;0;4
FILE_NAME_1=1189;C;0;EKOI8-R;0;1;0;%2Fhome%2Feddy%2FDocs%2FSAO%2FBTA%2FMIRROR_CONTROL_termo%2FProject%2FSTM32src%2FTSYS_controller%2Fcan.h;0;4
FILE_NAME_2=2113;C;0;EUTF-8;0;1;0;%2Fhome%2Feddy%2FDocs%2FSAO%2FBTA%2FMIRROR_CONTROL_termo%2FProject%2FSTM32src%2FTSYS_controller%2Fmain.c;0;4
FILE_NAME_3=10188;C;0;EKOI8-R;0;1;0;%2Fhome%2Feddy%2FDocs%2FSAO%2FBTA%2FMIRROR_CONTROL_termo%2FProject%2FSTM32src%2FTSYS_controller%2Fsensors_manage.c;0;4
FILE_NAME_4=8248;C;0;EKOI8-R;0;1;0;%2Fhome%2Feddy%2FDocs%2FSAO%2FELECTRONICS%2FSTM32%2FF0-srcs%2Fcanbus%2Fsrc%2Fcan.c;0;4
FILE_NAME_5=3404;C;0;EUTF-8;0;1;0;%2Fhome%2Feddy%2FDocs%2FSAO%2FELECTRONICS%2FSTM32%2FF0-srcs%2Fcanbus%2Fsrc%2Fmain.c;0;4
FILE_NAME_6=1593;C;0;EUTF-8;0;1;0;%2Fhome%2Feddy%2FDocs%2FSAO%2FBTA%2FMIRROR_CONTROL_termo%2FProject%2FSTM32src%2FTSYS_controller%2Fcan_process.c;0;4
FILE_NAME_7=1165;C;0;EUTF-8;0;1;0;%2Fhome%2Feddy%2FDocs%2FSAO%2FBTA%2FMIRROR_CONTROL_termo%2FProject%2FSTM32src%2FTSYS_controller%2Fcan_process.h;0;4
FILE_NAME_8=0;C;0;EKOI8-R;0;1;0;%2Fhome%2Feddy%2FDocs%2FSAO%2FBTA%2FMIRROR_CONTROL_termo%2FProject%2FSTM32src%2FTSYS_controller%2Fsensors_manage.h;0;4
[VTE] [VTE]
last_dir=/home/eddy last_dir=/home/eddy

View File

@ -218,6 +218,20 @@ void printu(uint32_t val){
while(LINE_BUSY == usart_send_blocking(bufa, l+bpos)); while(LINE_BUSY == usart_send_blocking(bufa, l+bpos));
} }
// print 32bit unsigned int as hex
void printuhex(uint32_t val){
SEND("0x");
uint8_t *ptr = (uint8_t*)&val + 3;
int i, j;
for(i = 0; i < 4; ++i, --ptr){
for(j = 1; j > -1; --j){
uint8_t half = (*ptr >> (4*j)) & 0x0f;
if(half < 10) usart_putchar(half + '0');
else usart_putchar(half - 10 + 'a');
}
}
}
#if USARTNUM == 2 #if USARTNUM == 2
void dma1_channel4_5_isr(){ void dma1_channel4_5_isr(){
if(DMA1->ISR & DMA_ISR_TCIF4){ // Tx if(DMA1->ISR & DMA_ISR_TCIF4){ // Tx

View File

@ -56,5 +56,6 @@ TXstatus usart_send_blocking(const char *str, int len);
void newline(); void newline();
void usart_putchar(const char ch); void usart_putchar(const char ch);
void printu(uint32_t val); void printu(uint32_t val);
void printuhex(uint32_t val);
#endif // __USART_H__ #endif // __USART_H__