mirror of
https://github.com/eddyem/IR-controller.git
synced 2025-12-06 10:45:15 +03:00
try to make 1-wire on timers
This commit is contained in:
parent
6af145db1c
commit
7455c600b0
@ -1,4 +1,3 @@
|
|||||||
eeschema (2013-feb-26)-stable >> Creation date: Пн 21 июл 2014 08:49:29
|
|
||||||
#Cmp ( order = Reference )
|
#Cmp ( order = Reference )
|
||||||
| C4 2200u, 40V
|
| C4 2200u, 40V
|
||||||
| C5 10u
|
| C5 10u
|
||||||
|
|||||||
@ -1,4 +1,4 @@
|
|||||||
EESchema Schematic File Version 2 date Пн 29 сен 2014 14:40:29
|
EESchema Schematic File Version 2 date Вт 07 окт 2014 17:18:47
|
||||||
LIBS:power
|
LIBS:power
|
||||||
LIBS:device
|
LIBS:device
|
||||||
LIBS:transistors
|
LIBS:transistors
|
||||||
@ -41,7 +41,7 @@ $Descr A3 16535 11693
|
|||||||
encoding utf-8
|
encoding utf-8
|
||||||
Sheet 1 12
|
Sheet 1 12
|
||||||
Title "IR-spectrometer Control System"
|
Title "IR-spectrometer Control System"
|
||||||
Date "29 sep 2014"
|
Date "7 oct 2014"
|
||||||
Rev ""
|
Rev ""
|
||||||
Comp "SAO RAS"
|
Comp "SAO RAS"
|
||||||
Comment1 ""
|
Comment1 ""
|
||||||
|
|||||||
@ -1,4 +1,4 @@
|
|||||||
EESchema Schematic File Version 2 date Пн 29 сен 2014 14:40:29
|
EESchema Schematic File Version 2 date Вт 07 окт 2014 17:18:47
|
||||||
LIBS:power
|
LIBS:power
|
||||||
LIBS:device
|
LIBS:device
|
||||||
LIBS:transistors
|
LIBS:transistors
|
||||||
@ -41,7 +41,7 @@ $Descr A3 16535 11693
|
|||||||
encoding utf-8
|
encoding utf-8
|
||||||
Sheet 3 12
|
Sheet 3 12
|
||||||
Title "MCU module on STM32F103"
|
Title "MCU module on STM32F103"
|
||||||
Date "29 sep 2014"
|
Date "7 oct 2014"
|
||||||
Rev ""
|
Rev ""
|
||||||
Comp "SAO RAS"
|
Comp "SAO RAS"
|
||||||
Comment1 ""
|
Comment1 ""
|
||||||
|
|||||||
@ -1,4 +1,4 @@
|
|||||||
EESchema Schematic File Version 2 date Пн 29 сен 2014 14:40:29
|
EESchema Schematic File Version 2 date Вт 07 окт 2014 17:18:47
|
||||||
LIBS:power
|
LIBS:power
|
||||||
LIBS:device
|
LIBS:device
|
||||||
LIBS:transistors
|
LIBS:transistors
|
||||||
@ -41,7 +41,7 @@ $Descr A4 11693 8268
|
|||||||
encoding utf-8
|
encoding utf-8
|
||||||
Sheet 5 12
|
Sheet 5 12
|
||||||
Title "RS-232 level converter"
|
Title "RS-232 level converter"
|
||||||
Date "29 sep 2014"
|
Date "7 oct 2014"
|
||||||
Rev ""
|
Rev ""
|
||||||
Comp "SAO RAS"
|
Comp "SAO RAS"
|
||||||
Comment1 ""
|
Comment1 ""
|
||||||
|
|||||||
@ -1,102 +1,102 @@
|
|||||||
嬲嗡蒙衔撂匚吓 瘟谖赁盼膳 邢以献 蜕艘纤衔砸咸膛伊
|
Functional map of MCU pins
|
||||||
|
|
||||||
# 瘟谧廖膳 瘟谖赁盼膳
|
# name functionality
|
||||||
001 PE2 DIR_3 direction of steppers' rotation
|
001 PE2 DIR_3 direction of steppers' rotation
|
||||||
002 PE3 DIR_4
|
002 PE3 DIR_4
|
||||||
003 PE4 DIR_5
|
003 PE4 DIR_5
|
||||||
004
|
004 PE6 DG_FEEDBACK feedback from power switch POW_LOAD (+10..12V)
|
||||||
005
|
005 -
|
||||||
006
|
006 -
|
||||||
007
|
007 -
|
||||||
008
|
008 -
|
||||||
009
|
009 -
|
||||||
010 VSS
|
010 VSS GND
|
||||||
011 VDD
|
011 VDD +3.3V
|
||||||
012 OSC_IN
|
012 OSC_IN 8MHz in
|
||||||
013 OSC_OUT
|
013 OSC_OUT 8MHz out
|
||||||
014 NRST RST
|
014 NRST Reset
|
||||||
015 PC0 \
|
015 PC0 SHTR Shutter on pulse
|
||||||
016 PC1 | ADG506 address
|
016 PC1 SHTR_FB Error signal from shutter H-bridge
|
||||||
017 PC2 | selection
|
017 PC2 POW0 Shutter polarity (open/close)
|
||||||
018 PC3 /
|
018 -
|
||||||
019 VSSA 0v analog
|
019 VSSA 0v analog
|
||||||
020 VREF- ref (0v)
|
020 VREF- ref (0v)
|
||||||
021 VREF+ ref (+3.3v)
|
021 VREF+ ref (+3.3v)
|
||||||
022 VDDA +3.3V analog
|
022 VDDA +3.3V analog
|
||||||
023
|
023 -
|
||||||
024 PA1 TIM2 timer for motors 4&5
|
024 -
|
||||||
025 PA2 UART_TX RS-232
|
025 PA2 1WIRE_TX 1-wire interface
|
||||||
026 PA3 UART_RX
|
026 PA3 1WIRE_RX
|
||||||
027 VSS
|
027 VSS GND
|
||||||
028 VDD
|
028 VDD +3.3V
|
||||||
029 PA4 7\
|
029 PA4 ADC7\
|
||||||
030 PA5 6 |
|
030 PA5 ADC6 |
|
||||||
031 PA6 5 |
|
031 PA6 ADC5 |
|
||||||
032 PA7 4 | ADC 12bit input channels (TRD)
|
032 PA7 ADC4 | ADC 12bit input channels (TRD)
|
||||||
033 PC4 3 |
|
033 PC4 ADC3 |
|
||||||
034 PC5 2 |
|
034 PC5 ADC2 |
|
||||||
035 PB0 1 |
|
035 PB0 ADC1 |
|
||||||
036 PB1 0/
|
036 PB1 ADC0/
|
||||||
037 BOOT1 BOOT 100k resistor to GND
|
037 BOOT1 BOOT 100k resistor to GND
|
||||||
038 PE7 EN1 \
|
038 PE7 EN1 \
|
||||||
039 PE8 EN2 |
|
039 PE8 EN2 |
|
||||||
040 PE9 EN3 | enable Xth stepper motor
|
040 PE9 EN3 | enable Xth stepper motor
|
||||||
041 PE10 EN4 |
|
041 PE10 EN4 |
|
||||||
042 PE11 EN5 /
|
042 PE11 EN5 /
|
||||||
043 PE12 POW0\
|
043 PE12 POW2\
|
||||||
044 PE13 POW1 | Power load (12V, up to 17A on single channel)
|
044 PE13 POW1/ Power load (10..12V, pull-down)
|
||||||
045 PE14 POW2 |
|
045 -
|
||||||
046 PE15 POW3/
|
046 -
|
||||||
047 PB10 USART3_TX 1-wire data tx/rx
|
047 PB10 USART3_TX RS-232 (master)
|
||||||
048 PB11 USART3_RX
|
048 PB11 USART3_RX
|
||||||
049 VSS
|
049 VSS GND
|
||||||
050 VDD
|
050 VDD +3.3V
|
||||||
051
|
051 -
|
||||||
052 SPI2_SCK \
|
052 SPI2_SCK \
|
||||||
053 SPI2_MISO | External SPI connection
|
053 SPI2_MISO | External SPI connection (at edge of the board)
|
||||||
054 SPI2_MOSI /
|
054 SPI2_MOSI /
|
||||||
055 PD8 \ Tur3[1..2] Upper filters turret Hall 1 & 2
|
055 -
|
||||||
056 PD9 /
|
056 -
|
||||||
057 PD10 \ LS1 Linear stage 1 (long) DOWN end-switch
|
057 PD10 EXT0\
|
||||||
058 PD11 / Linear stage 1 (long) UP end-switch
|
058 PD11 EXT1 | ADG506 address selection
|
||||||
059 PD12 \ LS2 Linear stage 2 (short) DOWN end-switch
|
059 PD12 EXT2 | or custom external ports
|
||||||
060 PD13 / Linear stage 2 (short) UP end-switch
|
060 PD13 EXT3/
|
||||||
061
|
061 -
|
||||||
062
|
062 PD15 TIM2 timer for motors 4&5
|
||||||
063 PC6 TIM1 timer for stepper motors 1..3
|
063 PC6 TIM1 timer for stepper motors 1..3
|
||||||
064 PC7 \
|
064 PC7 \ LS1 Linear stage 1 (long) DOWN end-switch
|
||||||
065 PC8 |
|
065 PC8 / Linear stage 1 (long) UP end-switch
|
||||||
066 PC9 | EXT External ports +
|
066 PC9 \ LS2 Linear stage 2 (short) DOWN end-switch
|
||||||
067 PA8 |
|
067 PA8 / Linear stage 2 (short) UP end-switch
|
||||||
068 PA9 | TX External UART (+ boot UART)
|
068 PA9 BOOT_TX \ UART1 (slave): boot + ext UART
|
||||||
069 PA10 / RX
|
069 PA10 BOOT_RX /
|
||||||
070 PA11 USB_DM USB data-
|
070 PA11 USB_DM USB data-
|
||||||
071 PA12 USB_DP USB data+
|
071 PA12 USB_DP USB data+
|
||||||
072
|
072 -
|
||||||
073
|
073 -
|
||||||
074 VSS
|
074 VSS GND
|
||||||
075 VDD
|
075 VDD +3.3V
|
||||||
076
|
076 -
|
||||||
077
|
077 -
|
||||||
078
|
078 PC10 USB_POWER +3V when USB connected
|
||||||
079 PC11 USB_DISC disconnect USB)
|
079 PC11 USB_DISC software USB disconnection (low lewel for bipolar VT1, high level for p-channel MOSFET)
|
||||||
080
|
080 -
|
||||||
081 PD0 \
|
081 PD0 \
|
||||||
082 PD1 | Tur1 Slits turret Hall sensors
|
082 PD1 | Tur1 Slits turret Hall sensors
|
||||||
083 PD2 |
|
083 PD2 |
|
||||||
084 PD3 /
|
084 PD3 /
|
||||||
085 PD4 \
|
085 PD4 \
|
||||||
086 PD5 | Tur2 Middle filters turret Hall sensors
|
086 PD5 | Tur2 Middle filters turret Hall sensors
|
||||||
087 PD6 / Upper filters turret Hall 0
|
087 PD6 /
|
||||||
088 PD7 Tur3_0
|
088 PD7 Tur3_0 Upper filters turret Hall 0
|
||||||
089 SPI1_SCK
|
089 SPI1_SCK \
|
||||||
090 SPI1_MISO
|
090 SPI1_MISO | SPI connection (near USB connector)
|
||||||
091 SPI1_MOSI/I2C_SMBAI
|
091 SPI1_MOSI/I2C_SMBAI/
|
||||||
092
|
092 PB6 Tur3_1 \ Upper filters turret Hall 1,2
|
||||||
093
|
093 PB7 Tur3_2 /
|
||||||
094 BOOT BOOT Button to boot from bootloader
|
094 BOOT BOOT Button to boot from bootloader
|
||||||
095 I2C_SCL/CANRX
|
095 I2C_SCL/CANRX \ External CAN connection (or I2S, etc)
|
||||||
096 I2C_SDA/CANTX
|
096 I2C_SDA/CANTX /
|
||||||
097 PE0 DIR_1 direction of SM 1,2
|
097 PE0 DIR_1 direction of SM 1,2
|
||||||
098 PE1 DIR_2
|
098 PE1 DIR_2
|
||||||
099 VSS
|
099 VSS
|
||||||
|
|||||||
@ -1,4 +1,4 @@
|
|||||||
EESchema Schematic File Version 2 date Пн 29 сен 2014 14:40:29
|
EESchema Schematic File Version 2 date Вт 07 окт 2014 17:18:47
|
||||||
LIBS:power
|
LIBS:power
|
||||||
LIBS:device
|
LIBS:device
|
||||||
LIBS:transistors
|
LIBS:transistors
|
||||||
@ -41,7 +41,7 @@ $Descr A4 11693 8268
|
|||||||
encoding utf-8
|
encoding utf-8
|
||||||
Sheet 12 12
|
Sheet 12 12
|
||||||
Title "Power load module"
|
Title "Power load module"
|
||||||
Date "29 sep 2014"
|
Date "7 oct 2014"
|
||||||
Rev ""
|
Rev ""
|
||||||
Comp "SAO RAS"
|
Comp "SAO RAS"
|
||||||
Comment1 ""
|
Comment1 ""
|
||||||
|
|||||||
@ -1,4 +1,4 @@
|
|||||||
EESchema Schematic File Version 2 date Пн 29 сен 2014 14:40:29
|
EESchema Schematic File Version 2 date Вт 07 окт 2014 17:18:47
|
||||||
LIBS:power
|
LIBS:power
|
||||||
LIBS:device
|
LIBS:device
|
||||||
LIBS:transistors
|
LIBS:transistors
|
||||||
@ -41,7 +41,7 @@ $Descr A4 11693 8268
|
|||||||
encoding utf-8
|
encoding utf-8
|
||||||
Sheet 4 12
|
Sheet 4 12
|
||||||
Title "USB input circuit"
|
Title "USB input circuit"
|
||||||
Date "29 sep 2014"
|
Date "7 oct 2014"
|
||||||
Rev ""
|
Rev ""
|
||||||
Comp "SAO RAS"
|
Comp "SAO RAS"
|
||||||
Comment1 ""
|
Comment1 ""
|
||||||
@ -301,10 +301,20 @@ Wire Wire Line
|
|||||||
Wire Wire Line
|
Wire Wire Line
|
||||||
3900 2500 2500 2500
|
3900 2500 2500 2500
|
||||||
Connection ~ 2500 2500
|
Connection ~ 2500 2500
|
||||||
Connection ~ 3900 2500
|
|
||||||
Wire Wire Line
|
|
||||||
5200 2000 3900 2000
|
|
||||||
Wire Wire Line
|
|
||||||
3900 2000 3900 3300
|
|
||||||
Connection ~ 3900 3100
|
Connection ~ 3900 3100
|
||||||
|
Wire Wire Line
|
||||||
|
3900 3300 3900 2500
|
||||||
|
$Comp
|
||||||
|
L +3.3V #PWR?
|
||||||
|
U 1 1 5433F723
|
||||||
|
P 5200 1900
|
||||||
|
F 0 "#PWR?" H 5200 1860 30 0001 C CNN
|
||||||
|
F 1 "+3.3V" H 5200 2010 30 0000 C CNN
|
||||||
|
F 2 "" H 5200 1900 60 0000 C CNN
|
||||||
|
F 3 "" H 5200 1900 60 0000 C CNN
|
||||||
|
1 5200 1900
|
||||||
|
1 0 0 -1
|
||||||
|
$EndComp
|
||||||
|
Wire Wire Line
|
||||||
|
5200 1900 5200 2000
|
||||||
$EndSCHEMATC
|
$EndSCHEMATC
|
||||||
|
|||||||
@ -1,4 +1,4 @@
|
|||||||
EESchema Schematic File Version 2 date Пн 29 сен 2014 14:40:29
|
EESchema Schematic File Version 2 date Вт 07 окт 2014 17:18:47
|
||||||
LIBS:power
|
LIBS:power
|
||||||
LIBS:device
|
LIBS:device
|
||||||
LIBS:transistors
|
LIBS:transistors
|
||||||
@ -41,7 +41,7 @@ $Descr A4 11693 8268
|
|||||||
encoding utf-8
|
encoding utf-8
|
||||||
Sheet 2 12
|
Sheet 2 12
|
||||||
Title "Stepper motor module"
|
Title "Stepper motor module"
|
||||||
Date "29 sep 2014"
|
Date "7 oct 2014"
|
||||||
Rev ""
|
Rev ""
|
||||||
Comp "SAO RAS"
|
Comp "SAO RAS"
|
||||||
Comment1 ""
|
Comment1 ""
|
||||||
|
|||||||
@ -1,4 +1,4 @@
|
|||||||
EESchema Schematic File Version 2 date Пн 29 сен 2014 14:40:29
|
EESchema Schematic File Version 2 date Вт 07 окт 2014 17:18:47
|
||||||
LIBS:power
|
LIBS:power
|
||||||
LIBS:device
|
LIBS:device
|
||||||
LIBS:transistors
|
LIBS:transistors
|
||||||
@ -41,7 +41,7 @@ $Descr A4 11693 8268
|
|||||||
encoding utf-8
|
encoding utf-8
|
||||||
Sheet 11 12
|
Sheet 11 12
|
||||||
Title "Power load module"
|
Title "Power load module"
|
||||||
Date "29 sep 2014"
|
Date "7 oct 2014"
|
||||||
Rev ""
|
Rev ""
|
||||||
Comp "SAO RAS"
|
Comp "SAO RAS"
|
||||||
Comment1 ""
|
Comment1 ""
|
||||||
|
|||||||
@ -1,9 +1,11 @@
|
|||||||
BINARY = ircontroller
|
BINARY = ircontroller
|
||||||
BOOTPORT ?= /dev/ttyUSB0
|
BOOTPORT ?= /dev/ttyUSB0
|
||||||
BOOTSPEED ?= 115200
|
BOOTSPEED ?= 115200
|
||||||
LDSCRIPT = stm32-h103.ld
|
# change this linking script depending on particular MCU model,
|
||||||
|
# for example, if you have STM32F103VBT6, you should write:
|
||||||
|
LDSCRIPT = ld/stm32f103xB.ld
|
||||||
LIBNAME = opencm3_stm32f1
|
LIBNAME = opencm3_stm32f1
|
||||||
DEFS = -DSTM32F1
|
DEFS = -DSTM32F1 -DEBUG
|
||||||
|
|
||||||
OBJDIR = mk
|
OBJDIR = mk
|
||||||
INDEPENDENT_HEADERS=
|
INDEPENDENT_HEADERS=
|
||||||
@ -11,7 +13,6 @@ INDEPENDENT_HEADERS=
|
|||||||
FP_FLAGS ?= -msoft-float
|
FP_FLAGS ?= -msoft-float
|
||||||
ARCH_FLAGS = -mthumb -mcpu=cortex-m3 $(FP_FLAGS) -mfix-cortex-m3-ldrd
|
ARCH_FLAGS = -mthumb -mcpu=cortex-m3 $(FP_FLAGS) -mfix-cortex-m3-ldrd
|
||||||
|
|
||||||
|
|
||||||
###############################################################################
|
###############################################################################
|
||||||
# Executables
|
# Executables
|
||||||
PREFIX ?= arm-none-eabi
|
PREFIX ?= arm-none-eabi
|
||||||
@ -46,7 +47,7 @@ SCRIPT_DIR = $(OPENCM3_DIR)/scripts
|
|||||||
###############################################################################
|
###############################################################################
|
||||||
# C flags
|
# C flags
|
||||||
CFLAGS += -Os -g
|
CFLAGS += -Os -g
|
||||||
CFLAGS += -Wextra -Wshadow -Wimplicit-function-declaration
|
CFLAGS += -Wall -Wextra -Wshadow -Wimplicit-function-declaration
|
||||||
CFLAGS += -Wredundant-decls
|
CFLAGS += -Wredundant-decls
|
||||||
# -Wmissing-prototypes -Wstrict-prototypes
|
# -Wmissing-prototypes -Wstrict-prototypes
|
||||||
CFLAGS += -fno-common -ffunction-sections -fdata-sections
|
CFLAGS += -fno-common -ffunction-sections -fdata-sections
|
||||||
|
|||||||
1
with_opencm3/NVIC
Normal file
1
with_opencm3/NVIC
Normal file
@ -0,0 +1 @@
|
|||||||
|
don't forget to call nvic_enable_irq(irq) to allow interrupts
|
||||||
@ -1,3 +1,11 @@
|
|||||||
|
The work begins
|
||||||
|
First PCB have been prodused, so I need "only" to solder elements & finish the code
|
||||||
|
|
||||||
|
Pinout of MCI is in file schematics/STM32_PINS
|
||||||
|
|
||||||
|
|
||||||
|
-- OLD --
|
||||||
|
|
||||||
This is a sketch for futher work
|
This is a sketch for futher work
|
||||||
I found that libopencm3 is more friendly than SPL. Also I have some new thoughts about modular system: for
|
I found that libopencm3 is more friendly than SPL. Also I have some new thoughts about modular system: for
|
||||||
flexibility.
|
flexibility.
|
||||||
|
|||||||
@ -292,20 +292,19 @@ usbd_device *USB_init(){
|
|||||||
return current_usb;
|
return current_usb;
|
||||||
}
|
}
|
||||||
|
|
||||||
uint8_t send_block = 0;
|
mutex_t send_block_mutex = MUTEX_UNLOCKED;
|
||||||
/**
|
/**
|
||||||
* Put byte into USB buffer to send
|
* Put byte into USB buffer to send
|
||||||
* @param byte - a byte to put into a buffer
|
* @param byte - a byte to put into a buffer
|
||||||
*/
|
*/
|
||||||
void usb_send(uint8_t byte){
|
void usb_send(uint8_t byte){
|
||||||
while(send_block); // wait for unlock
|
mutex_lock(&send_block_mutex);
|
||||||
send_block = 1;
|
|
||||||
USB_Tx_Buffer[USB_Tx_ptr++] = byte;
|
USB_Tx_Buffer[USB_Tx_ptr++] = byte;
|
||||||
if(USB_Tx_ptr == USB_TX_DATA_SIZE){ // buffer can be overflowed - send it!
|
if(USB_Tx_ptr == USB_TX_DATA_SIZE){ // buffer can be overflowed - send it!
|
||||||
send_block = 0;
|
mutex_unlock(&send_block_mutex);
|
||||||
usb_send_buffer();
|
usb_send_buffer();
|
||||||
}
|
}else
|
||||||
send_block = 0;
|
mutex_unlock(&send_block_mutex);
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@ -313,8 +312,7 @@ void usb_send(uint8_t byte){
|
|||||||
* this function runs when buffer is full or on SysTick
|
* this function runs when buffer is full or on SysTick
|
||||||
*/
|
*/
|
||||||
void usb_send_buffer(){
|
void usb_send_buffer(){
|
||||||
if(send_block) return;
|
if(MUTEX_LOCKED == mutex_trylock(&send_block_mutex)) return;
|
||||||
send_block = 1;
|
|
||||||
if(USB_Tx_ptr){
|
if(USB_Tx_ptr){
|
||||||
if(current_usb && USB_connected){
|
if(current_usb && USB_connected){
|
||||||
// usbd_ep_write_packet return 0 if previous packet isn't transmit yet
|
// usbd_ep_write_packet return 0 if previous packet isn't transmit yet
|
||||||
@ -323,5 +321,5 @@ void usb_send_buffer(){
|
|||||||
}
|
}
|
||||||
USB_Tx_ptr = 0;
|
USB_Tx_ptr = 0;
|
||||||
}
|
}
|
||||||
send_block = 0;
|
mutex_unlock(&send_block_mutex);
|
||||||
}
|
}
|
||||||
|
|||||||
@ -31,14 +31,17 @@ function [Time T Tfxd] = get_T(filename, filter_treshold)
|
|||||||
endfor
|
endfor
|
||||||
endif
|
endif
|
||||||
|
|
||||||
plot(Time, R);
|
Leg = ['1'; '2'; '3'; '4'; '5'; '6'; '7'; '8'];
|
||||||
|
|
||||||
|
more_colors(plot(Time, R), 8);
|
||||||
Tit = sprintf("Resistance, \\Omega");
|
Tit = sprintf("Resistance, \\Omega");
|
||||||
xlabel("Time, s"); ylabel("R, \\Omega"); title(Tit);
|
xlabel("Time, s"); ylabel("R, \\Omega"); title(Tit);
|
||||||
print -dpng -color resistance.png;
|
print -dpng -color resistance.png;
|
||||||
close
|
close
|
||||||
plot(Time, T);
|
more_colors(plot(Time, T), 8);
|
||||||
Tit = sprintf("Temperature, ^\\circ{}C");
|
Tit = sprintf("Temperature, ^\\circ{}C");
|
||||||
xlabel("Time, s"); ylabel("T, ^\\circ{}C"); title(Tit);
|
xlabel("Time, s"); ylabel("T, ^\\circ{}C"); title(Tit);
|
||||||
|
legend(Leg);
|
||||||
print -dpng -color temperatures.png;
|
print -dpng -color temperatures.png;
|
||||||
close
|
close
|
||||||
|
|
||||||
@ -46,12 +49,18 @@ function [Time T Tfxd] = get_T(filename, filter_treshold)
|
|||||||
Tavr = mean(T, 2);
|
Tavr = mean(T, 2);
|
||||||
Tadd = mean(T - repmat(Tavr, [1 8]));
|
Tadd = mean(T - repmat(Tavr, [1 8]));
|
||||||
Tfxd = T - repmat(Tadd,[size(T,1) 1]);
|
Tfxd = T - repmat(Tadd,[size(T,1) 1]);
|
||||||
plot(Time, Tfxd);
|
more_colors(plot(Time, Tfxd), 8);
|
||||||
Tit = sprintf("Temperature fixed to average value, ^\\circ{}C");
|
Tit = sprintf("Temperature fixed to average value, ^\\circ{}C");
|
||||||
xlabel("Time, s"); ylabel("T, ^\\circ{}C"); title(Tit);
|
xlabel("Time, s"); ylabel("T, ^\\circ{}C"); title(Tit);
|
||||||
print -dpng -color temperatures_fixed.png;
|
print -dpng -color temperatures_fixed.png;
|
||||||
|
legend(Leg);
|
||||||
close
|
close
|
||||||
printf("differences:\n"); printf("%g\n", -Tadd);
|
printf("differences:\n"); printf("%g\n", -Tadd);
|
||||||
endfunction
|
endfunction
|
||||||
|
|
||||||
|
function more_colors(h, N)
|
||||||
|
palette = jet (N);
|
||||||
|
for i = 1:N
|
||||||
|
set(h(i),"color",palette(i,:))
|
||||||
|
endfor
|
||||||
|
endfunction
|
||||||
|
|||||||
@ -19,24 +19,108 @@
|
|||||||
* MA 02110-1301, USA.
|
* MA 02110-1301, USA.
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
/*
|
||||||
|
* All hardware-dependent initialisation & definition should be placed here
|
||||||
|
* and in hardware_ini.h
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
#include "main.h"
|
#include "main.h"
|
||||||
#include "hardware_ini.h"
|
#include "hardware_ini.h"
|
||||||
|
|
||||||
volatile uint16_t ADC_value[8]; // ADC DMA value
|
volatile uint16_t ADC_value[8]; // ADC DMA value
|
||||||
|
|
||||||
/**
|
/*
|
||||||
* GPIO initialisaion: clocking + ports setup
|
* Configure SPI ports
|
||||||
*/
|
*/
|
||||||
void GPIO_init(){
|
/*
|
||||||
rcc_periph_clock_enable(RCC_GPIOC);
|
* SPI1 remapped:
|
||||||
gpio_set_mode(GPIOC, GPIO_MODE_OUTPUT_2_MHZ,
|
* SCK - PB3
|
||||||
GPIO_CNF_OUTPUT_PUSHPULL, GPIO11|GPIO12); // LED + USB
|
* MISO - PB4
|
||||||
// AD7794 addr + en
|
* MOSI - PB5
|
||||||
gpio_set_mode(GPIOC, GPIO_MODE_OUTPUT_2_MHZ,
|
*/
|
||||||
GPIO_CNF_OUTPUT_PUSHPULL, ADC_ADDR_MASK | GPIO10); // ADDRESS: PC6..9; EN: PC10
|
void SPI1_init(){
|
||||||
GPIO_BSRR(GPIOC) = (ADC_ADDR_MASK | GPIO10) << 16; // clear address & disable com
|
// enable AFIO & other clocking
|
||||||
|
rcc_peripheral_enable_clock(&RCC_APB2ENR,
|
||||||
|
RCC_APB2ENR_SPI1EN | RCC_APB2ENR_AFIOEN | RCC_APB2ENR_IOPBEN);
|
||||||
|
// remap SPI1 (change pins from PA5..7 to PB3..5); also turn off JTAG
|
||||||
|
gpio_primary_remap(AFIO_MAPR_SWJ_CFG_JTAG_OFF_SW_OFF, AFIO_MAPR_SPI1_REMAP);
|
||||||
|
// SCK, MOSI - push-pull output
|
||||||
|
gpio_set_mode(GPIO_BANK_SPI1_RE_SCK, GPIO_MODE_OUTPUT_50_MHZ,
|
||||||
|
GPIO_CNF_OUTPUT_ALTFN_PUSHPULL, GPIO_SPI1_RE_SCK);
|
||||||
|
gpio_set_mode(GPIO_BANK_SPI1_RE_MOSI, GPIO_MODE_OUTPUT_50_MHZ,
|
||||||
|
GPIO_CNF_OUTPUT_ALTFN_PUSHPULL, GPIO_SPI1_RE_MOSI);
|
||||||
|
// MISO - opendrain in
|
||||||
|
gpio_set_mode(GPIO_BANK_SPI1_RE_MISO, GPIO_MODE_INPUT, GPIO_CNF_INPUT_FLOAT, GPIO_SPI1_RE_MISO);
|
||||||
|
spi_reset(SPI1);
|
||||||
|
/* Set up SPI in Master mode with:
|
||||||
|
* Clock baud rate: 1/128 of peripheral clock frequency (APB2, 72MHz)
|
||||||
|
* Clock polarity: Idle High
|
||||||
|
* Clock phase: Data valid on 2nd clock pulse
|
||||||
|
* Data frame format: 8-bit
|
||||||
|
* Frame format: MSB First
|
||||||
|
*/
|
||||||
|
spi_init_master(SPI1, SPI_CR1_BAUDRATE_FPCLK_DIV_128, SPI_CR1_CPOL_CLK_TO_1_WHEN_IDLE,
|
||||||
|
SPI_CR1_CPHA_CLK_TRANSITION_2, SPI_CR1_DFF_8BIT, SPI_CR1_MSBFIRST);
|
||||||
|
nvic_enable_irq(NVIC_SPI1_IRQ); // enable SPI interrupt
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/*
|
||||||
|
* SPI2:
|
||||||
|
* SCK - PB13
|
||||||
|
* MISO - PB14
|
||||||
|
* MOSI - PB15
|
||||||
|
*/
|
||||||
|
void SPI2_init(){
|
||||||
|
// turn on clocking
|
||||||
|
//rcc_periph_clock_enable(RCC_SPI2 | RCC_GPIOB);
|
||||||
|
rcc_peripheral_enable_clock(&RCC_APB1ENR, RCC_APB1ENR_SPI2EN);
|
||||||
|
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_AFIOEN | RCC_APB2ENR_IOPBEN);
|
||||||
|
// SCK, MOSI - push-pull output
|
||||||
|
gpio_set_mode(GPIO_BANK_SPI2_SCK, GPIO_MODE_OUTPUT_50_MHZ,
|
||||||
|
GPIO_CNF_OUTPUT_ALTFN_PUSHPULL, GPIO_SPI2_SCK);
|
||||||
|
gpio_set_mode(GPIO_BANK_SPI2_MOSI, GPIO_MODE_OUTPUT_50_MHZ,
|
||||||
|
GPIO_CNF_OUTPUT_ALTFN_PUSHPULL, GPIO_SPI2_MOSI);
|
||||||
|
// MISO - opendrain in
|
||||||
|
gpio_set_mode(GPIO_BANK_SPI2_MISO, GPIO_MODE_INPUT, GPIO_CNF_INPUT_FLOAT, GPIO_SPI2_MISO);
|
||||||
|
spi_reset(SPI2);
|
||||||
|
/* Set up SPI in Master mode with:
|
||||||
|
* Clock baud rate: 1/64 of peripheral clock frequency (APB1, 36MHz)
|
||||||
|
* Clock polarity: Idle High
|
||||||
|
* Clock phase: Data valid on 2nd clock pulse
|
||||||
|
* Data frame format: 8-bit
|
||||||
|
* Frame format: MSB First
|
||||||
|
*/
|
||||||
|
spi_init_master(SPI2, SPI_CR1_BAUDRATE_FPCLK_DIV_64, SPI_CR1_CPOL_CLK_TO_1_WHEN_IDLE,
|
||||||
|
SPI_CR1_CPHA_CLK_TRANSITION_2, SPI_CR1_DFF_8BIT, SPI_CR1_MSBFIRST);
|
||||||
|
nvic_enable_irq(NVIC_SPI2_IRQ); // enable SPI interrupt
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* 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);
|
||||||
|
// USB_DISC: push-pull
|
||||||
|
gpio_set_mode(USB_DISC_PORT, GPIO_MODE_OUTPUT_2_MHZ,
|
||||||
|
GPIO_CNF_OUTPUT_PUSHPULL, USB_DISC_PIN);
|
||||||
|
// USB_POWER: open drain, externall pull down with R7 (22k)
|
||||||
|
gpio_set_mode(USB_POWER_PORT, GPIO_MODE_INPUT,
|
||||||
|
GPIO_CNF_INPUT_FLOAT, USB_POWER_PIN);
|
||||||
|
// AD7794 addr + en
|
||||||
|
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
|
||||||
|
}
|
||||||
|
|
||||||
|
/*
|
||||||
|
* SysTick used for system timer with period of 1ms
|
||||||
|
*/
|
||||||
void SysTick_init(){
|
void SysTick_init(){
|
||||||
systick_set_clocksource(STK_CSR_CLKSOURCE_AHB_DIV8); // Systyck: 72/8=9MHz
|
systick_set_clocksource(STK_CSR_CLKSOURCE_AHB_DIV8); // Systyck: 72/8=9MHz
|
||||||
systick_set_reload(8999); // 9000 pulses: 1kHz
|
systick_set_reload(8999); // 9000 pulses: 1kHz
|
||||||
@ -44,13 +128,31 @@ void SysTick_init(){
|
|||||||
systick_counter_enable();
|
systick_counter_enable();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/*
|
||||||
|
* Due to inconvenient pins position on STM32F103VxT6 I had to make this strange location:
|
||||||
|
* my channel # -> ADC1/2 channel #
|
||||||
|
* 0 -> 9 PB1
|
||||||
|
* 1 -> 8 PB0
|
||||||
|
* 2 -> 15 PC5
|
||||||
|
* 3 -> 14 PC4
|
||||||
|
* 4 -> 7 PA7
|
||||||
|
* 5 -> 6 PA6
|
||||||
|
* 6 -> 5 PA5
|
||||||
|
* 7 -> 4 PA4
|
||||||
|
*/
|
||||||
|
uint8_t adc_channel_array[16] = {9,8,15,14,7,6,5,4};
|
||||||
|
#define ADC_CHANNELS_NUMBER 8
|
||||||
void ADC_init(){
|
void ADC_init(){
|
||||||
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_ADC1EN); // enable clocking
|
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_ADC1EN); // enable clocking
|
||||||
rcc_periph_clock_enable(RCC_ADC1);
|
rcc_periph_clock_enable(RCC_ADC1);
|
||||||
rcc_set_adcpre(RCC_CFGR_ADCPRE_PCLK2_DIV4);
|
rcc_set_adcpre(RCC_CFGR_ADCPRE_PCLK2_DIV4);
|
||||||
rcc_periph_clock_enable(RCC_GPIOB | RCC_GPIOC); // clocking for ADC ports
|
rcc_periph_clock_enable(RCC_GPIOA | RCC_GPIOB | RCC_GPIOC); // clocking for ADC ports
|
||||||
gpio_set_mode(GPIOB, GPIO_MODE_INPUT, GPIO_CNF_INPUT_ANALOG, 3); // ADC8 - PB0, ADC9 -PB1
|
// channels 4-7: PA7-PA4
|
||||||
gpio_set_mode(GPIOC, GPIO_MODE_INPUT, GPIO_CNF_INPUT_ANALOG, 63); // ADC10-15: PC0-PC5
|
gpio_set_mode(GPIOA, GPIO_MODE_INPUT, GPIO_CNF_INPUT_ANALOG, GPIO4|GPIO5|GPIO6|GPIO7);
|
||||||
|
// channels 0,1: PB1, PB0
|
||||||
|
gpio_set_mode(GPIOB, GPIO_MODE_INPUT, GPIO_CNF_INPUT_ANALOG, GPIO0|GPIO1);
|
||||||
|
// channels 2,3: PC5, PC4
|
||||||
|
gpio_set_mode(GPIOC, GPIO_MODE_INPUT, GPIO_CNF_INPUT_ANALOG, GPIO4|GPIO5);
|
||||||
|
|
||||||
// Make sure the ADC doesn't run during config
|
// Make sure the ADC doesn't run during config
|
||||||
adc_off(ADC1);
|
adc_off(ADC1);
|
||||||
@ -60,7 +162,7 @@ void ADC_init(){
|
|||||||
dma_channel_reset(DMA1, DMA_CHANNEL1); //DMA_DeInit(DMA1_Channel1);
|
dma_channel_reset(DMA1, DMA_CHANNEL1); //DMA_DeInit(DMA1_Channel1);
|
||||||
dma_set_peripheral_address(DMA1, DMA_CHANNEL1, (uint32_t) &(ADC_DR(ADC1))); // DMA_InitStructure.DMA_PeripheralBaseAddr = ADC1_DR_Address;
|
dma_set_peripheral_address(DMA1, DMA_CHANNEL1, (uint32_t) &(ADC_DR(ADC1))); // DMA_InitStructure.DMA_PeripheralBaseAddr = ADC1_DR_Address;
|
||||||
dma_set_memory_address(DMA1, DMA_CHANNEL1, (uint32_t) ADC_value); // DMA_InitStructure.DMA_MemoryBaseAddr = (uint32_t)&ADC_value;
|
dma_set_memory_address(DMA1, DMA_CHANNEL1, (uint32_t) ADC_value); // DMA_InitStructure.DMA_MemoryBaseAddr = (uint32_t)&ADC_value;
|
||||||
dma_set_number_of_data(DMA1, DMA_CHANNEL1, 8); // DMA_InitStructure.DMA_BufferSize = 1;
|
dma_set_number_of_data(DMA1, DMA_CHANNEL1, ADC_CHANNELS_NUMBER); // DMA_InitStructure.DMA_BufferSize = 1;
|
||||||
dma_set_read_from_peripheral(DMA1, DMA_CHANNEL1); // DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralSRC;
|
dma_set_read_from_peripheral(DMA1, DMA_CHANNEL1); // DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralSRC;
|
||||||
dma_enable_memory_increment_mode(DMA1, DMA_CHANNEL1); // DMA_InitStructure.DMA_MemoryInc = DMA_MemoryInc_Disable;
|
dma_enable_memory_increment_mode(DMA1, DMA_CHANNEL1); // DMA_InitStructure.DMA_MemoryInc = DMA_MemoryInc_Disable;
|
||||||
dma_disable_peripheral_increment_mode(DMA1, DMA_CHANNEL1); // DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable;
|
dma_disable_peripheral_increment_mode(DMA1, DMA_CHANNEL1); // DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable;
|
||||||
@ -76,8 +178,8 @@ void ADC_init(){
|
|||||||
adc_set_continuous_conversion_mode(ADC1); // ADC_InitStructure.ADC_ContinuousConvMode = ENABLE;
|
adc_set_continuous_conversion_mode(ADC1); // ADC_InitStructure.ADC_ContinuousConvMode = ENABLE;
|
||||||
adc_disable_external_trigger_regular(ADC1); // ADC_InitStructure.ADC_ExternalTrigConv = ADC_ExternalTrigConv_None;
|
adc_disable_external_trigger_regular(ADC1); // ADC_InitStructure.ADC_ExternalTrigConv = ADC_ExternalTrigConv_None;
|
||||||
adc_set_right_aligned(ADC1); // ADC_InitStructure.ADC_DataAlign = ADC_DataAlign_Right;
|
adc_set_right_aligned(ADC1); // ADC_InitStructure.ADC_DataAlign = ADC_DataAlign_Right;
|
||||||
//adc_set_sample_time_on_all_channels(ADC1, ADC_SMPR_SMP_239DOT5CYC); // ADC_SampleTime_239Cycles5
|
adc_set_sample_time_on_all_channels(ADC1, ADC_SMPR_SMP_239DOT5CYC); // ADC_SampleTime_239Cycles5
|
||||||
adc_set_sample_time(ADC1, ADC_CHANNEL8, ADC_SMPR_SMP_239DOT5CYC); // ADC_RegularChannelConfig(ADC1, ADC_Channel_8, 1, ADC_SampleTime_239Cycles5);
|
//adc_set_sample_time(ADC1, ADC_CHANNEL8, ADC_SMPR_SMP_239DOT5CYC); // ADC_RegularChannelConfig(ADC1, ADC_Channel_8, 1, ADC_SampleTime_239Cycles5);
|
||||||
adc_enable_dma(ADC1); // ADC_DMACmd(ADC1, ENABLE);
|
adc_enable_dma(ADC1); // ADC_DMACmd(ADC1, ENABLE);
|
||||||
adc_power_on(ADC1); // ADC_Cmd(ADC1, ENABLE);
|
adc_power_on(ADC1); // ADC_Cmd(ADC1, ENABLE);
|
||||||
}
|
}
|
||||||
@ -87,13 +189,112 @@ void ADC_init(){
|
|||||||
* First call ADC_init(), than wait a little and call this function
|
* First call ADC_init(), than wait a little and call this function
|
||||||
*/
|
*/
|
||||||
void ADC_calibrate_and_start(){
|
void ADC_calibrate_and_start(){
|
||||||
uint8_t channel_array[16] = {8,9,10,11,12,13,14,15};
|
adc_set_regular_sequence(ADC1, ADC_CHANNELS_NUMBER, adc_channel_array);
|
||||||
// adc_set_regular_sequence 1 channel -- 0 // ADC_InitStructure.ADC_NbrOfChannel = 1;
|
|
||||||
channel_array[0] = ADC_CHANNEL8;
|
|
||||||
adc_set_regular_sequence(ADC1, 8, channel_array);
|
|
||||||
adc_reset_calibration(ADC1);
|
adc_reset_calibration(ADC1);
|
||||||
adc_calibration(ADC1);
|
adc_calibration(ADC1);
|
||||||
adc_start_conversion_regular(ADC1); // ADC_SoftwareStartConvCmd(ADC1, ENABLE);
|
adc_start_conversion_regular(ADC1); // ADC_SoftwareStartConvCmd(ADC1, ENABLE);
|
||||||
adc_start_conversion_direct(ADC1);
|
adc_start_conversion_direct(ADC1);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
uint16_t tim2_buff[8] = {10,20,30,40,50,60,70,80};
|
||||||
|
uint16_t tim2_inbuff[8];
|
||||||
|
|
||||||
|
void init_dmatimer(){ // tim2_ch4 - PA3, no remap
|
||||||
|
gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_50_MHZ,
|
||||||
|
GPIO_CNF_OUTPUT_ALTFN_OPENDRAIN, GPIO3);
|
||||||
|
rcc_periph_clock_enable(RCC_TIM2);
|
||||||
|
timer_reset(TIM2);
|
||||||
|
// timers have frequency of 1MHz -- 1us for one step
|
||||||
|
// 36MHz of APB1
|
||||||
|
timer_set_mode(TIM2, TIM_CR1_CKD_CK_INT, TIM_CR1_CMS_EDGE, TIM_CR1_DIR_UP);
|
||||||
|
// 72MHz div 72 = 1MHz
|
||||||
|
timer_set_prescaler(TIM2, 71); // prescaler is (div - 1)
|
||||||
|
timer_continuous_mode(TIM2); // automatically reload
|
||||||
|
timer_enable_preload(TIM2); // force changing period
|
||||||
|
timer_set_period(TIM2, 86); // period is 87us
|
||||||
|
timer_enable_update_event(TIM2);
|
||||||
|
timer_set_oc_mode(TIM2, TIM_OC4, TIM_OCM_PWM1); // edge-aligned mode
|
||||||
|
timer_enable_oc_preload(TIM2, TIM_OC4);
|
||||||
|
timer_enable_oc_output(TIM2, TIM_OC4);
|
||||||
|
timer_enable_irq(TIM2, TIM_DIER_UDE | TIM_DIER_CC4DE | TIM_DIER_CC3DE);
|
||||||
|
timer_set_oc_polarity_low(TIM2, TIM_OC4);
|
||||||
|
|
||||||
|
// TIM2_CH4 - DMA1, channel 7
|
||||||
|
rcc_periph_clock_enable(RCC_DMA1);
|
||||||
|
dma_channel_reset(DMA1, DMA_CHANNEL7);
|
||||||
|
dma_set_peripheral_address(DMA1, DMA_CHANNEL7, (uint32_t) &(TIM_CCR4(TIM2)));
|
||||||
|
dma_set_read_from_memory(DMA1, DMA_CHANNEL7);
|
||||||
|
dma_enable_memory_increment_mode(DMA1, DMA_CHANNEL7);
|
||||||
|
dma_disable_peripheral_increment_mode(DMA1, DMA_CHANNEL7);
|
||||||
|
dma_set_peripheral_size(DMA1, DMA_CHANNEL7, DMA_CCR_PSIZE_16BIT);
|
||||||
|
dma_set_memory_size(DMA1, DMA_CHANNEL7, DMA_CCR_MSIZE_16BIT);
|
||||||
|
dma_enable_transfer_error_interrupt(DMA1, DMA_CHANNEL7);
|
||||||
|
dma_enable_transfer_complete_interrupt(DMA1, DMA_CHANNEL7);
|
||||||
|
dma_set_memory_address(DMA1, DMA_CHANNEL7, (uint32_t)tim2_buff);
|
||||||
|
|
||||||
|
nvic_enable_irq(NVIC_DMA1_CHANNEL7_IRQ); // enable dma1_channel7_isr
|
||||||
|
|
||||||
|
// capture: TIM2_CH3
|
||||||
|
timer_ic_set_input(TIM2, TIM_IC3, TIM_IC_IN_TI4);
|
||||||
|
timer_set_oc_polarity_high(TIM2, TIM_OC3);
|
||||||
|
timer_ic_enable(TIM2, TIM_IC3);
|
||||||
|
timer_enable_oc_output(TIM2, TIM_OC3);
|
||||||
|
|
||||||
|
// configure DMA1 Channel1 (ADC1)
|
||||||
|
dma_channel_reset(DMA1, DMA_CHANNEL1);
|
||||||
|
dma_set_peripheral_address(DMA1, DMA_CHANNEL1, (uint32_t) &(TIM_CCR3(TIM2)));
|
||||||
|
dma_set_memory_address(DMA1, DMA_CHANNEL1, (uint32_t) tim2_inbuff);
|
||||||
|
dma_set_number_of_data(DMA1, DMA_CHANNEL1, 8);
|
||||||
|
dma_set_read_from_peripheral(DMA1, DMA_CHANNEL1);
|
||||||
|
dma_enable_memory_increment_mode(DMA1, DMA_CHANNEL1);
|
||||||
|
dma_disable_peripheral_increment_mode(DMA1, DMA_CHANNEL1);
|
||||||
|
dma_set_peripheral_size(DMA1, DMA_CHANNEL1, DMA_CCR_PSIZE_16BIT);
|
||||||
|
dma_set_memory_size(DMA1, DMA_CHANNEL1, DMA_CCR_MSIZE_16BIT);
|
||||||
|
nvic_enable_irq(NVIC_DMA1_CHANNEL1_IRQ);
|
||||||
|
dma_enable_transfer_error_interrupt(DMA1, DMA_CHANNEL1);
|
||||||
|
dma_enable_transfer_complete_interrupt(DMA1, DMA_CHANNEL1);
|
||||||
|
}
|
||||||
|
|
||||||
|
void run_dmatimer(){
|
||||||
|
int i;
|
||||||
|
DMA1_IFCR = DMA_ISR_TEIF7|DMA_ISR_HTIF7|DMA_ISR_TCIF7|DMA_ISR_GIF7 |
|
||||||
|
DMA_ISR_TEIF1|DMA_ISR_HTIF1|DMA_ISR_TCIF1|DMA_ISR_GIF1; // clear flags
|
||||||
|
|
||||||
|
dma_set_number_of_data(DMA1, DMA_CHANNEL7, 8);
|
||||||
|
timer_set_dma_on_compare_event(TIM2);
|
||||||
|
timer_enable_oc_output(TIM2, TIM_OC4);
|
||||||
|
dma_enable_channel(DMA1, DMA_CHANNEL7);
|
||||||
|
timer_enable_counter(TIM2);
|
||||||
|
|
||||||
|
for(i = 0; i < 8; i++) tim2_inbuff[i] = 0;
|
||||||
|
dma_set_number_of_data(DMA1, DMA_CHANNEL1, 8);
|
||||||
|
dma_enable_channel(DMA1, DMA_CHANNEL1);
|
||||||
|
}
|
||||||
|
|
||||||
|
void dma1_channel7_isr(){
|
||||||
|
if(DMA1_ISR & DMA_ISR_TCIF7) {
|
||||||
|
DMA1_IFCR = DMA_IFCR_CTCIF7;
|
||||||
|
dma_disable_channel(DMA1, DMA_CHANNEL7);
|
||||||
|
}else if(DMA1_ISR & DMA_ISR_TEIF7){
|
||||||
|
DMA1_IFCR = DMA_IFCR_CTEIF7;
|
||||||
|
MSG("out transfer error\n");
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void dma1_channel1_isr(){
|
||||||
|
int i;
|
||||||
|
if(DMA1_ISR & DMA_ISR_TCIF1) {
|
||||||
|
DMA1_IFCR = DMA_IFCR_CTCIF1;
|
||||||
|
dma_disable_channel(DMA1, DMA_CHANNEL1);
|
||||||
|
timer_disable_counter(TIM2);
|
||||||
|
gpio_set(GPIOA, GPIO3);
|
||||||
|
for(i = 0; i < 8; i++){
|
||||||
|
print_int(tim2_inbuff[i], lastsendfun);
|
||||||
|
MSG(" ");
|
||||||
|
}
|
||||||
|
MSG("\n");
|
||||||
|
}else if(DMA1_ISR & DMA_ISR_TEIF1){
|
||||||
|
DMA1_IFCR = DMA_IFCR_CTEIF1;
|
||||||
|
MSG("in transfer error\n");
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|||||||
@ -23,23 +23,72 @@
|
|||||||
#ifndef __HARDWARE_INI_H__
|
#ifndef __HARDWARE_INI_H__
|
||||||
#define __HARDWARE_INI_H__
|
#define __HARDWARE_INI_H__
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
extern volatile uint16_t ADC_value[]; // ADC DMA value
|
extern volatile uint16_t ADC_value[]; // ADC DMA value
|
||||||
|
|
||||||
#define ADC_ADDR_MASK (GPIO6|GPIO7|GPIO8|GPIO9)
|
|
||||||
#define TRD_NO 8 // number of TRD devices
|
#define TRD_NO 8 // number of TRD devices
|
||||||
|
// bits used to address external SPI ADC - PD10..12
|
||||||
|
#define ADC_ADDR_MASK (GPIO10|GPIO11|GPIO12)
|
||||||
|
#define ADC_SET_ADDR(X) ((X << 10) & ADC_ADDR_MASK)
|
||||||
|
#define ADC_EN_PIN GPIO13
|
||||||
|
#define ADC_ADDR_PORT GPIOD
|
||||||
|
|
||||||
|
void SPI1_init();
|
||||||
|
void SPI2_init();
|
||||||
void GPIO_init();
|
void GPIO_init();
|
||||||
void SysTick_init();
|
void SysTick_init();
|
||||||
void ADC_init();
|
void ADC_init();
|
||||||
void ADC_calibrate_and_start();
|
void ADC_calibrate_and_start();
|
||||||
|
|
||||||
|
/*
|
||||||
|
* USB interface
|
||||||
|
*/
|
||||||
|
// USB_DICS (disconnect) - PC11
|
||||||
|
#define USB_DISC_PIN GPIO11
|
||||||
|
#define USB_DISC_PORT GPIOC
|
||||||
|
// USB_POWER (high level when USB connected to PC)
|
||||||
|
#define USB_POWER_PIN GPIO10
|
||||||
|
#define USB_POWER_PORT GPIOC
|
||||||
|
// change signal level on USB diconnect pin
|
||||||
|
#define usb_disc_high() gpio_set(USB_DISC_PORT, USB_DISC_PIN)
|
||||||
|
#define usb_disc_low() gpio_clear(USB_DISC_PORT, USB_DISC_PIN)
|
||||||
|
// in case of pnp bipolar transistor on 1.5k pull-up disconnect means low level
|
||||||
|
// in case of p-channel FET on 1.5k pull-up change on/off disconnect means high level
|
||||||
|
#define usb_disconnect() usb_disc_low()
|
||||||
|
#define usb_connect() usb_disc_high()
|
||||||
|
|
||||||
|
/*
|
||||||
|
* Stepper motors
|
||||||
|
* motors' interface use timers 1 & 2, so even hardware-dependent functions are
|
||||||
|
* moved to stepper_motors.c
|
||||||
|
*/
|
||||||
|
// PE7..11 - EN
|
||||||
|
#define MOROT_EN_MASK (0x1f << 7)
|
||||||
|
#define MOTOR_EN_PORT (GPIOE)
|
||||||
|
// N == 1..5
|
||||||
|
#define MOTOR_EN_PIN(N) (GPIO6 << (N))
|
||||||
|
// PE0..PE5 - DIR
|
||||||
|
#define MOROT_DIR_MASK (0x1f)
|
||||||
|
#define MOTOR_DIR_PORT (GPIOE)
|
||||||
|
// N == 1..5
|
||||||
|
#define MOTOR_DIR_PIN(N) (GPIO0 << (N - 1))
|
||||||
|
// timers: TIM1 - PC6, TIM2 - PD15
|
||||||
|
#define MOTOR_TIM1_PORT (GPIOC)
|
||||||
|
#define MOTOR_TIM1_PIN (GPIO6)
|
||||||
|
#define MOTOR_TIM2_PORT (GPIOD)
|
||||||
|
#define MOTOR_TIM2_PIN (GPIO15)
|
||||||
|
|
||||||
/*
|
/*
|
||||||
* One Wire interface
|
* One Wire interface
|
||||||
*/
|
*/
|
||||||
// In case of using USART2 for 1-wire port, make corresponding change
|
// In case of using other USART for 1-wire port, make corresponding change
|
||||||
// and redefine pins in OW_Init
|
// and redefine pins in OW_Init
|
||||||
//#define OW_USART_X USART2
|
#define OW_USART_X USART2
|
||||||
#define OW_USART_X USART3
|
#define OW_RX_PORT GPIO_BANK_USART2_RX
|
||||||
|
#define OW_RX_PIN GPIO_USART2_RX
|
||||||
|
|
||||||
|
void init_dmatimer();
|
||||||
|
void run_dmatimer();
|
||||||
|
|
||||||
#endif // __HARDWARE_INI_H__
|
#endif // __HARDWARE_INI_H__
|
||||||
|
|||||||
Binary file not shown.
@ -24,6 +24,7 @@
|
|||||||
#include "cdcacm.h"
|
#include "cdcacm.h"
|
||||||
#include "uart.h"
|
#include "uart.h"
|
||||||
#include "spi.h"
|
#include "spi.h"
|
||||||
|
#include "stepper_motors.h"
|
||||||
|
|
||||||
volatile uint32_t Timer = 0, tOVRFL = 0; // global timer (milliseconds), overflow counter
|
volatile uint32_t Timer = 0, tOVRFL = 0; // global timer (milliseconds), overflow counter
|
||||||
usbd_device *usbd_dev;
|
usbd_device *usbd_dev;
|
||||||
@ -55,10 +56,7 @@ void read_next_TRD(){
|
|||||||
//P("Step 0: read_next_TRD, N=", uart1_send);
|
//P("Step 0: read_next_TRD, N=", uart1_send);
|
||||||
//print_int(N, uart1_send);
|
//print_int(N, uart1_send);
|
||||||
//newline(uart1_send);
|
//newline(uart1_send);
|
||||||
GPIO_BSRR(GPIOC) = N << 6; // set address
|
gpio_set(ADC_ADDR_PORT, ADC_SET_ADDR(N) | ADC_EN_PIN); // set address & enable switch
|
||||||
GPIO_BSRR(GPIOC) = GPIO10; // enable com
|
|
||||||
N++; // and increment TRD counter
|
|
||||||
if(N == TRD_NO) N = 0;
|
|
||||||
val0 = val1 = 0;
|
val0 = val1 = 0;
|
||||||
step++;
|
step++;
|
||||||
break;
|
break;
|
||||||
@ -102,17 +100,29 @@ void read_next_TRD(){
|
|||||||
break;
|
break;
|
||||||
default: // last step - turn off multiplexer
|
default: // last step - turn off multiplexer
|
||||||
step = 0;
|
step = 0;
|
||||||
GPIO_BSRR(GPIOC) = (ADC_ADDR_MASK | GPIO10) << 16; // disable com & clear address bytes
|
gpio_clear(ADC_ADDR_PORT, ADC_ADDR_MASK | ADC_EN_PIN); // disable com & clear address bytes
|
||||||
|
N++; // and increment TRD counter
|
||||||
|
if(N == TRD_NO) N = 0;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
//uint8_t curSPI = 1;
|
||||||
|
|
||||||
void AD7794_init(){
|
void AD7794_init(){
|
||||||
uint8_t i;
|
uint8_t i;
|
||||||
ad7794_on = 0;
|
ad7794_on = 0;
|
||||||
i = reset_AD7794();
|
i = reset_AD7794();
|
||||||
if(i != ADC_NO_ERROR){
|
if(i != ADC_NO_ERROR){
|
||||||
if(i == ADC_ERR_NO_DEVICE){
|
if(i == ADC_ERR_NO_DEVICE){
|
||||||
MSG("ADC signal is absent! Check connection.\r\n");
|
// print_int(curSPI, lastsendfun);
|
||||||
|
MSG(": ADC signal is absent! Check connection.\r\n");
|
||||||
|
/* if(curSPI == 1){
|
||||||
|
curSPI = 2;
|
||||||
|
switch_SPI(SPI2);
|
||||||
|
}else{
|
||||||
|
curSPI = 1;
|
||||||
|
switch_SPI(SPI1);
|
||||||
|
}*/
|
||||||
}
|
}
|
||||||
}else{
|
}else{
|
||||||
if(!setup_AD7794(INTREFIN | REF_DETECTION | UNIPOLAR_CODING, IEXC_DIRECT | IEXC_1MA)
|
if(!setup_AD7794(INTREFIN | REF_DETECTION | UNIPOLAR_CODING, IEXC_DIRECT | IEXC_1MA)
|
||||||
@ -133,11 +143,12 @@ int main(){
|
|||||||
//rcc_clock_setup_in_hsi_out_48mhz();
|
//rcc_clock_setup_in_hsi_out_48mhz();
|
||||||
// RCC clocking: 8MHz oscillator -> 72MHz system
|
// RCC clocking: 8MHz oscillator -> 72MHz system
|
||||||
rcc_clock_setup_in_hse_8mhz_out_72mhz();
|
rcc_clock_setup_in_hse_8mhz_out_72mhz();
|
||||||
|
|
||||||
// GPIO
|
// GPIO
|
||||||
GPIO_init();
|
GPIO_init();
|
||||||
gpio_set(GPIOC, GPIO11); // turn off USB
|
|
||||||
gpio_clear(GPIOC, GPIO12); // turn on LED
|
steppers_init();
|
||||||
|
|
||||||
|
usb_disconnect(); // turn off USB
|
||||||
|
|
||||||
// init USART1
|
// init USART1
|
||||||
UART_init(USART1);
|
UART_init(USART1);
|
||||||
@ -146,21 +157,26 @@ int main(){
|
|||||||
usbd_dev = USB_init();
|
usbd_dev = USB_init();
|
||||||
|
|
||||||
// init ADC
|
// init ADC
|
||||||
ADC_init();
|
// ADC_init();
|
||||||
|
|
||||||
// SysTick is a system timer with 1mc period
|
// SysTick is a system timer with 1mc period
|
||||||
SysTick_init();
|
SysTick_init();
|
||||||
|
|
||||||
SPI1_init();
|
|
||||||
|
|
||||||
OW_Init();
|
// switch_SPI(SPI2); // init SPI2
|
||||||
|
// SPI_init();
|
||||||
|
|
||||||
|
switch_SPI(SPI1); // init SPI1
|
||||||
|
SPI_init();
|
||||||
|
//OW_Init();
|
||||||
|
|
||||||
// wait a little and then turn on USB pullup
|
// wait a little and then turn on USB pullup
|
||||||
for (i = 0; i < 0x800000; i++)
|
for (i = 0; i < 0x800000; i++)
|
||||||
__asm__("nop");
|
__asm__("nop");
|
||||||
gpio_clear(GPIOC, GPIO11);
|
usb_connect(); // turn on USB
|
||||||
ADC_calibrate_and_start();
|
|
||||||
|
|
||||||
|
//ADC_calibrate_and_start();
|
||||||
|
init_dmatimer();
|
||||||
while(1){
|
while(1){
|
||||||
usbd_poll(usbd_dev);
|
usbd_poll(usbd_dev);
|
||||||
if(usbdatalen){ // there's something in USB buffer
|
if(usbdatalen){ // there's something in USB buffer
|
||||||
@ -174,10 +190,13 @@ int main(){
|
|||||||
read_next_TRD();
|
read_next_TRD();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
process_stepper_motors(); // check flags of motors' timers
|
||||||
if(Timer - Old_timer > 999){ // one-second cycle
|
if(Timer - Old_timer > 999){ // one-second cycle
|
||||||
Old_timer += 1000;
|
Old_timer += 1000;
|
||||||
gpio_toggle(GPIOC, GPIO12); // toggle LED
|
//gpio_toggle(GPIOC, GPIO12); // toggle LED
|
||||||
if(!ad7794_on) AD7794_init(); // try to init ADC if it doesn't work
|
//gpio_toggle(GPIO_BANK_SPI2_MOSI, GPIO_SPI2_MOSI);
|
||||||
|
//gpio_toggle(GPIO_BANK_SPI2_SCK, GPIO_SPI2_SCK);
|
||||||
|
// if(!ad7794_on) AD7794_init(); // try to init ADC if it doesn't work
|
||||||
//print_int(Timer/1000, usb_send);
|
//print_int(Timer/1000, usb_send);
|
||||||
}else if(Timer < Old_timer){ // Timer overflow
|
}else if(Timer < Old_timer){ // Timer overflow
|
||||||
Old_timer = 0;
|
Old_timer = 0;
|
||||||
|
|||||||
@ -37,9 +37,12 @@
|
|||||||
#include <libopencm3/stm32/dma.h>
|
#include <libopencm3/stm32/dma.h>
|
||||||
#include <libopencm3/stm32/spi.h>
|
#include <libopencm3/stm32/spi.h>
|
||||||
|
|
||||||
|
#include "sync.h" // mutexes
|
||||||
#include "user_proto.h"
|
#include "user_proto.h"
|
||||||
#include "AD7794.h"
|
#include "AD7794.h"
|
||||||
#include "onewire.h"
|
#include "onewire.h"
|
||||||
|
#include "stepper_motors.h"
|
||||||
|
#include "sensors.h"
|
||||||
|
|
||||||
#define _U_ __attribute__((__unused__))
|
#define _U_ __attribute__((__unused__))
|
||||||
#define U8(x) ((uint8_t) x)
|
#define U8(x) ((uint8_t) x)
|
||||||
|
|||||||
@ -24,8 +24,10 @@
|
|||||||
#define OW_RST 0xf0
|
#define OW_RST 0xf0
|
||||||
|
|
||||||
|
|
||||||
// In/Out buffer
|
uint8_t dev_amount = 0; // amount of 1-wire devices
|
||||||
uint8_t ow_buf[8];
|
uint8_t ID_buf[64] = {0}; // 1-wire devices ID buffer (8 bytes for every device)
|
||||||
|
uint8_t NUM_buf[8] = {0}; // numerical identificators for each sensor
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* this function sends bits of ow_byte (LSB first) to 1-wire line
|
* this function sends bits of ow_byte (LSB first) to 1-wire line
|
||||||
* @param ow_byte - byte to convert
|
* @param ow_byte - byte to convert
|
||||||
@ -46,22 +48,29 @@ void OW_SendBits(uint8_t ow_byte, uint8_t Nbits){
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
void OW_ClearBuff(){
|
||||||
* Inverce conversion - read data (not more than 8 b
|
|
||||||
*/
|
|
||||||
uint8_t OW_ReadByte(){
|
|
||||||
UART_buff *curbuff = get_uart_buffer(OW_USART_X);
|
UART_buff *curbuff = get_uart_buffer(OW_USART_X);
|
||||||
uint8_t ow_byte = 0, i, L, *buf;
|
curbuff->end = 0;
|
||||||
if(!curbuff || !(L = curbuff->end)) return 0; // no data?
|
}
|
||||||
|
|
||||||
|
/*
|
||||||
|
* Inverce conversion - read data (not more than 8 bits)
|
||||||
|
*/
|
||||||
|
uint8_t OW_ConvertByte(uint8_t *bits, uint8_t L){
|
||||||
|
uint8_t ow_byte = 0, i, *st = bits;
|
||||||
if(L > 8) L = 8; // forget all other data
|
if(L > 8) L = 8; // forget all other data
|
||||||
buf = curbuff->buf;
|
for(i = 0; i < L; i++, st++){
|
||||||
for(i = 0; i < L; i++, buf++){
|
|
||||||
ow_byte = ow_byte >> 1; // prepare for next bit filling
|
ow_byte = ow_byte >> 1; // prepare for next bit filling
|
||||||
if(*buf == OW_1){
|
if(*st == OW_1){
|
||||||
ow_byte |= 0x80; // MSB = 1
|
ow_byte |= 0x80; // MSB = 1
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
return ow_byte >> (8 - L); // shift to the end: L could be != 8 ???
|
ow_byte >>= (8 - L);
|
||||||
|
print_hex(bits, L, lastsendfun);
|
||||||
|
lastsendfun(' ');
|
||||||
|
print_hex(&ow_byte, 1, lastsendfun);
|
||||||
|
newline(lastsendfun);
|
||||||
|
return ow_byte; // shift to the end: L could be != 8 ???
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
@ -88,7 +97,7 @@ void OW_Init(){
|
|||||||
*
|
*
|
||||||
* return 1 in case of 1-wire devices present; otherwise return 0
|
* return 1 in case of 1-wire devices present; otherwise return 0
|
||||||
*/
|
*/
|
||||||
uint8_t OW_Reset() {
|
uint8_t OW_Reset(){
|
||||||
uint8_t ow_presence;
|
uint8_t ow_presence;
|
||||||
UART_buff *curbuff;
|
UART_buff *curbuff;
|
||||||
// change speed to 9600
|
// change speed to 9600
|
||||||
@ -111,52 +120,61 @@ uint8_t OW_Reset() {
|
|||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
/**
|
||||||
* Procedure of 1-wire communications
|
* Procedure of 1-wire communications
|
||||||
* variables:
|
* variables:
|
||||||
* sendReset - send RESET before transmission
|
* @param sendReset - send RESET before transmission
|
||||||
* command - bytes sent to the bus (if we want to read, send OW_READ_SLOT)
|
* @param command - bytes sent to the bus (if we want to read, send OW_READ_SLOT)
|
||||||
* cLen - command buffer length (how many bytes to send)
|
* @param cLen - command buffer length (how many bytes to send)
|
||||||
* data - pointer for reading buffer (if reading needed)
|
* @return 1 if succeed, 0 if failure
|
||||||
* readStart - first byte to read (starts from 0) or OW_NO_READ (not read)
|
|
||||||
*
|
|
||||||
* return 1 if succeed, 0 if failure
|
|
||||||
*/
|
*/
|
||||||
uint8_t OW_Send(uint8_t sendReset, uint8_t *command, uint8_t cLen,
|
uint8_t OW_Send(uint8_t sendReset, uint8_t *command, uint8_t cLen){
|
||||||
uint8_t *data, uint8_t dLen, uint8_t readStart) {
|
|
||||||
// if reset needed - send RESET and check bus
|
// if reset needed - send RESET and check bus
|
||||||
if(sendReset){
|
if(sendReset){
|
||||||
if(OW_Reset() == 0){
|
if(OW_Reset() == 0){
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
while(cLen > 0){
|
while(cLen-- > 0){
|
||||||
OW_SendBits(*command, 8);
|
OW_SendBits(*command, 8);
|
||||||
command++;
|
command++;
|
||||||
cLen--;
|
}
|
||||||
// wait for EOT
|
return 1;
|
||||||
while(!(USART_SR(OW_USART_X) & USART_SR_TC));
|
}
|
||||||
// put data from bus into user buffer
|
|
||||||
if(readStart == 0 && dLen > 0){
|
/**
|
||||||
*data = OW_ReadByte();
|
* Check USART IN buffer for ready & fill user buffer with data on success
|
||||||
data++;
|
* @param buflen - expected buffer length
|
||||||
dLen--;
|
* @param data - pointer for reading buffer (if reading needed must be at least buflen-readStart bytes)
|
||||||
|
* @param readStart - first byte to read (starts from 0) or OW_NO_READ (not read)
|
||||||
|
* @return 0 if buffer not ready; 1 if OK
|
||||||
|
*/
|
||||||
|
uint8_t OW_Get(uint8_t buflen, uint8_t *data, uint8_t readStart){
|
||||||
|
UART_buff *curbuff = get_uart_buffer(OW_USART_X);
|
||||||
|
uint8_t *buff = curbuff->buf;
|
||||||
|
if(curbuff->end < buflen/8) return 0;
|
||||||
|
while(buflen-- > 0){
|
||||||
|
if(readStart == 0){
|
||||||
|
*data++ = OW_ConvertByte(buff, 8);
|
||||||
}else{
|
}else{
|
||||||
if(readStart != OW_NO_READ){
|
if(readStart != OW_NO_READ){
|
||||||
readStart--;
|
readStart--;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
buff += 8;
|
||||||
}
|
}
|
||||||
|
curbuff->end = 0; // zero counter
|
||||||
return 1;
|
return 1;
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
* scan 1-wire bus
|
* scan 1-wire bus
|
||||||
|
* WARNING! The procedure works in real-time, so it is VERY LONG
|
||||||
* num - max number of devices
|
* num - max number of devices
|
||||||
* buf - array for devices' ID's (8*num bytes)
|
* buf - array for devices' ID's (8*num bytes)
|
||||||
* return amount of founded devices
|
* return amount of founded devices
|
||||||
*/
|
*
|
||||||
uint8_t OW_Scan(uint8_t *buf, uint8_t num) {
|
uint8_t OW_Scan(uint8_t *buf, uint8_t num){
|
||||||
unsigned long path,next,pos;
|
unsigned long path,next,pos;
|
||||||
uint8_t bit,chk;
|
uint8_t bit,chk;
|
||||||
uint8_t cnt_bit, cnt_byte, cnt_num;
|
uint8_t cnt_bit, cnt_byte, cnt_num;
|
||||||
@ -165,17 +183,19 @@ uint8_t OW_Scan(uint8_t *buf, uint8_t num) {
|
|||||||
do{
|
do{
|
||||||
//(issue the 'ROM search' command)
|
//(issue the 'ROM search' command)
|
||||||
if( 0 == OW_WriteCmd(OW_SEARCH_ROM) ) return 0;
|
if( 0 == OW_WriteCmd(OW_SEARCH_ROM) ) return 0;
|
||||||
next=0; // next path to follow
|
OW_Wait_TX();
|
||||||
pos=1; // path bit pointer
|
OW_ClearBuff(); // clear RX buffer
|
||||||
|
next = 0; // next path to follow
|
||||||
|
pos = 1; // path bit pointer
|
||||||
for(cnt_byte = 0; cnt_byte != 8; cnt_byte++){
|
for(cnt_byte = 0; cnt_byte != 8; cnt_byte++){
|
||||||
buf[cnt_num*8 + cnt_byte] = 0;
|
buf[cnt_num*8 + cnt_byte] = 0;
|
||||||
for(cnt_bit = 0; cnt_bit != 8; cnt_bit++){
|
for(cnt_bit = 0; cnt_bit != 8; cnt_bit++){
|
||||||
//(read two bits, 'bit' and 'chk', from the 1-wire bus)
|
//(read two bits, 'bit' and 'chk', from the 1-wire bus)
|
||||||
OW_SendBits(OW_R, 2);
|
OW_SendBits(OW_R, 2);
|
||||||
bit = OW_ReadByte();
|
OW_Wait_TX();
|
||||||
|
bit = -----OW_ReadByte();
|
||||||
chk = bit & 0x02; // bit 1
|
chk = bit & 0x02; // bit 1
|
||||||
bit = bit & 0x01; // bit 0
|
bit = bit & 0x01; // bit 0
|
||||||
//bit = (ow_buf[0] == OW_1); chk = (ow_buf[1] == OW_1);
|
|
||||||
if(bit && chk) return 0; // error
|
if(bit && chk) return 0; // error
|
||||||
if(!bit && !chk){ // collision, both are zero
|
if(!bit && !chk){ // collision, both are zero
|
||||||
if (pos & path) bit = 1; // if we've been here before
|
if (pos & path) bit = 1; // if we've been here before
|
||||||
@ -186,11 +206,54 @@ uint8_t OW_Scan(uint8_t *buf, uint8_t num) {
|
|||||||
if (bit) buf[cnt_num*8 + cnt_byte]|=(1<<cnt_bit);
|
if (bit) buf[cnt_num*8 + cnt_byte]|=(1<<cnt_bit);
|
||||||
//(write 'bit' to the 1-wire bus)
|
//(write 'bit' to the 1-wire bus)
|
||||||
OW_SendBits(bit, 1);
|
OW_SendBits(bit, 1);
|
||||||
|
OW_Wait_TX();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
//(output the just-completed ROM value)
|
|
||||||
path=next;
|
path=next;
|
||||||
cnt_num++;
|
cnt_num++;
|
||||||
}while(path && cnt_num < num);
|
}while(path && cnt_num < num);
|
||||||
return cnt_num;
|
return cnt_num;
|
||||||
|
}*/
|
||||||
|
|
||||||
|
uint8_t OW_Scan(uint8_t *buf, uint8_t num){
|
||||||
|
uint8_t flg, b[11], i;
|
||||||
|
flg = OW_Send(1, (uint8_t*)"\xcc\x33\xff\xff\xff\xff\xff\xff\xff\xff\xff", 11);
|
||||||
|
if(!flg) return 0;
|
||||||
|
OW_Wait_TX();
|
||||||
|
if(!OW_Get(11, b, 0)) return 0;
|
||||||
|
num += 2;
|
||||||
|
for(i = 2; i < num; i++) *buf++ = b[i];
|
||||||
|
return 1;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
//OW_USART_X
|
||||||
|
/*
|
||||||
|
void OW_getTemp(){
|
||||||
|
uint8_t buf[9], i;
|
||||||
|
void printTBuf(){
|
||||||
|
uint8_t j;
|
||||||
|
OW_Send(0, (uint8_t*)"\xbe\xff\xff\xff\xff\xff\xff\xff\xff\xff", 10, buf, 9, 1);
|
||||||
|
for(j = 0; j != 9; j++)
|
||||||
|
printInt(&buf[j], 1);
|
||||||
|
newline();
|
||||||
|
}
|
||||||
|
// send broadcast message to start measurement
|
||||||
|
if(!OW_Send(1, (uint8_t*)"\xcc\x44", 2)) return;
|
||||||
|
Delay(1000);
|
||||||
|
// read values
|
||||||
|
if(dev_amount == 1){
|
||||||
|
if(OW_WriteCmd(OW_SKIP_ROM)) printTBuf();
|
||||||
|
}else{
|
||||||
|
for(i = 0; i < dev_amount; i++){
|
||||||
|
MSG("Device ", "ow");
|
||||||
|
USB_Send_Data(i + '0');
|
||||||
|
MSG(": ", 0);
|
||||||
|
if(OW_WriteCmd(OW_MATCH_ROM)){
|
||||||
|
OW_SendOnly(0, &ID_buf[i*8], 8);
|
||||||
|
printTBuf();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
*/
|
||||||
|
|||||||
@ -34,17 +34,20 @@
|
|||||||
#define OW_READ_SLOT (uint8_t*)"0xff"
|
#define OW_READ_SLOT (uint8_t*)"0xff"
|
||||||
|
|
||||||
void OW_Init();
|
void OW_Init();
|
||||||
uint8_t OW_Send(uint8_t sendReset, uint8_t *command, uint8_t cLen,
|
uint8_t OW_Send(uint8_t sendReset, uint8_t *command, uint8_t cLen);
|
||||||
uint8_t *data, uint8_t dLen, uint8_t readStart);
|
uint8_t OW_Get(uint8_t buflen, uint8_t *data, uint8_t readStart);
|
||||||
uint8_t OW_Scan(uint8_t *buf, uint8_t num);
|
uint8_t OW_Scan(uint8_t *buf, uint8_t num);
|
||||||
|
|
||||||
// shortcuts for functions
|
// shortcuts for functions
|
||||||
// only send message b wich length is c with RESET flag a
|
// only send message b wich length is c with RESET flag a
|
||||||
#define OW_SendOnly(a,b,c) OW_Send(a, b, c, (void*)0, 0, OW_NO_READ)
|
#define OW_SendOnly(a,b,c) OW_Send(a, b, c)
|
||||||
// send 1 command (with bus reset)
|
// send 1 command (with bus reset)
|
||||||
#define OW_WriteCmd(cmd) OW_Send(1, cmd, 1, (void*)0, 0, OW_NO_READ)
|
#define OW_WriteCmd(cmd) OW_Send(1, cmd, 1)
|
||||||
// send 1 function (without bus reset)
|
// send 1 function (without bus reset)
|
||||||
#define OW_WriteFn(cmd) OW_Send(0, cmd, 1, (void*)0, 0, OW_NO_READ)
|
#define OW_WriteFn(cmd) OW_Send(0, cmd, 1)
|
||||||
|
#define OW_Wait_TX() while(!(USART_SR(OW_USART_X) & USART_SR_TC))
|
||||||
|
|
||||||
|
void OW_getTemp();
|
||||||
|
|
||||||
/*
|
/*
|
||||||
* thermometer identificator is: 8bits CRC, 48bits serial, 8bits device code (10h)
|
* thermometer identificator is: 8bits CRC, 48bits serial, 8bits device code (10h)
|
||||||
|
|||||||
24
with_opencm3/sensors.c
Normal file
24
with_opencm3/sensors.c
Normal file
@ -0,0 +1,24 @@
|
|||||||
|
/*
|
||||||
|
* sensors.c - funtions to work with end-switches & MOSFETs
|
||||||
|
*
|
||||||
|
* Copyright 2014 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 "main.h"
|
||||||
|
#include "sensors.h"
|
||||||
|
|
||||||
29
with_opencm3/sensors.h
Normal file
29
with_opencm3/sensors.h
Normal file
@ -0,0 +1,29 @@
|
|||||||
|
/*
|
||||||
|
* sensors.h
|
||||||
|
*
|
||||||
|
* Copyright 2014 Edward V. Emelianov <eddy@sao.ru, edward.emelianoff@gmail.com>
|
||||||
|
*
|
||||||
|
* This program is free software; you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation; either version 2 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* This program is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with this program; if not, write to the Free Software
|
||||||
|
* Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston,
|
||||||
|
* MA 02110-1301, USA.
|
||||||
|
*/
|
||||||
|
#pragma once
|
||||||
|
#ifndef __SENSORS_H__
|
||||||
|
#define __SENSORS_H__
|
||||||
|
|
||||||
|
#include "hardware_ini.h"
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
#endif // __SENSORS_H__
|
||||||
@ -21,6 +21,7 @@
|
|||||||
|
|
||||||
#include "main.h"
|
#include "main.h"
|
||||||
#include "spi.h"
|
#include "spi.h"
|
||||||
|
#include "hardware_ini.h"
|
||||||
|
|
||||||
// Rx/Tx buffer
|
// Rx/Tx buffer
|
||||||
volatile uint8_t SPI_TxBuffer[SPI_BUFFERSIZE];
|
volatile uint8_t SPI_TxBuffer[SPI_BUFFERSIZE];
|
||||||
@ -32,35 +33,31 @@ volatile uint8_t SPI_datalen = 0;
|
|||||||
#endif
|
#endif
|
||||||
volatile uint8_t SPI_EOT_FLAG = 1; // end of transmission flag, set by interrupt
|
volatile uint8_t SPI_EOT_FLAG = 1; // end of transmission flag, set by interrupt
|
||||||
|
|
||||||
/*
|
|
||||||
* Configure SPI port
|
|
||||||
*/
|
|
||||||
void SPI1_init(){
|
|
||||||
rcc_periph_clock_enable(RCC_SPI1);
|
|
||||||
//rcc_periph_clock_enable(RCC_GPIOB); // PB3..5
|
|
||||||
rcc_periph_clock_enable(RCC_GPIOA); // PA5..7
|
|
||||||
// PA5 - SCK, PA6 - MISO, PA7 - MOSI
|
|
||||||
gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_50_MHZ,
|
|
||||||
GPIO_CNF_OUTPUT_ALTFN_PUSHPULL, GPIO5 | GPIO7 );
|
|
||||||
gpio_set_mode(GPIOA, GPIO_MODE_INPUT, GPIO_CNF_INPUT_FLOAT, GPIO6);
|
|
||||||
|
|
||||||
spi_reset(SPI1);
|
uint32_t Current_SPI = SPI1; // this is SPI interface which would b
|
||||||
/* Set up SPI in Master mode with:
|
/**
|
||||||
* Clock baud rate: 1/128 of peripheral clock frequency
|
* Set current SPI to given value
|
||||||
* Clock polarity: Idle High
|
|
||||||
* Clock phase: Data valid on 2nd clock pulse
|
|
||||||
* Data frame format: 8-bit
|
|
||||||
* Frame format: MSB First
|
|
||||||
*/
|
*/
|
||||||
spi_init_master(SPI1, SPI_CR1_BAUDRATE_FPCLK_DIV_128, SPI_CR1_CPOL_CLK_TO_1_WHEN_IDLE,
|
void switch_SPI(uint32_t SPI){
|
||||||
SPI_CR1_CPHA_CLK_TRANSITION_2, SPI_CR1_DFF_8BIT, SPI_CR1_MSBFIRST);
|
Current_SPI = SPI;
|
||||||
nvic_enable_irq(NVIC_SPI1_IRQ); // enable SPI interrupt
|
}
|
||||||
|
|
||||||
|
void SPI_init(){
|
||||||
|
switch(Current_SPI){
|
||||||
|
case SPI1:
|
||||||
|
SPI1_init();
|
||||||
|
break;
|
||||||
|
case SPI2:
|
||||||
|
SPI2_init();
|
||||||
|
break;
|
||||||
|
default:
|
||||||
|
return; // error
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
//uint32_t read_end; // read timeout
|
//uint32_t read_end; // read timeout
|
||||||
/**
|
/**
|
||||||
* Write data to SPI1
|
* Write data to current SPI
|
||||||
* @param data - buffer with data
|
* @param data - buffer with data
|
||||||
* @param len - buffer length (<= DMA_BUFFERSIZE)
|
* @param len - buffer length (<= DMA_BUFFERSIZE)
|
||||||
* @return 0 in case of error (or 1 in case of success)
|
* @return 0 in case of error (or 1 in case of success)
|
||||||
@ -72,7 +69,7 @@ uint8_t write_SPI(uint8_t *data, uint8_t len){
|
|||||||
//DBG("check\r\n");
|
//DBG("check\r\n");
|
||||||
while(!SPI_EOT_FLAG && Timer < tend); // wait for previous DMA interrupt
|
while(!SPI_EOT_FLAG && Timer < tend); // wait for previous DMA interrupt
|
||||||
if(!SPI_EOT_FLAG){
|
if(!SPI_EOT_FLAG){
|
||||||
//DBG("ERR!\r\n");
|
DBG("SPI error: no EOT flag!\r\n");
|
||||||
return 0; // error: there's no receiver???
|
return 0; // error: there's no receiver???
|
||||||
}
|
}
|
||||||
if(len > SPI_BUFFERSIZE) len = SPI_BUFFERSIZE;
|
if(len > SPI_BUFFERSIZE) len = SPI_BUFFERSIZE;
|
||||||
@ -88,9 +85,9 @@ uint8_t write_SPI(uint8_t *data, uint8_t len){
|
|||||||
SPI_TxIndex = 0;
|
SPI_TxIndex = 0;
|
||||||
SPI_datalen = len; // set length of data to transmit
|
SPI_datalen = len; // set length of data to transmit
|
||||||
// start transmission - enable interrupts
|
// start transmission - enable interrupts
|
||||||
SPI_CR2(SPI1) |= SPI_CR2_TXEIE | SPI_CR2_RXNEIE; //spi_enable_rx_buffer_not_empty_interrupt(SPI1); spi_enable_tx_buffer_empty_interrupt(SPI1);
|
SPI_CR2(Current_SPI) |= SPI_CR2_TXEIE | SPI_CR2_RXNEIE; //spi_enable_rx_buffer_not_empty_interrupt(SPI1); spi_enable_tx_buffer_empty_interrupt(SPI1);
|
||||||
// Enable the SPI peripheral
|
// Enable the SPI peripheral
|
||||||
spi_enable(SPI1);
|
spi_enable(Current_SPI);
|
||||||
#endif // SPI_USE_DMA
|
#endif // SPI_USE_DMA
|
||||||
return 1;
|
return 1;
|
||||||
}
|
}
|
||||||
@ -108,7 +105,7 @@ uint8_t *read_SPI(uint8_t *data, uint8_t len){
|
|||||||
//DBG("check\r\n");
|
//DBG("check\r\n");
|
||||||
while((!SPI_EOT_FLAG || len != SPI_RxIndex) && Timer < tend);
|
while((!SPI_EOT_FLAG || len != SPI_RxIndex) && Timer < tend);
|
||||||
if(len != SPI_RxIndex){
|
if(len != SPI_RxIndex){
|
||||||
//DBG("ERR\r\n");
|
//DBG("SPI error: bad data length\r\n");
|
||||||
return NULL;
|
return NULL;
|
||||||
}
|
}
|
||||||
//DBG("OK\r\n");
|
//DBG("OK\r\n");
|
||||||
|
|||||||
@ -31,9 +31,11 @@ typedef enum{
|
|||||||
SPI_READ_ERROR
|
SPI_READ_ERROR
|
||||||
} SPI_read_status;
|
} SPI_read_status;
|
||||||
|
|
||||||
void SPI1_init();
|
void SPI_init();
|
||||||
uint8_t write_SPI(uint8_t *data, uint8_t len);
|
uint8_t write_SPI(uint8_t *data, uint8_t len);
|
||||||
SPI_read_status check_SPI();
|
SPI_read_status check_SPI();
|
||||||
uint8_t *read_SPI(uint8_t *data, uint8_t len);
|
uint8_t *read_SPI(uint8_t *data, uint8_t len);
|
||||||
|
|
||||||
|
void switch_SPI(uint32_t SPI);
|
||||||
|
|
||||||
#endif // __SPI_H__
|
#endif // __SPI_H__
|
||||||
|
|||||||
212
with_opencm3/stepper_motors.c
Normal file
212
with_opencm3/stepper_motors.c
Normal file
@ -0,0 +1,212 @@
|
|||||||
|
/*
|
||||||
|
* stepper_motors.c - moving of stepper motors
|
||||||
|
*
|
||||||
|
* Copyright 2014 Edward V. Emelianoff <eddy@sao.ru>
|
||||||
|
*
|
||||||
|
* 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 "main.h"
|
||||||
|
|
||||||
|
static uint8_t timers_activated[2] = {0, 0}; // flag of activated timers
|
||||||
|
uint16_t Motor_period[2] = {10000, 10000}; // near 100 steps per second
|
||||||
|
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};
|
||||||
|
// flag of active motor
|
||||||
|
volatile uint8_t Motor_active[5] = {0, 0, 0, 0, 0};
|
||||||
|
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Setup stepper motors' timer Tim
|
||||||
|
* N == 0 for TIM3, == 1 for TIM4
|
||||||
|
*/
|
||||||
|
static void setup_timer(uint8_t N){
|
||||||
|
uint32_t Tim;
|
||||||
|
switch (N){
|
||||||
|
case 0:
|
||||||
|
Tim = TIM3;
|
||||||
|
nvic_enable_irq(NVIC_TIM3_IRQ);
|
||||||
|
break;
|
||||||
|
case 1:
|
||||||
|
Tim = TIM4;
|
||||||
|
nvic_enable_irq(NVIC_TIM4_IRQ);
|
||||||
|
break;
|
||||||
|
default:
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
timer_reset(Tim);
|
||||||
|
// timers have frequency of 2MHz, 2 pulse == 1 microstep
|
||||||
|
// 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_continuous_mode(Tim); // automatically reload
|
||||||
|
timer_enable_preload(Tim); // force changing period
|
||||||
|
timer_set_period(Tim, Motor_period[N] - 1);
|
||||||
|
timer_enable_update_event(Tim);
|
||||||
|
timer_enable_irq(Tim, TIM_DIER_UIE); // update IRQ enable
|
||||||
|
timer_enable_counter(Tim);
|
||||||
|
timers_activated[N] = 1;
|
||||||
|
lastsendfun('3' + N);
|
||||||
|
MSG(" timer\n");
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Set up motors pins & activate timers 3 & 4
|
||||||
|
* Timer3 gives ticks to motors 1..3 (turrets)
|
||||||
|
* Timer4 gives ticks to motors 4,5 (long & short stages)
|
||||||
|
*
|
||||||
|
* Timers are always work, stopping motors can be done by EN
|
||||||
|
* Timers simply works as counters, no PWM mode
|
||||||
|
*/
|
||||||
|
void steppers_init(){
|
||||||
|
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPAEN |
|
||||||
|
RCC_APB2ENR_IOPBEN | RCC_APB2ENR_IOPCEN | RCC_APB2ENR_IOPDEN | RCC_APB2ENR_IOPEEN);
|
||||||
|
rcc_peripheral_enable_clock(&RCC_APB1ENR, RCC_APB1ENR_TIM3EN | RCC_APB1ENR_TIM4EN);
|
||||||
|
// timer pins
|
||||||
|
gpio_set_mode(MOTOR_TIM1_PORT, GPIO_MODE_OUTPUT_2_MHZ,
|
||||||
|
GPIO_CNF_OUTPUT_PUSHPULL, MOTOR_TIM1_PIN);
|
||||||
|
gpio_set_mode(MOTOR_TIM2_PORT, GPIO_MODE_OUTPUT_2_MHZ,
|
||||||
|
GPIO_CNF_OUTPUT_PUSHPULL, MOTOR_TIM2_PIN);
|
||||||
|
// EN pins
|
||||||
|
gpio_set_mode(MOTOR_EN_PORT, GPIO_MODE_OUTPUT_2_MHZ,
|
||||||
|
GPIO_CNF_OUTPUT_PUSHPULL, MOROT_EN_MASK);
|
||||||
|
// DIR pins
|
||||||
|
gpio_set_mode(MOTOR_DIR_PORT, GPIO_MODE_OUTPUT_2_MHZ,
|
||||||
|
GPIO_CNF_OUTPUT_PUSHPULL, MOROT_DIR_MASK);
|
||||||
|
setup_timer(0);
|
||||||
|
setup_timer(1);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Move motor Motor_number to User_value steps
|
||||||
|
*/
|
||||||
|
void move_motor(uint8_t num, int32_t steps){
|
||||||
|
if(steps == 0) return;
|
||||||
|
// check whether motor is moving
|
||||||
|
if(Motor_active[num]){
|
||||||
|
MSG("err: moving\r\n");
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
if(steps < 0){
|
||||||
|
steps = -steps;
|
||||||
|
gpio_set(MOTOR_DIR_PORT, MOTOR_DIR_PIN(num)); // set DIR bit to rotate ccw
|
||||||
|
}else
|
||||||
|
gpio_clear(MOTOR_DIR_PORT, MOTOR_DIR_PIN(num)); // reset DIR bit
|
||||||
|
Motor_steps[num] = steps << 4; // multiply by 16 to get usteps count
|
||||||
|
Motor_active[num] = 1;
|
||||||
|
gpio_set(MOTOR_EN_PORT, MOTOR_EN_PIN(num)); // activate motor
|
||||||
|
}
|
||||||
|
|
||||||
|
void stop_motor(uint8_t num){
|
||||||
|
if(!Motor_active[num]) return;
|
||||||
|
MSG("stop motor ");
|
||||||
|
lastsendfun('0' + num);
|
||||||
|
MSG("\r\n");
|
||||||
|
gpio_clear(MOTOR_EN_PORT, MOTOR_EN_PIN(num));
|
||||||
|
Motor_active[num] = 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Check flags set by timers & do next:
|
||||||
|
* - decrease step counter if it isn't zero;
|
||||||
|
* - stop motor if counter is zero but motor still active
|
||||||
|
*/
|
||||||
|
void process_stepper_motors(){
|
||||||
|
int i, j;
|
||||||
|
const uint32_t ports[] = {MOTOR_TIM1_PORT, MOTOR_TIM2_PORT};
|
||||||
|
const uint32_t pins[] = {MOTOR_TIM1_PIN, MOTOR_TIM2_PIN};
|
||||||
|
const uint8_t startno[] = {0, 3};
|
||||||
|
const uint8_t stopno[] = {3, 5};
|
||||||
|
for(j = 0; j < 2; j++){
|
||||||
|
if(timer_flag[j]){
|
||||||
|
timer_flag[j] = 0;
|
||||||
|
gpio_toggle(ports[j], pins[j]); // change clock state
|
||||||
|
if(gpio_get(ports[j], pins[j])){ // positive pulse - next microstep
|
||||||
|
for(i = startno[j]; i < stopno[j]; i++){ // check motors
|
||||||
|
if(Motor_steps[i]) Motor_steps[i]--;
|
||||||
|
else if(Motor_active[i]){ // stop motor - all done
|
||||||
|
stop_motor(i);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Stop timers; turn off motor voltage
|
||||||
|
*
|
||||||
|
void stop_timer(){
|
||||||
|
// disable IRQs & stop timer
|
||||||
|
TIM_Cmd(SM_Timer, DISABLE);
|
||||||
|
TIM_ITConfig(SM_Timer, TIM_IT_Update, DISABLE);
|
||||||
|
// turn off power
|
||||||
|
SM_EN_GPIOx->BRR = SM_EN_PINS; // reset all EN bits
|
||||||
|
SM_PUL_GPIOx->BRR = SM_PUL_PIN; // reset signal on PUL
|
||||||
|
timers_activated = 0;
|
||||||
|
Motor_steps = 0;
|
||||||
|
}*/
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Sets motor period to user value & refresh timer
|
||||||
|
* @param num - number of motor
|
||||||
|
* @param period - period of one STEP in microseconds
|
||||||
|
*/
|
||||||
|
void set_motor_period(uint8_t num, uint16_t period){
|
||||||
|
uint32_t Tim, N;
|
||||||
|
switch (num){
|
||||||
|
case 1:
|
||||||
|
case 2:
|
||||||
|
case 3:
|
||||||
|
Tim = TIM3;
|
||||||
|
N = 0;
|
||||||
|
break;
|
||||||
|
case 4:
|
||||||
|
case 5:
|
||||||
|
Tim = TIM4;
|
||||||
|
N = 1;
|
||||||
|
break;
|
||||||
|
default:
|
||||||
|
MSG("err: bad motor");
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
period >>= 4; // divide by 4 to get 16usteps for one step
|
||||||
|
if(period == 0) Motor_period[N] = 1;
|
||||||
|
else Motor_period[N] = period;
|
||||||
|
if(!timers_activated[N]) setup_timer(N);
|
||||||
|
else timer_set_period(Tim, period);
|
||||||
|
}
|
||||||
|
|
||||||
|
/*
|
||||||
|
* Interrupts: just set flag
|
||||||
|
*/
|
||||||
|
void tim3_isr(){
|
||||||
|
if(timer_get_flag(TIM3, TIM_SR_UIF)){
|
||||||
|
// Clear compare interrupt flag
|
||||||
|
timer_clear_flag(TIM3, TIM_SR_UIF);
|
||||||
|
timer_flag[0] = 1;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void tim4_isr(){
|
||||||
|
if(timer_get_flag(TIM4, TIM_SR_UIF)){
|
||||||
|
// Clear compare interrupt flag
|
||||||
|
timer_clear_flag(TIM4, TIM_SR_UIF);
|
||||||
|
timer_flag[1] = 1;
|
||||||
|
}
|
||||||
|
}
|
||||||
33
with_opencm3/stepper_motors.h
Normal file
33
with_opencm3/stepper_motors.h
Normal file
@ -0,0 +1,33 @@
|
|||||||
|
/*
|
||||||
|
* stepper_motors.h
|
||||||
|
*
|
||||||
|
* Copyright 2014 Edward V. Emelianoff <eddy@sao.ru>
|
||||||
|
*
|
||||||
|
* This program is free software; you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation; either version 2 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* This program is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with this program; if not, write to the Free Software
|
||||||
|
* Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston,
|
||||||
|
* MA 02110-1301, USA.
|
||||||
|
*/
|
||||||
|
#pragma once
|
||||||
|
#ifndef __STEPPER_MOTORS_H__
|
||||||
|
#define __STEPPER_MOTORS_H__
|
||||||
|
|
||||||
|
#include <libopencm3/stm32/timer.h>
|
||||||
|
|
||||||
|
void steppers_init();
|
||||||
|
void process_stepper_motors();
|
||||||
|
void move_motor(uint8_t num, int32_t steps);
|
||||||
|
void stop_motor(uint8_t num);
|
||||||
|
void set_motor_period(uint8_t num, uint16_t period);
|
||||||
|
|
||||||
|
#endif // __STEPPER_MOTORS_H__
|
||||||
88
with_opencm3/sync.c
Normal file
88
with_opencm3/sync.c
Normal file
@ -0,0 +1,88 @@
|
|||||||
|
/*
|
||||||
|
* This file is part of the libopencm3 project.
|
||||||
|
*
|
||||||
|
* Copyright (C) 2012 Fergus Noble <fergusnoble@gmail.com>
|
||||||
|
*
|
||||||
|
* This library is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU Lesser General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* This library 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 Lesser General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU Lesser General Public License
|
||||||
|
* along with this library. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include <libopencm3/cm3/sync.h>
|
||||||
|
|
||||||
|
/* DMB is supported on CM0 */
|
||||||
|
void __dmb()
|
||||||
|
{
|
||||||
|
__asm__ volatile ("dmb");
|
||||||
|
}
|
||||||
|
|
||||||
|
/* Those are defined only on CM3 or CM4 */
|
||||||
|
#if defined(__ARM_ARCH_7M__) || defined(__ARM_ARCH_7EM__)
|
||||||
|
|
||||||
|
uint32_t __ldrex(volatile uint32_t *addr)
|
||||||
|
{
|
||||||
|
uint32_t res;
|
||||||
|
__asm__ volatile ("ldrex %0, [%1]" : "=r" (res) : "r" (addr));
|
||||||
|
return res;
|
||||||
|
}
|
||||||
|
|
||||||
|
uint32_t __strex(uint32_t val, volatile uint32_t *addr)
|
||||||
|
{
|
||||||
|
uint32_t res;
|
||||||
|
__asm__ volatile ("strex %0, %2, [%1]"
|
||||||
|
: "=&r" (res) : "r" (addr), "r" (val));
|
||||||
|
return res;
|
||||||
|
}
|
||||||
|
|
||||||
|
void mutex_lock(mutex_t *m)
|
||||||
|
{
|
||||||
|
uint32_t status = 0;
|
||||||
|
|
||||||
|
do {
|
||||||
|
/* Wait until the mutex is unlocked. */
|
||||||
|
while (__ldrex(m) != MUTEX_UNLOCKED);
|
||||||
|
|
||||||
|
/* Try to acquire it. */
|
||||||
|
status = __strex(MUTEX_LOCKED, m);
|
||||||
|
|
||||||
|
/* Did we get it? If not then try again. */
|
||||||
|
} while (status != 0);
|
||||||
|
|
||||||
|
/* Execute the mysterious Data Memory Barrier instruction! */
|
||||||
|
__dmb();
|
||||||
|
}
|
||||||
|
|
||||||
|
void mutex_unlock(mutex_t *m)
|
||||||
|
{
|
||||||
|
/* Ensure accesses to protected resource are finished */
|
||||||
|
__dmb();
|
||||||
|
|
||||||
|
/* Free the lock. */
|
||||||
|
*m = MUTEX_UNLOCKED;
|
||||||
|
}
|
||||||
|
|
||||||
|
/*
|
||||||
|
* Try to lock mutex
|
||||||
|
* if it's already locked or there was error in STREX, return MUTEX_LOCKED
|
||||||
|
* else return MUTEX_UNLOCKED
|
||||||
|
*/
|
||||||
|
mutex_t mutex_trylock(mutex_t *m){
|
||||||
|
uint32_t status = 0;
|
||||||
|
mutex_t old_lock = __ldrex(m); // get mutex value
|
||||||
|
// set mutex
|
||||||
|
status = __strex(MUTEX_LOCKED, m);
|
||||||
|
if(status == 0) __dmb();
|
||||||
|
else old_lock = MUTEX_LOCKED;
|
||||||
|
return old_lock;
|
||||||
|
}
|
||||||
|
|
||||||
|
#endif
|
||||||
53
with_opencm3/sync.h
Normal file
53
with_opencm3/sync.h
Normal file
@ -0,0 +1,53 @@
|
|||||||
|
/*
|
||||||
|
* This file is part of the libopencm3 project.
|
||||||
|
*
|
||||||
|
* Copyright (C) 2012 Fergus Noble <fergusnoble@gmail.com>
|
||||||
|
*
|
||||||
|
* This library is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU Lesser General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* This library 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 Lesser General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU Lesser General Public License
|
||||||
|
* along with this library. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*/
|
||||||
|
|
||||||
|
#ifndef LIBOPENCM3_CM3_SYNC_H
|
||||||
|
#define LIBOPENCM3_CM3_SYNC_H
|
||||||
|
|
||||||
|
void __dmb(void);
|
||||||
|
|
||||||
|
/* Implements synchronisation primitives as discussed in the ARM document
|
||||||
|
* DHT0008A (ID081709) "ARM Synchronization Primitives" and the ARM v7-M
|
||||||
|
* Architecture Reference Manual.
|
||||||
|
*/
|
||||||
|
|
||||||
|
/* --- Exclusive load and store instructions ------------------------------- */
|
||||||
|
|
||||||
|
/* Those are defined only on CM3 or CM4 */
|
||||||
|
#if defined(__ARM_ARCH_7M__) || defined(__ARM_ARCH_7EM__)
|
||||||
|
|
||||||
|
uint32_t __ldrex(volatile uint32_t *addr);
|
||||||
|
uint32_t __strex(uint32_t val, volatile uint32_t *addr);
|
||||||
|
|
||||||
|
/* --- Convenience functions ----------------------------------------------- */
|
||||||
|
|
||||||
|
/* Here we implement some simple synchronisation primitives. */
|
||||||
|
|
||||||
|
typedef uint32_t mutex_t;
|
||||||
|
|
||||||
|
#define MUTEX_UNLOCKED 0
|
||||||
|
#define MUTEX_LOCKED 1
|
||||||
|
|
||||||
|
void mutex_lock(mutex_t *m);
|
||||||
|
void mutex_unlock(mutex_t *m);
|
||||||
|
mutex_t mutex_trylock(mutex_t *m);
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#endif
|
||||||
@ -74,7 +74,7 @@ void UART_setspeed(uint32_t UART, struct usb_cdc_line_coding *lc){
|
|||||||
void UART_init(uint32_t UART){
|
void UART_init(uint32_t UART){
|
||||||
uint32_t irq, rcc, rccgpio, gpioport, gpiopin;
|
uint32_t irq, rcc, rccgpio, gpioport, gpiopin;
|
||||||
switch(UART){
|
switch(UART){
|
||||||
case USART2:
|
case USART2: // 1-wire
|
||||||
irq = NVIC_USART2_IRQ; // interrupt for given USART
|
irq = NVIC_USART2_IRQ; // interrupt for given USART
|
||||||
rcc = RCC_USART2; // RCC timing of USART
|
rcc = RCC_USART2; // RCC timing of USART
|
||||||
rccgpio = RCC_GPIOA; // RCC timing of GPIO pin (for output)
|
rccgpio = RCC_GPIOA; // RCC timing of GPIO pin (for output)
|
||||||
@ -84,7 +84,7 @@ void UART_init(uint32_t UART){
|
|||||||
gpioport = GPIO_BANK_USART2_TX;
|
gpioport = GPIO_BANK_USART2_TX;
|
||||||
gpiopin = GPIO_USART2_TX;
|
gpiopin = GPIO_USART2_TX;
|
||||||
break;
|
break;
|
||||||
case USART3:
|
case USART3: // without remapping
|
||||||
irq = NVIC_USART3_IRQ;
|
irq = NVIC_USART3_IRQ;
|
||||||
rcc = RCC_USART3;
|
rcc = RCC_USART3;
|
||||||
rccgpio = RCC_GPIOB;
|
rccgpio = RCC_GPIOB;
|
||||||
@ -106,10 +106,19 @@ void UART_init(uint32_t UART){
|
|||||||
// enable clocking
|
// enable clocking
|
||||||
rcc_periph_clock_enable(RCC_AFIO); // alternate functions
|
rcc_periph_clock_enable(RCC_AFIO); // alternate functions
|
||||||
rcc_periph_clock_enable(rcc); // USART
|
rcc_periph_clock_enable(rcc); // USART
|
||||||
rcc_periph_clock_enable(rccgpio); // output pin
|
rcc_periph_clock_enable(rccgpio); // GPIO pins
|
||||||
// enable output pin
|
// enable output pin
|
||||||
|
if(UART == OW_USART_X){ // one wire
|
||||||
|
// TX: open-drain output
|
||||||
|
gpio_set_mode(gpioport, GPIO_MODE_OUTPUT_50_MHZ,
|
||||||
|
GPIO_CNF_OUTPUT_ALTFN_OPENDRAIN, gpiopin);
|
||||||
|
// RX: floating input
|
||||||
|
gpio_set_mode(OW_RX_PORT, GPIO_MODE_INPUT,
|
||||||
|
GPIO_CNF_INPUT_FLOAT, OW_RX_PIN);
|
||||||
|
}else{
|
||||||
gpio_set_mode(gpioport, GPIO_MODE_OUTPUT_50_MHZ,
|
gpio_set_mode(gpioport, GPIO_MODE_OUTPUT_50_MHZ,
|
||||||
GPIO_CNF_OUTPUT_ALTFN_PUSHPULL, gpiopin);
|
GPIO_CNF_OUTPUT_ALTFN_PUSHPULL, gpiopin);
|
||||||
|
}
|
||||||
// enable IRQ
|
// enable IRQ
|
||||||
nvic_enable_irq(irq);
|
nvic_enable_irq(irq);
|
||||||
UART_setspeed(UART, NULL);
|
UART_setspeed(UART, NULL);
|
||||||
|
|||||||
@ -24,7 +24,7 @@
|
|||||||
#define __UART_H__
|
#define __UART_H__
|
||||||
|
|
||||||
// Size of buffers
|
// Size of buffers
|
||||||
#define UART_TX_DATA_SIZE 64
|
#define UART_TX_DATA_SIZE 128
|
||||||
|
|
||||||
typedef struct {
|
typedef struct {
|
||||||
uint8_t buf[UART_TX_DATA_SIZE];
|
uint8_t buf[UART_TX_DATA_SIZE];
|
||||||
|
|||||||
@ -26,6 +26,8 @@
|
|||||||
|
|
||||||
// integer value given by user
|
// integer value given by user
|
||||||
static volatile int32_t User_value = 0;
|
static volatile int32_t User_value = 0;
|
||||||
|
// number of motor to process
|
||||||
|
static volatile uint8_t active_motor = 6;
|
||||||
// last active send function - to post "anonymous" replies
|
// last active send function - to post "anonymous" replies
|
||||||
sendfun lastsendfun = usb_send; // make it usb_send by default (to prevent suspension)
|
sendfun lastsendfun = usb_send; // make it usb_send by default (to prevent suspension)
|
||||||
// flag: !=0 when user value reading ends - for character terminals
|
// flag: !=0 when user value reading ends - for character terminals
|
||||||
@ -62,7 +64,8 @@ void print_ad_vals(sendfun s){
|
|||||||
|
|
||||||
void parce_incoming_buf(char *buf, int len, sendfun s){
|
void parce_incoming_buf(char *buf, int len, sendfun s){
|
||||||
uint8_t command;
|
uint8_t command;
|
||||||
int i = 0, j;
|
uint8_t onewire_addr[8];
|
||||||
|
int i = 0, j, m;
|
||||||
lastsendfun = s;
|
lastsendfun = s;
|
||||||
if(Uval_ready == UVAL_START){ // we are in process of user's value reading
|
if(Uval_ready == UVAL_START){ // we are in process of user's value reading
|
||||||
i += read_int(buf, len);
|
i += read_int(buf, len);
|
||||||
@ -78,11 +81,40 @@ void parce_incoming_buf(char *buf, int len, sendfun s){
|
|||||||
for(; i < len; i++){
|
for(; i < len; i++){
|
||||||
command = buf[i];
|
command = buf[i];
|
||||||
if(!command) continue; // omit zero
|
if(!command) continue; // omit zero
|
||||||
switch (command){
|
if(command >= '0' && command <= '4'){ // stepper motors
|
||||||
case '1': // single conversion
|
active_motor = command - '0';
|
||||||
|
I = stepper_proc;
|
||||||
|
READINT();
|
||||||
|
}else switch (command){
|
||||||
|
case 'P':
|
||||||
|
run_dmatimer();
|
||||||
|
break;
|
||||||
|
case 'x': // set period of TIM1 (motors 1..3)
|
||||||
|
active_motor = 1;
|
||||||
|
I = set_timr;
|
||||||
|
READINT();
|
||||||
|
break;
|
||||||
|
case 'X': // set period of TIM2 (motors 4,5)
|
||||||
|
active_motor = 4;
|
||||||
|
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("\r\n", s);
|
||||||
|
break;
|
||||||
|
case 'S': // single conversion
|
||||||
doubleconv = 0;
|
doubleconv = 0;
|
||||||
break;
|
break;
|
||||||
case '2': // double conversion
|
case 'D': // double conversion
|
||||||
doubleconv = 1;
|
doubleconv = 1;
|
||||||
break;
|
break;
|
||||||
case 'A': // show ADC value
|
case 'A': // show ADC value
|
||||||
@ -94,19 +126,12 @@ void parce_incoming_buf(char *buf, int len, sendfun s){
|
|||||||
}
|
}
|
||||||
newline(s);
|
newline(s);
|
||||||
break;
|
break;
|
||||||
case 'b': // turn LED off
|
|
||||||
gpio_set(GPIOC, GPIO12);
|
|
||||||
break;
|
|
||||||
case 'B': // turn LED on
|
|
||||||
gpio_clear(GPIOC, GPIO12);
|
|
||||||
break;
|
|
||||||
case 'I': // read & print integer value
|
|
||||||
I = process_int;
|
|
||||||
READINT();
|
|
||||||
break;
|
|
||||||
case 'i': // init AD7794
|
case 'i': // init AD7794
|
||||||
AD7794_init();
|
AD7794_init();
|
||||||
break;
|
break;
|
||||||
|
case 'I': // turn off flag AD7794
|
||||||
|
ad7794_on = 0;
|
||||||
|
break;
|
||||||
case '+': // user check number value & confirm it's right
|
case '+': // user check number value & confirm it's right
|
||||||
if(Uval_ready == UVAL_PRINTED) Uval_ready = UVAL_CHECKED;
|
if(Uval_ready == UVAL_PRINTED) Uval_ready = UVAL_CHECKED;
|
||||||
else WRONG_COMMAND();
|
else WRONG_COMMAND();
|
||||||
@ -140,9 +165,9 @@ void parce_incoming_buf(char *buf, int len, sendfun s){
|
|||||||
print_time(s);
|
print_time(s);
|
||||||
newline(s);
|
newline(s);
|
||||||
break;
|
break;
|
||||||
case 'U': // test: init USART1
|
/* case 'U': // test: init USART1
|
||||||
UART_init(USART1);
|
UART_init(USART1);
|
||||||
break;
|
break; */
|
||||||
case '\n': // show newline as is
|
case '\n': // show newline as is
|
||||||
break;
|
break;
|
||||||
case '\r':
|
case '\r':
|
||||||
@ -210,6 +235,27 @@ int read_int(char *buf, int cnt){
|
|||||||
return readed;
|
return readed;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Print buff as hex values
|
||||||
|
* @param buf - buffer to print
|
||||||
|
* @param l - buf length
|
||||||
|
* @param s - function to send a byte
|
||||||
|
*/
|
||||||
|
void print_hex(uint8_t *buff, uint8_t l, sendfun s){
|
||||||
|
void putc(uint8_t c){
|
||||||
|
if(c < 10)
|
||||||
|
s(c + '0');
|
||||||
|
else
|
||||||
|
s(c + 'a' - 10);
|
||||||
|
}
|
||||||
|
s('0'); s('x'); // prefix 0x
|
||||||
|
while(l--){
|
||||||
|
putc(buff[l] >> 4);
|
||||||
|
putc(buff[l] & 0x0f);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Print decimal integer value
|
* Print decimal integer value
|
||||||
* @param N - value to print
|
* @param N - value to print
|
||||||
@ -230,12 +276,14 @@ void print_int(int32_t N, sendfun s){
|
|||||||
}else s('0');
|
}else s('0');
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/*
|
||||||
void process_int(int32_t v, sendfun s){
|
void process_int(int32_t v, sendfun s){
|
||||||
newline(s);
|
newline(s);
|
||||||
P("You have entered a value ", s);
|
P("You have entered a value ", s);
|
||||||
print_int(v, s);
|
print_int(v, s);
|
||||||
newline(s);
|
newline(s);
|
||||||
}
|
}
|
||||||
|
*/
|
||||||
|
|
||||||
void set_ADC_gain(int32_t v, sendfun s){
|
void set_ADC_gain(int32_t v, sendfun s){
|
||||||
if(ad7794_on){
|
if(ad7794_on){
|
||||||
@ -246,3 +294,34 @@ void set_ADC_gain(int32_t v, sendfun s){
|
|||||||
AD7794_calibration(0);
|
AD7794_calibration(0);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Process stepper
|
||||||
|
* @param v - user value
|
||||||
|
* @param s - active sendfunction
|
||||||
|
*/
|
||||||
|
void stepper_proc(int32_t v, sendfun s){
|
||||||
|
if(active_motor > 4){
|
||||||
|
P("wrong motor number\r\n", s);
|
||||||
|
return; // error
|
||||||
|
}
|
||||||
|
MSG("move ");
|
||||||
|
lastsendfun('0' + active_motor);
|
||||||
|
MSG(" to ");
|
||||||
|
print_int(v, lastsendfun);
|
||||||
|
MSG("\r\n");
|
||||||
|
move_motor(active_motor, v);
|
||||||
|
active_motor = 6;
|
||||||
|
}
|
||||||
|
|
||||||
|
void set_timr(int32_t v, sendfun s){
|
||||||
|
if(active_motor > 4){
|
||||||
|
P("wrong motor number\r\n", s);
|
||||||
|
return; // error
|
||||||
|
}
|
||||||
|
MSG("set period: ");
|
||||||
|
print_int(v, lastsendfun);
|
||||||
|
MSG("\r\n");
|
||||||
|
set_motor_period(active_motor, (uint16_t)v);
|
||||||
|
active_motor = 6;
|
||||||
|
}
|
||||||
|
|||||||
@ -50,8 +50,11 @@ void print_int(int32_t N, sendfun s);
|
|||||||
|
|
||||||
void parce_incoming_buf(char *buf, int len, sendfun s);
|
void parce_incoming_buf(char *buf, int len, sendfun s);
|
||||||
|
|
||||||
void process_int(int32_t v, sendfun s);
|
// void process_int(int32_t v, sendfun s);
|
||||||
void set_ADC_gain(int32_t v, sendfun s);
|
void set_ADC_gain(int32_t v, sendfun s);
|
||||||
void print_ad_vals(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_hex(uint8_t *buff, uint8_t l, sendfun s);
|
||||||
|
|
||||||
#endif // __USER_PROTO_H__
|
#endif // __USER_PROTO_H__
|
||||||
|
|||||||
Loading…
x
Reference in New Issue
Block a user