Added string protocol + some modifications of code

This commit is contained in:
eddyem 2015-03-24 11:14:16 +03:00
parent 3c6450b9d4
commit 6bd9724193
18 changed files with 787 additions and 308 deletions

2
.gitignore vendored
View File

@ -7,4 +7,6 @@
*.pho
*.drl
*.pdf
*.svg
.hg*
.dropbox.attr

View File

@ -52,9 +52,9 @@ Functional map of MCU pins
049 VSS GND
050 VDD +3.3V
051 PB12 -
052 SPI2_SCK \
053 SPI2_MISO | External SPI connection (at edge of the board)
054 SPI2_MOSI /
052 PB13 Shtr_cam (signal from camera electronics, 0 to open, high prio) \
053 PB14 Shtr_man (signal from manual switch, 0 to open, low priority) | External signals connector (at edge of the board)
054 PB15 /
055 PD8 -
056 PD9 -
057 PD10 EXT0\
@ -95,8 +95,8 @@ Functional map of MCU pins
092 PB6 Tur3_1 \ Upper filters turret Hall 1,2
093 PB7 Tur3_2 /
094 BOOT BOOT Button to boot from bootloader
095 I2C_SCL/CANRX \ External CAN connection (or I2S, etc)
096 I2C_SDA/CANTX /
095 PB8 LED_status \ LED indicators: status lights when all OK
096 PB9 LED_shutter / shutter LED lights when shutter opened
097 PE0 DIR_1 direction of SM 1,2
098 PE1 DIR_2
099 VSS GND

View File

@ -52,9 +52,9 @@ Functional map of MCU pins
049 VSS GND
050 VDD +3.3V
051 PB12 -
052 SPI2_SCK \
053 SPI2_MISO | External SPI connection (at edge of the board)
054 SPI2_MOSI /
052 PB13 SPI2_SCK \
053 PB14 SPI2_MISO | SPI connection (near USB connector)
054 PB15 SPI2_MOSI /
055 PD8 -
056 PD9 -
057 PD10 EXT0\
@ -89,14 +89,14 @@ Functional map of MCU pins
086 PD5 | Tur2 Middle filters turret Hall sensors
087 PD6 /
088 PD7 Tur3_0 Upper filters turret Hall 0
089 SPI1_SCK \
090 SPI1_MISO | SPI connection (near USB connector)
091 SPI1_MOSI/I2C_SMBAI/
089 PB3/SPI1_SCK Shtr_cam (signal from camera electronics, 0 to open, high prio) \
090 PB4/SPI1_MISO Shtr_man (signal from manual switch, 0 to open, low priority) | External signals connector (near USB)
091 PB5/SPI1_MOSI Shtf_fb (shutter feedback, ==0 when opened) /
092 PB6 Tur3_1 \ Upper filters turret Hall 1,2
093 PB7 Tur3_2 /
094 BOOT BOOT Button to boot from bootloader
095 I2C_SCL/CANRX \ External CAN connection (or I2S, etc)
096 I2C_SDA/CANTX /
095 PB8/CanRx LED_status \ LED indicators: status lights when all OK
096 PB9/CanTx LED_shutter / shutter LED lights when shutter opened
097 PE0 DIR_1 direction of SM 1,2
098 PE1 DIR_2
099 VSS GND

View File

@ -45,7 +45,7 @@ static const struct usb_device_descriptor dev = {
.bNumConfigurations = 1,
};
char usbdatabuf[64]; // buffer for received data
char usbdatabuf[USB_RX_DATA_SIZE]; // buffer for received data
int usbdatalen = 0; // lenght of received data
/*
@ -199,9 +199,11 @@ static int cdcacm_control_request(usbd_device *usbd_dev, struct usb_setup_data *
switch (req->bRequest) {
case SET_CONTROL_LINE_STATE:{
#ifdef EBUG
P("SET_CONTROL_LINE_STATE\n", uart1_send);
print_int(req->wValue, uart1_send);
newline(uart1_send);
if(mode == BYTE_MODE){
P("SET_CONTROL_LINE_STATE\n", uart1_send);
print_int(req->wValue, uart1_send);
newline(uart1_send);
}
#endif
if(req->wValue){ // terminal is opened
USB_connected = 1;
@ -228,13 +230,15 @@ static int cdcacm_control_request(usbd_device *usbd_dev, struct usb_setup_data *
}break;
case SET_LINE_CODING:
#ifdef EBUG
P("SET_LINE_CODING, len=", uart1_send);
if(mode == BYTE_MODE) P("SET_LINE_CODING, len=", uart1_send);
#endif
if (!len || (*len != sizeof(struct usb_cdc_line_coding)))
return 0;
#ifdef EBUG
print_int(*len, uart1_send);
newline(uart1_send);
if(mode == BYTE_MODE){
print_int(*len, uart1_send);
newline(uart1_send);
}
#endif
memcpy((void *)&lc, (void *)*buf, *len);
// Mark & Space parity don't support by hardware, check it
@ -250,12 +254,12 @@ static int cdcacm_control_request(usbd_device *usbd_dev, struct usb_setup_data *
memcpy((void *)*buf, (void *)&linecoding, sizeof(struct usb_cdc_line_coding));
//usbd_ep_write_packet(usbd_dev, 0x83, (char*)&linecoding, sizeof(linecoding));
#ifdef EBUG
P("GET_LINE_CODING\n", uart1_send);
if(mode == BYTE_MODE) P("GET_LINE_CODING\n", uart1_send);
#endif
break;
default:
#ifdef EBUG
P("UNKNOWN\n", uart1_send);
if(mode == BYTE_MODE) P("UNKNOWN\n", uart1_send);
#endif
return 0;
}
@ -264,8 +268,11 @@ static int cdcacm_control_request(usbd_device *usbd_dev, struct usb_setup_data *
static void cdcacm_data_rx_cb(usbd_device *usbd_dev, uint8_t ep){
(void)ep;
int len = usbd_ep_read_packet(usbd_dev, 0x01, usbdatabuf, USB_RX_DATA_SIZE - usbdatalen);
int len = usbd_ep_read_packet(usbd_dev, 0x01, usbdatabuf + usbdatalen, USB_RX_DATA_SIZE - usbdatalen);
usbdatalen += len;
if(usbdatalen >= USB_RX_DATA_SIZE){ // buffer overflow - drop all its contents
usbdatalen = 0;
}
//if(len > 0) parce_incoming_buf(buf, len, usb_send);
}

View File

@ -23,20 +23,6 @@
#include <libopencm3/stm32/flash.h>
#include <string.h>
/*
* this is a default values of stored data
* they could be changed by appropriate command
* align by 2k & make size 2k for using with high density devices
*/
#define FLASH_BLOCK_SIZE (2048)
#define FLASH_WRONG_DATA_WRITTEN 0x80
/*
.bss._flash_buffer
0x20001000 0x800 mk/flash.o
0x20001000 _flash_buffer
*/
//const uint8_t _flash_buffer[FLASH_BLOCK_SIZE] __attribute__ ((aligned(FLASH_BLOCK_SIZE)));
const flash_data Stored_Data __attribute__ ((aligned(FLASH_BLOCK_SIZE))) = {
//.magick = FLASH_MAGICK,
._ADC_multipliers = {100000,100000,100000,100000,100000,100000,100000,100000, // TRD
@ -49,25 +35,6 @@ const flash_data Stored_Data __attribute__ ((aligned(FLASH_BLOCK_SIZE))) = {
}
};
/**
* these are default values
* they can be changed in runtime to change data stored in flash
*
flash_data Default_stored_data = {
.magick = FLASH_MAGICK,
._ADC_multipliers = {100000,100000,100000,100000,100000,100000,100000,100000, // TRD
26, // shutter
2 // power
},
._ADC_divisors = {1,1,1,1,1,1,1,1, // TRD
25, // shutter
7 // power
}
};
*/
//flash_data *Stored_Data = (flash_data*) _flash_buffer;
uint32_t flash_write_data(uint32_t *dataptr, uint16_t datalen){
uint32_t start_address = (uint32_t)&Stored_Data;
uint16_t i, rem;

View File

@ -26,6 +26,14 @@
#include "main.h"
#include "user_proto.h"
/*
* this is a default values of stored data
* they could be changed by appropriate command
* align by 2k & make size 2k for using with high density devices
*/
#define FLASH_BLOCK_SIZE (2048)
#define FLASH_WRONG_DATA_WRITTEN 0x80
#define FLASH_MAGICK ((uint32_t) 0xAA55A55A)
typedef struct{
@ -33,8 +41,8 @@ typedef struct{
// A-D value[x] = ADU * ADC_multipliers[x] / ADC_divisors[x]
uint32_t _ADC_multipliers[ADC_CHANNELS_NUMBER];
uint32_t _ADC_divisors[ADC_CHANNELS_NUMBER];
char last_addr[0];
char struct_end[0] __attribute__ ((aligned(2048)));
char last_addr[0]; // we need this pointer to calculate real size of structure
char struct_end[0] __attribute__ ((aligned(FLASH_BLOCK_SIZE))); // this pointer provides size of structure multiple of page size
} flash_data;
extern const flash_data Stored_Data;

View File

@ -117,9 +117,6 @@ void SPI2_init(){
* GPIO initialisaion: clocking + pins setup
*/
void GPIO_init(){
/* rcc_periph_clock_enable(RCC_AFIO);
rcc_periph_clock_enable(RCC_SPI1);
rcc_periph_clock_enable(RCC_GPIOC);*/
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPAEN |
RCC_APB2ENR_IOPBEN | RCC_APB2ENR_IOPCEN | RCC_APB2ENR_IOPDEN |
RCC_APB2ENR_IOPEEN);
@ -133,6 +130,18 @@ void GPIO_init(){
gpio_set_mode(ADC_ADDR_PORT, GPIO_MODE_OUTPUT_2_MHZ,
GPIO_CNF_OUTPUT_PUSHPULL, ADC_ADDR_MASK | ADC_EN_PIN); // ADDRESS: PD10..12; EN: PD13
gpio_clear(ADC_ADDR_PORT, ADC_ADDR_MASK | ADC_EN_PIN); // clear address & turn switch off
// LED status: opendrain
gpio_set_mode(LED_STATUS_PORT, GPIO_MODE_OUTPUT_2_MHZ,
GPIO_CNF_OUTPUT_OPENDRAIN, LED_STATUS_PIN);
LED_STATUS_BAD(); // turn LED off
// Shutter control: input pull up
gpio_set_mode(SHUTTER_EXT_PORT, GPIO_MODE_INPUT,
GPIO_CNF_INPUT_PULL_UPDOWN, SHUTTER_CAM_PIN | SHUTTER_MAN_PIN | SHUTTER_FBSW_PIN);
gpio_set(SHUTTER_EXT_PORT, SHUTTER_CAM_PIN | SHUTTER_MAN_PIN | SHUTTER_FBSW_PIN); // turn on pull up
// shutter status LED: opendrain
gpio_set_mode(LED_SHUTTER_PORT, GPIO_MODE_OUTPUT_2_MHZ,
GPIO_CNF_OUTPUT_OPENDRAIN, LED_SHUTTER_PIN);
LED_SHUTTER_CLOSE(); // turn it off
}
/*
@ -299,8 +308,10 @@ uint8_t OW_add_read_seq(uint8_t Nbytes){
if(tum2buff_ctr == TIM2_DMABUFF_SIZE) return 0;
}
#ifdef EBUG
print_int(tum2buff_ctr, lastsendfun);
MSG(" bytes in send buffer\n");
if(mode == BYTE_MODE){
print_int(tum2buff_ctr, lastsendfun);
P(" bytes in send buffer\n", lastsendfun);
}
#endif
return 1;
}
@ -319,16 +330,16 @@ void read_from_OWbuf(_U_ uint8_t start_idx, _U_ uint8_t N, _U_ uint8_t *outbuf){
for(j = 0; j < 8; j++){
byte >>= 1;
#ifdef EBUG
print_int(tim2_inbuff[i], lastsendfun);
MSG(" ");
if(mode == BYTE_MODE){
print_int(tim2_inbuff[i], lastsendfun);
lastsendfun(' ');
}
#endif
if(tim2_inbuff[i++] < OW_READ1)
byte |= 0x80;
}
*outbuf++ = byte;
#ifdef EBUG
MSG("readed \n");
#endif
DBG("readed \n");
}
}
// there's a mistake in opencm3, so redefine this if needed (TIM_CCMR2_CC3S_IN_TI1 -> TIM_CCMR2_CC3S_IN_TI4)
@ -345,6 +356,7 @@ void init_ow_dmatimer(){ // tim2_ch4 - PA3, no remap
// 36MHz of APB1
timer_set_mode(TIM2, TIM_CR1_CKD_CK_INT, TIM_CR1_CMS_EDGE, TIM_CR1_DIR_UP);
// 72MHz div 72 = 1MHz
// TODO: WHY 71 if freq = 36MHz?
TIM2_PSC = 71; // prescaler is (div - 1)
TIM2_CR1 &= ~(TIM_CR1_OPM | TIM_CR1_UDIS); // continuous mode & enable update events
TIM2_CR1 |= TIM_CR1_ARPE; // changing period immediately
@ -474,7 +486,7 @@ void dma1_channel7_isr(){
//TIM2_DIER &= ~TIM_DIER_CC4DE;
}else if(DMA1_ISR & DMA_ISR_TEIF7){
DMA1_IFCR = DMA_IFCR_CTEIF7;
MSG("DMA out transfer error\n");
DBG("DMA out transfer error\n");
}
}
@ -494,7 +506,7 @@ void dma1_channel1_isr(){
MSG("\n");*/
}else if(DMA1_ISR & DMA_ISR_TEIF1){
DMA1_IFCR = DMA_IFCR_CTEIF1;
MSG("DMA in transfer error\n");
DBG("DMA in transfer error\n");
}
}

View File

@ -23,13 +23,14 @@
#ifndef __HARDWARE_INI_H__
#define __HARDWARE_INI_H__
// to have a compatibility with medium-density devices we can use only timers 1..4!!!
/*
* Timers:
* SysTick - system time
* TIM1 - not used
* TIM2 - 1-wire
* TIM3, TIM4 - stepper motors
* TIM5 - pause for shutter
*/
@ -109,10 +110,32 @@ void ADC_calibrate_and_start();
/*
* Shutter defines
*/
// We use timer 5 to process pauses with shutter
#define Shutter_tim_isr tim5_isr
#define SHUTTER_TIM TIM5
#define NVIC_SHUTTER_IRQ NVIC_TIM5_IRQ
// external signals for shutter opening: PB3 (SPI1_SCK) - from camera electronics, PB4 (SPI1_MISO) - from manual switch
// both are pull-up inputs
#define SHUTTER_EXT_PORT (GPIOB)
#define SHUTTER_CAM_PIN (GPIO3)
#define SHUTTER_MAN_PIN (GPIO4)
// shutter feedback ==0 when opened, PB5 (SPI1_MOSI)
#define SHUTTER_FBSW_PIN (GPIO5)
// LED status open-drain output: PB8 (CAN RX)
#define LED_STATUS_PORT (GPIOB)
#define LED_STATUS_PIN (GPIO8)
#define LED_STATUS_OK() do{gpio_clear(LED_STATUS_PORT, LED_STATUS_PIN);}while(0)
#define LED_STATUS_BAD() do{gpio_set(LED_STATUS_PORT, LED_STATUS_PIN);}while(0)
// Shutter LED (lights when shutter opened) open-drain output, PB9 (CAN TX)
#define LED_SHUTTER_PORT (GPIOB)
#define LED_SHUTTER_PIN (GPIO9)
#define LED_SHUTTER_OPEN() do{gpio_clear(LED_SHUTTER_PORT, LED_SHUTTER_PIN);}while(0)
#define LED_SHUTTER_CLOSE() do{gpio_set(LED_SHUTTER_PORT, LED_SHUTTER_PIN);}while(0)
/*
// We use timer 1 to process pauses with shutter
#define Shutter_tim_isr tim1_isr
#define SHUTTER_TIM TIM1
//#define NVIC_SHUTTER_IRQ NVIC_TIM5_IRQ
#define NVIC_SHUTTER_IRQ NVIC_TIM1_UP_IRQ
#define RCC_SHUTTER_TIM RCC_TIM1
*/
// Shutter pins: PC0 & PC2 are polarity & on/off pins; PC1 is feedback pin
#define SHUTTER_PORT (GPIOC)
#define SHUTTER_ON_PIN (GPIO2)

Binary file not shown.

View File

@ -115,7 +115,7 @@ void AD7794_init(){
if(i != ADC_NO_ERROR){
if(i == ADC_ERR_NO_DEVICE){
// print_int(curSPI, lastsendfun);
MSG("ADC signal is absent! Check connection.\n");
MSG("ADC signal is absent! Check connection.\n", "[ " STR_EXTADC_INIT " ERR ]\n");
/* if(curSPI == 1){
curSPI = 2;
switch_SPI(SPI2);
@ -127,7 +127,7 @@ void AD7794_init(){
}else{
if(!setup_AD7794(INTREFIN | REF_DETECTION | UNIPOLAR_CODING, IEXC_DIRECT | IEXC_1MA)
|| !AD7794_calibration(0)){
MSG("Error: can't initialize AD7794!\n");
MSG("Error: can't initialize AD7794!\n", "[ " STR_EXTADC_INIT " ERR ]\n");
}else{
ad7794_on = 1;
DBG("ADC ready\n");
@ -136,8 +136,9 @@ void AD7794_init(){
}
int main(){
int i;
//int i;
uint32_t Old_timer = 0, lastTRDread = 0, lastTmon = 0;
int oldusbdatalen = 0;
//SPI_read_status SPI_stat;
// RCC clocking: 8MHz oscillator -> 72MHz system
@ -158,10 +159,9 @@ int main(){
// SysTick is a system timer with 1mc period
SysTick_init();
// switch_SPI(SPI2); // init SPI2
// SPI_init();
switch_SPI(SPI1); // init SPI1
// instead of SPI1 we use those pins to control shutter and system state
// SPI2 used for working with external ADC
switch_SPI(SPI2); // init SPI2
SPI_init();
init_ow_dmatimer();
@ -175,11 +175,13 @@ int main(){
usb_connect(); // turn on USB
shutter_init();
LED_STATUS_OK(); // All initialized - light up LED
while(1){
usbd_poll(usbd_dev);
if(usbdatalen){ // there's something in USB buffer
parce_incoming_buf(usbdatabuf, usbdatalen, usb_send);
usbdatalen = 0; // all data have been processed - prepare to get new portion
if(oldusbdatalen != usbdatalen){ // there's something in USB buffer
usbdatalen = parce_incoming_buf(usbdatabuf, usbdatalen, usb_send);
oldusbdatalen = usbdatalen;
}
check_and_parce_UART(USART1); // also check data in UART buffers
if(ad7794_on){
@ -216,11 +218,7 @@ int main(){
lastTmon += 10000;
if(ADC_monitoring){
print_time(lastsendfun);
lastsendfun(' ');
for(i = 0; i < 8; i++){
print_int(TRD_value(i), lastsendfun);
lastsendfun(' ');
}
print_int_ad_vals(lastsendfun);
print_ad_vals(lastsendfun);
}
}
@ -248,7 +246,10 @@ void Delay(uint16_t _U_ time){
* with ' ' as delimeter
*/
void print_time(sendfun s){
if(mode == LINE_MODE) P("[ " STR_PRINT_TIME " ", s);
print_int(tOVRFL, s);
s(' ');
print_int(Timer, s);
if(mode == LINE_MODE) P(" ]\n", s);
else if(mode == BYTE_MODE) s(' ');
}

View File

@ -17,6 +17,7 @@
* MA 02110-1301, USA.
*/
#include "onewire.h"
#include "user_proto.h"
OW_ID id_array[OW_MAX_NUM]; // 1-wire devices ID buffer (not more than eight)
uint8_t dev_amount = 0; // amount of 1-wire devices
@ -70,7 +71,7 @@ void OW_process(){
if(!OW_READY()) return; // reset in work
if(ow_was_reseting){
if(!OW_get_reset_status()){
MSG("error: no 1-wire devices found\n");
BYTE_MSG("error: no 1-wire devices found\n");
ow_was_reseting = 0;
// OW_State = OW_OFF_STATE;
// return;
@ -100,7 +101,7 @@ void OW_process(){
//uint8_t comtosend = 0;
void OW_fill_ID(uint8_t N){
if(N >= OW_MAX_NUM){
MSG("number too big\n");
BYTE_MSG("number too big\n");
return;
}
//OW_Send(1, (uint8_t*)"\xcc\x33", 2);

View File

@ -23,16 +23,24 @@
// state of shutter - global variable to omit interface functions
shutter_state Shutter_State = SHUTTER_NOTREADY;
uint16_t Shutter_delay = SHUTTER_DELAY;
int8_t manual_pin_old_state = -1;
int8_t camera_pin_old_state = -1;
uint8_t changed_manually = 0; // ==1 if shutter state was changed by manual switch
// function to be runned from timer irq
void (*shutter_timer_fn)() = NULL;
//void (*shutter_timer_fn)() = NULL;
#define DWT_CYCCNT *(volatile uint32_t *)0xE0001004
#define DWT_CONTROL *(volatile uint32_t *)0xE0001000
#define SCB_DEMCR *(volatile uint32_t *)0xE000EDFC
/**
* Make background pause in 'us' microsecond, after which run function fn_ready
* @param us - pause in microseconds
* @param fn_ready - function to run at end of pause
*/
void shutter_wait(int us, void(*fn_ready)()){
void shutter_wait(uint32_t us, void(*fn_ready)()){
/*
if(!fn_ready) return;
//DBG("wait for previous .. ");
while(shutter_timer_fn); // wait for ending of previous operation
@ -40,12 +48,23 @@ void shutter_wait(int us, void(*fn_ready)()){
shutter_timer_fn = fn_ready;
timer_set_period(SHUTTER_TIM, us);
timer_enable_counter(SHUTTER_TIM);
*/
if(!fn_ready) return;
//int i;
us *= 72;
// wait for us*72 cycles
SCB_DEMCR |= 0x01000000;
DWT_CYCCNT = 0;
DWT_CONTROL|= 1; // enable the counter
// for (i = 0; i < us; i++) __asm__("nop");
while(DWT_CYCCNT < us);
fn_ready();
}
// macro to open/close/set default state
// open shutter is 0:0 -> when MCU power is off, shutter "automatically" opens
#define shutter_open() do{gpio_clear(SHUTTER_PORT, SHUTTER_ON_PIN | SHUTTER_POLARITY_PIN);}while(0)
#define shutter_close() do{gpio_clear(SHUTTER_PORT, SHUTTER_ON_PIN); \
#define shutter_close() do{gpio_clear(SHUTTER_PORT, SHUTTER_ON_PIN | SHUTTER_POLARITY_PIN);}while(0)
#define shutter_open() do{gpio_clear(SHUTTER_PORT, SHUTTER_ON_PIN); \
gpio_set(SHUTTER_PORT, SHUTTER_POLARITY_PIN);}while(0)
#define shutter_hiZ() do{gpio_set(SHUTTER_PORT, SHUTTER_ON_PIN | SHUTTER_POLARITY_PIN);}while(0)
#define shutter_off() do{gpio_set(SHUTTER_PORT, SHUTTER_ON_PIN); \
@ -60,6 +79,7 @@ void shutter_wait(int us, void(*fn_ready)()){
* if shutter was uninitialized we open it
*/
void shutter_test(){
//DBG("shutter test\n");
static shutter_state old_State = SHUTTER_NOTREADY;
// test for undervoltage
if(shutter_voltage() < SHUTTER_UNDERVOLTAGE_THRES){
@ -81,7 +101,7 @@ void shutter_test(){
Shutter_State = SHUTTER_NOTREADY;
}else{
if(old_State == SHUTTER_NOTREADY){
Shutter_State = SHUTTER_OPENING;
Shutter_State = SHUTTER_CLOSING; // close shutter on power on
DBG("ready!\n");
}else{
Shutter_State = old_State;
@ -95,6 +115,7 @@ void shutter_test(){
/**
* after open/close pulse we should return bridge to default state
* If shutter opened/closed by manual switch we don't need to check EP (reed)
* 3 stages:
* 1) check for short-circuit & turn off power of the shutter
* 2) check for overtemperature or undervoltage
@ -103,12 +124,26 @@ void shutter_test(){
void shutter_ready(){
uint8_t test_err = 0;
//DBG("shtr ready\n");
uint32_t shtr_status = gpio_get(SHUTTER_EXT_PORT, SHUTTER_FBSW_PIN); // 0 when opened
switch (Shutter_State){
case SHUTTER_CLOSED: // repeated pulse to check errors
if(shtr_status)
LED_SHUTTER_CLOSE(); // turn off shutter status LED
else{
ERR("shutter is still opened\n");
if(!changed_manually) Shutter_State = SHUTTER_NOTREADY;
}
case SHUTTER_OPENED:
if(shutter_error()){
ERR("shutter overtemperature or undervoltage\n");
Shutter_State = SHUTTER_NOTREADY;
}else{
if(shtr_status == 0)
LED_SHUTTER_OPEN(); // turn on LED
else{
ERR("shutter is still closed\n");
if(!changed_manually) Shutter_State = SHUTTER_NOTREADY;
}
}
break;
case SHUTTER_PROC_CLOSING: // closing - set to closed state
@ -128,6 +163,7 @@ void shutter_ready(){
ERR("wrong shutter state\n");
print_shutter_state(lastsendfun);
}
changed_manually = 0;
shutter_off();
if(Shutter_State == SHUTTER_NOTREADY) return;
if(test_err){
@ -145,9 +181,11 @@ void shutter_ready(){
*/
shutter_state shutter_init(){
Shutter_State = SHUTTER_NOTREADY;
/*
// setup timer
rcc_peripheral_enable_clock(&RCC_APB1ENR, RCC_APB1ENR_TIM5EN);// enable timer clocking
nvic_enable_irq(NVIC_SHUTTER_IRQ);
rcc_periph_clock_enable(RCC_SHUTTER_TIM);
//rcc_peripheral_enable_clock(&RCC_APB1ENR, RCC_APB1ENR_TIM5EN);
//rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_TIM1EN);
timer_reset(SHUTTER_TIM);
// timer have frequency of 1MHz, so, to make pause in Xus set period to X
// 36MHz of APB1
@ -158,16 +196,21 @@ shutter_state shutter_init(){
timer_disable_preload(SHUTTER_TIM); // force changing period
timer_update_on_overflow(SHUTTER_TIM); // generate UEV only on overflow
timer_enable_update_event(SHUTTER_TIM);
nvic_enable_irq(NVIC_SHUTTER_IRQ);
timer_enable_irq(SHUTTER_TIM, TIM_DIER_UIE); // update IRQ enable
*/
//DBG("shutter timer ready\n");
// setup pins
// on/off & polarity: open drain
gpio_set_mode(SHUTTER_PORT, GPIO_MODE_OUTPUT_2_MHZ,
GPIO_CNF_OUTPUT_OPENDRAIN, SHUTTER_ON_PIN | SHUTTER_POLARITY_PIN);
//DBG("shutter on&polarity ready\n");
// feedback: floating input
gpio_set_mode(SHUTTER_PORT, GPIO_MODE_INPUT,
GPIO_CNF_INPUT_FLOAT, SHUTTER_FB_PIN);
//DBG("shutter fb ready\n");
shutter_off();
//shutter_timer_fn = NULL;
shutter_wait(SHUTTER_OP_DELAY, shutter_test);
return SHUTTER_INITIALIZED; // we return this state in spite of the shutter isn't really initialized yet
}
@ -177,8 +220,47 @@ shutter_state shutter_init(){
* (wait for capasitor charge and run needed functions
*/
void process_shutter(){
uint8_t man_pin_state, cam_pin_state, ext_open = 0, ext_close = 0;
if(Shutter_State == SHUTTER_NOTREADY) return;
// test state of external control pins
cam_pin_state = (gpio_get(SHUTTER_EXT_PORT, SHUTTER_CAM_PIN)) ? 1 : 0;
if(camera_pin_old_state != cam_pin_state){ // camera signal changed or initialisation
camera_pin_old_state = cam_pin_state;
if(cam_pin_state){ // close
ext_close = 1;
}else{ // open
ext_open = 1;
}
}
man_pin_state = (gpio_get(SHUTTER_EXT_PORT, SHUTTER_MAN_PIN)) ? 1 : 0;
// to avoid opening shutter if user forget to set manual switch to "closed" position
// all operations with manual switch processed only in changing state of the switch
if(manual_pin_old_state == -1){ // refresh manual pin state
manual_pin_old_state = man_pin_state;
}else if(manual_pin_old_state != man_pin_state){ // user changed switch state -> open/close
manual_pin_old_state = man_pin_state;
changed_manually = 1;
if(man_pin_state){ // close
ext_close = 1;
}else{ // open
ext_open = 1;
}
}
// "open" signal have highest priority
if(ext_open){ // external signal for opening shutter
if(Shutter_State != SHUTTER_OPENED && Shutter_State != SHUTTER_PROC_OPENING)
Shutter_State = SHUTTER_OPENING;
else
changed_manually = 0;
}else if(ext_close){ // close shutter
if(Shutter_State != SHUTTER_CLOSED && Shutter_State != SHUTTER_PROC_CLOSING)
Shutter_State = SHUTTER_CLOSING;
else
changed_manually = 0;
}
if(Shutter_State != SHUTTER_OPENING && Shutter_State != SHUTTER_CLOSING)
return;
if(shutter_voltage() < SHUTTER_UNDERVOLTAGE_THRES){
@ -209,8 +291,9 @@ void process_shutter(){
shutter_wait(Shutter_delay, shutter_ready);
}
/*
void Shutter_tim_isr(){
//DBG("shutter timer\n");
DBG("shutter timer\n");
void (*fn)() = shutter_timer_fn;
if(timer_get_flag(SHUTTER_TIM, TIM_SR_UIF)){
// Clear compare interrupt flag
@ -222,12 +305,14 @@ void Shutter_tim_isr(){
}
}
}
*/
/**
* printout shutter state
*/
void print_shutter_state(sendfun s){
P("shutter ", s);
if(mode == BYTE_MODE) P("shutter ", s);
else if(mode == LINE_MODE) P("[ " STR_SHTR_STATE " ", s);
switch (Shutter_State){
case SHUTTER_INITIALIZED:
P("testing", s);
@ -257,35 +342,43 @@ void print_shutter_state(sendfun s){
}else
P("not initialised or broken", s);
}
newline(s);
P(" (reed ", s);
if(gpio_get(SHUTTER_EXT_PORT, SHUTTER_FBSW_PIN)){ // closed
P("closed", s);
}else{//opened
P("opened", s);
}
if(mode == BYTE_MODE) P(")\n", s);
else if(mode == LINE_MODE) P(") ]\n", s);
}
/**
* Try to open/close shutter depending on argument:
* state == SHUTTER_CLOSING - try to close
* state == SHUTTER_OPENING - try to open
* return 1 if state was changed
*/
void shutter_try(shutter_state state){
uint8_t shutter_try(shutter_state state){
uint8_t changestate = 0;
switch (Shutter_State){ // right states are only OPENED, CLOSED & READY
case SHUTTER_OPENED:
if(state == SHUTTER_OPENING){ // try to open opened shutter?
P("alerady opened\n", lastsendfun);
return;
}
BYTE_MSG("alerady opened\n");
}else changestate = 1;
break;
case SHUTTER_CLOSED:
if(state == SHUTTER_CLOSING){ // try to close closed?
P("alerady closed\n", lastsendfun);
return;
}
BYTE_MSG("alerady closed\n");
}else changestate = 1;
break;
case SHUTTER_READY:
; // All OK
changestate = 1; // All OK - change state
break;
default:
print_shutter_state(lastsendfun);
return;
default: break;
}
Shutter_State = state; // all OK, now we can change current state of shutter
if(mode == BYTE_MODE) print_shutter_state(lastsendfun);
if(changestate)
Shutter_State = state; // all OK, now we can change current state of shutter
return changestate;
}

View File

@ -45,7 +45,7 @@ shutter_state shutter_init();
void process_shutter();
void print_shutter_state(sendfun s);
void shutter_try(shutter_state state);
uint8_t shutter_try(shutter_state state);
#define try_to_close_shutter() shutter_try(SHUTTER_CLOSING)
#define try_to_open_shutter() shutter_try(SHUTTER_OPENING)

View File

@ -29,6 +29,8 @@ uint32_t Turrets_pause = 2 * TURRETS_PAUSE_US / 1300; // pause in half-steps
volatile uint8_t timer_flag[2] = {0,0};
// amount of steps for each motor
volatile uint32_t Motor_steps[5] = {0, 0, 0, 0, 0};
// absolute value of current position, usefull for stages
volatile int32_t Motor_abs_steps[5] = {0, 0, 0, 0, 0};
// flag of active motor
volatile uint8_t Motor_active[5] = {0, 0, 0, 0, 0};
/*
@ -40,6 +42,10 @@ uint8_t waits[5] = {0,0,0,0,0};
uint8_t lastpos[5] = {0,0,0,0,0};
// number of position to move turret or stage, zero to move only for N given steps
uint8_t move2pos[5] = {0,0,0,0,0};
// number of positions passed for given
uint8_t positions_pass[3] = {0,0,0};
// maximum amount of positions passed to reach given
#define MAX_POSITIONS_PASS (8)
/**
* Setup stepper motors' timer Tim
@ -64,7 +70,7 @@ static void setup_timer(uint8_t N){
// 36MHz of APB1
timer_set_mode(Tim, TIM_CR1_CKD_CK_INT, TIM_CR1_CMS_EDGE, TIM_CR1_DIR_UP);
// 72MHz div 36 = 2MHz
timer_set_prescaler(Tim, 35); // prescaler is (div - 1)
timer_set_prescaler(Tim, 35); // prescaler is (div - 1), 2pulse == 1 step
timer_continuous_mode(Tim); // automatically reload
timer_disable_preload(Tim); // force changing period
timer_set_period(Tim, Motor_period[N] - 1);
@ -73,8 +79,10 @@ static void setup_timer(uint8_t N){
timer_enable_counter(Tim);
timers_activated[N] = 1;
#ifdef EBUG
lastsendfun('3' + N);
MSG(" timer\n");
if(mode == BYTE_MODE){
lastsendfun('3' + N);
P(" timer\n", lastsendfun);
}
#endif
}
@ -123,7 +131,7 @@ uint8_t test_stages_endpos(uint8_t num, uint8_t curpos){
const uint8_t stage_minus[2] = {STAGE_CHECK(3, MINUS), STAGE_CHECK(4, MINUS)};
uint8_t negative_dir = 0;
num -= 3; // convern num to index in arrays
if((uint16_t)GPIO_IDR(MOTOR_EN_PORT) & MOTOR_EN_PIN(num)){ // negative direction
if((uint16_t)(GPIO_IDR(MOTOR_DIR_PORT) & MOTOR_DIR_PIN(num))){ // negative direction
negative_dir = 1;
}
if(stage_plus[num] == curpos){ // we are on "+" end-switch
@ -138,8 +146,10 @@ uint8_t test_stages_endpos(uint8_t num, uint8_t curpos){
}
}else{ // error: WTF is going up? curpos != 2 or 1
ERR("Wrong current position: ");
print_int(curpos, lastsendfun);
lastsendfun('\n');
if(mode == BYTE_MODE){
print_int(curpos, lastsendfun);
lastsendfun('\n');
}
return 1;
}
return 0;
@ -172,22 +182,26 @@ uint8_t check_ep(uint8_t num){
/**
* Move motor Motor_number to User_value steps
* return 0 if motor is still moving
*/
void move_motor(uint8_t num, int32_t steps){
uint8_t move_motor(uint8_t num, int32_t steps){
uint8_t curpos, negative_dir = 0;
if(steps == 0) return;
if(steps == 0) return 0;
// check whether motor is moving
if(Motor_active[num]){
ERR("moving\n");
return;
return 0;
}
#ifdef EBUG
MSG("move ");
lastsendfun('0' + num);
MSG(" to ");
print_int(steps, lastsendfun);
MSG("\n");
if(mode == BYTE_MODE){
P("move ", lastsendfun);
lastsendfun('0' + num);
P(" to ", lastsendfun);
print_int(steps, lastsendfun);
lastsendfun('\n');
}
#endif
Motor_abs_steps[num] += steps; // fix absolute position
if(steps < 0){
negative_dir = 1;
steps = -steps;
@ -199,29 +213,60 @@ void move_motor(uint8_t num, int32_t steps){
}else{
gpio_clear(MOTOR_DIR_PORT, MOTOR_DIR_PIN(num)); // reset DIR bit
}
if(test_stages_endpos(num, curpos)) return; // error: we can't move
if(test_stages_endpos(num, curpos)){ // error: we can't move
stop_motor(num); // say about it
return 0;
}
// set all flags and variables
Motor_steps[num] = steps; // we run in full-step mode!
waits[num] = 0;
Motor_active[num] = 1;
if(num < 3) // this is turret -> reset counter of passed positions
positions_pass[num] = 0;
gpio_set(MOTOR_EN_PORT, MOTOR_EN_PIN(num));
return 1;
}
void stop_motor(uint8_t num){
if(!Motor_active[num]) return;
#ifdef EBUG
MSG("stop motor ");
lastsendfun('0' + num);
MSG("\n");
#endif
gpio_clear(MOTOR_EN_PORT, MOTOR_EN_PIN(num));
Motor_active[num] = 0;
const uint8_t stage_minus[2] = {STAGE_CHECK(3, MINUS), STAGE_CHECK(4, MINUS)};
//if(!) return;
MSG("stop motor ", "[ " STR_STOP_ALL_MOTORS " ");
if(mode != BINARY_MODE) lastsendfun('0' + num);
if(Motor_active[num]){
if(!gpio_get(MOTOR_EN_PORT, MOTOR_EN_PIN(num)) && mode == LINE_MODE)
P(" HEAT ", lastsendfun);
gpio_clear(MOTOR_EN_PORT, MOTOR_EN_PIN(num));
Motor_active[num] = 0;
}
uint8_t curpos = check_ep(num);
// set absolute counter to zero on 1st position for turrets or on MINUS EP for stages
if(num < 3){ // this is a turret
move2pos[num] = 0; // reset target position value
if(check_ep(num) == 0){ // a turret is out of fixed position
ERR("stop out of position\n");
if(curpos == 1){
Motor_abs_steps[num] = 0;
goto retn;
}else{
if(curpos == 0) // a turret is out of fixed position
MSG(" stop out of position", "ERR ");
}
}else{ // linear stage
if(curpos == stage_minus[num-3]){
Motor_abs_steps[num] = 0;
goto retn;
}
}
int32_t sign = 1;
if(GPIO_IDR(MOTOR_DIR_PORT) & MOTOR_DIR_PIN(num)){ // negative direction
sign = -1;
}
Motor_abs_steps[num] -= Motor_steps[num] * sign;
Motor_steps[num] = 0;
retn:
BYTE_MSG(" absolute steps: ");
print_int(Motor_abs_steps[num], lastsendfun);
if(mode == LINE_MODE) P(" ]", lastsendfun);
lastsendfun('\n');
}
@ -262,8 +307,11 @@ void process_stepper_motors(){
if(waits[i]) continue; // there's more half-steps to skip
lastpos[i] = curpos;
// tell user current position
MSG("position: ");
MSG("position of motor ", "[ " STR_ENDSW_STATE " ");
print_int(i, lastsendfun);
lastsendfun(' ');
print_int(curpos, lastsendfun);
if(mode == LINE_MODE) P(" ]", lastsendfun);
lastsendfun('\n');
// turn on motor after pause
gpio_set(MOTOR_EN_PORT, MOTOR_EN_PIN(i));
@ -276,7 +324,11 @@ void process_stepper_motors(){
if(curpos == move2pos[i]){ // we are on position
stop_motor(i);
}else{ // add some steps to move to next position
Motor_steps[i] += TURRETS_NEXT_POS_STEPS;
if(++positions_pass[i] > MAX_POSITIONS_PASS){
ERR("Can't reach given position");
stop_motor(i);
}else
Motor_steps[i] += TURRETS_NEXT_POS_STEPS;
}
}
}
@ -340,7 +392,7 @@ void set_motor_period(uint8_t num, uint16_t period){
N = 1;
break;
default:
MSG("err: bad motor");
ERR("bad motor");
return;
}
if(period == 0) Motor_period[N] = 1;

View File

@ -54,16 +54,31 @@
#define STAGE_CHECK(N, DIR) CONCAT(EP ## N, DIR)
// setup ports: PA8, PB6, PB7, PC7..PC9, PD0..PD7
/*
#define SETUP_ESW() do{gpio_set_mode(GPIOA, GPIO_MODE_INPUT, GPIO_CNF_INPUT_FLOAT, GPIO8); \
gpio_set_mode(GPIOB, GPIO_MODE_INPUT, GPIO_CNF_INPUT_FLOAT, GPIO6|GPIO7); \
gpio_set_mode(GPIOC, GPIO_MODE_INPUT, GPIO_CNF_INPUT_FLOAT, (uint16_t)0x0380);\
gpio_set_mode(GPIOD, GPIO_MODE_INPUT, GPIO_CNF_INPUT_FLOAT, (uint16_t)0xff); \
}while(0)
*/
#define SETUP_ESW() do{gpio_set_mode(GPIOA, GPIO_MODE_INPUT, GPIO_CNF_INPUT_PULL_UPDOWN, GPIO8); \
gpio_set(GPIOA, GPIO8); \
gpio_set_mode(GPIOB, GPIO_MODE_INPUT, GPIO_CNF_INPUT_PULL_UPDOWN, GPIO6|GPIO7); \
gpio_set(GPIOB, GPIO6|GPIO7); \
gpio_set_mode(GPIOC, GPIO_MODE_INPUT, GPIO_CNF_INPUT_PULL_UPDOWN, (uint16_t)0x0380);\
gpio_set(GPIOC, (uint16_t)0x0380);\
gpio_set_mode(GPIOD, GPIO_MODE_INPUT, GPIO_CNF_INPUT_PULL_UPDOWN, (uint16_t)0xff); \
gpio_set(GPIOD, (uint16_t)0xff); \
}while(0)
extern uint8_t move2pos[]; // export this array for ability of moving turret to given position from outside
void steppers_init();
void process_stepper_motors();
void move_motor(uint8_t num, int32_t steps);
uint8_t move_motor(uint8_t num, int32_t steps);
void stop_motor(uint8_t num);
void set_motor_period(uint8_t num, uint16_t period);
uint8_t check_ep(uint8_t num);
#endif // __STEPPER_MOTORS_H__

View File

@ -268,6 +268,7 @@ UART_buff *get_uart_buffer(uint32_t UART){
*/
void check_and_parce_UART(uint32_t UART){
sendfun sf;
static int oldlen = 0;
UART_buff *curbuff = get_uart_buffer(UART);
uint8_t datalen; // length of data in buffer - here we use param "end"
if(!curbuff) return;
@ -286,8 +287,10 @@ void check_and_parce_UART(uint32_t UART){
}
datalen = curbuff->end;
if(!datalen) return; // buffer is empty
parce_incoming_buf((char*)curbuff->buf, datalen, sf); // process data
curbuff->end = 0; // and zero counter
if(oldlen != datalen){ // run checking buffer contents only when data size changed
// process data and zero counter if all OK
oldlen = curbuff->end = parce_incoming_buf((char*)curbuff->buf, datalen, sf);
}
}
/**

View File

@ -25,6 +25,8 @@
#include "hardware_ini.h"
#include "flash.h"
// mode:
curmode_t mode = BYTE_MODE; // text protocol, activated on 1st meeteng of '['
// integer value given by user
static volatile int32_t User_value = 0;
// number of motor to process
@ -46,38 +48,71 @@ int read_int(char *buf, int cnt);
intfun I = NULL; // function to process entered integer
#define READINT() do{i += read_int(&buf[i+1], len-i-1);}while(0)
#define WRONG_COMMAND() do{command = '?';}while(0)
#define WRONG_COMMAND() do{if(mode == BYTE_MODE) command = '?';}while(0)
/**
* displays all TRD values
* displays all TRD values from AD7794
* @param s -- current output
*/
void print_ad_vals(sendfun s){
int j;
if(ad7794_on){
for(j = 0; j < TRD_NO; j++){
if(mode == LINE_MODE){
P("[ " STR_EXTADC_VALUES " ", s);
print_int(j, s);
s(' ');
}
print_int(ad7794_values[j], s);
s(' ');
if(mode == LINE_MODE)
P(" ]\n", s);
else s(' ');
}
newline(s);
if(mode == BYTE_MODE) newline(s);
}else{
P("no AD7794 found\n", s);
if(mode == BYTE_MODE) P("no AD7794 found\n", s);
else if(mode == LINE_MODE) P("[ " STR_EXTADC_VALUES " ERR ]\n", s);
}
}
void set_shtr_delay(int32_t v, sendfun s){
/**
* displays all TRD values from inner ADC
* @param s -- current output
*/
void print_int_ad_vals(sendfun s){
int j;
for(j = 0; j < 8; j++){
if(mode == LINE_MODE){
P("[ " STR_INTADC_VALUES " ", s);
print_int(j, s);
s(' ');
}
print_int(TRD_value(j), s);
if(mode == BYTE_MODE) s(' ');
else if(mode == LINE_MODE)
P(" ]\n", s);
}
}
/*
uint8_t set_shtr_delay(int32_t v, sendfun s){
uint16_t d = (uint16_t) v;
Shutter_delay = d;
P("Change delay to ", s);
print_int(d, s);
return 0;
}
*/
int adc_channel = -1;
int div_mul = 0; // 0 - multip., !0 - div.
void ch_divmul(int32_t v, sendfun s){
/**
* change dividers/multipliers
* work only in BYTE_MODE
*/
uint8_t ch_divmul(int32_t v, sendfun s){
uint32_t val = (uint32_t) v;
if(adc_channel == -1) return;
if(adc_channel == -1) return 0;
if(div_mul){ // != 0 - divisors
flash_store_U32((uint32_t)&ADC_divisors[adc_channel], &val);
}else{ // == 0 - mul
@ -85,40 +120,196 @@ void ch_divmul(int32_t v, sendfun s){
}
adc_channel = -1;
P("stored\n", s);
return 1;
}
/**
* Change divisor
* Change divisor (work only in BYTE_MODE)
* @param v - user value (sensor number)
* @param s - active sendfunction
*/
void try_ch_divmul(int32_t v, sendfun s){
uint8_t try_ch_divmul(int32_t v, sendfun s){
if(v > ADC_CHANNELS_NUMBER || v < 0){
P("wrong channel number\n", s);
adc_channel = -1;
return; // error
return 0; // error
}
adc_channel = v;
I = ch_divmul;
read_int(NULL, 0); //start reading next int
return 0;
}
void parce_incoming_buf(char *buf, int len, sendfun s){
uint8_t command;
/**
* prints state of end switches for motor v
*/
uint8_t endswitchstate(int32_t v, sendfun s){
int32_t i;
if(v < 0 || v > 4){
if(mode == BYTE_MODE) P("Wrong motor number\n", s);
return 0;
}
i = check_ep(v);
if(mode == BYTE_MODE){
P("Endswitches for motor ", s);
s('0' + v);
P(": ", s);
}else if(mode == LINE_MODE){ // in LINE_MODE print [ E No_motor state ]
P("[ " STR_ENDSW_STATE " ",s);
s('0' + v);
s(' ');
}
if(mode != BINARY_MODE){
print_int(i, s);
if(mode == LINE_MODE) P(" ]\n", s);
else s('\n');
}
return 0;
}
/**
* moves turret 'active_motor' to position v
*/
uint8_t move_turret(int32_t v, sendfun s){
const int32_t maxpos[3] = {8, 6, 6}; // maximum position number for given turret
int32_t sign = 1;
if(active_motor > 2){
if(mode == BYTE_MODE) P("Wrong turret number\n", s);
return 0;
}
int32_t m = maxpos[active_motor];
if(v > m){
if(mode == BYTE_MODE){
P("Wrong position, shoud be not more than ", s);
print_int(m, s);
}
return 0;
}
move2pos[active_motor] = v;
// check the nearest direction
uint8_t curpos = check_ep(active_motor);
if(curpos){ // we are not between positions
if((v + m - curpos) > m/2) // rotation in positive direction will take more steps than in negative
sign = -1; // move CCV
}
return move_motor(active_motor, TURRETS_NEXT_POS_STEPS * sign);
}
/**
* function 'help' works only in BYTE_MODE
*/
void help(sendfun s){
#define pr(arg) do{prnt((uint8_t*)arg, s); s('\n');}while(0)
pr("0..4\t move stepper motor to N steps");
pr("Commands in char protocol:");
pr(STR_INTADC_VALUES "\tget TRD values");
pr(STR_STOP_ALL_MOTORS "\tstop all motors");
//pr("C");
pr("D\tturn AD7794 to double conversion mode");
pr(STR_ENDSW_STATE "\tshow end-switches state for given motor");
pr("F\tdump flash data");
//pr("G");
pr("H\tshow this help");
pr("I\tturn off AD7794 init flag");
pr("J\tmove slits (0) wheel to Nth position");
pr("K\tmove filters (1) wheel to Nth position");
pr("L\tmove filters (2) wheel to Nth position");
pr("M\tswitch on/off ADC monitoring");
//pr("N");
//pr("O");
pr("P\ttest (ow_fill_id)");
//pr("Q");
//pr("R");
pr("S\tturn AD7794 to single conversion mode");
pr(STR_PRINT_TIME "\tprint current value of time counters");
//pr("U\t(reserved)");
//pr("V");
//pr("W\t(reserved)");
pr("X\tset timer period for linear stages");
//pr("Y");
//pr("Z");
//pr("a");
//pr("b");
pr("c\tclose shutter");
pr("d\tchange value of ADC divisor No N");
//pr("e");
//pr("f");
pr("g\tchange AD7794 gain");
pr(STR_SHTR_VOLTAGE "\tshow shutter voltage");
pr(STR_EXTADC_INIT "\tinit AD7794");
//pr("j");
//pr("k");
//pr("l");
pr("m\tchange value of ADC multiplier No N");
//pr("n");
pr("o\topen shutter");
pr(STR_MOTORS_VOLTAGE "\tshow motors voltage");
//pr("q");
pr("r\treinit shutter");
pr(STR_EXTADC_VALUES "\tshow AD7794 values");
pr(STR_SHTR_STATE "\tprint shutter state");
pr("u\tcheck USB connection");
//pr("v");
//pr("w");
pr("x\tset timer period for turrets' motors");
//pr("y");
//pr("z");
pr("\nAfter entering of user value press '+' to submit or '-' to reject it");
#undef pr
}
/**
* parce command buffer buf with length len
* return 0 if buffer processed or len if there's not enough data in buffer
*/
int parce_incoming_buf(char *buf, int len, sendfun s){
uint8_t command, do_echo = 1;
//uint32_t utmp;
int i = 0, j, m;
lastsendfun = s;
if(Uval_ready == UVAL_START){ // we are in process of user's value reading
i += read_int(buf, len);
}
if(Uval_ready == UVAL_ENTERED){
P("confirm entered value (+/-): ", s);
print_int(User_value, s); // printout readed integer value for error control
Uval_ready = UVAL_PRINTED;
}
if(I && Uval_ready == UVAL_CHECKED){
Uval_ready = UVAL_BAD; // clear Uval_ready
I(User_value, s);
return;
if(buf[0] == '[') mode = LINE_MODE;
if(mode == BYTE_MODE){
if(Uval_ready == UVAL_START){ // we are in process of user's value reading
i += read_int(buf, len);
}
if(Uval_ready == UVAL_ENTERED){
P("confirm entered value (+/-): ", s);
print_int(User_value, s); // printout readed integer value for error control
Uval_ready = UVAL_PRINTED;
}
if(I && Uval_ready == UVAL_CHECKED){
Uval_ready = UVAL_BAD; // clear Uval_ready
I(User_value, s);
return 0;
}
}else if(mode == LINE_MODE){ // text mode: check for "]\n" presence
uint8_t bad_cmd = 1;
s(buf[0]);
P(" check buffer in line mode: ", s);
if(buf[0] == '['){
for(j = 1; j < len; j++){
s(buf[j]);
if(buf[j] != '\n') continue; // search end of line
else{
if(buf[j-1] == ']'){
P("OK, good!\n", s);
bad_cmd = 0;
len = j; buf[j] = 0; // truncate buffer to only one command
break;
}
else{
P("broken command!\n",s);
return 0; // end of line without closing bracket
}
}
}} else{
P("wrong first\n",s );
return 0;
}
if(bad_cmd){
P("not full\n",s);
return len; // not enough data in buffer
}
}
for(; i < len; i++){
command = buf[i];
@ -128,10 +319,149 @@ void parce_incoming_buf(char *buf, int len, sendfun s){
I = stepper_proc;
READINT();
}else switch (command){
case 'P':
case '[': // line mode - do nothing, this is start symbol
//mode = LINE_MODE;
break;
case '+': // user check number value & confirm it's right
if(mode != BYTE_MODE) return 0; // bad command - no echo
if(Uval_ready == UVAL_PRINTED) Uval_ready = UVAL_CHECKED;
else WRONG_COMMAND();
break;
case '-': // user check number value & confirm it's wrong
if(mode != BYTE_MODE) return 0; // bad command - no echo
if(Uval_ready == UVAL_PRINTED) Uval_ready = UVAL_BAD;
else WRONG_COMMAND();
break;
case CMD_INTADC_VALUES: // [A] show TRD values by inner ADC [ A 0 val0 ]\n[A 1 val1 ] ...
//adc_start_conversion_direct(ADC1);
print_int_ad_vals(s);
if(mode == BYTE_MODE) s('\n');
do_echo = 0; // don't echo command in line mode as there's output
break;
case 'b': // byte mode
mode = BYTE_MODE;
//return 0; //don't echo this command
break;
case CMD_STOP_ALL_MOTORS: // [B] stop all motors
for(m = 0; m < 5; m++)
stop_motor(m);
do_echo = 0; // echo called from sto
break;
case 'c': // [c] close shutter
do_echo = try_to_close_shutter(); // don't echo in case of state wouldn't be changed
break;
case 'd': // change ADC_divisor (only for byte mode)
if(mode != BYTE_MODE) return 0;
div_mul = 1; //divisors
I = try_ch_divmul;
READINT();
break;
case 'D': // double conversion (only for byte mode)
if(mode != BYTE_MODE) return 0;
doubleconv = 1;
break;
case CMD_ENDSW_STATE: // [E] print end-switch state for given motor
I = endswitchstate;
READINT();
break;
case 'F': // dump flash data (only in byte mode)
if(mode != BYTE_MODE) return 0;
dump_flash_data(s);
break;
case 'g': // change gain (only in byte mode)
if(mode != BYTE_MODE) return 0;
I = set_ADC_gain;
READINT();
break;
case CMD_SHTR_VOLTAGE: // [h] show sHutter voltage * 100
if(mode == LINE_MODE) P("[ " STR_SHTR_VOLTAGE " ", s);
print_int(shutter_voltage(), s);
if(mode == LINE_MODE) P(" ]", s);
newline(s);
do_echo = 0;
break;
case 'H': // show help (only in byte mode)
if(mode != BYTE_MODE) return 0;
help(s);
break;
case CMD_EXTADC_INIT: // [i] init AD7794
AD7794_init();
break;
case 'I': // turn off flag AD7794
ad7794_on = 0;
break;
case 'J': // move turret 0/1/2 to given position
case 'K':
case 'L':
active_motor = command - 'J'; // J == 0, K == 1, L == 2
I = move_turret;
READINT();
break;
case 'm': // change ADC_multiplier (only for byte mode)
if(mode != BYTE_MODE) return 0;
div_mul = 0; // multipliers
I = try_ch_divmul;
READINT();
break;
case 'M': // ADC monitoring ON
ADC_monitoring = !ADC_monitoring;
break;
case 'o': // open shutter
do_echo = try_to_open_shutter();
break;
case CMD_MOTORS_VOLTAGE: // [p] show motors voltage * 100
if(mode == LINE_MODE) P("[ " STR_MOTORS_VOLTAGE " ", s);
print_int(power_voltage(), s);
if(mode == LINE_MODE) P(" ]", s);
newline(s);
break;
case 'P': // (only for byte mode)
if(mode != BYTE_MODE) return 0;
OW_fill_ID(0);
//run_dmatimer();
break;
case 'r': // reinit shutter
shutter_init();
break;
case CMD_EXTADC_VALUES: // [s] read ADC val through SPI
if(!ad7794_on){
AD7794_init();
if(mode == BYTE_MODE) P("wait: values aren't ready yet\n", s);
break;
}
if(mode == BYTE_MODE) P("AD7794 values: ", s);
print_ad_vals(s);
do_echo = 0;
break;
case 'S': // single conversion (only for byte mode)
if(mode != BYTE_MODE) return 0;
doubleconv = 0;
break;
case CMD_SHTR_STATE: // [t] print shutter state
print_shutter_state(s);
do_echo = 0;
break;
case CMD_PRINT_TIME: // print time
print_time(s);
if(mode == BYTE_MODE) newline(s);
break;
case 'u': // check USB connection (only byte mode)
if(mode != BYTE_MODE) return 0;
P("\nUSB ", s);
if(!USB_connected) P("dis", s);
P("connected\n",s);
break;
/* case 'U': // test: init USART1
UART_init(USART1);
break; */
/* case 'W': // scan for one 1-wire device
if(1 == OW_Scan(onewire_addr, 1)){
P("found 1-wire: ", s);
print_hex(onewire_addr, 8, s);
}else
P("1-wire error",s );
P("\n", s);
break;*/
case 'x': // set period of TIM1 (motors 1..3)
active_motor = 1;
I = set_timr;
@ -142,117 +472,26 @@ void parce_incoming_buf(char *buf, int len, sendfun s){
I = set_timr;
READINT();
break;
case 'B': // stop all motors
for(m = 0; m < 5; m++)
stop_motor(m);
break;
/* case 'W': // scan for one 1-wire device
if(1 == OW_Scan(onewire_addr, 1)){
P("found 1-wire: ", s);
print_hex(onewire_addr, 8, s);
}else
P("1-wire error",s );
P("\n", s);
break;*/
case 'S': // single conversion
doubleconv = 0;
break;
case 'D': // double conversion
doubleconv = 1;
break;
case 'A': // show TRD values
//adc_start_conversion_direct(ADC1);
P("\nTRD resistance: ", s);
for(j = 0; j < 8; j++){
print_int(TRD_value(i), s);
s('\t');
}
newline(s);
break;
case 'i': // init AD7794
AD7794_init();
break;
case 'I': // turn off flag AD7794
ad7794_on = 0;
break;
case '+': // user check number value & confirm it's right
if(Uval_ready == UVAL_PRINTED) Uval_ready = UVAL_CHECKED;
else WRONG_COMMAND();
break;
case '-': // user check number value & confirm it's wrong
if(Uval_ready == UVAL_PRINTED) Uval_ready = UVAL_BAD;
else WRONG_COMMAND();
break;
case 'g': // change gain
I = set_ADC_gain;
READINT();
break;
case 's': // read ADC val through SPI
if(!ad7794_on){
AD7794_init();
P("wait: values aren't ready yet\n", s);
break;
}
P("AD7794 values: ", s);
print_ad_vals(s);
break;
case 'u': // check USB connection
P("\nUSB ", s);
if(!USB_connected) P("dis", s);
P("connected\n",s);
break;
case 'M': // ADC monitoring ON
ADC_monitoring = !ADC_monitoring;
break;
case 'T': // print time
print_time(s);
newline(s);
break;
/* case 'U': // test: init USART1
UART_init(USART1);
break; */
case 'p': // show motors voltage * 100
print_int(power_voltage(), s);
newline(s);
break;
case 'h': // show sHutter voltage * 100
print_int(shutter_voltage(), s);
newline(s);
break;
case 'r': // reinit shutter
shutter_init();
break;
case 't': // print shutter state
print_shutter_state(s);
break;
case 'c': // close shutter
try_to_close_shutter();
break;
case 'o': // open shutter
try_to_open_shutter();
break;
case 'F': // dump flash data
dump_flash_data(s);
break;
case 'd': // change ADC_divisor
div_mul = 1; //divisors
I = try_ch_divmul;
READINT();
break;
case 'm': // change ADC_multiplier
div_mul = 0; // multipliers
I = try_ch_divmul;
READINT();
break;
case '\n': // show newline as is
break;
case '\n': // show newline, space and tab as is
case '\r':
case ' ':
case '\t':
break;
default:
WRONG_COMMAND(); // echo '?' on unknown command
WRONG_COMMAND(); // echo '?' on unknown command in byte mode
}
s(command); // echo readed byte
if(mode == BYTE_MODE) s(command); // echo readed byte in byte mode
}
if(mode == LINE_MODE){ // process command which needs for user value
if(I && Uval_ready == UVAL_ENTERED){
Uval_ready = UVAL_BAD; // clear Uval_ready
do_echo = I(User_value, s);
I = NULL;
}
}
if(do_echo && mode == LINE_MODE)
P(buf, s);
return 0; // all data processed - 0 bytes leave in buffer
}
/*
@ -269,8 +508,6 @@ void newline(sendfun s){
}
*/
// sign of readed value
int32_t sign;
/**
* Read from TTY integer value given by user (in DEC).
* Reading stops on first non-numeric symbol.
@ -283,8 +520,11 @@ int32_t sign;
*/
int read_int(char *buf, int cnt){
int readed = 0, i;
static int enteredDigits; // amount of entered digits
static int sign; // sign of readed value
if(Uval_ready){ // this is first run
Uval_ready = UVAL_START; // clear flag
enteredDigits = 0; // 0 digits entered
User_value = 0; // clear value
sign = 1; // clear sign
}
@ -292,21 +532,27 @@ int read_int(char *buf, int cnt){
for(i = 0; i < cnt; i++, readed++){
uint8_t chr = buf[i];
if(chr == '-'){
if(sign == 1){
if(enteredDigits == 0){ // sign should be first
sign = -1;
continue;
}else{ // '-' after numbers
Uval_ready = UVAL_ENTERED;
}else{ // '-' after number - reject entered value
Uval_ready = UVAL_BAD;
break;
}
}
if(chr < '0' || chr > '9'){
Uval_ready = UVAL_ENTERED;
if(enteredDigits)
Uval_ready = UVAL_ENTERED;
else{
if(chr == ' ' || chr == '\t') continue; // omit leading space|tab
else Uval_ready = UVAL_BAD; // bad symbol
}
break;
}
User_value = User_value * 10 + (int32_t)(chr - '0');
enteredDigits++;
}
if(Uval_ready != UVAL_START) // reading has met an non-numeric character
if(Uval_ready == UVAL_ENTERED) // reading has met an non-numeric character
User_value *= sign;
return readed;
}
@ -361,7 +607,10 @@ void process_int(int32_t v, sendfun s){
}
*/
void set_ADC_gain(int32_t v, sendfun s){
/**
* change AD7794 gain. Run only in byte mode!
*/
uint8_t set_ADC_gain(int32_t v, sendfun s){
if(ad7794_on){
P("Change gain to ", s);
print_int(v, s);
@ -369,6 +618,7 @@ void set_ADC_gain(int32_t v, sendfun s){
change_AD7794_gain(v);
AD7794_calibration(0);
}
return 0;
}
/**
@ -376,28 +626,32 @@ void set_ADC_gain(int32_t v, sendfun s){
* @param v - user value
* @param s - active sendfunction
*/
void stepper_proc(int32_t v, sendfun s){
uint8_t stepper_proc(int32_t v, sendfun s){
if(active_motor > 4){
P("wrong motor number\n", s);
return; // error
if(mode == BYTE_MODE) P("wrong motor number\n", s);
return 0; // error
}
move_motor(active_motor, v);
uint8_t ret = move_motor(active_motor, v);
active_motor = 6;
return ret;
}
void set_timr(int32_t v, sendfun s){
uint8_t set_timr(int32_t v, sendfun s){
if(active_motor > 4){
P("wrong motor number\n", s);
return; // error
if(mode == BYTE_MODE) P("wrong motor number\n", s);
return 0; // error
}
if(v < 0 || v > 0xffff){
MSG("Bad period!\n");
if(mode == BYTE_MODE) P("Bad period!\n", s);
active_motor = 6;
return;
return 0;
}
if(mode == BYTE_MODE){
P("set period: ", s);
print_int(v, s);
P("\n", s);
}
MSG("set period: ");
print_int(v, lastsendfun);
MSG("\n");
set_motor_period(active_motor, (uint16_t)v);
active_motor = 6;
return 1;
}

View File

@ -30,18 +30,33 @@
#define P(arg, s) prnt((uint8_t*)arg, s)
// debug message - over USB
#ifdef EBUG
#define DBG(a) prnt((uint8_t*)a, usb_send)
#define DBG(a) do{if(mode == BYTE_MODE) prnt((uint8_t*)a, usb_send);}while(0)
#else
#define DBG(a)
#endif
#define MSG(arg) prnt((uint8_t*)arg, lastsendfun)
#define MSG(argb, argl) do{if(mode == BYTE_MODE) prnt((uint8_t*)argb, lastsendfun); \
else if(mode == LINE_MODE) prnt((uint8_t*)argl, lastsendfun);}while(0)
#define ERR(arg) do{prnt((uint8_t*)"Error! ",lastsendfun); prnt((uint8_t*)arg, lastsendfun);}while(0)
#define BYTE_MSG(arg) do{if(mode == BYTE_MODE) prnt((uint8_t*)arg, lastsendfun);}while(0)
typedef void (*sendfun)(uint8_t); // function to send a byte
typedef void (*intfun)(int32_t, sendfun); // function to process entered integer value at end of input
#define ERR(arg) do{if(mode == BYTE_MODE){prnt((uint8_t*)"Error! ",lastsendfun); \
prnt((uint8_t*)arg, lastsendfun);}}while(0)
// function to send a byte
typedef void (*sendfun)(uint8_t);
// function to process entered integer value at end of input
//return 1 if there's no output in this function (for echo), 0 if there's output
typedef uint8_t (*intfun)(int32_t, sendfun);
typedef enum{
BYTE_MODE // data entered byte by byte interactively
,LINE_MODE // line mode like '[ command parameters ]\n'
,BINARY_MODE // reserved
} curmode_t;
extern curmode_t mode;
extern sendfun lastsendfun; // last active send function - to post "anonymous" replies
void prnt(uint8_t *wrd, sendfun s);
@ -50,13 +65,39 @@ void prnt(uint8_t *wrd, sendfun s);
void print_int(int32_t N, sendfun s);
void parce_incoming_buf(char *buf, int len, sendfun s);
int parce_incoming_buf(char *buf, int len, sendfun s);
// void process_int(int32_t v, sendfun s);
void set_ADC_gain(int32_t v, sendfun s);
uint8_t set_ADC_gain(int32_t v, sendfun s);
void print_ad_vals(sendfun s);
void stepper_proc(int32_t v, sendfun s);
void set_timr(int32_t v, sendfun s);
void print_int_ad_vals(sendfun s);
uint8_t stepper_proc(int32_t v, sendfun s);
uint8_t set_timr(int32_t v, sendfun s);
void print_hex(uint8_t *buff, uint8_t l, sendfun s);
/**
* here is commands definition (what is outhern function should print message?)
* in line mode commands are echoed with some usefull information
* in case of error inside command arguments will be word "ERR"
*/
#define CMD_INTADC_VALUES 'A'
#define STR_INTADC_VALUES "A"
#define CMD_STOP_ALL_MOTORS 'B'
#define STR_STOP_ALL_MOTORS "B"
#define CMD_ENDSW_STATE 'E'
#define STR_ENDSW_STATE "E"
#define CMD_SHTR_VOLTAGE 'h'
#define STR_SHTR_VOLTAGE "h"
#define CMD_EXTADC_INIT 'i'
#define STR_EXTADC_INIT "i"
#define CMD_MOTORS_VOLTAGE 'p'
#define STR_MOTORS_VOLTAGE "p"
#define CMD_EXTADC_VALUES 's'
#define STR_EXTADC_VALUES "s"
#define CMD_SHTR_STATE 't'
#define STR_SHTR_STATE "t"
#define CMD_PRINT_TIME 'T'
#define STR_PRINT_TIME "T"
#endif // __USER_PROTO_H__