From f554e66e2455d5d7e5c391d1147e5a3616988838 Mon Sep 17 00:00:00 2001 From: Edward Emelianov Date: Sat, 24 Jul 2021 15:17:00 +0300 Subject: [PATCH] usbcan_relay works! --- F0-nolib/usbcan_relay/adc.c | 105 +++++++++++++++++++ F0-nolib/usbcan_relay/adc.h | 32 ++++++ F0-nolib/usbcan_relay/buttons.c | 4 +- F0-nolib/usbcan_relay/can.c | 16 ++- F0-nolib/usbcan_relay/canproto.c | 171 +++++++++++++++++++++++++++++++ F0-nolib/usbcan_relay/canproto.h | 47 +++++++++ F0-nolib/usbcan_relay/hardware.c | 26 ++++- F0-nolib/usbcan_relay/hardware.h | 12 ++- F0-nolib/usbcan_relay/main.c | 2 + F0-nolib/usbcan_relay/proto.c | 57 ++++++++++- F0-nolib/usbcan_relay/usbcan.bin | Bin 13676 -> 15448 bytes 11 files changed, 459 insertions(+), 13 deletions(-) create mode 100644 F0-nolib/usbcan_relay/adc.c create mode 100644 F0-nolib/usbcan_relay/adc.h create mode 100644 F0-nolib/usbcan_relay/canproto.c create mode 100644 F0-nolib/usbcan_relay/canproto.h diff --git a/F0-nolib/usbcan_relay/adc.c b/F0-nolib/usbcan_relay/adc.c new file mode 100644 index 0000000..95c1c3a --- /dev/null +++ b/F0-nolib/usbcan_relay/adc.c @@ -0,0 +1,105 @@ +/* + * This file is part of the canrelay project. + * Copyright 2021 Edward V. Emelianov . + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + */ + +#include "adc.h" + +/** + * @brief ADC_array - array for ADC channels with median filtering: + * 0 & 1 - external channels (5 & 12V) + * 2 - internal Tsens + * 3 - Vref + */ +static uint16_t ADC_array[NUMBER_OF_ADC_CHANNELS*9]; + +void adc_setup(){ + uint16_t ctr = 0; // 0xfff0 - more than 1.3ms + ADC1->CR &= ~ADC_CR_ADEN; + DMA1_Channel1->CCR &= ~DMA_CCR_EN; + RCC->APB2ENR |= RCC_APB2ENR_ADC1EN; // Enable the peripheral clock of the ADC + RCC->CR2 |= RCC_CR2_HSI14ON; // Start HSI14 RC oscillator + while ((RCC->CR2 & RCC_CR2_HSI14RDY) == 0 && ++ctr < 0xfff0){}; // Wait HSI14 is ready + // calibration + if(ADC1->CR & ADC_CR_ADEN){ // Ensure that ADEN = 0 + ADC1->CR &= (uint32_t)(~ADC_CR_ADEN); // Clear ADEN + } + ADC1->CR |= ADC_CR_ADCAL; // Launch the calibration by setting ADCAL + ctr = 0; // ADC calibration time is 5.9us + while(ADC1->CR & ADC_CR_ADCAL && ++ctr < 0xfff0); // Wait until ADCAL=0 + // enable ADC + ctr = 0; + do{ + ADC1->CR |= ADC_CR_ADEN; + }while((ADC1->ISR & ADC_ISR_ADRDY) == 0 && ++ctr < 0xfff0); + // configure ADC + ADC1->CFGR1 |= ADC_CFGR1_CONT; // Select the continuous mode + // channels 6,7,16 and 17 + ADC1->CHSELR = ADC_CHSELR_CHSEL6 | ADC_CHSELR_CHSEL7 | ADC_CHSELR_CHSEL16 | ADC_CHSELR_CHSEL17; + ADC1->SMPR |= ADC_SMPR_SMP; // Select a sampling mode of 111 i.e. 239.5 ADC clk to be greater than 17.1us + ADC->CCR |= ADC_CCR_TSEN | ADC_CCR_VREFEN; // Wake-up the VREFINT and Temperature sensor + // configure DMA for ADC + RCC->AHBENR |= RCC_AHBENR_DMA1EN; // Enable the peripheral clock on DMA + ADC1->CFGR1 |= ADC_CFGR1_DMAEN | ADC_CFGR1_DMACFG; // Enable DMA transfer on ADC and circular mode + DMA1_Channel1->CPAR = (uint32_t) (&(ADC1->DR)); // Configure the peripheral data register address + DMA1_Channel1->CMAR = (uint32_t)(ADC_array); // Configure the memory address + DMA1_Channel1->CNDTR = NUMBER_OF_ADC_CHANNELS * 9; // Configure the number of DMA tranfer to be performs on DMA channel 1 + DMA1_Channel1->CCR |= DMA_CCR_MINC | DMA_CCR_MSIZE_0 | DMA_CCR_PSIZE_0 | DMA_CCR_CIRC; // Configure increment, size, interrupts and circular mode + DMA1_Channel1->CCR |= DMA_CCR_EN; // Enable DMA Channel 1 + ADC1->CR |= ADC_CR_ADSTART; // start the ADC conversions +} + +/** + * @brief getADCval - calculate median value for `nch` channel + * @param nch - number of channel + * @return + */ +uint16_t getADCval(int nch){ + int i, addr = nch; + register uint16_t temp; +#define PIX_SORT(a,b) { if ((a)>(b)) PIX_SWAP((a),(b)); } +#define PIX_SWAP(a,b) { temp=(a);(a)=(b);(b)=temp; } + uint16_t p[9]; + for(i = 0; i < 9; ++i, addr += NUMBER_OF_ADC_CHANNELS) // first we should prepare array for optmed + p[i] = ADC_array[addr]; + PIX_SORT(p[1], p[2]) ; PIX_SORT(p[4], p[5]) ; PIX_SORT(p[7], p[8]) ; + PIX_SORT(p[0], p[1]) ; PIX_SORT(p[3], p[4]) ; PIX_SORT(p[6], p[7]) ; + PIX_SORT(p[1], p[2]) ; PIX_SORT(p[4], p[5]) ; PIX_SORT(p[7], p[8]) ; + PIX_SORT(p[0], p[3]) ; PIX_SORT(p[5], p[8]) ; PIX_SORT(p[4], p[7]) ; + PIX_SORT(p[3], p[6]) ; PIX_SORT(p[1], p[4]) ; PIX_SORT(p[2], p[5]) ; + PIX_SORT(p[4], p[7]) ; PIX_SORT(p[4], p[2]) ; PIX_SORT(p[6], p[4]) ; + PIX_SORT(p[4], p[2]) ; + return p[4]; +#undef PIX_SORT +#undef PIX_SWAP +} + +// return MCU temperature (degrees of celsius * 10) +int32_t getMCUtemp(){ + int32_t ADval = getADCval(2); + int32_t temperature = (int32_t) *TEMP30_CAL_ADDR - ADval; + temperature *= (int32_t)(1100 - 300); + temperature /= (int32_t)(*TEMP30_CAL_ADDR - *TEMP110_CAL_ADDR); + temperature += 300; + return(temperature); +} + +// return Vdd * 100 (V) +uint32_t getVdd(){ + uint32_t vdd = ((uint32_t) *VREFINT_CAL_ADDR) * (uint32_t)330; // 3.3V + vdd /= getADCval(3); + return vdd; +} diff --git a/F0-nolib/usbcan_relay/adc.h b/F0-nolib/usbcan_relay/adc.h new file mode 100644 index 0000000..54c6ba4 --- /dev/null +++ b/F0-nolib/usbcan_relay/adc.h @@ -0,0 +1,32 @@ +/* + * This file is part of the canrelay project. + * Copyright 2021 Edward V. Emelianov . + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + */ + +#ifndef ADC_H +#define ADC_H +#include "stm32f0.h" + +// 2 external & 2 internal +#define NUMBER_OF_ADC_CHANNELS (4) + +void adc_setup(); +int32_t getMCUtemp(); +uint32_t getVdd(); +uint16_t getADCval(int nch); +int16_t getNTC(int nch); + +#endif // ADC_H diff --git a/F0-nolib/usbcan_relay/buttons.c b/F0-nolib/usbcan_relay/buttons.c index 44ea7a5..24a032f 100644 --- a/F0-nolib/usbcan_relay/buttons.c +++ b/F0-nolib/usbcan_relay/buttons.c @@ -52,10 +52,10 @@ void process_keys(){ break; } }else{ // released - if(e == EVT_PRESS || e == EVT_RELEASE){ // released + if(e == EVT_PRESS || e == EVT_HOLD){ // released if(k->counter > PRESSTHRESHOLD) k->counter = PRESSTHRESHOLD; else if((k->counter -= d) < 0){ - k->event = EVT_NONE; // button released + k->event = EVT_RELEASE; // button released } } } diff --git a/F0-nolib/usbcan_relay/can.c b/F0-nolib/usbcan_relay/can.c index d9bb268..a51641c 100644 --- a/F0-nolib/usbcan_relay/can.c +++ b/F0-nolib/usbcan_relay/can.c @@ -17,6 +17,7 @@ */ #include "can.h" +#include "canproto.h" #include "hardware.h" #include "proto.h" @@ -120,8 +121,9 @@ void CAN_setup(uint16_t speed){ /* Enable the peripheral clock CAN */ RCC->APB1ENR |= RCC_APB1ENR_CANEN; // Configure CAN - while((CAN->MSR & CAN_MSR_INAK)!=CAN_MSR_INAK) - { + CAN->MCR |= CAN_MCR_INRQ; // Enter CAN init mode to write the configuration + while((CAN->MSR & CAN_MSR_INAK) != CAN_MSR_INAK){ + IWDG->KR = IWDG_REFRESH; if(--tmout == 0) break; } CAN->MCR &=~ CAN_MCR_SLEEP; @@ -129,7 +131,10 @@ void CAN_setup(uint16_t speed){ CAN->BTR = 2 << 20 | 3 << 16 | (6000/speed - 1); // speed CAN->MCR &=~ CAN_MCR_INRQ; tmout = 16000000; - while((CAN->MSR & CAN_MSR_INAK)==CAN_MSR_INAK) if(--tmout == 0) break; + while((CAN->MSR & CAN_MSR_INAK) == CAN_MSR_INAK){ // Wait the init mode leaving + IWDG->KR = IWDG_REFRESH; + if(--tmout == 0) break; + } // accept self ID at filter 0, ALL other at filters 1 and 2 CAN->FMR = CAN_FMR_FINIT; CAN->FA1R = CAN_FA1R_FACT0 | CAN_FA1R_FACT1 | CAN_FA1R_FACT2; @@ -188,6 +193,7 @@ void can_proc(){ if(CAN->ESR & CAN_ESR_EPVF) SEND("Passive error limit"); if(CAN->ESR & CAN_ESR_EWGF) SEND("Error counter limit"); NL(); + IWDG->KR = IWDG_REFRESH; // request abort for all mailboxes CAN->TSR |= CAN_TSR_ABRQ0 | CAN_TSR_ABRQ1 | CAN_TSR_ABRQ2; // reset CAN bus @@ -271,7 +277,6 @@ static void can_process_fifo(uint8_t fifo_num){ // 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 & 0x0f; @@ -307,7 +312,8 @@ static void can_process_fifo(uint8_t fifo_num){ dat[0] = lb & 0xff; } } - if(CAN_messagebuf_push(&msg)) return; // error: buffer is full, try later + if(msg.ID == CANID) parseCANcommand(&msg); + else 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; diff --git a/F0-nolib/usbcan_relay/canproto.c b/F0-nolib/usbcan_relay/canproto.c new file mode 100644 index 0000000..cc0d1c5 --- /dev/null +++ b/F0-nolib/usbcan_relay/canproto.c @@ -0,0 +1,171 @@ +/* + * This file is part of the canrelay project. + * Copyright 2021 Edward V. Emelianov . + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + */ + +#include "adc.h" +#include "buttons.h" +#include "canproto.h" +#include "hardware.h" +#include "proto.h" + +/* + * Protocol (endian format depends on command!): + * answer will be send to `OUTPID` CAN ID, length depends on received command + * IN packet (sent to `CANID`) data bytes: + * 0 - command (any from CAN_commands), 1..7 - data + * To set value command should have CAN_CMD_SETFLAG == 1 + * OUT packet depending on command: + * CAN_CMD_PING (or any incoming packet with zero lenght) - zero length answer + * other commands have data[0] equal to in command (without CAN_CMD_SETFLAG) + * CAN_CMD_ADC: data[1]..data[6] - 12bits*4channels RAW ADC data (ADC channels 0..3) + * CAN_CMD_BTNS: data[1] = button number (0..3), data[2] - state (keyevent), data[4..7] - event time (LITTLE endian!) + * CAN_CMD_LED: data[1] = LEDs state (bits 0..3 for LEDs number 0..3) + * CAN_CMD_MCU: data[2,3] = int16_t MCUT*10, data[4,5] = uint16_t Vdd*100 (LITTLE endian!) + * CAN_CMD_PWM: data[1..3] = pwm value for each channel (0..2) + * CAN_CMD_RELAY: data[0] = (bits 0 & 1) - state of relay N] + * CAN_CMD_TMS: data[4..7] = Tms (LITTLE endian!) + */ + +// return total message length +TRUE_INLINE uint8_t ADCget(uint8_t values[8]){ + uint16_t v[NUMBER_OF_ADC_CHANNELS]; + for(int i = 0; i < NUMBER_OF_ADC_CHANNELS; ++i) v[i] = getADCval(i); + // if NUMBER_OF_ADC_CHANNELS != 4 - need for manual refactoring! + values[1] = v[0] >> 4; + values[2] = (v[0] << 4) | ((v[1] >> 8) & 0x0f); + values[3] = v[1] & 0xff; + values[4] = v[2] >> 4; + values[5] = (v[2] << 4) | ((v[3] >> 8) & 0x0f); + values[6] = v[3] & 0xff; + return 7; +} + +TRUE_INLINE void BTNSget(uint8_t values[8]){ + uint32_t T; + for(uint8_t i = 0; i < BTNSNO; ++i){ + values[1] = i; + values[2] = keystate(i, &T); + values[3] = 0; + *((uint32_t*)&values[4]) = T; + int N = 1000; + while(CAN_BUSY == can_send(values, 8, OUTPID)) if(--N == 0) break; + } +} + +TRUE_INLINE void LEDSset(uint8_t data[8]){ + for(int i = 0; i < LEDSNO; ++i){ + if(data[1] & 1<CCR1; + for(int i = 0; i < 3; ++i) + reg[i] = data[i+1]; +} + +TRUE_INLINE uint8_t PWMget(uint8_t data[8]){ + volatile uint32_t *reg = &TIM1->CCR1; + for(int i = 0; i < 3; ++i) + data[i+1] = reg[i]; + return 4; +} + +TRUE_INLINE void Rset(uint8_t data[8]){ + for(int i = 0; i < RelaysNO; ++i){ + if(data[1] & 1<length; ++i){ + printuhex(msg->data[i]); bufputchar(' '); + } + NL(); +#endif + int N = 1000; + uint8_t cmd = msg->data[0] & CANCMDMASK, setter = msg->data[0] & CAN_CMD_SETFLAG; + if(msg->length == 0 || cmd == CAN_CMD_PING){ // no commands or ping cmd -> return empty message (ping) + goto sendans; + } + outpdata[0] = cmd; + switch(cmd){ + case CAN_CMD_ADC: + len = ADCget(outpdata); + break; + case CAN_CMD_BTNS: + BTNSget(outpdata); + return; + break; + case CAN_CMD_LED: + if(setter) LEDSset(msg->data); + len = LEDSget(outpdata); + break; + case CAN_CMD_MCU: + len = MCUget(outpdata); + break; + case CAN_CMD_PWM: + if(setter) PWMset(msg->data); + len = PWMget(outpdata); + break; + case CAN_CMD_RELAY: + if(setter) Rset(msg->data); + len = Rget(outpdata); + break; + case CAN_CMD_TMS: + len = showTms(outpdata); + break; + default: // wrong command -> + outpdata[0] = CAN_CMD_ERRCMD; + len = 1; + } +sendans: + while(CAN_BUSY == can_send(outpdata, len, OUTPID)) if(--N == 0) break; +} diff --git a/F0-nolib/usbcan_relay/canproto.h b/F0-nolib/usbcan_relay/canproto.h new file mode 100644 index 0000000..2de8898 --- /dev/null +++ b/F0-nolib/usbcan_relay/canproto.h @@ -0,0 +1,47 @@ +/* + * This file is part of the canrelay project. + * Copyright 2021 Edward V. Emelianov . + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + */ + +#pragma once +#ifndef CANPROTO_H__ +#define CANPROTO_H__ + +#include "stm32f0.h" +#include "can.h" + +// command without setter flag +#define CANCMDMASK (0x7f) + +typedef enum{ + CAN_CMD_PING, // ping (without setter) + CAN_CMD_RELAY, // relay get/set + CAN_CMD_PWM, // PWM get/set + CAN_CMD_ADC, // get ADC (without setter) + CAN_CMD_MCU, // MCU T and Vdd + CAN_CMD_LED, // LEDs get/set + CAN_CMD_BTNS, // get Buttons state (without setter) + CAN_CMD_TMS, // get time from start (in ms) + CAN_CMD_ERRCMD, // wrong command + CAN_CMD_SETFLAG = 0x80 // command is setter +} CAN_commands; + +// output messages identifier +#define OUTPID (CANID + 0x100) + +void parseCANcommand(CAN_message *msg); + +#endif // CANPROTO_H__ diff --git a/F0-nolib/usbcan_relay/hardware.c b/F0-nolib/usbcan_relay/hardware.c index 6d48316..fd2c7ae 100644 --- a/F0-nolib/usbcan_relay/hardware.c +++ b/F0-nolib/usbcan_relay/hardware.c @@ -27,6 +27,10 @@ const uint32_t LEDpins[LEDSNO] = {1<<12, 1<<13, 1<<14, 1<<15}; // Buttons: PA2..PA5, pullup GPIO_TypeDef *BTNports[BTNSNO] = {GPIOA, GPIOA, GPIOA, GPIOA}; const uint32_t BTNpins[BTNSNO] = {1<<2, 1<<3, 1<<4, 1<<5}; +// relays: PA0/1 +GPIO_TypeDef *R_ports[RelaysNO] = {GPIOA, GPIOA}; +const uint32_t R_pins[RelaysNO] = {1<<0, 1<<1}; + void gpio_setup(void){ RCC->AHBENR |= RCC_AHBENR_GPIOAEN | RCC_AHBENR_GPIOBEN; @@ -37,8 +41,8 @@ void gpio_setup(void){ GPIOB->PUPDR = GPIO_PUPDR0_PU | GPIO_PUPDR1_PU | GPIO_PUPDR2_PU | GPIO_PUPDR3_PU | GPIO_PUPDR4_PU | GPIO_PUPDR5_PU | GPIO_PUPDR6_PU | GPIO_PUPDR7_PU; // relays (PA0..1) as outputs, buttons (PA2..5) as pullup inputs - // PA8..10 - PWM @ TIM1 - GPIOA->MODER = GPIO_MODER_MODER0_O | GPIO_MODER_MODER1_O | + // PA6,7 - ADC IN, PA8..10 - PWM @ TIM1 + GPIOA->MODER = GPIO_MODER_MODER0_O | GPIO_MODER_MODER1_O | GPIO_MODER_MODER6_AI | GPIO_MODER_MODER7_AI | GPIO_MODER_MODER8_AF | GPIO_MODER_MODER9_AF | GPIO_MODER_MODER10_AF; GPIOA->PUPDR = GPIO_PUPDR2_PU | GPIO_PUPDR3_PU | GPIO_PUPDR4_PU | GPIO_PUPDR5_PU; CANID = (~READ_INV_CAN_ADDR()) & CAN_INV_ID_MASK; @@ -90,6 +94,8 @@ void pause_ms(uint32_t pause){ while(Tms < Tnxt) nop(); } + +#ifdef EBUG void Jump2Boot(){ __disable_irq(); IWDG->KR = IWDG_REFRESH; @@ -123,6 +129,20 @@ void Jump2Boot(){ // set main stack pointer __set_MSP(*((uint32_t *)addr)); IWDG->KR = IWDG_REFRESH; - // jump to bootloader + // due to "empty check" mechanism, STM32F042 can jump to bootloader only with empty first 4 bytes of user code + while ((FLASH->SR & FLASH_SR_BSY) != 0){} + FLASH->SR = FLASH_SR_EOP | FLASH_SR_PGERR | FLASH_SR_WRPRTERR; + if ((FLASH->CR & FLASH_CR_LOCK) != 0){ + FLASH->KEYR = FLASH_KEY1; + FLASH->KEYR = FLASH_KEY2; + } + FLASH->CR |= FLASH_CR_PER; + FLASH->AR = 0x08000000; // erase zero's page + FLASH->CR |= FLASH_CR_STRT; + while(!(FLASH->SR & FLASH_SR_EOP)); + FLASH->SR |= FLASH_SR_EOP; + FLASH->CR &= ~FLASH_CR_PER; + // jump to bootloader (don't work :( ) SysMemBootJump(); } +#endif diff --git a/F0-nolib/usbcan_relay/hardware.h b/F0-nolib/usbcan_relay/hardware.h index 700bde2..00f5dd3 100644 --- a/F0-nolib/usbcan_relay/hardware.h +++ b/F0-nolib/usbcan_relay/hardware.h @@ -48,6 +48,14 @@ extern const uint32_t LEDpins[LEDSNO]; #define LED_toggle(x) do{pin_toggle(LEDports[x], LEDpins[x]);}while(0) #define LED_on(x) do{pin_clear(LEDports[x], LEDpins[x]);}while(0) #define LED_off(x) do{pin_set(LEDports[x], LEDpins[x]);}while(0) +#define LED_chk(x) ((LEDports[x]->IDR & LEDpins[x]) ? 0 : 1) + +#define RelaysNO (2) +extern GPIO_TypeDef *R_ports[RelaysNO]; +extern const uint32_t R_pins[RelaysNO]; +#define Relay_ON(x) do{pin_set(R_ports[x], R_pins[x]);}while(0) +#define Relay_OFF(x) do{pin_clear(R_ports[x], R_pins[x]);}while(0) +#define Relay_chk(x) (pin_read(R_ports[x], R_pins[x])) // Buttons amount #define BTNSNO (4) @@ -66,10 +74,12 @@ extern uint16_t CANID; // self CAN ID (read @ init) extern volatile uint32_t Tms; -void gpio_setup(void); +void gpio_setup(); void iwdg_setup(); void tim1_setup(); void pause_ms(uint32_t pause); +#ifdef EBUG void Jump2Boot(); +#endif #endif // __HARDWARE_H__ diff --git a/F0-nolib/usbcan_relay/main.c b/F0-nolib/usbcan_relay/main.c index 361debd..4d6343e 100644 --- a/F0-nolib/usbcan_relay/main.c +++ b/F0-nolib/usbcan_relay/main.c @@ -16,6 +16,7 @@ * along with this program. If not, see . */ +#include "adc.h" #include "buttons.h" #include "can.h" #include "hardware.h" @@ -70,6 +71,7 @@ int main(void){ sysreset(); SysTick_Config(6000, 1); gpio_setup(); + adc_setup(); tim1_setup(); USB_setup(); CAN_setup(100); diff --git a/F0-nolib/usbcan_relay/proto.c b/F0-nolib/usbcan_relay/proto.c index fcd0fee..9e5ee19 100644 --- a/F0-nolib/usbcan_relay/proto.c +++ b/F0-nolib/usbcan_relay/proto.c @@ -16,6 +16,7 @@ * along with this program. If not, see . */ +#include "adc.h" #include "buttons.h" #include "can.h" #include "hardware.h" @@ -179,7 +180,7 @@ static CAN_message *parseCANmsg(char *txt){ TRUE_INLINE void sendCANcommand(char *txt){ CAN_message *msg = parseCANmsg(txt); if(!msg) return; - uint32_t N = 1000000; + uint32_t N = 1000; while(CAN_BUSY == can_send(msg->data, msg->length, msg->ID)){ if(--N == 0) break; } @@ -428,7 +429,7 @@ TRUE_INLINE void getPWM(){ volatile uint32_t *reg = &TIM1->CCR1; for(int n = 0; n < 3; ++n){ SEND("PWM"); - bufputchar(n); + bufputchar('0' + n); bufputchar('='); printu(*reg++); bufputchar('\n'); @@ -455,6 +456,35 @@ TRUE_INLINE void changePWM(char *str){ SEND("OK, changed"); } +TRUE_INLINE void printADC(){ // show all 4 channels ADC + for(int i = 0; i < NUMBER_OF_ADC_CHANNELS; ++i){ + SEND("ADC"); bufputchar('0' + i); bufputchar('='); + printu(getADCval(i)); bufputchar('\n'); + } + sendbuf(); +} + +TRUE_INLINE void printVT(){ // show T and Vdd + int32_t t = getMCUtemp(); + SEND("T="); + if(t < 0){ bufputchar('-'); t = -t; } + printu(t); SEND("/10degC\nVDD="); + printu(getVdd()); SEND("/100V"); +} + +// set or check relay(N) state +TRUE_INLINE void relayX(uint8_t N, const char *txt){ + if(N >= RelaysNO) return; + txt = omit_spaces(txt); + uint32_t sr; + char *b = getnum(txt, &sr); + if(b && b != txt && sr < 2){ + if(sr) Relay_ON(N); else Relay_OFF(N); + } + SEND("Relay"); bufputchar('0'+N); bufputchar('='); + bufputchar('0' + Relay_chk(N)); +} + /** * @brief cmd_parser - command parsing * @param txt - buffer with commands & data @@ -466,6 +496,14 @@ void cmd_parser(char *txt){ * parse long commands here */ switch(_1st){ + case '0': + relayX(0, txt + 1); + goto eof; + break; + case '1': + relayX(1, txt + 1); + goto eof; + break; case 'a': addIGN(txt + 1); goto eof; @@ -502,23 +540,32 @@ void cmd_parser(char *txt){ } if(txt[1] != '\n') *txt = '?'; // help for wrong message length switch(_1st){ + case 'A': + printADC(); + return; + break; case 'b': getBtnState(); break; case 'd': IgnSz = 0; break; +#ifdef EBUG case 'D': SEND("Go into DFU mode\n"); sendbuf(); Jump2Boot(); break; +#endif case 'I': SEND("CAN ID: "); printuhex(CANID); break; case 'l': list_filters(); break; + case 'm': + printVT(); + break; case 'p': print_ign_buf(); break; @@ -543,15 +590,21 @@ void cmd_parser(char *txt){ break; default: // help SEND( + "'0' - turn relay0 on(1) or off(0)\n" + "'1' - turn relay1 on(1) or off(0)\n" "'a' - add ID to ignore list (max 10 IDs)\n" + "'A' - get ADC values @ all 4 channels\n" "'b' - get buttons' state\n" "'C' - reinit CAN with given baudrate\n" "'d' - delete ignore list\n" + #ifdef EBUG "'D' - activate DFU mode\n" + #endif "'f' - add/delete filter, format: bank# FIFO# mode(M/I) num0 [num1 [num2 [num3]]]\n" "'F' - send/clear flood message: F ID byte0 ... byteN\n" "'I' - read CAN ID\n" "'l' - list all active filters\n" + "'m' - get MCU temp & Vdd\n" "'o' - turn nth LED OFF\n" "'O' - turn nth LED ON\n" "'p' - print ignore buffer\n" diff --git a/F0-nolib/usbcan_relay/usbcan.bin b/F0-nolib/usbcan_relay/usbcan.bin index 00e5a24b2ef0e657f76af94374dbb1b386399769..84068e39d435722b489293619d33235ab7c5d449 100755 GIT binary patch delta 8179 zcmcIpdstIfw%IY~z`ki|4n!Mh@{iW>O%o3(;r}0w z8wWAOBYB$+CZSnWmDIP}>SlLaN~#i|Ot3h$#Z?~UYLl|NoB4YrOft)_G4N79F7@;x zoy5!ClVlq9Voe_3ZB>{g-frtYwi~3ftI}dStjVBhP87StislYqR6F>LD$HC{665W# zO4tsI!kT3I-s{xN<~#9uE6!4|aq0_}*<4RcW1E6)Z0^_0teP&916N^5syfMVZT(2Y za?Mip1*?L+V3}GK&+W5Jsq$H})U}prRymslziM`xMW*fnMvo=wbU#5^*yxZWi4i49 zj6ngRek4Wm9BeeggGz*$VBb3g^|5H@u_cxGg;`nsDG6wOg~TP-E1i;}{iYG0+2wLQ zVv-C<5rb5SYfor@g1Ak1U_VJl@3&9s=!Iv+Xcn4_ZgM>e_4z0UEkd8T)-96^oFePU z+YZv+ejFaShyfAul1cLE0g{iFk*A^W6v;#^*(W}ohD^jsEX&YYKQR(#uan4CubI&K zMJi`+4@gZzN|b=g$uVFURFCyy)nRy=r)uwIR8N@D*(B9Nz(eO#fWO0}IC~uW3`nYS zxJ>Z_UA?i#WWU=>f~R+yM$XHT0eu@tP+bl56KaK|J_#d)whM85sw+X+h5Az-2E_12 zoaTB@DG6qd&(jO~q|>KDLgt%*I6kRQ>5?*T|4w)Bh}*K_7i{KLOvER%Q##v z%f72(KQWqOjB6`&)<=(d;#PVMJbtN*82BE52hdHXYPVREjfGb2mX$ZP>_EDi-jMaU zRj!*hP(wWEt@@`)>6A;GOA`-nE>*1AoU=J$$|YMu;z3)2VvSAhu(2e~w`X>CFWSPK^cUCb)#U1waA#*ii|U0;mDAH z#V*UmKCDsNY`6B4lkVrFw>Ulo4&~bVP%iS?{pH|VyfPW0J;iuHnW(%cbn6%~-RzQVP?QT5cB8O0k6|A(M3mBq52W$h@FZ zYb{vrX0;Zrb!lNTl#*aWgw5E)V28#jO=11bTB{mS0%mggIcA!K@b>1HQV)yVZsnW{#TRklb~Q(vEI-pkh4 z)VHNnVfGJ9L-TCjiBjv;#?%_8`n{M`%M894Y;k%G-5OH73tN1TlYs>77m|qUlQzgs}?V)^`!M40$($ zMbp|mac#c1EF*8^mM&LXj0%W<3KW$&xPL!faQ$TlGKW)z`8VWe+Q)%ymJrW5TGAW2{;FcwrDG~ zhXI!Xp95kbwe7e17lWBpaKZ_p~vB_GgZhPz&}E@)=n{`uk$G?>r`X8OIdHIW_ZBIyWaF-Qn~9mWfCoswc%e#pm?R99SfLi|>U{d(6_twfTR$^02SO@~HWl-*5kUr|nS(Kee9Iuqf^Xx3Gm%yY~pbw}%xtAEf{AnL-!f9;jc z8}ywEG{H5Y<|5%8w{ktCj)0@9akk1j+nUvuW0Lyv(HWaA9EfM)zn^G$jh?RtXpj*e46!ytr&i<+ByRZxZU zvdW4(k>}HyKn9-y zQ_MtII};&wHz~97|X>OxtuEbnXIuLG?8V%+R=&$Y02 zPh8SD?AhJ&R={MxiC0=45`W*cCqn&TU=3LeqRoQ=pfvXekmq3Y74VMwLL{eoGzH*- z`ht9HTm&csbU`~8`tz}SOB|1b?$_haI;bB@ILMbp$rhSfX&bAD`^00FEF;@_f1lF2 zy%NI5(rA?!8!bxf{go1<63Y9;veCK?%Bf7F<-*+$u@_pD_iUm4YmlbL(s)k?+qh;E zmt>d*(i^K9;g>=IdJbqBtex&%@#&5xGq9i+-wd}hOQL2CoL+KW*w?SVgS&&jv$D=2 zy*oZOO_HWaV5Kcc>$XT?wn8XQ5JKBVgwRg~9Lx!~GD0XR;?%a>-6Tt9*R%*BwNS&? zn7c_0U%R4*)K=G#B9Q7B6+-K_=ohDrQNJh28avyCfv+?pHims|P#j!I(53EP#^c1{d@l03*K*pmyws@^=vL za6VKQ`?!#+I> z{p8pZ`0X4kwc?(%Hl=Bi*N|1>|M3A|8GDj%njG+Dalj)m;J(QL<&oX|p2_ik3FA4g z4cH*a5C?1=``P4x$fp;xXYJU7<_7{;Ppu)#Nc4_oAEl{q37Qw{ZE06;ry2H- zBa+9N21$uK9RqPTLU81Olp)!>x5Es#}L+IaO4-qu=$apcOfij2we+}Yw7Xr1rV{& zPtzz3y?ddaRE*>*z+u3t1n7fuFW@Cd36it0o7j7cR%$CRyWCrnkIp~x)hBRsNo#nT zFc3$NeTDT>h?QaA2mA-3yHzmnN4fXR2zBpzB7_RYFmor7A*W_n_DSQLaIfyFIf@z@ zo?#nmyX)UD?_j%Ya)+X$%0a^_CqhGM%U7}q@F!+(_d4ew7kr}!tr2{ z6-;lGMLrKx7dT>;4E=_Go@;~WmCTW-=O2pC51PNd@|zX64?VXcedrlpKc|Nr;yo+6 zNjKj`SaN%IrlrQgn8^>mcU%-(Md%gaNSKD|;V}MC2)z}ddE?pelRPf@d+&Zzj`vye zWx&m&Io)I@ziS0mR{`qEZ_w5uYSSaVz8^g1VNstmtViRa_J|Pbj^Gjn;}Amkhh+tS z^ljs}K}xz`Oxwu!?3JglJP2V12?|1KcVq*QNR}_|L_md(!Ug)oQ+T_2u z%Dn2zc<9wgHNS$3MM}$(>{U!t)bMGd3RHkEpdcTiHq%E~zJfErVDp)kQOsD8IUYI; z>&}QQ=1V6zoZ0b%@xL3Td%Do9ys}GM42k<(J%W1(B-?!CYrKSudPqL(Tbv(zTIIM1 zyEniof_%#_)e)`fJ1vCv40V|-;PU!(EFok{;&^2I9>{~B%Nb`ku38x`TZ#Cy2^6HD>!&5HA>B)siZiG%hbkf*; z5ZW|uy>R+gLfs5l4Uhp60W$z908g6i^#n2-Y}{al5ULw(B1m`D_b!J$`^ZJqU9nf| zK_0@BM$%RPb~R01%Ofmdm<(84*=VB!9(C2DL?L9l-fbA&7bQeR7F>U(9i31`CGteC zQI0MQAPt16S!r8(nO>7k}f4Nt*)8r+k@U1lLPE#l#l?G2`e@@Y2kc<)nRJ;Cpt zOu@g3k~}L)?gokB@E(2_R}SvTGLJ4A~M{343s5g9gMoCzBs5I^$k;rCC28~8Ty>>|v)QS3)Vb}O)746o%a zoa1&-Si`K3qHGl@tAWxTUTmeY{rf@eal=bre|WptJ~P=4hF9@5;-t;Y9Z?!qiW+#( zU=N%5TSZ1S^OGn>xyWG6LSblKnB{NbDqtE_Om!4RFH#nRlG`A3O1S0V+2!Eb#Qn8h`+J!;tF<0v^#v<>PA(m*kDqvRtyNI&Ye;b})Q&zB^denCiS2MYM zU@^d&Ls^c`ZeURlJ3sm|Xp7_Yz!O663@eAQwwthalM3Eve7->%PxJyyLx#rHNjUoG zad;R)gI-|ig?10rhas%!aX0|aPeD6Ek3r}&LfHlQ4*K;q@SqG}1mMDCF{>UJWOT#l z8TD>9^X3k+9K5b`u+F~f#%m9~9)jCvA~a{>&T(j%-Z_Hq4XG)P5*dP*qk=#AoEohC zva%CBT+>K)solnQWU5!PrW%gGXHlPIP=517d!^V$gFDn`D=DW3I8Eep^a;OLv!8s- zw^nqbgEg|kgEi6u!WeSpa{>Ul*HO>Z(z%Z{xF(e|R4;&$Pw2mC(R>5XiwY}9I zBJpn(v(I=aC^QjVf^>iP(K9D*q>lWCV}RG@(7td3@$>6M9`b|-eO6yb_QS!ax1-z` zFD@AmeIU^Kh_8tIT?Wyh-hpL26nd70~3jE|yQb_A(hZW3t=(tcvIwo)Q$oC?g zS`P`&UqRq24*w9u4!lc^j!cvVqYmCV84-_OU*&jcuR!haAguD$k^A}kx$Wl37X+UW zIyy2QYJ_*S7e-J4^2!D`@tY=7#kMF7n?w!kLBo?HbR$^eu{JqiC-!ORjr z{loZuCL#0+V&=Hp`GI~AiHer zjjJmjcg*5vaThGKIu4%~Xu^0LJ%0UlbPptf0|1&lE<;IQErU?%At@|^@^vl=5?J&uK=BZ#{eAw z7vK?q6YwCQD`o=Qp>zUv0y+SX0Zf2SKq9bwX3_uSs0xAmK+jW0umcsXb_?MIX zvI5C3z`qU8LHQJ56<`7MyKVVQEQSe6ko&RxxsEwAU|Imup@2+cR>Ti32*6}MGXKuc`vZ$ro((BH=DbC`L|z1y~I zWVTQpdS=tcTtgnSX$!OIuDf#ed5RpvjSRy-G2CT_xmo3uwQlXb3=GcP*Svn)+O3R{ zX`MA%jo6RCE|K bFiQwKRH=t_bPH7I$3TpX2)#+YUXK17`A+4E delta 6481 zcmcIoeNn$ zP+NujUKbEYZR=`lZ95ia>RO{umecRrHnDade$)wmfb-hd$t*j)5I*kP=L$ADzV-fk zto37`kG;>?XP^B$=iGETeq0-cVi27-1F5qC8GxnyHoit*A4ibt6`$)n0q&x%U>n^$?F zzlLe zCn{{$dMg^Li^AJ0T%V@?`TIf~YrorDA=gpr*H@_4So;sXo!EvDeGOm)r~vkKq>k!P zri||jXa9seRYISVc9Kqi$8}ikW3XnV_jSB{!VPX6#7aRWgb1NRm{7>6s20p5v=plJ zMpKM&Ay-t?f{jH=-W|5qQ;Fwuislv^etf*HhL14n_>!?y6G}_;^zd)-?O2^Qwd+-M z5?A1y(v8;rxD1Dn3u`LFxWz$0F*oPNFtD>pDy%A%a zTr%4+-m$g)LsOmyWh$-|Vw61A{zCk;l3&`#+1tVS1p6AS-9)t=vRCfhhW;~F%PJ2E zSc|UPRfiO<2^&KWokLG;3_Vm~KeRFI(9=cNH`aVn^XW3osM8c)lsL8|!cOZHd<3Jg zDfp>#Czx8jNUyYwJy8&}NuBt_YGfQ!iy&x-jxiwhYLMFnUC8c91yECRF%DG<<)sp} zcKhN^Tq~RnS>)UfIz%t31EnC(dS3w-+fcy9x(bRle1SQ}ctjtkR5B8+v6Zjg#r!c} z$&}Z)^mACZ%2TIgzOAO{JWk=G<|Bi`Q^QA@`aO!oOmlXzo);LsP0ugP(STI=p9?Sv z`)DfBrHo;G)q0+yN&j@`gT`K$ZZ{}}B_(i;$b~8`@s@Ch2G9kt0e%DoM{_&Wqu>Y_1o<-{gp2ApC`Twh)THo8qFxwM$4x5lQ*rUO zsIv+##x?*`+F^KJ$OwO4QHzA@ksO7Dv@sW*Waa}MyH23rZ~6mD)Rbt7qdB$hc}Rn3 zv(^^P#aBn0ui2=iwi<2q6hNos}Y=mUQ5lYtwM;JM>AH&aa zz78$_TrtGjR>>=jl{PKEwOC=)g4`m@N`5oQ@pPr_%Gwv1D>d468%g^rl-OpgT(^g* zT(yCX%ANq$>xH_pGo6)YXoDIxHv;6C#8te;s5T6EJ9SlT758LuxlOq?JTy)b7ZJ%Q zYmi>BDZw{M{Bl?llO@VOGf)egi-uhKnzbuc8fI0EB=!zlIE%RzTez~NZMdwo9M1v^ z>wqM_K1BI{3`pXcK~+j2?8^DP!H@*C$Jj{uxAdbFrDri0=RgL=OY@XJWgsM>+k^Bp z&pb|LD7;FC(~#kz{HFtgW!xG?X+StVZhM&zLX-j^S(6Tu#5bRU{ex^c1t1|j0rC=L zg}nnMg)9jzHSk#|-cI>v1XNt6E#7X2eaQm70RBhhAO9CB z%>_j%40dQ_`#iIdT9Obd&P8gX=7;(iD5vKNJrhh(yN0NOtZbb<1x4s6|1X0={={nu zE^uSiz7zC60$c#R3+OWlIht3vDi|WF<4>UquQ6N_+vSsk++g>%-`AmVG@j5PX8zUo zECafn*4jBr!=kYmR{JxHxo%J1ay+PZdfh#W;J1j+iJfP=83(lAVIO zcHMlJYcZkA^*3GZl2{dZlY5I@ovgJjqu(-9z7(|DLFGzf+Yrj=^Qu}T@#OF!?hso8 z8tdr8K^l#+#;fMv_flDssD^|XH_&W;8)_8z^4aiy^XsI?DGm&&5`OSBFM)%80m|s{ z)HLe0(MS^i8c?MC!}G7^{k@E%D4v=>&7kU{a`g^U3S3qmBRY*kA?OGka!R+tfVz(R zp69l+tH6~~+8N|Zk?hK|=C!@sN@qDD45vK5jwn1aDavUZiNQ~Uc2?z{*w7|Nh!=4@;st+nw%Q;fYIkLklJI4fHMPDIevK^lXDBw|?( zNt`rXYMvInDCe)MdOsU-R1#yrA>{r1hSKfE)O@W$b$Qth8n$%q4Ju0s6zKCVgsWin zbgiw3E?GkPvd{(xl_!Z`45G|FuN6z;%^`|@3agMSad+}5VZr{xvzT;D7#74wv!QaUwg&Aa3^Ys|-bG@OPlg8mXZF{uApxj)irZtY3n z(DXJO&b0zs@D$Dj&oB;uh@OGLS0r2Lta*1ruKsM&-$@q^0D54_)UmsqXsl6)2+@8X`Ko{NxH$UspCGg|PcoEvv?ZMf43tImf2M-G)^7SmunkFLVMlC4`dW^hb{Bpx0jj&uzu z^at@Q2Q|l6blBv(`hmIs_HO+t){QP%k)BGX1UT)ylW$V9+VI;D&oCe5u2oaBC}BN0 z2fg7p%dy_{vxmX2v2`@KKr{Qi6tMgJAcI?3dWP1PP9F}^ zXpuEu(zn2r-&&_aUfk+t@GERK@B(N#z~H@X9i%5sH!mgW`2x5qi8}^JdhXQkxo@== ztadtCGnkd=-M9fFq4aThrNfFL^I?tMMUq%Euo5G~UGEN-ayQ|tsI};T-i_RlACC!(+My+H&6*ZEmkx}63gzl8V8z!Y={MOzt5R7aBnDLk}n51b>Nv^l=vjK z(yX;Fxve_h3L8@cyQcY4b3TrL!VE7~PWgTt?rYCR!(!;L3zHY_+HPu&YUa=0+}j*y zX6s-hm(x!KWx;TOWWh3cw@KpU!6Gw#+rnxb6;4w{;RHLRhUc3b3%G?N$1N9RctbYK zH>+>wakJTa7|$PD$K4s54)=mB3A7t3h!FofV{bR91{Ne{m}tvUh1W+%4Wa-SFCxPdQ9a57K=_ z)*WX)bt{q^!;)0aqNfG*zaaOAnvdR6aw>KO^jqi{r#T0>J<4gqZ^B`ejnss{ci?I! zygdqheHU;Fa0Xxo?xuqdxx&en9tGv!LVF8<@V@}+`+)QLfMRGHrT7Bbh40L(Zhgmn zCvTFon7$O`V}`8omAU-ZSKL=}u+4NZm#518ADfw5A9Eke{iXCLLH1+i{`0H2&sMUk*O{ALu#uaw@(W@r%rKR?j~7!*LpP+c~12(_!wIP=0#xs-XqPwA?9FB zto&Az)fa(!2ibJ6qQUCOBdtz7U`3Mt!+{+z+bd2s3k)UkXn$-^Io`uAhZ?Uxu*8iO zzI8GsCGk}-rt*;C7cV)o-V2mt7fXX)oqqQNdN1DBV}Ltu^qsXFZ-sL+#eq^nJmj+4 z*iXv+-g0c0N2u029ZOo|sf@S$h zN)I3D4pTfbgm|}gQ#l&BcS|>I=(|ko_A=Av?!ildU(a-xJC^^`TY}Jg8bZn0W8}-% z+D|UuQ^HpXG0r>{Qq56i-0`{+DgEN&X0*#viFfM+V2JTb@PjfP8;Z~gqM0gcOdZ~F5qg5n$a5;Rn8k0Wd`#8&ZmO^^STxA|A=pY;zX6o zP0=eU4RavTP|}Q?Z&-};_F8MF?_%~^bX+29%z~2`axDw3k>6pT_K_2n+|IuKSWe5@ zfl)M_9F&cJ=p#qN1hXVw3m^znP49RviXA(8On4>H1INUUK1sX~2iF7c#v6uPS8gg$aBm0 z0`~%2pQp7|&^vEmD*IDG|0YPKR94vtDw_i&WE^($BxFsAB(!jn z^UFf2de?BzjI5 zxEzf00}NhzpPS1c!Lng-K)T0Ga#!8s<}l>5={`3XKhnzgfR&Sw^Cp<($_yD6z0#fA zNVf-DWOAAE8rRc#_uU*8&q-v*)4g?tUm5ab zZ#k`nH(WC01(iE2{!XF^H=W)|++<+e6#213d4|PxQV2aP`iIDeY#bNQUXed(hkMK6 z975g=JwJq@OY3^noSNML0W6`TgQk5}o>m3Zw)T(a&}Wc4B&T@Diz<>EkV7%#REJ#g zWoeQ6ASm2{3Js0uzmZRc0wF&_TeChZgj^FzLY}^y$`u;*)2Nq)WBU4uxp4T84!;l{ zg`J9%X-VU#@JQ0=|s<5NA*UN#k}-vhi17}X_X9T2umpC3Y6UOw3| zJ&X!H4aF`>I6vcSYPQgnqESHQ&6I5*P9~;)O_h?t_Mbz@>69d*dk)H%pbgoOu?wUF z+VWvwG9;x$=qP;FDM6kF`59mkkdg=d0l7W*=knEZ4CVKb7T0McPxQvOJBazjS5(z#ZF)N24XKqcS_ zfCW$tFaqWQT*`Z>0m%b405$=(0@48607>vNPY2`z@&UyFE1(KcT8~h~^7?vu{gzcc zy?WE8`c2QK)0b)XOJ7i1df*!Tq0&=&y~3&k)ja2<50qe(Aa zy;+uv>*=};o9pQ!{5ZY7zIJtl@Q>N$LhYQ#g`qjAf;oT1n07!~7#K^MWu