mirror of
https://github.com/eddyem/IR-controller.git
synced 2025-12-06 10:45:15 +03:00
Add something to stepper_motors.c + make little modifications
This commit is contained in:
parent
4ce1ca9c71
commit
48b8dd8f88
1
.gitignore
vendored
1
.gitignore
vendored
@ -6,4 +6,5 @@
|
|||||||
*.dcm
|
*.dcm
|
||||||
*.pho
|
*.pho
|
||||||
*.drl
|
*.drl
|
||||||
|
*.pdf
|
||||||
.hg*
|
.hg*
|
||||||
|
|||||||
@ -2,3 +2,6 @@ IR-controller
|
|||||||
=============
|
=============
|
||||||
|
|
||||||
Clone of same project from sourceforge
|
Clone of same project from sourceforge
|
||||||
|
|
||||||
|
Don't use files from root directory, they are obsolete!!!
|
||||||
|
Current code is in directory with_opencm3.
|
||||||
|
|||||||
@ -3,7 +3,7 @@
|
|||||||
(general
|
(general
|
||||||
(links 458)
|
(links 458)
|
||||||
(no_connects 0)
|
(no_connects 0)
|
||||||
(area 50.849999 56.849999 245.150001 145.150001)
|
(area 44.8945 56.306 271.000001 146.8628)
|
||||||
(thickness 1.6)
|
(thickness 1.6)
|
||||||
(drawings 26)
|
(drawings 26)
|
||||||
(tracks 1581)
|
(tracks 1581)
|
||||||
@ -30,7 +30,7 @@
|
|||||||
)
|
)
|
||||||
|
|
||||||
(setup
|
(setup
|
||||||
(last_trace_width 2.032)
|
(last_trace_width 0.254)
|
||||||
(user_trace_width 0.254)
|
(user_trace_width 0.254)
|
||||||
(user_trace_width 0.508)
|
(user_trace_width 0.508)
|
||||||
(user_trace_width 1.016)
|
(user_trace_width 1.016)
|
||||||
@ -56,8 +56,8 @@
|
|||||||
(mod_edge_width 0.3)
|
(mod_edge_width 0.3)
|
||||||
(mod_text_size 1.5 1.5)
|
(mod_text_size 1.5 1.5)
|
||||||
(mod_text_width 0.3)
|
(mod_text_width 0.3)
|
||||||
(pad_size 0.9 0.9)
|
(pad_size 1.5 2)
|
||||||
(pad_drill 0.9)
|
(pad_drill 0.8)
|
||||||
(pad_to_mask_clearance 0.2)
|
(pad_to_mask_clearance 0.2)
|
||||||
(aux_axis_origin 51 57)
|
(aux_axis_origin 51 57)
|
||||||
(visible_elements FFFFFFBF)
|
(visible_elements FFFFFFBF)
|
||||||
@ -5987,7 +5987,7 @@
|
|||||||
)
|
)
|
||||||
)
|
)
|
||||||
|
|
||||||
(module SIP-4-RO (layer F.Cu) (tedit 53BBF819) (tstamp 54746759)
|
(module SIP-4-RO (layer F.Cu) (tedit 54B3B085) (tstamp 54746759)
|
||||||
(at 126.746 86.233 90)
|
(at 126.746 86.233 90)
|
||||||
(path /5477C0AD)
|
(path /5477C0AD)
|
||||||
(fp_text reference DA3 (at 0 2.54 90) (layer F.SilkS)
|
(fp_text reference DA3 (at 0 2.54 90) (layer F.SilkS)
|
||||||
@ -6000,19 +6000,19 @@
|
|||||||
(fp_line (start -5.715 1.27) (end -5.715 -4.445) (layer F.SilkS) (width 0.15))
|
(fp_line (start -5.715 1.27) (end -5.715 -4.445) (layer F.SilkS) (width 0.15))
|
||||||
(fp_line (start -5.715 -4.445) (end 5.715 -4.445) (layer F.SilkS) (width 0.15))
|
(fp_line (start -5.715 -4.445) (end 5.715 -4.445) (layer F.SilkS) (width 0.15))
|
||||||
(fp_line (start 5.715 -4.445) (end 5.715 1.27) (layer F.SilkS) (width 0.15))
|
(fp_line (start 5.715 -4.445) (end 5.715 1.27) (layer F.SilkS) (width 0.15))
|
||||||
(pad 3 thru_hole circle (at 1.27 0 90) (size 1.5 1.5) (drill 0.6)
|
(pad 3 thru_hole circle (at 1.27 0 90) (size 1.5 1.5) (drill 0.8)
|
||||||
(layers *.Cu *.Mask F.SilkS)
|
(layers *.Cu *.Mask F.SilkS)
|
||||||
(net 99 GND)
|
(net 99 GND)
|
||||||
)
|
)
|
||||||
(pad 4 thru_hole circle (at 3.81 0 90) (size 1.5 1.5) (drill 0.6)
|
(pad 4 thru_hole circle (at 3.81 0 90) (size 1.5 1.5) (drill 0.8)
|
||||||
(layers *.Cu *.Mask F.SilkS)
|
(layers *.Cu *.Mask F.SilkS)
|
||||||
(net 2 +5V)
|
(net 2 +5V)
|
||||||
)
|
)
|
||||||
(pad 2 thru_hole circle (at -1.27 0 90) (size 1.5 1.5) (drill 0.6)
|
(pad 2 thru_hole circle (at -1.27 0 90) (size 1.5 1.5) (drill 0.8)
|
||||||
(layers *.Cu *.Mask F.SilkS)
|
(layers *.Cu *.Mask F.SilkS)
|
||||||
(net 7 "/Filters slit #1/+10V")
|
(net 7 "/Filters slit #1/+10V")
|
||||||
)
|
)
|
||||||
(pad 1 thru_hole rect (at -3.81 0 90) (size 1.5 2) (drill 0.6)
|
(pad 1 thru_hole rect (at -3.81 0 90) (size 1.5 2) (drill 0.8)
|
||||||
(layers *.Cu *.Mask F.SilkS)
|
(layers *.Cu *.Mask F.SilkS)
|
||||||
(net 99 GND)
|
(net 99 GND)
|
||||||
)
|
)
|
||||||
|
|||||||
@ -1,4 +1,4 @@
|
|||||||
eeschema (2013-feb-26)-stable >> Creation date: Вт 25 ноя 2014 15:57:59
|
eeschema (2013-feb-26)-stable >> Creation date: Пн 12 янв 2015 13:50:38
|
||||||
#Cmp ( order = Reference )
|
#Cmp ( order = Reference )
|
||||||
| C4 2200u, 40V
|
| C4 2200u, 40V
|
||||||
| C5 10u
|
| C5 10u
|
||||||
@ -126,6 +126,7 @@ eeschema (2013-feb-26)-stable >> Creation date: Вт 25 ноя 2014 15:57:59
|
|||||||
| R6.5 51k
|
| R6.5 51k
|
||||||
| SB1 RESET
|
| SB1 RESET
|
||||||
| SB2 BOOT
|
| SB2 BOOT
|
||||||
|
| U1 LM7805CT
|
||||||
| VD1 B120-E3
|
| VD1 B120-E3
|
||||||
| VD2 PWR
|
| VD2 PWR
|
||||||
| VD3 B120-E3
|
| VD3 B120-E3
|
||||||
@ -269,6 +270,7 @@ eeschema (2013-feb-26)-stable >> Creation date: Вт 25 ноя 2014 15:57:59
|
|||||||
| RT0805BRB071KL R34
|
| RT0805BRB071KL R34
|
||||||
| RESET SB1
|
| RESET SB1
|
||||||
| BOOT SB2
|
| BOOT SB2
|
||||||
|
| LM7805CT U1
|
||||||
| B120-E3 VD1
|
| B120-E3 VD1
|
||||||
| B120-E3 VD3
|
| B120-E3 VD3
|
||||||
| PWR VD2
|
| PWR VD2
|
||||||
|
|||||||
@ -4,12 +4,12 @@ Functional map of MCU pins
|
|||||||
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 PE6 DG_FEEDBACK feedback from power switch POW_LOAD (+10..12V)
|
004 PE5 POW3 Turn ON/OFF power switch POW_LOAD
|
||||||
005 -
|
005 PE6 DG_FEEDBACK feedback from power switch POW_LOAD (+10..12V)
|
||||||
006 -
|
006 VBAT -
|
||||||
007 -
|
007 PC13 -
|
||||||
008 -
|
008 PC14 -
|
||||||
009 -
|
009 PC15 -
|
||||||
010 VSS GND
|
010 VSS GND
|
||||||
011 VDD +3.3V
|
011 VDD +3.3V
|
||||||
012 OSC_IN 8MHz in
|
012 OSC_IN 8MHz in
|
||||||
@ -18,7 +18,7 @@ Functional map of MCU pins
|
|||||||
015 PC0 SHTR Shutter on pulse
|
015 PC0 SHTR Shutter on pulse
|
||||||
016 PC1 SHTR_FB Error signal from shutter H-bridge
|
016 PC1 SHTR_FB Error signal from shutter H-bridge
|
||||||
017 PC2 POW0 Shutter polarity (open/close)
|
017 PC2 POW0 Shutter polarity (open/close)
|
||||||
018 -
|
018 PC3 -
|
||||||
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)
|
||||||
@ -45,23 +45,23 @@ Functional map of MCU pins
|
|||||||
042 PE11 EN5 /
|
042 PE11 EN5 /
|
||||||
043 PE12 POW2\
|
043 PE12 POW2\
|
||||||
044 PE13 POW1/ Power load (10..12V, pull-down)
|
044 PE13 POW1/ Power load (10..12V, pull-down)
|
||||||
045 -
|
045 PE14 -
|
||||||
046 -
|
046 PE15 -
|
||||||
047 PB10 USART3_TX RS-232 (master)
|
047 PB10 USART3_TX RS-232 (master)
|
||||||
048 PB11 USART3_RX
|
048 PB11 USART3_RX
|
||||||
049 VSS GND
|
049 VSS GND
|
||||||
050 VDD +3.3V
|
050 VDD +3.3V
|
||||||
051 -
|
051 PB12 -
|
||||||
052 SPI2_SCK \
|
052 SPI2_SCK \
|
||||||
053 SPI2_MISO | External SPI connection (at edge of the board)
|
053 SPI2_MISO | External SPI connection (at edge of the board)
|
||||||
054 SPI2_MOSI /
|
054 SPI2_MOSI /
|
||||||
055 -
|
055 PD8 -
|
||||||
056 -
|
056 PD9 -
|
||||||
057 PD10 EXT0\
|
057 PD10 EXT0\
|
||||||
058 PD11 EXT1 | ADG506 address selection
|
058 PD11 EXT1 | ADG506 address selection
|
||||||
059 PD12 EXT2 | or custom external ports
|
059 PD12 EXT2 | or custom external ports
|
||||||
060 PD13 EXT3/
|
060 PD13 EXT3/
|
||||||
061 -
|
061 PD14 -
|
||||||
062 PD15 TIM2 timer for motors 4&5
|
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 \ LS1 Linear stage 1 (long) DOWN end-switch
|
064 PC7 \ LS1 Linear stage 1 (long) DOWN end-switch
|
||||||
@ -72,15 +72,15 @@ Functional map of MCU pins
|
|||||||
069 PA10 BOOT_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 PA13 -
|
||||||
073 -
|
073 NC -
|
||||||
074 VSS GND
|
074 VSS GND
|
||||||
075 VDD +3.3V
|
075 VDD +3.3V
|
||||||
076 -
|
076 PA14 -
|
||||||
077 -
|
077 PA15 -
|
||||||
078 PC10 USB_POWER +3V when USB connected
|
078 PC10 USB_POWER +3V when USB connected
|
||||||
079 PC11 USB_DISC software USB disconnection (low lewel for bipolar VT1, high level for p-channel MOSFET)
|
079 PC11 USB_DISC software USB disconnection (low lewel for n-channel VT1, high level for pnp bipolar or p-channel MOSFET)
|
||||||
080 -
|
080 PC12 -
|
||||||
081 PD0 \
|
081 PD0 \
|
||||||
082 PD1 | Tur1 Slits turret Hall sensors
|
082 PD1 | Tur1 Slits turret Hall sensors
|
||||||
083 PD2 |
|
083 PD2 |
|
||||||
@ -99,5 +99,5 @@ Functional map of MCU pins
|
|||||||
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 GND
|
||||||
100 VDD
|
100 VDD +3.3V
|
||||||
|
|||||||
File diff suppressed because it is too large
Load Diff
@ -1,10 +1,11 @@
|
|||||||
PCBNEW-LibModule-V1 Ср 12 ноя 2014 16:43:23
|
PCBNEW-LibModule-V1 Пн 01 дек 2014 09:34:38
|
||||||
# encoding utf-8
|
# encoding utf-8
|
||||||
Units mm
|
Units mm
|
||||||
$INDEX
|
$INDEX
|
||||||
AC_220
|
AC_220
|
||||||
DB9-F
|
DB9-F
|
||||||
DB9-M
|
DB9-M
|
||||||
|
HXQFN16
|
||||||
IRM-10
|
IRM-10
|
||||||
MICRO-B-USB
|
MICRO-B-USB
|
||||||
MINI-B-USB
|
MINI-B-USB
|
||||||
@ -249,6 +250,145 @@ Of 0 0 0
|
|||||||
Ro 0 0 0
|
Ro 0 0 0
|
||||||
$EndSHAPE3D
|
$EndSHAPE3D
|
||||||
$EndMODULE DB9-M
|
$EndMODULE DB9-M
|
||||||
|
$MODULE HXQFN16
|
||||||
|
Po 0 0 0 15 547C0BEB 00000000 ~~
|
||||||
|
Li HXQFN16
|
||||||
|
Sc 0
|
||||||
|
AR
|
||||||
|
Op 0 0 0
|
||||||
|
T0 0 -2.3 0.14986 0.14986 0 0.0381 N V 21 N "Test"
|
||||||
|
T1 0 2.3 0.14986 0.14986 0 0.0381 N V 21 N "VAL**"
|
||||||
|
DS -1 1.6 -1.5 1 0.15 21
|
||||||
|
DS -1.5 1 -1.8 1 0.15 21
|
||||||
|
DS -1.8 1 -1 2 0.15 21
|
||||||
|
DS -1 2 -1 1.6 0.15 21
|
||||||
|
DS 1.5 1.1 1.5 1.2 0.15 21
|
||||||
|
DS 1.5 1.2 1.5 1.5 0.15 21
|
||||||
|
DS 1.5 1.5 1.1 1.5 0.15 21
|
||||||
|
DS -1.5 -1.1 -1.5 -1.5 0.15 21
|
||||||
|
DS -1.5 -1.5 -1.1 -1.5 0.15 21
|
||||||
|
DS 1.5 -1.5 1.5 -1.1 0.15 21
|
||||||
|
DS 1.1 -1.5 1.5 -1.5 0.15 21
|
||||||
|
$PAD
|
||||||
|
Sh "1" R 0.3 0.6 0 0 1800
|
||||||
|
Dr 0 0 0
|
||||||
|
At SMD N 00888000
|
||||||
|
Ne 0 ""
|
||||||
|
Po -0.75 1.5
|
||||||
|
$EndPAD
|
||||||
|
$PAD
|
||||||
|
Sh "2" R 0.3 0.6 0 0 1800
|
||||||
|
Dr 0 0 0
|
||||||
|
At SMD N 00888000
|
||||||
|
Ne 0 ""
|
||||||
|
Po -0.25 1.5
|
||||||
|
$EndPAD
|
||||||
|
$PAD
|
||||||
|
Sh "3" R 0.3 0.6 0 0 1800
|
||||||
|
Dr 0 0 0
|
||||||
|
At SMD N 00888000
|
||||||
|
Ne 0 ""
|
||||||
|
Po 0.25 1.5
|
||||||
|
$EndPAD
|
||||||
|
$PAD
|
||||||
|
Sh "4" R 0.3 0.6 0 0 1800
|
||||||
|
Dr 0 0 0
|
||||||
|
At SMD N 00888000
|
||||||
|
Ne 0 ""
|
||||||
|
Po 0.75 1.5
|
||||||
|
$EndPAD
|
||||||
|
$PAD
|
||||||
|
Sh "5" R 0.3 0.6 0 0 2700
|
||||||
|
Dr 0 0 0
|
||||||
|
At SMD N 00888000
|
||||||
|
Ne 0 ""
|
||||||
|
Po 1.5 0.75
|
||||||
|
$EndPAD
|
||||||
|
$PAD
|
||||||
|
Sh "6" R 0.3 0.6 0 0 2700
|
||||||
|
Dr 0 0 0
|
||||||
|
At SMD N 00888000
|
||||||
|
Ne 0 ""
|
||||||
|
Po 1.5 0.25
|
||||||
|
$EndPAD
|
||||||
|
$PAD
|
||||||
|
Sh "7" R 0.3 0.6 0 0 2700
|
||||||
|
Dr 0 0 0
|
||||||
|
At SMD N 00888000
|
||||||
|
Ne 0 ""
|
||||||
|
Po 1.5 -0.25
|
||||||
|
$EndPAD
|
||||||
|
$PAD
|
||||||
|
Sh "8" R 0.3 0.6 0 0 2700
|
||||||
|
Dr 0 0 0
|
||||||
|
At SMD N 00888000
|
||||||
|
Ne 0 ""
|
||||||
|
Po 1.5 -0.75
|
||||||
|
$EndPAD
|
||||||
|
$PAD
|
||||||
|
Sh "9" R 0.3 0.6 0 0 0
|
||||||
|
Dr 0 0 0
|
||||||
|
At SMD N 00888000
|
||||||
|
Ne 0 ""
|
||||||
|
Po 0.75 -1.5
|
||||||
|
$EndPAD
|
||||||
|
$PAD
|
||||||
|
Sh "10" R 0.3 0.6 0 0 0
|
||||||
|
Dr 0 0 0
|
||||||
|
At SMD N 00888000
|
||||||
|
Ne 0 ""
|
||||||
|
Po 0.25 -1.5
|
||||||
|
$EndPAD
|
||||||
|
$PAD
|
||||||
|
Sh "11" R 0.3 0.6 0 0 0
|
||||||
|
Dr 0 0 0
|
||||||
|
At SMD N 00888000
|
||||||
|
Ne 0 ""
|
||||||
|
Po -0.25 -1.5
|
||||||
|
$EndPAD
|
||||||
|
$PAD
|
||||||
|
Sh "12" R 0.3 0.6 0 0 0
|
||||||
|
Dr 0 0 0
|
||||||
|
At SMD N 00888000
|
||||||
|
Ne 0 ""
|
||||||
|
Po -0.75 -1.5
|
||||||
|
$EndPAD
|
||||||
|
$PAD
|
||||||
|
Sh "13" R 0.3 0.6 0 0 900
|
||||||
|
Dr 0 0 0
|
||||||
|
At SMD N 00888000
|
||||||
|
Ne 0 ""
|
||||||
|
Po -1.5 -0.75
|
||||||
|
$EndPAD
|
||||||
|
$PAD
|
||||||
|
Sh "14" R 0.3 0.6 0 0 900
|
||||||
|
Dr 0 0 0
|
||||||
|
At SMD N 00888000
|
||||||
|
Ne 0 ""
|
||||||
|
Po -1.5 -0.25
|
||||||
|
$EndPAD
|
||||||
|
$PAD
|
||||||
|
Sh "15" R 0.3 0.6 0 0 900
|
||||||
|
Dr 0 0 0
|
||||||
|
At SMD N 00888000
|
||||||
|
Ne 0 ""
|
||||||
|
Po -1.5 0.25
|
||||||
|
$EndPAD
|
||||||
|
$PAD
|
||||||
|
Sh "16" R 0.3 0.6 0 0 900
|
||||||
|
Dr 0 0 0
|
||||||
|
At SMD N 00888000
|
||||||
|
Ne 0 ""
|
||||||
|
Po -1.5 0.75
|
||||||
|
$EndPAD
|
||||||
|
$PAD
|
||||||
|
Sh "nc" R 1.85 1.85 0 0 0
|
||||||
|
Dr 0 0 0
|
||||||
|
At SMD N 00888000
|
||||||
|
Ne 0 ""
|
||||||
|
Po 0 0
|
||||||
|
$EndPAD
|
||||||
|
$EndMODULE HXQFN16
|
||||||
$MODULE IRM-10
|
$MODULE IRM-10
|
||||||
Po 0 0 0 15 5461D14B 00000000 ~~
|
Po 0 0 0 15 5461D14B 00000000 ~~
|
||||||
Li IRM-10
|
Li IRM-10
|
||||||
@ -391,13 +531,13 @@ Po -3.79984 -1.4478
|
|||||||
$EndPAD
|
$EndPAD
|
||||||
$EndMODULE MICRO-B-USB
|
$EndMODULE MICRO-B-USB
|
||||||
$MODULE MINI-B-USB
|
$MODULE MINI-B-USB
|
||||||
Po 0 0 0 15 53C4D80A 00000000 ~~
|
Po 0 0 0 15 54749293 00000000 ~~
|
||||||
Li MINI-B-USB
|
Li MINI-B-USB
|
||||||
Sc 0
|
Sc 0
|
||||||
AR
|
AR /53973803/53976CAB/53BE6988
|
||||||
Op 0 0 0
|
Op 0 0 0
|
||||||
T0 0 -5.842 0.762 0.762 0 0.127 N V 21 N "MINI-B-USB"
|
T0 -4.1275 -5.4045 0.762 0.762 0 0.127 N V 21 N "CON1"
|
||||||
T1 -0.05 2.09 0.762 0.762 0 0.127 N V 21 N "VAL**"
|
T1 4.8895 -5.4045 0.762 0.762 0 0.127 N V 21 N "USB-MICRO-B"
|
||||||
DS -6 5 -6 -4.5 0.3 21
|
DS -6 5 -6 -4.5 0.3 21
|
||||||
DS 6 -4.5 6 5 0.3 21
|
DS 6 -4.5 6 5 0.3 21
|
||||||
DS 6 5 -6 5 0.3 21
|
DS 6 5 -6 5 0.3 21
|
||||||
@ -406,7 +546,7 @@ DS -8 5.85 8 5.85 0.3 21
|
|||||||
$PAD
|
$PAD
|
||||||
Sh "" C 0.9 0.9 0 0 0
|
Sh "" C 0.9 0.9 0 0 0
|
||||||
Dr 0.9 0 0
|
Dr 0.9 0 0
|
||||||
At HOLE N 00E0FFFF
|
At STD N 0020FFFF
|
||||||
Ne 0 ""
|
Ne 0 ""
|
||||||
Po 2.2 0
|
Po 2.2 0
|
||||||
$EndPAD
|
$EndPAD
|
||||||
@ -414,28 +554,28 @@ $PAD
|
|||||||
Sh "7" R 2 2.5 0 0 0
|
Sh "7" R 2 2.5 0 0 0
|
||||||
Dr 0 0 0
|
Dr 0 0 0
|
||||||
At SMD N 00888000
|
At SMD N 00888000
|
||||||
Ne 0 ""
|
Ne 1 "GND"
|
||||||
Po -4.45 2.87
|
Po -4.45 2.87
|
||||||
$EndPAD
|
$EndPAD
|
||||||
$PAD
|
$PAD
|
||||||
Sh "8" R 2 2.5 0 0 0
|
Sh "8" R 2 2.5 0 0 0
|
||||||
Dr 0 0 0
|
Dr 0 0 0
|
||||||
At SMD N 00888000
|
At SMD N 00888000
|
||||||
Ne 0 ""
|
Ne 1 "GND"
|
||||||
Po 4.45 -2.58
|
Po 4.45 -2.58
|
||||||
$EndPAD
|
$EndPAD
|
||||||
$PAD
|
$PAD
|
||||||
Sh "9" R 2 2.5 0 0 0
|
Sh "9" R 2 2.5 0 0 0
|
||||||
Dr 0 0 0
|
Dr 0 0 0
|
||||||
At SMD N 00888000
|
At SMD N 00888000
|
||||||
Ne 0 ""
|
Ne 1 "GND"
|
||||||
Po 4.45 2.87
|
Po 4.45 2.87
|
||||||
$EndPAD
|
$EndPAD
|
||||||
$PAD
|
$PAD
|
||||||
Sh "1" R 0.5 2.25 0 0 0
|
Sh "1" R 0.5 2.25 0 0 0
|
||||||
Dr 0 0 0
|
Dr 0 0 0
|
||||||
At SMD N 00888000
|
At SMD N 00888000
|
||||||
Ne 0 ""
|
Ne 4 "N-00000175"
|
||||||
Po -1.6 -2.58
|
Po -1.6 -2.58
|
||||||
.LocalClearance 0.1
|
.LocalClearance 0.1
|
||||||
$EndPAD
|
$EndPAD
|
||||||
@ -443,7 +583,7 @@ $PAD
|
|||||||
Sh "2" R 0.5 2.25 0 0 0
|
Sh "2" R 0.5 2.25 0 0 0
|
||||||
Dr 0 0 0
|
Dr 0 0 0
|
||||||
At SMD N 00888000
|
At SMD N 00888000
|
||||||
Ne 0 ""
|
Ne 3 "N-00000171"
|
||||||
Po -0.8 -2.58
|
Po -0.8 -2.58
|
||||||
.LocalClearance 0.1
|
.LocalClearance 0.1
|
||||||
$EndPAD
|
$EndPAD
|
||||||
@ -451,7 +591,7 @@ $PAD
|
|||||||
Sh "3" R 0.5 2.25 0 0 0
|
Sh "3" R 0.5 2.25 0 0 0
|
||||||
Dr 0 0 0
|
Dr 0 0 0
|
||||||
At SMD N 00888000
|
At SMD N 00888000
|
||||||
Ne 0 ""
|
Ne 2 "N-00000170"
|
||||||
Po 0 -2.58
|
Po 0 -2.58
|
||||||
.LocalClearance 0.1
|
.LocalClearance 0.1
|
||||||
$EndPAD
|
$EndPAD
|
||||||
@ -459,7 +599,7 @@ $PAD
|
|||||||
Sh "4" R 0.5 2.25 0 0 0
|
Sh "4" R 0.5 2.25 0 0 0
|
||||||
Dr 0 0 0
|
Dr 0 0 0
|
||||||
At SMD N 00888000
|
At SMD N 00888000
|
||||||
Ne 0 ""
|
Ne 1 "GND"
|
||||||
Po 0.8 -2.58
|
Po 0.8 -2.58
|
||||||
.LocalClearance 0.1
|
.LocalClearance 0.1
|
||||||
$EndPAD
|
$EndPAD
|
||||||
@ -467,7 +607,7 @@ $PAD
|
|||||||
Sh "5" R 0.5 2.25 0 0 0
|
Sh "5" R 0.5 2.25 0 0 0
|
||||||
Dr 0 0 0
|
Dr 0 0 0
|
||||||
At SMD N 00888000
|
At SMD N 00888000
|
||||||
Ne 0 ""
|
Ne 1 "GND"
|
||||||
Po 1.6 -2.58
|
Po 1.6 -2.58
|
||||||
.LocalClearance 0.1
|
.LocalClearance 0.1
|
||||||
$EndPAD
|
$EndPAD
|
||||||
@ -475,13 +615,13 @@ $PAD
|
|||||||
Sh "6" R 2 2.5 0 0 0
|
Sh "6" R 2 2.5 0 0 0
|
||||||
Dr 0 0 0
|
Dr 0 0 0
|
||||||
At SMD N 00888000
|
At SMD N 00888000
|
||||||
Ne 0 ""
|
Ne 1 "GND"
|
||||||
Po -4.45 -2.58
|
Po -4.45 -2.58
|
||||||
$EndPAD
|
$EndPAD
|
||||||
$PAD
|
$PAD
|
||||||
Sh "" C 0.9 0.9 0 0 0
|
Sh "" C 0.9 0.9 0 0 0
|
||||||
Dr 0.9 0 0
|
Dr 0.9 0 0
|
||||||
At HOLE N 00E0FFFF
|
At STD N 0020FFFF
|
||||||
Ne 0 ""
|
Ne 0 ""
|
||||||
Po -2.2 0
|
Po -2.2 0
|
||||||
$EndPAD
|
$EndPAD
|
||||||
@ -1688,13 +1828,13 @@ Po 59.99734 -2.9972
|
|||||||
$EndPAD
|
$EndPAD
|
||||||
$EndMODULE gprm1-61
|
$EndMODULE gprm1-61
|
||||||
$MODULE hole_3mm
|
$MODULE hole_3mm
|
||||||
Po 0 0 0 15 53C3925D 00000000 ~~
|
Po 0 0 0 15 547491FA 00000000 ~~
|
||||||
Li hole_3mm
|
Li hole_3mm
|
||||||
Sc 0
|
Sc 0
|
||||||
AR
|
AR
|
||||||
Op 0 0 0
|
Op 0 0 0
|
||||||
T0 0 -2.54 1.5 1.5 0 0.3 N I 21 N "hole_3mm"
|
T0 0 -2.54 1.5 1.5 0 0.3 N I 21 N "hole_3mm"
|
||||||
T1 0 3.175 1.5 1.5 0 0.3 N V 21 N ""
|
T1 0 3.175 1.5 1.5 0 0.3 N V 21 N "Val**"
|
||||||
DS 0 2.5 0 1.5 0.3 21
|
DS 0 2.5 0 1.5 0.3 21
|
||||||
DS -2.5 0 -1.5 0 0.3 21
|
DS -2.5 0 -1.5 0 0.3 21
|
||||||
DS 2.5 0 1.5 0 0.3 21
|
DS 2.5 0 1.5 0 0.3 21
|
||||||
@ -1703,7 +1843,7 @@ DC 0 0 2.5 0 0.3 21
|
|||||||
$PAD
|
$PAD
|
||||||
Sh "" C 3 3 0 0 0
|
Sh "" C 3 3 0 0 0
|
||||||
Dr 3 0 0
|
Dr 3 0 0
|
||||||
At STD N 00E0FFFF
|
At STD N 0020FFFF
|
||||||
Ne 0 ""
|
Ne 0 ""
|
||||||
Po 0 0
|
Po 0 0
|
||||||
$EndPAD
|
$EndPAD
|
||||||
|
|||||||
@ -105,7 +105,7 @@ uint32_t read_ADC_data(){
|
|||||||
*/
|
*/
|
||||||
uint8_t check_data_ready(){
|
uint8_t check_data_ready(){
|
||||||
uint8_t ret = 0;
|
uint8_t ret = 0;
|
||||||
//DBG("check_data_ready\r\n");
|
//DBG("check_data_ready\n");
|
||||||
uint8_t x = sendByte(STAT_REGISTER | READ_FROM_REG, 0);
|
uint8_t x = sendByte(STAT_REGISTER | READ_FROM_REG, 0);
|
||||||
if(data_error){
|
if(data_error){
|
||||||
DBG("some data error\n");
|
DBG("some data error\n");
|
||||||
@ -231,7 +231,7 @@ uint32_t read_AD7794(uint8_t channel){
|
|||||||
if(!dr) return AD7794_NOTRDY;
|
if(!dr) return AD7794_NOTRDY;
|
||||||
break;
|
break;
|
||||||
default: // last step -> return readed data
|
default: // last step -> return readed data
|
||||||
//P("\r\n", uart1_send);
|
//P("\n", uart1_send);
|
||||||
N = 0;
|
N = 0;
|
||||||
return read_ADC_data();
|
return read_ADC_data();
|
||||||
}
|
}
|
||||||
|
|||||||
@ -198,15 +198,17 @@ static int cdcacm_control_request(usbd_device *usbd_dev, struct usb_setup_data *
|
|||||||
|
|
||||||
switch (req->bRequest) {
|
switch (req->bRequest) {
|
||||||
case SET_CONTROL_LINE_STATE:{
|
case SET_CONTROL_LINE_STATE:{
|
||||||
P("SET_CONTROL_LINE_STATE\r\n", uart1_send);
|
#ifdef EBUG
|
||||||
print_int(req->wValue, uart1_send);
|
P("SET_CONTROL_LINE_STATE\n", uart1_send);
|
||||||
newline(uart1_send);
|
print_int(req->wValue, uart1_send);
|
||||||
|
newline(uart1_send);
|
||||||
|
#endif
|
||||||
if(req->wValue){ // terminal is opened
|
if(req->wValue){ // terminal is opened
|
||||||
USB_connected = 1;
|
USB_connected = 1;
|
||||||
//P("\r\n\tUSB connected!\r\n", uart1_send);
|
//P("\n\tUSB connected!\n", uart1_send);
|
||||||
}else{ // terminal is closed
|
}else{ // terminal is closed
|
||||||
USB_connected = 0;
|
USB_connected = 0;
|
||||||
//P("\r\n\tUSB disconnected!\r\n", uart1_send);
|
//P("\n\tUSB disconnected!\n", uart1_send);
|
||||||
}
|
}
|
||||||
/*
|
/*
|
||||||
* This Linux cdc_acm driver requires this to be implemented
|
* This Linux cdc_acm driver requires this to be implemented
|
||||||
@ -225,11 +227,15 @@ newline(uart1_send);
|
|||||||
usbd_ep_write_packet(usbd_dev, 0x83, local_buf, 10);
|
usbd_ep_write_packet(usbd_dev, 0x83, local_buf, 10);
|
||||||
}break;
|
}break;
|
||||||
case SET_LINE_CODING:
|
case SET_LINE_CODING:
|
||||||
P("SET_LINE_CODING, len=", uart1_send);
|
#ifdef EBUG
|
||||||
|
P("SET_LINE_CODING, len=", uart1_send);
|
||||||
|
#endif
|
||||||
if (!len || (*len != sizeof(struct usb_cdc_line_coding)))
|
if (!len || (*len != sizeof(struct usb_cdc_line_coding)))
|
||||||
return 0;
|
return 0;
|
||||||
print_int(*len, uart1_send);
|
#ifdef EBUG
|
||||||
newline(uart1_send);
|
print_int(*len, uart1_send);
|
||||||
|
newline(uart1_send);
|
||||||
|
#endif
|
||||||
memcpy((void *)&lc, (void *)*buf, *len);
|
memcpy((void *)&lc, (void *)*buf, *len);
|
||||||
// Mark & Space parity don't support by hardware, check it
|
// Mark & Space parity don't support by hardware, check it
|
||||||
if(lc.bParityType == USB_CDC_MARK_PARITY || lc.bParityType == USB_CDC_SPACE_PARITY){
|
if(lc.bParityType == USB_CDC_MARK_PARITY || lc.bParityType == USB_CDC_SPACE_PARITY){
|
||||||
@ -243,10 +249,14 @@ newline(uart1_send);
|
|||||||
if(len && *len == sizeof(struct usb_cdc_line_coding))
|
if(len && *len == sizeof(struct usb_cdc_line_coding))
|
||||||
memcpy((void *)*buf, (void *)&linecoding, sizeof(struct usb_cdc_line_coding));
|
memcpy((void *)*buf, (void *)&linecoding, sizeof(struct usb_cdc_line_coding));
|
||||||
//usbd_ep_write_packet(usbd_dev, 0x83, (char*)&linecoding, sizeof(linecoding));
|
//usbd_ep_write_packet(usbd_dev, 0x83, (char*)&linecoding, sizeof(linecoding));
|
||||||
P("GET_LINE_CODING\r\n", uart1_send);
|
#ifdef EBUG
|
||||||
|
P("GET_LINE_CODING\n", uart1_send);
|
||||||
|
#endif
|
||||||
break;
|
break;
|
||||||
default:
|
default:
|
||||||
P("UNKNOWN\r\n", uart1_send);
|
#ifdef EBUG
|
||||||
|
P("UNKNOWN\n", uart1_send);
|
||||||
|
#endif
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
return 1;
|
return 1;
|
||||||
@ -300,11 +310,10 @@ mutex_t send_block_mutex = MUTEX_UNLOCKED;
|
|||||||
void usb_send(uint8_t byte){
|
void usb_send(uint8_t byte){
|
||||||
mutex_lock(&send_block_mutex);
|
mutex_lock(&send_block_mutex);
|
||||||
USB_Tx_Buffer[USB_Tx_ptr++] = byte;
|
USB_Tx_Buffer[USB_Tx_ptr++] = byte;
|
||||||
|
mutex_unlock(&send_block_mutex);
|
||||||
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!
|
||||||
mutex_unlock(&send_block_mutex);
|
|
||||||
usb_send_buffer();
|
usb_send_buffer();
|
||||||
}else
|
}
|
||||||
mutex_unlock(&send_block_mutex);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
|
|||||||
@ -149,22 +149,30 @@ uint8_t adc_channel_array[16] = {9,8,15,14,7,6,5,4};
|
|||||||
*/
|
*/
|
||||||
void adc_dma_on(){
|
void adc_dma_on(){
|
||||||
// first configure DMA1 Channel1 (ADC1)
|
// first configure DMA1 Channel1 (ADC1)
|
||||||
rcc_periph_clock_enable(RCC_DMA1); // RCC_AHBPeriphClockCmd(RCC_AHBPeriph_DMA1, ENABLE);
|
|
||||||
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_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, ADC_CHANNELS_NUMBER); // DMA_InitStructure.DMA_BufferSize = 1;
|
|
||||||
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_disable_peripheral_increment_mode(DMA1, DMA_CHANNEL1); // DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable;
|
|
||||||
dma_set_peripheral_size(DMA1, DMA_CHANNEL1, DMA_CCR_PSIZE_16BIT); // DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_HalfWord;
|
|
||||||
dma_set_memory_size(DMA1, DMA_CHANNEL1, DMA_CCR_MSIZE_16BIT); // DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_HalfWord;
|
|
||||||
dma_enable_circular_mode(DMA1, DMA_CHANNEL1); // DMA_InitStructure.DMA_Mode = DMA_Mode_Circular; DMA_InitStructure.DMA_M2M = DMA_M2M_Disable;
|
|
||||||
dma_set_priority(DMA1, DMA_CHANNEL1, DMA_CCR_PL_HIGH); // DMA_InitStructure.DMA_Priority = DMA_Priority_High;
|
|
||||||
nvic_disable_irq(NVIC_DMA1_CHANNEL1_IRQ);
|
nvic_disable_irq(NVIC_DMA1_CHANNEL1_IRQ);
|
||||||
|
dma_channel_reset(DMA1, DMA_CHANNEL1);
|
||||||
|
DMA1_CPAR1 = (uint32_t) &(ADC_DR(ADC1));
|
||||||
|
DMA1_CMAR1 = (uint32_t) ADC_value;
|
||||||
|
DMA1_CNDTR1 = ADC_CHANNELS_NUMBER;
|
||||||
|
DMA1_CCR1 = DMA_CCR_MINC | DMA_CCR_PSIZE_16BIT | DMA_CCR_MSIZE_16BIT
|
||||||
|
| DMA_CCR_CIRC | DMA_CCR_PL_HIGH | DMA_CCR_EN;
|
||||||
|
adc_enable_dma(ADC1);
|
||||||
|
adc_power_on(ADC1);
|
||||||
|
/*
|
||||||
|
dma_set_peripheral_address(DMA1, DMA_CHANNEL1, (uint32_t) &(ADC_DR(ADC1)));
|
||||||
|
dma_set_memory_address(DMA1, DMA_CHANNEL1, (uint32_t) ADC_value);
|
||||||
|
dma_set_number_of_data(DMA1, DMA_CHANNEL1, ADC_CHANNELS_NUMBER);
|
||||||
|
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);
|
||||||
|
dma_enable_circular_mode(DMA1, DMA_CHANNEL1);
|
||||||
|
dma_set_priority(DMA1, DMA_CHANNEL1, DMA_CCR_PL_HIGH);
|
||||||
dma_disable_transfer_error_interrupt(DMA1, DMA_CHANNEL1);
|
dma_disable_transfer_error_interrupt(DMA1, DMA_CHANNEL1);
|
||||||
dma_disable_transfer_complete_interrupt(DMA1, DMA_CHANNEL1);
|
dma_disable_transfer_complete_interrupt(DMA1, DMA_CHANNEL1);
|
||||||
dma_enable_channel(DMA1, DMA_CHANNEL1); // DMA_Cmd(DMA1_Channel1, ENABLE);
|
dma_enable_channel(DMA1, DMA_CHANNEL1);
|
||||||
|
*/
|
||||||
}
|
}
|
||||||
|
|
||||||
void ADC_init(){
|
void ADC_init(){
|
||||||
@ -181,8 +189,7 @@ void ADC_init(){
|
|||||||
|
|
||||||
// Make sure the ADC doesn't run during config
|
// Make sure the ADC doesn't run during config
|
||||||
adc_off(ADC1);
|
adc_off(ADC1);
|
||||||
|
rcc_periph_clock_enable(RCC_DMA1);
|
||||||
adc_dma_on();
|
|
||||||
|
|
||||||
// Configure ADC as continuous scan mode with DMA
|
// Configure ADC as continuous scan mode with DMA
|
||||||
adc_set_dual_mode(ADC_CR1_DUALMOD_IND); // ADC_InitStructure.ADC_Mode = ADC_Mode_Independent;
|
adc_set_dual_mode(ADC_CR1_DUALMOD_IND); // ADC_InitStructure.ADC_Mode = ADC_Mode_Independent;
|
||||||
@ -192,8 +199,8 @@ void ADC_init(){
|
|||||||
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_power_on(ADC1); // ADC_Cmd(ADC1, ENABLE);
|
adc_dma_on();
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@ -208,16 +215,22 @@ void ADC_calibrate_and_start(){
|
|||||||
adc_start_conversion_direct(ADC1);
|
adc_start_conversion_direct(ADC1);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
uint16_t tim2_buff[TIM2_DMABUFF_SIZE];
|
uint16_t tim2_buff[TIM2_DMABUFF_SIZE];
|
||||||
uint16_t tim2_inbuff[TIM2_DMABUFF_SIZE];
|
uint16_t tim2_inbuff[TIM2_DMABUFF_SIZE];
|
||||||
int tum2buff_ctr = 0;
|
int tum2buff_ctr = 0;
|
||||||
|
uint8_t ow_done = 1;
|
||||||
/**
|
/**
|
||||||
* 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
|
||||||
* @param Nbits - number of bits to send
|
* @param Nbits - number of bits to send
|
||||||
* @param ini - 1 to zero counter
|
* @param ini - 1 to zero counter
|
||||||
*/
|
*/
|
||||||
uint8_t OW_add_byte(uint8_t ow_byte, uint8_t Nbits, uint8_t ini){
|
uint8_t OW_add_byte(_U_ uint8_t ow_byte, _U_ uint8_t Nbits, _U_ uint8_t ini){
|
||||||
uint8_t i, byte;
|
uint8_t i, byte;
|
||||||
if(ini) tum2buff_ctr = 0;
|
if(ini) tum2buff_ctr = 0;
|
||||||
if(Nbits == 0) return 0;
|
if(Nbits == 0) return 0;
|
||||||
@ -232,6 +245,26 @@ uint8_t OW_add_byte(uint8_t ow_byte, uint8_t Nbits, uint8_t ini){
|
|||||||
if(tum2buff_ctr == TIM2_DMABUFF_SIZE) return 0; // avoid buffer overflow
|
if(tum2buff_ctr == TIM2_DMABUFF_SIZE) return 0; // avoid buffer overflow
|
||||||
ow_byte = ow_byte >> 1;
|
ow_byte = ow_byte >> 1;
|
||||||
}
|
}
|
||||||
|
// print_int(tum2buff_ctr, lastsendfun);
|
||||||
|
// MSG(" bytes in send buffer\n");
|
||||||
|
return 1;
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Adds Nbytes bytes 0xff for reading sequence
|
||||||
|
*/
|
||||||
|
uint8_t OW_add_read_seq(uint8_t Nbytes){
|
||||||
|
uint8_t i;
|
||||||
|
if(Nbytes == 0) return 0;
|
||||||
|
Nbytes *= 8; // 8 bits for each byte
|
||||||
|
for(i = 0; i < Nbytes; i++){
|
||||||
|
tim2_buff[tum2buff_ctr++] = 1;
|
||||||
|
if(tum2buff_ctr == TIM2_DMABUFF_SIZE) return 0;
|
||||||
|
}
|
||||||
|
#ifdef EBUG
|
||||||
|
print_int(tum2buff_ctr, lastsendfun);
|
||||||
|
MSG(" bytes in send buffer\n");
|
||||||
|
#endif
|
||||||
return 1;
|
return 1;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -241,47 +274,79 @@ uint8_t OW_add_byte(uint8_t ow_byte, uint8_t Nbits, uint8_t ini){
|
|||||||
* @param N - data length (in **bytes**)
|
* @param N - data length (in **bytes**)
|
||||||
* @outbuf - where to place data
|
* @outbuf - where to place data
|
||||||
*/
|
*/
|
||||||
void read_from_OWbuf(uint8_t start_idx, uint8_t N, uint8_t *outbuf){
|
void read_from_OWbuf(_U_ uint8_t start_idx, _U_ uint8_t N, _U_ uint8_t *outbuf){
|
||||||
uint8_t i, j, last = start_idx + N * 8, byte;
|
uint8_t i, j, last = start_idx + N * 8, byte;
|
||||||
if(last >= TIM2_DMABUFF_SIZE) last = TIM2_DMABUFF_SIZE;
|
if(last >= TIM2_DMABUFF_SIZE) last = TIM2_DMABUFF_SIZE;
|
||||||
for(i = start_idx; i < last;){
|
for(i = start_idx; i < last;){
|
||||||
byte = 0;
|
byte = 0;
|
||||||
for(j = 0; j < 8; j++, byte <<= 1){
|
for(j = 0; j < 8; j++){
|
||||||
if(tim2_inbuff[i++] > OW_READ1) byte |= 1;
|
byte >>= 1;
|
||||||
|
#ifdef EBUG
|
||||||
|
print_int(tim2_inbuff[i], lastsendfun);
|
||||||
|
MSG(" ");
|
||||||
|
#endif
|
||||||
|
if(tim2_inbuff[i++] < OW_READ1)
|
||||||
|
byte |= 0x80;
|
||||||
}
|
}
|
||||||
*outbuf++ = byte;
|
*outbuf++ = byte;
|
||||||
|
#ifdef EBUG
|
||||||
|
MSG("readed \n");
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
// there's a mistake in opencm3, so redefine this if needed (TIM_CCMR2_CC3S_IN_TI1 -> TIM_CCMR2_CC3S_IN_TI4)
|
||||||
|
#ifndef TIM_CCMR2_CC3S_IN_TI4
|
||||||
|
#define TIM_CCMR2_CC3S_IN_TI4 (2)
|
||||||
|
#endif
|
||||||
void init_ow_dmatimer(){ // tim2_ch4 - PA3, no remap
|
void init_ow_dmatimer(){ // tim2_ch4 - PA3, no remap
|
||||||
gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_50_MHZ,
|
gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_50_MHZ,
|
||||||
GPIO_CNF_OUTPUT_ALTFN_OPENDRAIN, GPIO3);
|
GPIO_CNF_OUTPUT_ALTFN_OPENDRAIN, GPIO3);
|
||||||
rcc_periph_clock_enable(RCC_TIM2);
|
rcc_periph_clock_enable(RCC_TIM2);
|
||||||
|
rcc_periph_clock_enable(RCC_DMA1);
|
||||||
timer_reset(TIM2);
|
timer_reset(TIM2);
|
||||||
// timers have frequency of 1MHz -- 1us for one step
|
// timers have frequency of 1MHz -- 1us for one step
|
||||||
// 36MHz of APB1
|
// 36MHz of APB1
|
||||||
timer_set_mode(TIM2, TIM_CR1_CKD_CK_INT, TIM_CR1_CMS_EDGE, TIM_CR1_DIR_UP);
|
timer_set_mode(TIM2, TIM_CR1_CKD_CK_INT, TIM_CR1_CMS_EDGE, TIM_CR1_DIR_UP);
|
||||||
// 72MHz div 72 = 1MHz
|
// 72MHz div 72 = 1MHz
|
||||||
timer_set_prescaler(TIM2, 71); // prescaler is (div - 1)
|
TIM2_PSC = 71; // prescaler is (div - 1)
|
||||||
timer_continuous_mode(TIM2); // automatically reload
|
TIM2_CR1 &= ~(TIM_CR1_OPM | TIM_CR1_UDIS); // continuous mode & enable update events
|
||||||
timer_disable_preload(TIM2); // force changing period
|
TIM2_CR1 |= TIM_CR1_ARPE; // changing period immediately
|
||||||
timer_set_period(TIM2, OW_BIT); // bit length
|
TIM2_ARR = OW_BIT; // default period of timer
|
||||||
timer_enable_update_event(TIM2);
|
// PWM_OUT: TIM2_CH4; capture: TIM2_CH3
|
||||||
timer_set_oc_polarity_high(TIM2, TIM_OC4);
|
// PWM edge-aligned mode & enable preload for CCR4, CC3 takes input from TI4
|
||||||
timer_set_oc_mode(TIM2, TIM_OC4, TIM_OCM_PWM1); // edge-aligned mode
|
TIM2_CCMR2 = TIM_CCMR2_OC4M_PWM1 | TIM_CCMR2_OC4PE | TIM_CCMR2_CC3S_IN_TI4;
|
||||||
timer_disable_oc_preload(TIM2, TIM_OC4);
|
TIM2_CCR4 = 0; // set output value to 1 by clearing CCR4
|
||||||
timer_set_oc_value(TIM2, TIM_OC4, OW_RESET);
|
TIM2_EGR = TIM_EGR_UG; // update values of ARR & CCR4
|
||||||
timer_enable_oc_output(TIM2, TIM_OC4);
|
// set low polarity for CC4, high for CC4 & enable CC4 out and CC3 in
|
||||||
|
TIM2_CCER = TIM_CCER_CC4P | TIM_CCER_CC4E | TIM_CCER_CC3E;
|
||||||
timer_disable_counter(TIM2);
|
|
||||||
timer_disable_irq(TIM2, TIM_DIER_UIE);
|
|
||||||
nvic_disable_irq(NVIC_TIM2_IRQ);
|
|
||||||
gpio_set(GPIOA, GPIO3);
|
|
||||||
|
|
||||||
// TIM2_CH4 - DMA1, channel 7
|
// TIM2_CH4 - DMA1, channel 7
|
||||||
rcc_periph_clock_enable(RCC_DMA1);
|
|
||||||
dma_channel_reset(DMA1, DMA_CHANNEL7);
|
dma_channel_reset(DMA1, DMA_CHANNEL7);
|
||||||
dma_set_peripheral_address(DMA1, DMA_CHANNEL7, (uint32_t) &(TIM_CCR4(TIM2)));
|
DMA1_CCR7 = DMA_CCR_DIR | DMA_CCR_MINC | DMA_CCR_PSIZE_16BIT | DMA_CCR_MSIZE_16BIT
|
||||||
|
| DMA_CCR_TEIE | DMA_CCR_TCIE | DMA_CCR_PL_HIGH;
|
||||||
|
/*
|
||||||
|
DMA1_CCR7 |= DMA_CCR_DIR; // dma_set_read_from_memory(DMA1, DMA_CHANNEL7);
|
||||||
|
DMA1_CCR7 |= DMA_CCR_MINC; // dma_enable_memory_increment_mode(DMA1, DMA_CHANNEL7);
|
||||||
|
//dma_disable_peripheral_increment_mode(DMA1, DMA_CHANNEL7);
|
||||||
|
DMA1_CCR7 |= DMA_CCR_PSIZE_16BIT; // dma_set_peripheral_size(DMA1, DMA_CHANNEL7, DMA_CCR_PSIZE_16BIT);
|
||||||
|
DMA1_CCR7 |= DMA_CCR_MSIZE_16BIT; // dma_set_memory_size(DMA1, DMA_CHANNEL7, DMA_CCR_MSIZE_16BIT);
|
||||||
|
DMA1_CCR7 |= DMA_CCR_TEIE; // dma_enable_transfer_error_interrupt(DMA1, DMA_CHANNEL7);
|
||||||
|
DMA1_CCR7 |= DMA_CCR_TCIE; // dma_enable_transfer_complete_interrupt(DMA1, DMA_CHANNEL7);
|
||||||
|
*/
|
||||||
|
nvic_enable_irq(NVIC_DMA1_CHANNEL7_IRQ); // enable dma1_channel7_isr
|
||||||
|
}
|
||||||
|
|
||||||
|
void run_dmatimer(){
|
||||||
|
ow_done = 0;
|
||||||
|
adc_disable_dma(ADC1); // turn off DMA & ADC
|
||||||
|
adc_off(ADC1);
|
||||||
|
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
|
||||||
|
|
||||||
|
//init_ow_dmatimer();
|
||||||
|
/*
|
||||||
|
// TIM2_CH4 - DMA1, channel 7
|
||||||
|
dma_channel_reset(DMA1, DMA_CHANNEL7);
|
||||||
dma_set_read_from_memory(DMA1, DMA_CHANNEL7);
|
dma_set_read_from_memory(DMA1, DMA_CHANNEL7);
|
||||||
dma_enable_memory_increment_mode(DMA1, DMA_CHANNEL7);
|
dma_enable_memory_increment_mode(DMA1, DMA_CHANNEL7);
|
||||||
dma_disable_peripheral_increment_mode(DMA1, DMA_CHANNEL7);
|
dma_disable_peripheral_increment_mode(DMA1, DMA_CHANNEL7);
|
||||||
@ -289,146 +354,116 @@ void init_ow_dmatimer(){ // tim2_ch4 - PA3, no remap
|
|||||||
dma_set_memory_size(DMA1, DMA_CHANNEL7, DMA_CCR_MSIZE_16BIT);
|
dma_set_memory_size(DMA1, DMA_CHANNEL7, DMA_CCR_MSIZE_16BIT);
|
||||||
dma_enable_transfer_error_interrupt(DMA1, DMA_CHANNEL7);
|
dma_enable_transfer_error_interrupt(DMA1, DMA_CHANNEL7);
|
||||||
dma_enable_transfer_complete_interrupt(DMA1, DMA_CHANNEL7);
|
dma_enable_transfer_complete_interrupt(DMA1, DMA_CHANNEL7);
|
||||||
dma_set_memory_address(DMA1, DMA_CHANNEL7, (uint32_t)tim2_buff);
|
*/
|
||||||
|
DMA1_CCR7 &= ~DMA_CCR_EN; // disable (what if it's enabled?) to set address
|
||||||
nvic_enable_irq(NVIC_DMA1_CHANNEL7_IRQ); // enable dma1_channel7_isr
|
DMA1_CPAR7 = (uint32_t) &(TIM_CCR4(TIM2)); // dma_set_peripheral_address(DMA1, DMA_CHANNEL7, (uint32_t) &(TIM_CCR4(TIM2)));
|
||||||
|
DMA1_CMAR7 = (uint32_t) tim2_buff; // dma_set_memory_address(DMA1, DMA_CHANNEL7, (uint32_t)tim2_buff);
|
||||||
// capture: TIM2_CH3
|
DMA1_CNDTR7 = tum2buff_ctr;//dma_set_number_of_data(DMA1, DMA_CHANNEL7, tum2buff_ctr);
|
||||||
timer_ic_set_input(TIM2, TIM_IC3, TIM_IC_IN_TI4);
|
// TIM2_CH4 - DMA1, channel 7
|
||||||
timer_set_oc_polarity_high(TIM2, TIM_OC3);
|
|
||||||
timer_ic_enable(TIM2, TIM_IC3);
|
|
||||||
//timer_enable_oc_output(TIM2, TIM_OC3);
|
|
||||||
//gpio_set(GPIOA, GPIO3);
|
|
||||||
ow_reset();
|
|
||||||
}
|
|
||||||
|
|
||||||
/**
|
|
||||||
* reconfigure DMA1_1 for 1-wire
|
|
||||||
*/
|
|
||||||
void ow_dma_on(){
|
|
||||||
dma_channel_reset(DMA1, DMA_CHANNEL1);
|
dma_channel_reset(DMA1, DMA_CHANNEL1);
|
||||||
dma_set_peripheral_address(DMA1, DMA_CHANNEL1, (uint32_t) &(TIM_CCR3(TIM2)));
|
DMA1_CCR1 = DMA_CCR_MINC | DMA_CCR_PSIZE_16BIT | DMA_CCR_MSIZE_16BIT
|
||||||
dma_set_memory_address(DMA1, DMA_CHANNEL1, (uint32_t) tim2_inbuff);
|
| DMA_CCR_TEIE | DMA_CCR_TCIE | DMA_CCR_PL_HIGH;
|
||||||
|
/*
|
||||||
dma_set_read_from_peripheral(DMA1, DMA_CHANNEL1);
|
dma_set_read_from_peripheral(DMA1, DMA_CHANNEL1);
|
||||||
dma_enable_memory_increment_mode(DMA1, DMA_CHANNEL1);
|
dma_enable_memory_increment_mode(DMA1, DMA_CHANNEL1);
|
||||||
dma_disable_peripheral_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_peripheral_size(DMA1, DMA_CHANNEL1, DMA_CCR_PSIZE_16BIT);
|
||||||
dma_set_memory_size(DMA1, DMA_CHANNEL1, DMA_CCR_MSIZE_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_error_interrupt(DMA1, DMA_CHANNEL1);
|
||||||
dma_enable_transfer_complete_interrupt(DMA1, DMA_CHANNEL1);
|
dma_enable_transfer_complete_interrupt(DMA1, DMA_CHANNEL1);
|
||||||
}
|
*/
|
||||||
|
DMA1_CPAR1 = (uint32_t) &(TIM_CCR3(TIM2)); //dma_set_peripheral_address(DMA1, DMA_CHANNEL1, (uint32_t) &(TIM_CCR3(TIM2)));
|
||||||
|
DMA1_CMAR1 = (uint32_t) tim2_inbuff; //dma_set_memory_address(DMA1, DMA_CHANNEL1, (uint32_t) tim2_inbuff);
|
||||||
|
DMA1_CNDTR1 = tum2buff_ctr; //dma_set_number_of_data(DMA1, DMA_CHANNEL1, tum2buff_ctr);
|
||||||
|
nvic_enable_irq(NVIC_DMA1_CHANNEL1_IRQ);
|
||||||
|
|
||||||
void run_dmatimer(){
|
DMA1_CCR7 |= DMA_CCR_EN; //dma_enable_channel(DMA1, DMA_CHANNEL7);
|
||||||
//int i;
|
DMA1_CCR1 |= DMA_CCR_EN; //dma_enable_channel(DMA1, DMA_CHANNEL1);
|
||||||
ow_done = 0;
|
|
||||||
ow_dma_on();
|
|
||||||
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
|
|
||||||
TIM_SR(TIM2) = 0;
|
|
||||||
timer_set_period(TIM2, OW_BIT); // bit length
|
|
||||||
dma_set_number_of_data(DMA1, DMA_CHANNEL7, tum2buff_ctr);
|
|
||||||
//timer_set_dma_on_compare_event(TIM2);
|
|
||||||
timer_set_dma_on_update_event(TIM2);
|
|
||||||
timer_ic_enable(TIM2, TIM_IC3);
|
|
||||||
dma_enable_channel(DMA1, DMA_CHANNEL7);
|
|
||||||
|
|
||||||
//for(i = 0; i < TIM2_DMABUFF_SIZE; i++) tim2_inbuff[i] = 0;
|
TIM2_SR = 0; // clear all flags
|
||||||
dma_set_number_of_data(DMA1, DMA_CHANNEL1, tum2buff_ctr);
|
TIM2_CR1 &= ~TIM_CR1_OPM; // continuous mode
|
||||||
dma_enable_channel(DMA1, DMA_CHANNEL1);
|
TIM2_ARR = OW_BIT; // bit length
|
||||||
|
TIM2_EGR = TIM_EGR_UG; // update value of ARR
|
||||||
|
|
||||||
timer_enable_irq(TIM2, TIM_DIER_UDE | TIM_DIER_CC4DE | TIM_DIER_CC3DE);
|
TIM2_CR2 &= ~TIM_CR2_CCDS; // timer_set_dma_on_compare_event(TIM2);
|
||||||
TIM2_CCER |= TIM_CCER_CC4P | TIM_CCER_CC4E;
|
TIM2_CCER |= TIM_CCER_CC3E; // enable input capture
|
||||||
TIM2_CR1 |= TIM_CR1_CEN; // timer_enable_counter(TIM2);
|
TIM2_DIER = TIM_DIER_CC4DE | TIM_DIER_CC3DE; // enable DMA events
|
||||||
}
|
// set low polarity, enable cc out & enable input capture
|
||||||
|
TIM2_CCER |= TIM_CCER_CC4P | TIM_CCER_CC4E | TIM_CCER_CC3E;
|
||||||
|
TIM2_CR1 |= TIM_CR1_CEN; // run timer
|
||||||
|
|
||||||
void ow_reset(){
|
|
||||||
ow_done = 0;
|
|
||||||
timer_disable_counter(TIM2);
|
|
||||||
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
|
|
||||||
TIM_SR(TIM2) = 0;
|
|
||||||
timer_set_period(TIM2, OW_RESET*2); // reset length
|
|
||||||
timer_set_oc_value(TIM2, TIM_OC4, OW_RESET);
|
|
||||||
|
|
||||||
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_irq(TIM2, TIM_DIER_CC3DE);
|
|
||||||
timer_set_dma_on_update_event(TIM2); // wait until end of signal!
|
|
||||||
timer_enable_irq(TIM2, TIM_DIER_UIE | TIM_DIER_CC3IE);
|
|
||||||
nvic_enable_irq(NVIC_TIM2_IRQ);
|
|
||||||
|
|
||||||
//timer_generate_event(TIM2, TIM_SR_UIF);
|
|
||||||
/*
|
|
||||||
tim2_inbuff[0] = 0;
|
|
||||||
dma_set_number_of_data(DMA1, DMA_CHANNEL1, 6);
|
|
||||||
dma_enable_channel(DMA1, DMA_CHANNEL1); // enable only reading - for interrupt
|
|
||||||
*/
|
|
||||||
// NOT USE THIS: wery long
|
|
||||||
//timer_set_oc_polarity_low(TIM2, TIM_OC4);
|
|
||||||
//timer_enable_oc_output(TIM2, TIM_OC4);
|
|
||||||
TIM2_CCER |= TIM_CCER_CC4P | TIM_CCER_CC4E;
|
|
||||||
TIM2_CR1 |= TIM_CR1_CEN; // timer_enable_counter(TIM2);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
uint16_t rstat = 0, lastcc3;
|
uint16_t rstat = 0, lastcc3;
|
||||||
|
void ow_reset(){
|
||||||
|
ow_done = 0;
|
||||||
|
rstat = 0;
|
||||||
|
TIM2_SR = 0; // clear all flags
|
||||||
|
TIM2_DIER = 0; // disable timer interrupts
|
||||||
|
TIM2_ARR = OW_RESET_TIME; // set period to 1ms
|
||||||
|
TIM2_CCR4 = OW_RESET; // zero pulse length
|
||||||
|
TIM2_EGR = TIM_EGR_UG; // update values of ARR & CCR4
|
||||||
|
TIM2_CR1 |= TIM_CR1_OPM | TIM_CR1_CEN; // we need only single pulse & run timer
|
||||||
|
TIM2_SR = 0; // clear update flag generated after timer's running
|
||||||
|
TIM2_DIER = TIM_DIER_UIE | TIM_DIER_CC3IE; // generate interrupts on update event & cc
|
||||||
|
nvic_enable_irq(NVIC_TIM2_IRQ);
|
||||||
|
}
|
||||||
|
|
||||||
void tim2_isr(){
|
void tim2_isr(){
|
||||||
if(timer_get_flag(TIM2, TIM_SR_UIF)){
|
if(TIM2_SR & TIM_SR_UIF){ // update interrupt
|
||||||
timer_clear_flag(TIM2, TIM_SR_UIF);
|
TIM2_SR &= ~TIM_SR_UIF; // clear flag
|
||||||
TIM2_CCER &= ~TIM_CCER_CC4P; //timer_set_oc_polarity_high(TIM2, TIM_OC4);
|
TIM2_DIER = 0; // disable all timer interrupts
|
||||||
|
TIM2_CCR4 = 0; // set output value to 1
|
||||||
|
TIM2_EGR |= TIM_EGR_UG; // generate update event to change value in CCR4
|
||||||
TIM2_CR1 &= ~TIM_CR1_CEN; // timer_disable_counter(TIM2);
|
TIM2_CR1 &= ~TIM_CR1_CEN; // timer_disable_counter(TIM2);
|
||||||
gpio_set(GPIOA, GPIO3);
|
|
||||||
timer_disable_irq(TIM2, TIM_DIER_UIE | TIM_DIER_CC3IE);
|
|
||||||
nvic_disable_irq(NVIC_TIM2_IRQ);
|
nvic_disable_irq(NVIC_TIM2_IRQ);
|
||||||
ow_done = 1;
|
ow_done = 1;
|
||||||
rstat = lastcc3;
|
rstat = lastcc3;
|
||||||
print_int(rstat, lastsendfun);
|
/* print_int(rstat, lastsendfun);
|
||||||
MSG("\n");
|
MSG("\n");*/
|
||||||
}
|
}
|
||||||
if(timer_get_flag(TIM2, TIM_SR_CC3IF)){
|
if(TIM2_SR & TIM_SR_CC3IF){ // we need this interrupt to store CCR3 value
|
||||||
timer_clear_flag(TIM2, TIM_SR_CC3IF);
|
TIM2_SR = 0; // clear flag (we've manage TIM_SR_UIF before, so can simply do =0)
|
||||||
lastcc3 = TIM_CCR3(TIM2);
|
lastcc3 = TIM2_CCR3;
|
||||||
|
//TIM2_DIER &= ~TIM_DIER_CC3IE; // disable CCR3 interrupts
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
void dma1_channel7_isr(){
|
void dma1_channel7_isr(){
|
||||||
if(DMA1_ISR & DMA_ISR_TCIF7) {
|
if(DMA1_ISR & DMA_ISR_TCIF7){
|
||||||
DMA1_IFCR = DMA_IFCR_CTCIF7;
|
DMA1_IFCR = DMA_IFCR_CTCIF7; // clear flag
|
||||||
dma_disable_channel(DMA1, DMA_CHANNEL7);
|
DMA1_CCR7 &= ~DMA_CCR_EN; // disable DMA1 channel 7
|
||||||
timer_disable_irq(TIM2, TIM_DIER_CC4DE);
|
//TIM2_DIER &= ~TIM_DIER_CC4DE;
|
||||||
}else if(DMA1_ISR & DMA_ISR_TEIF7){
|
}else if(DMA1_ISR & DMA_ISR_TEIF7){
|
||||||
DMA1_IFCR = DMA_IFCR_CTEIF7;
|
DMA1_IFCR = DMA_IFCR_CTEIF7;
|
||||||
MSG("out transfer error\n");
|
MSG("DMA out transfer error\n");
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
uint8_t ow_done = 1;
|
|
||||||
void dma1_channel1_isr(){
|
void dma1_channel1_isr(){
|
||||||
int i;
|
//int i;
|
||||||
if(DMA1_ISR & DMA_ISR_TCIF1) {
|
if(DMA1_ISR & DMA_ISR_TCIF1) {
|
||||||
DMA1_IFCR = DMA_IFCR_CTCIF1;
|
DMA1_IFCR = DMA_IFCR_CTCIF1;
|
||||||
TIM2_CCER &= ~TIM_CCER_CC4P; //timer_set_oc_polarity_high(TIM2, TIM_OC4);
|
|
||||||
TIM2_CR1 &= ~TIM_CR1_CEN; // timer_disable_counter(TIM2);
|
TIM2_CR1 &= ~TIM_CR1_CEN; // timer_disable_counter(TIM2);
|
||||||
timer_disable_irq(TIM2, TIM_DIER_CC3DE);
|
//TIM2_DIER &= ~TIM_DIER_CC3DE;
|
||||||
gpio_set(GPIOA, GPIO3);
|
DMA1_CCR1 &= ~DMA_CCR_EN; // disable DMA1 channel 1
|
||||||
dma_disable_channel(DMA1, DMA_CHANNEL1);
|
|
||||||
nvic_disable_irq(NVIC_DMA1_CHANNEL1_IRQ);
|
nvic_disable_irq(NVIC_DMA1_CHANNEL1_IRQ);
|
||||||
ow_done = 1;
|
ow_done = 1;
|
||||||
for(i = 0; i < tum2buff_ctr; i++){
|
/* for(i = 0; i < tum2buff_ctr; i++){
|
||||||
print_int(tim2_inbuff[i], lastsendfun);
|
print_int(tim2_inbuff[i], lastsendfun);
|
||||||
MSG(" ");
|
MSG(" ");
|
||||||
}
|
}
|
||||||
MSG("\n");
|
MSG("\n");*/
|
||||||
}else if(DMA1_ISR & DMA_ISR_TEIF1){
|
}else if(DMA1_ISR & DMA_ISR_TEIF1){
|
||||||
DMA1_IFCR = DMA_IFCR_CTEIF1;
|
DMA1_IFCR = DMA_IFCR_CTEIF1;
|
||||||
MSG("in transfer error\n");
|
MSG("DMA in transfer error\n");
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
uint8_t OW_get_reset_status(){
|
uint8_t OW_get_reset_status(){
|
||||||
|
/* print_int(rstat, lastsendfun);
|
||||||
|
MSG("\n");*/
|
||||||
if(rstat < OW_PRESENT) return 0; // no devices
|
if(rstat < OW_PRESENT) return 0; // no devices
|
||||||
return 1;
|
return 1;
|
||||||
}
|
}
|
||||||
|
|||||||
@ -25,12 +25,13 @@
|
|||||||
|
|
||||||
#define TIM2_DMABUFF_SIZE 128
|
#define TIM2_DMABUFF_SIZE 128
|
||||||
// 1-wire zero-state lengths (in us minus 1)
|
// 1-wire zero-state lengths (in us minus 1)
|
||||||
#define OW_1 (9)
|
#define OW_1 (9)
|
||||||
#define OW_0 (69)
|
#define OW_0 (69)
|
||||||
#define OW_READ1 (14)
|
#define OW_READ1 (14)
|
||||||
#define OW_BIT (79)
|
#define OW_BIT (79)
|
||||||
#define OW_RESET (499)
|
#define OW_RESET (499)
|
||||||
#define OW_PRESENT (599)
|
#define OW_RESET_TIME (999)
|
||||||
|
#define OW_PRESENT (549)
|
||||||
|
|
||||||
extern volatile uint16_t ADC_value[]; // ADC DMA value
|
extern volatile uint16_t ADC_value[]; // ADC DMA value
|
||||||
|
|
||||||
@ -60,10 +61,10 @@ void ADC_calibrate_and_start();
|
|||||||
// change signal level on USB diconnect pin
|
// change signal level on USB diconnect pin
|
||||||
#define usb_disc_high() gpio_set(USB_DISC_PORT, USB_DISC_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)
|
#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 n-channel FET on 1.5k pull-up change on/off disconnect means low level
|
||||||
// in case of p-channel FET on 1.5k pull-up change on/off disconnect means high level
|
// in case of pnp bipolar transistor or p-channel FET on 1.5k pull-up disconnect means high level
|
||||||
#define usb_disconnect() usb_disc_low()
|
#define usb_disconnect() usb_disc_high()
|
||||||
#define usb_connect() usb_disc_high()
|
#define usb_connect() usb_disc_low()
|
||||||
|
|
||||||
/*
|
/*
|
||||||
* Stepper motors
|
* Stepper motors
|
||||||
@ -71,15 +72,15 @@ void ADC_calibrate_and_start();
|
|||||||
* moved to stepper_motors.c
|
* moved to stepper_motors.c
|
||||||
*/
|
*/
|
||||||
// PE7..11 - EN
|
// PE7..11 - EN
|
||||||
#define MOROT_EN_MASK (0x1f << 7)
|
#define MOTOR_EN_MASK (0x1f << 7)
|
||||||
#define MOTOR_EN_PORT (GPIOE)
|
#define MOTOR_EN_PORT (GPIOE)
|
||||||
// N == 1..5
|
// N == 0..4
|
||||||
#define MOTOR_EN_PIN(N) (GPIO6 << (N))
|
#define MOTOR_EN_PIN(N) (GPIO7 << (N))
|
||||||
// PE0..PE5 - DIR
|
// PE0..PE5 - DIR
|
||||||
#define MOROT_DIR_MASK (0x1f)
|
#define MOTOR_DIR_MASK (0x1f)
|
||||||
#define MOTOR_DIR_PORT (GPIOE)
|
#define MOTOR_DIR_PORT (GPIOE)
|
||||||
// N == 1..5
|
// N == 0..4
|
||||||
#define MOTOR_DIR_PIN(N) (GPIO0 << (N - 1))
|
#define MOTOR_DIR_PIN(N) (GPIO0 << (N))
|
||||||
// timers: TIM1 - PC6, TIM2 - PD15
|
// timers: TIM1 - PC6, TIM2 - PD15
|
||||||
#define MOTOR_TIM1_PORT (GPIOC)
|
#define MOTOR_TIM1_PORT (GPIOC)
|
||||||
#define MOTOR_TIM1_PIN (GPIO6)
|
#define MOTOR_TIM1_PIN (GPIO6)
|
||||||
@ -102,6 +103,7 @@ extern uint8_t ow_done;
|
|||||||
void ow_dma_on();
|
void ow_dma_on();
|
||||||
void adc_dma_on();
|
void adc_dma_on();
|
||||||
uint8_t OW_add_byte(uint8_t ow_byte, uint8_t Nbits, uint8_t ini);
|
uint8_t OW_add_byte(uint8_t ow_byte, uint8_t Nbits, uint8_t ini);
|
||||||
|
uint8_t OW_add_read_seq(uint8_t Nbytes);
|
||||||
void read_from_OWbuf(uint8_t start_idx, uint8_t N, uint8_t *outbuf);
|
void read_from_OWbuf(uint8_t start_idx, uint8_t N, uint8_t *outbuf);
|
||||||
void ow_reset();
|
void ow_reset();
|
||||||
uint8_t OW_get_reset_status();
|
uint8_t OW_get_reset_status();
|
||||||
|
|||||||
Binary file not shown.
@ -115,7 +115,7 @@ void AD7794_init(){
|
|||||||
if(i != ADC_NO_ERROR){
|
if(i != ADC_NO_ERROR){
|
||||||
if(i == ADC_ERR_NO_DEVICE){
|
if(i == ADC_ERR_NO_DEVICE){
|
||||||
// print_int(curSPI, lastsendfun);
|
// print_int(curSPI, lastsendfun);
|
||||||
MSG(": ADC signal is absent! Check connection.\r\n");
|
MSG("ADC signal is absent! Check connection.\n");
|
||||||
/* if(curSPI == 1){
|
/* if(curSPI == 1){
|
||||||
curSPI = 2;
|
curSPI = 2;
|
||||||
switch_SPI(SPI2);
|
switch_SPI(SPI2);
|
||||||
@ -127,10 +127,10 @@ void AD7794_init(){
|
|||||||
}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)
|
||||||
|| !AD7794_calibration(0)){
|
|| !AD7794_calibration(0)){
|
||||||
MSG("Error: can't initialize AD7794!\r\n");
|
MSG("Error: can't initialize AD7794!\n");
|
||||||
}else{
|
}else{
|
||||||
ad7794_on = 1;
|
ad7794_on = 1;
|
||||||
DBG("ADC ready\r\n");
|
DBG("ADC ready\n");
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@ -140,29 +140,24 @@ int main(){
|
|||||||
uint32_t Old_timer = 0, lastTRDread = 0, lastTmon = 0;
|
uint32_t Old_timer = 0, lastTRDread = 0, lastTmon = 0;
|
||||||
//SPI_read_status SPI_stat;
|
//SPI_read_status SPI_stat;
|
||||||
|
|
||||||
//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();
|
||||||
|
usb_disconnect(); // turn off USB while initializing all
|
||||||
|
|
||||||
// GPIO
|
// GPIO
|
||||||
GPIO_init();
|
GPIO_init();
|
||||||
|
|
||||||
steppers_init();
|
steppers_init();
|
||||||
|
|
||||||
usb_disconnect(); // turn off USB
|
|
||||||
|
|
||||||
// init USART1
|
// init USART1
|
||||||
UART_init(USART1);
|
UART_init(USART1);
|
||||||
|
|
||||||
// USB
|
// USB
|
||||||
usbd_dev = USB_init();
|
usbd_dev = USB_init();
|
||||||
|
|
||||||
// init ADC
|
|
||||||
ADC_init();
|
|
||||||
|
|
||||||
// SysTick is a system timer with 1mc period
|
// SysTick is a system timer with 1mc period
|
||||||
SysTick_init();
|
SysTick_init();
|
||||||
|
|
||||||
|
|
||||||
// switch_SPI(SPI2); // init SPI2
|
// switch_SPI(SPI2); // init SPI2
|
||||||
// SPI_init();
|
// SPI_init();
|
||||||
|
|
||||||
@ -171,11 +166,13 @@ int main(){
|
|||||||
init_ow_dmatimer();
|
init_ow_dmatimer();
|
||||||
|
|
||||||
// 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");
|
||||||
usb_connect(); // turn on USB
|
|
||||||
|
|
||||||
|
// init ADC
|
||||||
|
ADC_init();
|
||||||
ADC_calibrate_and_start();
|
ADC_calibrate_and_start();
|
||||||
|
usb_connect(); // turn on USB
|
||||||
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
|
||||||
@ -192,7 +189,9 @@ int main(){
|
|||||||
OW_process(); // process 1-wire commands
|
OW_process(); // process 1-wire commands
|
||||||
if(OW_DATA_READY()){
|
if(OW_DATA_READY()){
|
||||||
OW_CLEAR_READY_FLAG();
|
OW_CLEAR_READY_FLAG();
|
||||||
MSG("Ready!\n");
|
#ifdef EBUG
|
||||||
|
OW_printID(0, lastsendfun);
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
process_stepper_motors(); // check flags of motors' timers
|
process_stepper_motors(); // check flags of motors' timers
|
||||||
if(Timer - Old_timer > 999){ // one-second cycle
|
if(Timer - Old_timer > 999){ // one-second cycle
|
||||||
@ -248,5 +247,3 @@ void print_time(sendfun s){
|
|||||||
s(' ');
|
s(' ');
|
||||||
print_int(Timer, s);
|
print_int(Timer, s);
|
||||||
}
|
}
|
||||||
|
|
||||||
// D = dlmread('file')
|
|
||||||
|
|||||||
@ -36,16 +36,21 @@ uint8_t *read_buf = NULL; // buffer to read
|
|||||||
|
|
||||||
uint8_t ow_data_ready = 0; // flag of reading OK
|
uint8_t ow_data_ready = 0; // flag of reading OK
|
||||||
|
|
||||||
/**
|
void OW_printID(uint8_t N, sendfun s){
|
||||||
* fill buffer with zeros - read slots
|
void putc(uint8_t c){
|
||||||
* @param N - amount of bytes to read
|
if(c < 10)
|
||||||
*/
|
s(c + '0');
|
||||||
uint8_t OW_Read(uint8_t N){
|
else
|
||||||
uint8_t i;
|
s(c + 'a' - 10);
|
||||||
for(i = 0; i < N; i++)
|
}
|
||||||
if(!OW_add_byte(0, 8, 0))
|
int i;
|
||||||
return 0;
|
uint8_t *b = id_array[N].bytes;
|
||||||
return 1;
|
s('0'); s('x'); // prefix 0x
|
||||||
|
for(i = 0; i < 8; i++){
|
||||||
|
putc(b[i] >> 4);
|
||||||
|
putc(b[i] & 0x0f);
|
||||||
|
}
|
||||||
|
s('\n');
|
||||||
}
|
}
|
||||||
|
|
||||||
uint8_t ow_was_reseting = 0;
|
uint8_t ow_was_reseting = 0;
|
||||||
@ -59,22 +64,22 @@ void OW_process(){
|
|||||||
OW_State = OW_SEND_STATE;
|
OW_State = OW_SEND_STATE;
|
||||||
ow_was_reseting = 1;
|
ow_was_reseting = 1;
|
||||||
ow_reset();
|
ow_reset();
|
||||||
MSG("reset\n");
|
//MSG("reset\n");
|
||||||
break;
|
break;
|
||||||
case OW_SEND_STATE:
|
case OW_SEND_STATE:
|
||||||
if(!OW_READY()) return; // reset in work
|
if(!OW_READY()) return; // reset in work
|
||||||
if(ow_was_reseting){
|
if(ow_was_reseting){
|
||||||
if(!OW_get_reset_status()){
|
if(!OW_get_reset_status()){
|
||||||
MSG("error: no devices found\n");
|
MSG("error: no 1-wire devices found\n");
|
||||||
ow_was_reseting = 0;
|
ow_was_reseting = 0;
|
||||||
OW_State = OW_OFF_STATE;
|
// OW_State = OW_OFF_STATE;
|
||||||
return;
|
// return;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
ow_was_reseting = 0;
|
ow_was_reseting = 0;
|
||||||
OW_State = OW_READ_STATE;
|
OW_State = OW_READ_STATE;
|
||||||
run_dmatimer(); // turn on data transfer
|
run_dmatimer(); // turn on data transfer
|
||||||
MSG("send\n");
|
//MSG("send\n");
|
||||||
break;
|
break;
|
||||||
case OW_READ_STATE:
|
case OW_READ_STATE:
|
||||||
if(!OW_READY()) return; // data isn't ready
|
if(!OW_READY()) return; // data isn't ready
|
||||||
@ -84,7 +89,7 @@ void OW_process(){
|
|||||||
read_from_OWbuf(OW_start_idx, OW_wait_bytes, read_buf);
|
read_from_OWbuf(OW_start_idx, OW_wait_bytes, read_buf);
|
||||||
}
|
}
|
||||||
ow_data_ready = 1;
|
ow_data_ready = 1;
|
||||||
MSG("read\n");
|
//MSG("read\n");
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@ -92,16 +97,28 @@ void OW_process(){
|
|||||||
/**
|
/**
|
||||||
* fill Nth array with identificators
|
* fill Nth array with identificators
|
||||||
*/
|
*/
|
||||||
|
//uint8_t comtosend = 0;
|
||||||
void OW_fill_ID(uint8_t N){
|
void OW_fill_ID(uint8_t N){
|
||||||
if(N >= OW_MAX_NUM){
|
if(N >= OW_MAX_NUM){
|
||||||
MSG("number too big\n");
|
MSG("number too big\n");
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
OW_Send(1, (uint8_t*)"\xcc\x33", 2);
|
//OW_Send(1, (uint8_t*)"\xcc\x33", 2);
|
||||||
OW_Read(8); // wait for 8 bytes
|
OW_Send(1, (uint8_t*)"\x19", 1);
|
||||||
|
// OW_Send(1, &comtosend, 1);
|
||||||
|
// comtosend++;
|
||||||
|
//OW_Send(1, (uint8_t*)"\xcc\xbe", 2);
|
||||||
|
OW_add_read_seq(9); // wait for 9 bytes
|
||||||
|
//OW_Send(0, (uint8_t*)"\xcc\x33\x10\x45\x94\x67\x7e\x8a", 8);
|
||||||
read_buf = id_array[N].bytes;
|
read_buf = id_array[N].bytes;
|
||||||
OW_wait_bytes = 8;
|
OW_wait_bytes = 8;
|
||||||
OW_start_idx = 16;
|
OW_start_idx = 0;
|
||||||
|
/*
|
||||||
|
OW_Send(0, (uint8_t*)"\x99\xee", 2);
|
||||||
|
OW_wait_bytes = 2;
|
||||||
|
OW_start_idx = 0;
|
||||||
|
read_buf = id_array[N].bytes;
|
||||||
|
*/
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@ -114,7 +131,6 @@ void OW_fill_ID(uint8_t N){
|
|||||||
*/
|
*/
|
||||||
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 f = 1;
|
uint8_t f = 1;
|
||||||
ow_dma_on(); // reconfigure DMA1
|
|
||||||
ow_data_ready = 0;
|
ow_data_ready = 0;
|
||||||
// if reset needed - send RESET and check bus
|
// if reset needed - send RESET and check bus
|
||||||
if(sendReset)
|
if(sendReset)
|
||||||
|
|||||||
@ -42,10 +42,12 @@ typedef struct{
|
|||||||
extern uint8_t ow_data_ready;
|
extern uint8_t ow_data_ready;
|
||||||
#define OW_DATA_READY() (ow_data_ready)
|
#define OW_DATA_READY() (ow_data_ready)
|
||||||
#define OW_CLEAR_READY_FLAG() do{ow_data_ready = 0;}while(0)
|
#define OW_CLEAR_READY_FLAG() do{ow_data_ready = 0;}while(0)
|
||||||
|
|
||||||
void OW_process();
|
void OW_process();
|
||||||
void OW_fill_ID(uint8_t N);
|
void OW_fill_ID(uint8_t N);
|
||||||
|
|
||||||
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);
|
||||||
|
void OW_printID(uint8_t N, sendfun s);
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
#if 0
|
#if 0
|
||||||
|
|||||||
@ -66,15 +66,15 @@ uint8_t write_SPI(uint8_t *data, uint8_t len){
|
|||||||
//DBG("Write SPI.."); //return 1;
|
//DBG("Write SPI.."); //return 1;
|
||||||
uint8_t i;
|
uint8_t i;
|
||||||
uint32_t tend = Timer + 10; // we will wait for end of previous transmission not more than 10ms
|
uint32_t tend = Timer + 10; // we will wait for end of previous transmission not more than 10ms
|
||||||
//DBG("check\r\n");
|
//DBG("check\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("SPI error: no EOT flag!\r\n");
|
DBG("SPI error: no EOT flag!\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;
|
||||||
SPI_EOT_FLAG = 0;
|
SPI_EOT_FLAG = 0;
|
||||||
//DBG("OK\r\n");
|
//DBG("OK\n");
|
||||||
//read_end = Timer + 100; // we will wait for end of previous transmission not more than 0.1s
|
//read_end = Timer + 100; // we will wait for end of previous transmission not more than 0.1s
|
||||||
for(i = 0; i < len; i++)
|
for(i = 0; i < len; i++)
|
||||||
SPI_TxBuffer[i] = data[i];
|
SPI_TxBuffer[i] = data[i];
|
||||||
@ -102,13 +102,13 @@ uint8_t *read_SPI(uint8_t *data, uint8_t len){
|
|||||||
//DBG("read SPI.. "); //return NULL;
|
//DBG("read SPI.. "); //return NULL;
|
||||||
uint8_t i;
|
uint8_t i;
|
||||||
uint32_t tend = Timer + 100; // we will wait for end of previous transmission not more than 0.1s
|
uint32_t tend = Timer + 100; // we will wait for end of previous transmission not more than 0.1s
|
||||||
//DBG("check\r\n");
|
//DBG("check\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("SPI error: bad data length\r\n");
|
//DBG("SPI error: bad data length\n");
|
||||||
return NULL;
|
return NULL;
|
||||||
}
|
}
|
||||||
//DBG("OK\r\n");
|
//DBG("OK\n");
|
||||||
for(i = 0; i < len; i++){
|
for(i = 0; i < len; i++){
|
||||||
data[i] = SPI_RxBuffer[i];
|
data[i] = SPI_RxBuffer[i];
|
||||||
//print_int(SPI_RxBuffer[i], usb_send);
|
//print_int(SPI_RxBuffer[i], usb_send);
|
||||||
|
|||||||
@ -18,17 +18,28 @@
|
|||||||
* Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston,
|
* Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston,
|
||||||
* MA 02110-1301, USA.
|
* MA 02110-1301, USA.
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#include "main.h"
|
#include "main.h"
|
||||||
|
#include "stepper_motors.h"
|
||||||
|
|
||||||
|
// TODO: function "move motor to given position"
|
||||||
|
|
||||||
static uint8_t timers_activated[2] = {0, 0}; // flag of activated timers
|
static uint8_t timers_activated[2] = {0, 0}; // flag of activated timers
|
||||||
uint16_t Motor_period[2] = {10000, 10000}; // near 100 steps per second
|
uint16_t Motor_period[2] = {1300, 1300}; // one step per 1.3ms
|
||||||
|
uint32_t Turrets_pause = 2 * TURRETS_PAUSE_US / 1300; // pause in half-steps
|
||||||
volatile uint8_t timer_flag[2] = {0,0};
|
volatile uint8_t timer_flag[2] = {0,0};
|
||||||
// amount of steps for each motor
|
// amount of steps for each motor
|
||||||
volatile uint32_t Motor_steps[5] = {0, 0, 0, 0, 0};
|
volatile uint32_t Motor_steps[5] = {0, 0, 0, 0, 0};
|
||||||
// flag of active motor
|
// flag of active motor
|
||||||
volatile uint8_t Motor_active[5] = {0, 0, 0, 0, 0};
|
volatile uint8_t Motor_active[5] = {0, 0, 0, 0, 0};
|
||||||
|
/*
|
||||||
|
* Wait flags: if non-zero, flag just decremented
|
||||||
|
* (we need it to wait a little on turrets' fixed positions to omit Halls' histeresis)
|
||||||
|
*/
|
||||||
|
uint8_t waits[5] = {0,0,0,0,0};
|
||||||
|
// Halls & end-switches values on previous step
|
||||||
|
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};
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Setup stepper motors' timer Tim
|
* Setup stepper motors' timer Tim
|
||||||
@ -61,8 +72,10 @@ static void setup_timer(uint8_t N){
|
|||||||
timer_enable_irq(Tim, TIM_DIER_UIE); // update IRQ enable
|
timer_enable_irq(Tim, TIM_DIER_UIE); // update IRQ enable
|
||||||
timer_enable_counter(Tim);
|
timer_enable_counter(Tim);
|
||||||
timers_activated[N] = 1;
|
timers_activated[N] = 1;
|
||||||
|
#ifdef EBUG
|
||||||
lastsendfun('3' + N);
|
lastsendfun('3' + N);
|
||||||
MSG(" timer\n");
|
MSG(" timer\n");
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@ -83,44 +96,141 @@ void steppers_init(){
|
|||||||
gpio_set_mode(MOTOR_TIM2_PORT, GPIO_MODE_OUTPUT_2_MHZ,
|
gpio_set_mode(MOTOR_TIM2_PORT, GPIO_MODE_OUTPUT_2_MHZ,
|
||||||
GPIO_CNF_OUTPUT_PUSHPULL, MOTOR_TIM2_PIN);
|
GPIO_CNF_OUTPUT_PUSHPULL, MOTOR_TIM2_PIN);
|
||||||
// EN pins
|
// EN pins
|
||||||
|
// WARNING! EN pins would be shortened to GND in case of overcurrent/overheating
|
||||||
|
// so, they should be pull-up inputs in active mode & pull-down inputs in inactive mode!!!
|
||||||
gpio_set_mode(MOTOR_EN_PORT, GPIO_MODE_OUTPUT_2_MHZ,
|
gpio_set_mode(MOTOR_EN_PORT, GPIO_MODE_OUTPUT_2_MHZ,
|
||||||
GPIO_CNF_OUTPUT_PUSHPULL, MOROT_EN_MASK);
|
GPIO_CNF_INPUT_PULL_UPDOWN, MOTOR_EN_MASK);
|
||||||
|
gpio_clear(MOTOR_EN_PORT, MOTOR_EN_MASK);
|
||||||
// DIR pins
|
// DIR pins
|
||||||
gpio_set_mode(MOTOR_DIR_PORT, GPIO_MODE_OUTPUT_2_MHZ,
|
gpio_set_mode(MOTOR_DIR_PORT, GPIO_MODE_OUTPUT_2_MHZ,
|
||||||
GPIO_CNF_OUTPUT_PUSHPULL, MOROT_DIR_MASK);
|
GPIO_CNF_OUTPUT_PUSHPULL, MOTOR_DIR_MASK);
|
||||||
setup_timer(0);
|
setup_timer(0);
|
||||||
setup_timer(1);
|
setup_timer(1);
|
||||||
|
// Now setup Halls & end-switches
|
||||||
|
SETUP_ESW();
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Test end-switches &
|
||||||
|
* @param num - motor number
|
||||||
|
* @param curpos - end-switches data for motor
|
||||||
|
* @return 0 if we can move further, 1 if there's the end
|
||||||
|
*/
|
||||||
|
uint8_t test_stages_endpos(uint8_t num, uint8_t curpos){
|
||||||
|
if(curpos == 0 || num < 3) return 0;
|
||||||
|
// end-switches numbers for stages
|
||||||
|
const uint8_t stage_plus[2] = {STAGE_CHECK(3, PLUS), STAGE_CHECK(4, PLUS)};
|
||||||
|
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
|
||||||
|
negative_dir = 1;
|
||||||
|
}
|
||||||
|
if(stage_plus[num] == curpos){ // we are on "+" end-switch
|
||||||
|
if(!negative_dir){ // and wanna move to "+"
|
||||||
|
ERR("End-switch +\n");
|
||||||
|
return 1;
|
||||||
|
}
|
||||||
|
}else if(stage_minus[num] == curpos){ // we are on "-" end-switch
|
||||||
|
if(negative_dir){ // and wanna move to "-"
|
||||||
|
ERR("End-switch -\n");
|
||||||
|
return 1;
|
||||||
|
}
|
||||||
|
}else{ // error: WTF is going up? curpos != 2 or 1
|
||||||
|
ERR("Wrong current position: ");
|
||||||
|
print_int(curpos, lastsendfun);
|
||||||
|
lastsendfun('\n');
|
||||||
|
return 1;
|
||||||
|
}
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Return value of current Hall/end-switches position
|
||||||
|
* (converted to normal uint8_t, 0 == none
|
||||||
|
*/
|
||||||
|
uint8_t check_ep(uint8_t num){
|
||||||
|
switch (num){
|
||||||
|
case 0:
|
||||||
|
return CHECK_EP(0);
|
||||||
|
break;
|
||||||
|
case 1:
|
||||||
|
return CHECK_EP(1);
|
||||||
|
break;
|
||||||
|
case 2:
|
||||||
|
return CHECK_EP(2);
|
||||||
|
break;
|
||||||
|
case 3:
|
||||||
|
return CHECK_EP(3);
|
||||||
|
break;
|
||||||
|
case 4:
|
||||||
|
return CHECK_EP(4);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
return 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Move motor Motor_number to User_value steps
|
* Move motor Motor_number to User_value steps
|
||||||
*/
|
*/
|
||||||
void move_motor(uint8_t num, int32_t steps){
|
void move_motor(uint8_t num, int32_t steps){
|
||||||
|
uint8_t curpos, negative_dir = 0;
|
||||||
if(steps == 0) return;
|
if(steps == 0) return;
|
||||||
// check whether motor is moving
|
// check whether motor is moving
|
||||||
if(Motor_active[num]){
|
if(Motor_active[num]){
|
||||||
MSG("err: moving\r\n");
|
ERR("moving\n");
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
#ifdef EBUG
|
||||||
|
MSG("move ");
|
||||||
|
lastsendfun('0' + num);
|
||||||
|
MSG(" to ");
|
||||||
|
print_int(steps, lastsendfun);
|
||||||
|
MSG("\n");
|
||||||
|
#endif
|
||||||
if(steps < 0){
|
if(steps < 0){
|
||||||
|
negative_dir = 1;
|
||||||
steps = -steps;
|
steps = -steps;
|
||||||
|
}
|
||||||
|
curpos = check_ep(num);
|
||||||
|
lastpos[num] = curpos;
|
||||||
|
if(negative_dir){
|
||||||
gpio_set(MOTOR_DIR_PORT, MOTOR_DIR_PIN(num)); // set DIR bit to rotate ccw
|
gpio_set(MOTOR_DIR_PORT, MOTOR_DIR_PIN(num)); // set DIR bit to rotate ccw
|
||||||
}else
|
}else{
|
||||||
gpio_clear(MOTOR_DIR_PORT, MOTOR_DIR_PIN(num)); // reset DIR bit
|
gpio_clear(MOTOR_DIR_PORT, MOTOR_DIR_PIN(num)); // reset DIR bit
|
||||||
Motor_steps[num] = steps << 4; // multiply by 16 to get usteps count
|
}
|
||||||
|
if(test_stages_endpos(num, curpos)) return; // error: we can't move
|
||||||
|
// set all flags and variables
|
||||||
|
Motor_steps[num] = steps; // we run in full-step mode!
|
||||||
|
waits[num] = 0;
|
||||||
Motor_active[num] = 1;
|
Motor_active[num] = 1;
|
||||||
gpio_set(MOTOR_EN_PORT, MOTOR_EN_PIN(num)); // activate motor
|
gpio_set(MOTOR_EN_PORT, MOTOR_EN_PIN(num));
|
||||||
}
|
}
|
||||||
|
|
||||||
void stop_motor(uint8_t num){
|
void stop_motor(uint8_t num){
|
||||||
if(!Motor_active[num]) return;
|
if(!Motor_active[num]) return;
|
||||||
|
#ifdef EBUG
|
||||||
MSG("stop motor ");
|
MSG("stop motor ");
|
||||||
lastsendfun('0' + num);
|
lastsendfun('0' + num);
|
||||||
MSG("\r\n");
|
MSG("\n");
|
||||||
|
#endif
|
||||||
gpio_clear(MOTOR_EN_PORT, MOTOR_EN_PIN(num));
|
gpio_clear(MOTOR_EN_PORT, MOTOR_EN_PIN(num));
|
||||||
Motor_active[num] = 0;
|
Motor_active[num] = 0;
|
||||||
|
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");
|
||||||
|
}
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
/*
|
||||||
|
* Wa cannot use EXTI because multiplexer doesn't allow simultaneous interrupts
|
||||||
|
* handling on the same bits of different ports (e.g. PB7 & PD7)
|
||||||
|
* So, I need to check registers' state before each step!
|
||||||
|
*/
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Check flags set by timers & do next:
|
* Check flags set by timers & do next:
|
||||||
* - decrease step counter if it isn't zero;
|
* - decrease step counter if it isn't zero;
|
||||||
@ -132,15 +242,61 @@ void process_stepper_motors(){
|
|||||||
const uint32_t pins[] = {MOTOR_TIM1_PIN, MOTOR_TIM2_PIN};
|
const uint32_t pins[] = {MOTOR_TIM1_PIN, MOTOR_TIM2_PIN};
|
||||||
const uint8_t startno[] = {0, 3};
|
const uint8_t startno[] = {0, 3};
|
||||||
const uint8_t stopno[] = {3, 5};
|
const uint8_t stopno[] = {3, 5};
|
||||||
|
uint8_t curpos;
|
||||||
for(j = 0; j < 2; j++){
|
for(j = 0; j < 2; j++){
|
||||||
if(timer_flag[j]){
|
if(timer_flag[j]){
|
||||||
timer_flag[j] = 0;
|
timer_flag[j] = 0;
|
||||||
gpio_toggle(ports[j], pins[j]); // change clock state
|
gpio_toggle(ports[j], pins[j]); // change clock state
|
||||||
if(gpio_get(ports[j], pins[j])){ // positive pulse - next microstep
|
if(!gpio_get(ports[j], pins[j])){ // negative pulse - omit this half-step
|
||||||
for(i = startno[j]; i < stopno[j]; i++){ // check motors
|
continue;
|
||||||
if(Motor_steps[i]) Motor_steps[i]--;
|
}
|
||||||
else if(Motor_active[i]){ // stop motor - all done
|
for(i = startno[j]; i < stopno[j]; i++){ // check motors
|
||||||
stop_motor(i);
|
if(Motor_active[i] == 0) continue; // inactive motor
|
||||||
|
curpos = check_ep(i);
|
||||||
|
if(Motor_steps[i] == 0){ // end of moving
|
||||||
|
stop_motor(i); // even if this is a turret with move2pos[i]!=0 we should stop
|
||||||
|
//(what if there's some slipping or so on?)
|
||||||
|
}else{ // we should move further
|
||||||
|
if(waits[i]){ // waiting for position stabilisation
|
||||||
|
waits[i]--;
|
||||||
|
if(waits[i]) continue; // there's more half-steps to skip
|
||||||
|
lastpos[i] = curpos;
|
||||||
|
// tell user current position
|
||||||
|
MSG("position: ");
|
||||||
|
print_int(curpos, lastsendfun);
|
||||||
|
lastsendfun('\n');
|
||||||
|
// turn on motor after pause
|
||||||
|
gpio_set(MOTOR_EN_PORT, MOTOR_EN_PIN(i));
|
||||||
|
if(j == 1){ // this is a linear stage
|
||||||
|
if(test_stages_endpos(i, curpos)){ // this is the end of way
|
||||||
|
stop_motor(i);
|
||||||
|
}
|
||||||
|
}else{ // this is a turret
|
||||||
|
if(move2pos[i]){ // we should move to specific position
|
||||||
|
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;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}else{
|
||||||
|
// check for overcurrent: if MOTOR_EN_PIN == 0
|
||||||
|
if(!gpio_get(MOTOR_EN_PORT, MOTOR_EN_PIN(i))){
|
||||||
|
ERR("overcurrent\n");
|
||||||
|
stop_motor(i);
|
||||||
|
continue;
|
||||||
|
}
|
||||||
|
if(lastpos[i] != curpos){ // transition process
|
||||||
|
if(lastpos[i] == 0){ // come towards position
|
||||||
|
waits[i] = Turrets_pause;
|
||||||
|
// turn off motor while a pause
|
||||||
|
gpio_clear(MOTOR_EN_PORT, MOTOR_EN_PIN(i));
|
||||||
|
continue;
|
||||||
|
}
|
||||||
|
lastpos[i] = curpos;
|
||||||
|
}
|
||||||
|
Motor_steps[i]--;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@ -148,6 +304,7 @@ void process_stepper_motors(){
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Stop timers; turn off motor voltage
|
* Stop timers; turn off motor voltage
|
||||||
*
|
*
|
||||||
@ -165,7 +322,7 @@ void stop_timer(){
|
|||||||
/**
|
/**
|
||||||
* Sets motor period to user value & refresh timer
|
* Sets motor period to user value & refresh timer
|
||||||
* @param num - number of motor
|
* @param num - number of motor
|
||||||
* @param period - period of one STEP in microseconds
|
* @param period - period of one MICROSTEP in microseconds
|
||||||
*/
|
*/
|
||||||
void set_motor_period(uint8_t num, uint16_t period){
|
void set_motor_period(uint8_t num, uint16_t period){
|
||||||
uint32_t Tim, N;
|
uint32_t Tim, N;
|
||||||
@ -175,6 +332,7 @@ void set_motor_period(uint8_t num, uint16_t period){
|
|||||||
case 3:
|
case 3:
|
||||||
Tim = TIM3;
|
Tim = TIM3;
|
||||||
N = 0;
|
N = 0;
|
||||||
|
Turrets_pause = 2 * TURRETS_PAUSE_US / period + 1; // pause in half-steps
|
||||||
break;
|
break;
|
||||||
case 4:
|
case 4:
|
||||||
case 5:
|
case 5:
|
||||||
@ -185,7 +343,6 @@ void set_motor_period(uint8_t num, uint16_t period){
|
|||||||
MSG("err: bad motor");
|
MSG("err: bad motor");
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
period >>= 4; // divide by 4 to get 16usteps for one step
|
|
||||||
if(period == 0) Motor_period[N] = 1;
|
if(period == 0) Motor_period[N] = 1;
|
||||||
else Motor_period[N] = period;
|
else Motor_period[N] = period;
|
||||||
if(!timers_activated[N]) setup_timer(N);
|
if(!timers_activated[N]) setup_timer(N);
|
||||||
|
|||||||
@ -24,6 +24,42 @@
|
|||||||
|
|
||||||
#include <libopencm3/stm32/timer.h>
|
#include <libopencm3/stm32/timer.h>
|
||||||
|
|
||||||
|
// default pause to make sure that turret is on position
|
||||||
|
#define TURRETS_PAUSE_US 30000
|
||||||
|
// max amount of steps to add to turret for moving to next position
|
||||||
|
#define TURRETS_NEXT_POS_STEPS 300
|
||||||
|
|
||||||
|
#ifndef CONCAT
|
||||||
|
#define CONCAT(A, B) A ## B
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// check status of end-switches and Halls
|
||||||
|
// Motor 0 == turret 0, PD0..PD3
|
||||||
|
#define _CHECK_EP0 ((~GPIO_IDR(GPIOD)) & 0x0f)
|
||||||
|
// Motor 1 == turret 1, PD4..PD6
|
||||||
|
#define _CHECK_EP1 (((~GPIO_IDR(GPIOD)) >> 4) & 0x07)
|
||||||
|
// Motor 2 == turret 2, PD7, PB6, PB7
|
||||||
|
#define _CHECK_EP2 ((((~GPIO_IDR(GPIOD)) >> 7) & 0x01) | (((~GPIO_IDR(GPIOB))>> 6) & 0x03))
|
||||||
|
// Motor 3 == long (VPHG, pupil stop) stage, PC7/PC8 (down/up)
|
||||||
|
#define _CHECK_EP3 (((~GPIO_IDR(GPIOC)) >> 7) & 0x03)
|
||||||
|
// Motor 4 == short (focus) stage, PC9/PA8 (down/up)
|
||||||
|
#define _CHECK_EP4 ((((~GPIO_IDR(GPIOC)) >> 9) & 0x01) | (((~GPIO_IDR(GPIOA)) >> 8) & 0x01))
|
||||||
|
// this macro returns end-switches & Hall status: 0 - not active, 1 - active
|
||||||
|
#define CHECK_EP(X) CONCAT(_CHECK_EP, X)
|
||||||
|
// end-switches for motors 3,4 (stage 1 and stage 2): stop when direction positive/negative
|
||||||
|
#define EP3PLUS 2
|
||||||
|
#define EP3MINUS 1
|
||||||
|
#define EP4PLUS 2
|
||||||
|
#define EP4MINUS 1
|
||||||
|
#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)
|
||||||
|
|
||||||
void steppers_init();
|
void steppers_init();
|
||||||
void process_stepper_motors();
|
void process_stepper_motors();
|
||||||
void move_motor(uint8_t num, int32_t steps);
|
void move_motor(uint8_t num, int32_t steps);
|
||||||
|
|||||||
@ -17,6 +17,11 @@
|
|||||||
* along with this library. If not, see <http://www.gnu.org/licenses/>.
|
* along with this library. If not, see <http://www.gnu.org/licenses/>.
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
/*
|
||||||
|
* TODO:
|
||||||
|
* implement mutexes for other type of MCU (which doesn't have strex & ldrex)
|
||||||
|
*/
|
||||||
|
|
||||||
#include <libopencm3/cm3/sync.h>
|
#include <libopencm3/cm3/sync.h>
|
||||||
|
|
||||||
/* DMB is supported on CM0 */
|
/* DMB is supported on CM0 */
|
||||||
|
|||||||
@ -42,7 +42,7 @@ uint32_t __strex(uint32_t val, volatile uint32_t *addr);
|
|||||||
typedef uint32_t mutex_t;
|
typedef uint32_t mutex_t;
|
||||||
|
|
||||||
#define MUTEX_UNLOCKED 0
|
#define MUTEX_UNLOCKED 0
|
||||||
#define MUTEX_LOCKED 1
|
#define MUTEX_LOCKED 1
|
||||||
|
|
||||||
void mutex_lock(mutex_t *m);
|
void mutex_lock(mutex_t *m);
|
||||||
void mutex_unlock(mutex_t *m);
|
void mutex_unlock(mutex_t *m);
|
||||||
|
|||||||
@ -87,6 +87,7 @@ void parce_incoming_buf(char *buf, int len, sendfun s){
|
|||||||
}else switch (command){
|
}else switch (command){
|
||||||
case 'P':
|
case 'P':
|
||||||
OW_fill_ID(0);
|
OW_fill_ID(0);
|
||||||
|
//run_dmatimer();
|
||||||
break;
|
break;
|
||||||
case 'x': // set period of TIM1 (motors 1..3)
|
case 'x': // set period of TIM1 (motors 1..3)
|
||||||
active_motor = 1;
|
active_motor = 1;
|
||||||
@ -108,7 +109,7 @@ void parce_incoming_buf(char *buf, int len, sendfun s){
|
|||||||
print_hex(onewire_addr, 8, s);
|
print_hex(onewire_addr, 8, s);
|
||||||
}else
|
}else
|
||||||
P("1-wire error",s );
|
P("1-wire error",s );
|
||||||
P("\r\n", s);
|
P("\n", s);
|
||||||
break;*/
|
break;*/
|
||||||
case 'S': // single conversion
|
case 'S': // single conversion
|
||||||
doubleconv = 0;
|
doubleconv = 0;
|
||||||
@ -118,7 +119,7 @@ void parce_incoming_buf(char *buf, int len, sendfun s){
|
|||||||
break;
|
break;
|
||||||
case 'A': // show ADC value
|
case 'A': // show ADC value
|
||||||
//adc_start_conversion_direct(ADC1);
|
//adc_start_conversion_direct(ADC1);
|
||||||
P("\r\n ADC value: ", s);
|
P("\n ADC value: ", s);
|
||||||
for(j = 0; j < 8; j++){
|
for(j = 0; j < 8; j++){
|
||||||
print_int(ADC_value[j], s);
|
print_int(ADC_value[j], s);
|
||||||
P("\t", s);
|
P("\t", s);
|
||||||
@ -153,9 +154,9 @@ void parce_incoming_buf(char *buf, int len, sendfun s){
|
|||||||
print_ad_vals(s);
|
print_ad_vals(s);
|
||||||
break;
|
break;
|
||||||
case 'u': // check USB connection
|
case 'u': // check USB connection
|
||||||
P("\r\nUSB ", s);
|
P("\nUSB ", s);
|
||||||
if(!USB_connected) P("dis", s);
|
if(!USB_connected) P("dis", s);
|
||||||
P("connected\r\n",s);
|
P("connected\n",s);
|
||||||
break;
|
break;
|
||||||
case 'M': // ADC monitoring ON
|
case 'M': // ADC monitoring ON
|
||||||
ADC_monitoring = !ADC_monitoring;
|
ADC_monitoring = !ADC_monitoring;
|
||||||
@ -188,7 +189,7 @@ void prnt(uint8_t *wrd, sendfun s){
|
|||||||
|
|
||||||
/*
|
/*
|
||||||
void newline(sendfun s){
|
void newline(sendfun s){
|
||||||
P("\r\n", s);
|
P("\n", s);
|
||||||
}
|
}
|
||||||
*/
|
*/
|
||||||
|
|
||||||
@ -301,26 +302,26 @@ void set_ADC_gain(int32_t v, sendfun s){
|
|||||||
*/
|
*/
|
||||||
void stepper_proc(int32_t v, sendfun s){
|
void stepper_proc(int32_t v, sendfun s){
|
||||||
if(active_motor > 4){
|
if(active_motor > 4){
|
||||||
P("wrong motor number\r\n", s);
|
P("wrong motor number\n", s);
|
||||||
return; // error
|
return; // error
|
||||||
}
|
}
|
||||||
MSG("move ");
|
|
||||||
lastsendfun('0' + active_motor);
|
|
||||||
MSG(" to ");
|
|
||||||
print_int(v, lastsendfun);
|
|
||||||
MSG("\r\n");
|
|
||||||
move_motor(active_motor, v);
|
move_motor(active_motor, v);
|
||||||
active_motor = 6;
|
active_motor = 6;
|
||||||
}
|
}
|
||||||
|
|
||||||
void set_timr(int32_t v, sendfun s){
|
void set_timr(int32_t v, sendfun s){
|
||||||
if(active_motor > 4){
|
if(active_motor > 4){
|
||||||
P("wrong motor number\r\n", s);
|
P("wrong motor number\n", s);
|
||||||
return; // error
|
return; // error
|
||||||
}
|
}
|
||||||
|
if(v < 0 || v > 0xffff){
|
||||||
|
MSG("Bad period!\n");
|
||||||
|
active_motor = 6;
|
||||||
|
return;
|
||||||
|
}
|
||||||
MSG("set period: ");
|
MSG("set period: ");
|
||||||
print_int(v, lastsendfun);
|
print_int(v, lastsendfun);
|
||||||
MSG("\r\n");
|
MSG("\n");
|
||||||
set_motor_period(active_motor, (uint16_t)v);
|
set_motor_period(active_motor, (uint16_t)v);
|
||||||
active_motor = 6;
|
active_motor = 6;
|
||||||
}
|
}
|
||||||
|
|||||||
@ -37,6 +37,8 @@
|
|||||||
|
|
||||||
#define MSG(arg) prnt((uint8_t*)arg, lastsendfun)
|
#define MSG(arg) prnt((uint8_t*)arg, lastsendfun)
|
||||||
|
|
||||||
|
#define ERR(arg) do{prnt((uint8_t*)"Error! ",lastsendfun); prnt((uint8_t*)arg, lastsendfun);}while(0)
|
||||||
|
|
||||||
typedef void (*sendfun)(uint8_t); // function to send a byte
|
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
|
typedef void (*intfun)(int32_t, sendfun); // function to process entered integer value at end of input
|
||||||
|
|
||||||
|
|||||||
Loading…
x
Reference in New Issue
Block a user