├── .cproject
├── .gitignore
├── .gitmodules
├── .project
├── .pydevproject
├── .settings
├── language.settings.xml
└── org.eclipse.cdt.codan.core.prefs
├── Makefile
├── README.md
├── bldc_design_calculations.m
├── board
├── board.c
├── board.c~
├── board.h
├── board.h~
├── board.mk
└── cfg
│ └── board.chcfg
├── chconf.h
├── chibios-patch
└── adc_exttrig.patch
├── config
└── config.mk
├── docs
└── drawings
│ └── concept_strip.svg
├── halconf.h
├── mcuconf.h
├── python
└── led.py
└── src
├── blinky.c
├── blinky.h
├── main.c
├── obldc_can.c
├── obldc_can.h
├── obldc_catchmotor.c
├── obldc_catchmotor.h
├── obldc_def.h
├── obldcadc.c
├── obldcadc.h
├── obldcpwm.c
├── obldcpwm.h
├── ringbuffer.h
├── uart_scp.c
└── uart_scp.h
/.cproject:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
11 |
12 |
13 |
14 |
15 |
16 |
17 |
18 |
19 |
20 |
21 |
22 |
23 |
24 |
25 |
26 |
27 |
28 |
29 |
30 |
31 |
32 |
35 |
36 |
37 |
38 |
39 |
40 |
41 |
42 |
43 |
44 |
45 |
46 |
47 |
48 |
49 |
50 |
51 |
52 |
53 |
54 |
55 |
56 |
57 |
58 |
59 |
60 |
61 |
62 |
63 |
64 |
65 |
66 |
67 |
68 |
69 |
70 |
--------------------------------------------------------------------------------
/.gitignore:
--------------------------------------------------------------------------------
1 | # Object files
2 | *.o
3 | *.ko
4 |
5 | # Libraries
6 | *.lib
7 | *.a
8 |
9 | # Shared objects (inc. Windows DLLs)
10 | *.dll
11 | *.so
12 | *.so.*
13 | *.dylib
14 |
15 | # Executables
16 | *.exe
17 | *.out
18 | *.app
19 |
--------------------------------------------------------------------------------
/.gitmodules:
--------------------------------------------------------------------------------
1 | [submodule "ChibiOS"]
2 | path = ChibiOS
3 | url = https://github.com/ChibiOS/ChibiOS.git
4 |
--------------------------------------------------------------------------------
/.project:
--------------------------------------------------------------------------------
1 |
2 |
3 | bldc-strip
4 |
5 |
6 |
7 |
8 |
9 | org.python.pydev.PyDevBuilder
10 |
11 |
12 |
13 |
14 | org.eclipse.cdt.managedbuilder.core.genmakebuilder
15 | clean,full,incremental,
16 |
17 |
18 |
19 |
20 | org.eclipse.cdt.managedbuilder.core.ScannerConfigBuilder
21 | full,incremental,
22 |
23 |
24 |
25 |
26 |
27 | org.eclipse.cdt.core.cnature
28 | org.eclipse.cdt.managedbuilder.core.managedBuildNature
29 | org.eclipse.cdt.managedbuilder.core.ScannerConfigNature
30 | org.python.pydev.pythonNature
31 | org.eclipse.cdt.core.ccnature
32 |
33 |
34 |
35 | src
36 | file:/home/joerg/repos/OpenBLDC/kjellhar/bldc-strip/src
37 |
38 |
39 |
40 |
--------------------------------------------------------------------------------
/.pydevproject:
--------------------------------------------------------------------------------
1 |
2 |
3 | Default
4 | python 2.7
5 |
6 |
--------------------------------------------------------------------------------
/.settings/language.settings.xml:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
11 |
12 |
13 |
14 |
15 |
16 |
--------------------------------------------------------------------------------
/.settings/org.eclipse.cdt.codan.core.prefs:
--------------------------------------------------------------------------------
1 | eclipse.preferences.version=1
2 | org.eclipse.cdt.codan.checkers.errnoreturn=Warning
3 | org.eclipse.cdt.codan.checkers.errnoreturn.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true},implicit\=>false}
4 | org.eclipse.cdt.codan.checkers.errreturnvalue=Error
5 | org.eclipse.cdt.codan.checkers.errreturnvalue.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true}}
6 | org.eclipse.cdt.codan.checkers.noreturn=Error
7 | org.eclipse.cdt.codan.checkers.noreturn.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true},implicit\=>false}
8 | org.eclipse.cdt.codan.internal.checkers.AbstractClassCreation=Error
9 | org.eclipse.cdt.codan.internal.checkers.AbstractClassCreation.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true}}
10 | org.eclipse.cdt.codan.internal.checkers.AmbiguousProblem=Error
11 | org.eclipse.cdt.codan.internal.checkers.AmbiguousProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true}}
12 | org.eclipse.cdt.codan.internal.checkers.AssignmentInConditionProblem=Warning
13 | org.eclipse.cdt.codan.internal.checkers.AssignmentInConditionProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true}}
14 | org.eclipse.cdt.codan.internal.checkers.AssignmentToItselfProblem=Error
15 | org.eclipse.cdt.codan.internal.checkers.AssignmentToItselfProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true}}
16 | org.eclipse.cdt.codan.internal.checkers.CaseBreakProblem=Warning
17 | org.eclipse.cdt.codan.internal.checkers.CaseBreakProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true},no_break_comment\=>"no break",last_case_param\=>false,empty_case_param\=>false}
18 | org.eclipse.cdt.codan.internal.checkers.CatchByReference=Warning
19 | org.eclipse.cdt.codan.internal.checkers.CatchByReference.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true},unknown\=>false,exceptions\=>()}
20 | org.eclipse.cdt.codan.internal.checkers.CircularReferenceProblem=Error
21 | org.eclipse.cdt.codan.internal.checkers.CircularReferenceProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true}}
22 | org.eclipse.cdt.codan.internal.checkers.ClassMembersInitialization=Warning
23 | org.eclipse.cdt.codan.internal.checkers.ClassMembersInitialization.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true},skip\=>true}
24 | org.eclipse.cdt.codan.internal.checkers.FieldResolutionProblem=Error
25 | org.eclipse.cdt.codan.internal.checkers.FieldResolutionProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true}}
26 | org.eclipse.cdt.codan.internal.checkers.FunctionResolutionProblem=Error
27 | org.eclipse.cdt.codan.internal.checkers.FunctionResolutionProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true}}
28 | org.eclipse.cdt.codan.internal.checkers.InvalidArguments=Error
29 | org.eclipse.cdt.codan.internal.checkers.InvalidArguments.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true}}
30 | org.eclipse.cdt.codan.internal.checkers.InvalidTemplateArgumentsProblem=Error
31 | org.eclipse.cdt.codan.internal.checkers.InvalidTemplateArgumentsProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true}}
32 | org.eclipse.cdt.codan.internal.checkers.LabelStatementNotFoundProblem=Error
33 | org.eclipse.cdt.codan.internal.checkers.LabelStatementNotFoundProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true}}
34 | org.eclipse.cdt.codan.internal.checkers.MemberDeclarationNotFoundProblem=Error
35 | org.eclipse.cdt.codan.internal.checkers.MemberDeclarationNotFoundProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true}}
36 | org.eclipse.cdt.codan.internal.checkers.MethodResolutionProblem=Error
37 | org.eclipse.cdt.codan.internal.checkers.MethodResolutionProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true}}
38 | org.eclipse.cdt.codan.internal.checkers.NamingConventionFunctionChecker=-Info
39 | org.eclipse.cdt.codan.internal.checkers.NamingConventionFunctionChecker.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true},pattern\=>"^[a-z]",macro\=>true,exceptions\=>()}
40 | org.eclipse.cdt.codan.internal.checkers.NonVirtualDestructorProblem=Warning
41 | org.eclipse.cdt.codan.internal.checkers.NonVirtualDestructorProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true}}
42 | org.eclipse.cdt.codan.internal.checkers.OverloadProblem=Error
43 | org.eclipse.cdt.codan.internal.checkers.OverloadProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true}}
44 | org.eclipse.cdt.codan.internal.checkers.RedeclarationProblem=Error
45 | org.eclipse.cdt.codan.internal.checkers.RedeclarationProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true}}
46 | org.eclipse.cdt.codan.internal.checkers.RedefinitionProblem=Error
47 | org.eclipse.cdt.codan.internal.checkers.RedefinitionProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true}}
48 | org.eclipse.cdt.codan.internal.checkers.ReturnStyleProblem=-Warning
49 | org.eclipse.cdt.codan.internal.checkers.ReturnStyleProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true}}
50 | org.eclipse.cdt.codan.internal.checkers.ScanfFormatStringSecurityProblem=-Warning
51 | org.eclipse.cdt.codan.internal.checkers.ScanfFormatStringSecurityProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true}}
52 | org.eclipse.cdt.codan.internal.checkers.StatementHasNoEffectProblem=Warning
53 | org.eclipse.cdt.codan.internal.checkers.StatementHasNoEffectProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true},macro\=>true,exceptions\=>()}
54 | org.eclipse.cdt.codan.internal.checkers.SuggestedParenthesisProblem=Warning
55 | org.eclipse.cdt.codan.internal.checkers.SuggestedParenthesisProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true},paramNot\=>false}
56 | org.eclipse.cdt.codan.internal.checkers.SuspiciousSemicolonProblem=Warning
57 | org.eclipse.cdt.codan.internal.checkers.SuspiciousSemicolonProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true},else\=>false,afterelse\=>false}
58 | org.eclipse.cdt.codan.internal.checkers.TypeResolutionProblem=Error
59 | org.eclipse.cdt.codan.internal.checkers.TypeResolutionProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true}}
60 | org.eclipse.cdt.codan.internal.checkers.UnusedFunctionDeclarationProblem=Warning
61 | org.eclipse.cdt.codan.internal.checkers.UnusedFunctionDeclarationProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true},macro\=>true}
62 | org.eclipse.cdt.codan.internal.checkers.UnusedStaticFunctionProblem=Warning
63 | org.eclipse.cdt.codan.internal.checkers.UnusedStaticFunctionProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true},macro\=>true}
64 | org.eclipse.cdt.codan.internal.checkers.UnusedVariableDeclarationProblem=Warning
65 | org.eclipse.cdt.codan.internal.checkers.UnusedVariableDeclarationProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true},macro\=>true,exceptions\=>("@(\#)","$Id")}
66 | org.eclipse.cdt.codan.internal.checkers.VariableResolutionProblem=Error
67 | org.eclipse.cdt.codan.internal.checkers.VariableResolutionProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true}}
68 |
--------------------------------------------------------------------------------
/Makefile:
--------------------------------------------------------------------------------
1 | ##############################################################################
2 | # Build global options
3 | # NOTE: Can be overridden externally.
4 | #
5 |
6 | # Compiler options here.
7 | ifeq ($(USE_OPT),)
8 | USE_OPT = -O2 -ggdb -fomit-frame-pointer -falign-functions=16
9 | endif
10 |
11 | # C specific options here (added to USE_OPT).
12 | ifeq ($(USE_COPT),)
13 | USE_COPT =
14 | endif
15 |
16 | # C++ specific options here (added to USE_OPT).
17 | ifeq ($(USE_CPPOPT),)
18 | USE_CPPOPT = -fno-rtti
19 | endif
20 |
21 | # Enable this if you want the linker to remove unused code and data
22 | ifeq ($(USE_LINK_GC),)
23 | USE_LINK_GC = yes
24 | endif
25 |
26 | # Linker extra options here.
27 | ifeq ($(USE_LDOPT),)
28 | USE_LDOPT =
29 | endif
30 |
31 | # Enable this if you want link time optimizations (LTO)
32 | ifeq ($(USE_LTO),)
33 | # USE_LTO = yes removed because of bug in gcc5
34 | USE_LTO = no
35 | endif
36 |
37 | # If enabled, this option allows to compile the application in THUMB mode.
38 | ifeq ($(USE_THUMB),)
39 | USE_THUMB = yes
40 | endif
41 |
42 | # Enable this if you want to see the full log while compiling.
43 | ifeq ($(USE_VERBOSE_COMPILE),)
44 | USE_VERBOSE_COMPILE = no
45 | endif
46 |
47 | # If enabled, this option makes the build process faster by not compiling
48 | # modules not used in the current configuration.
49 | ifeq ($(USE_SMART_BUILD),)
50 | USE_SMART_BUILD = yes
51 | endif
52 |
53 | #
54 | # Build global options
55 | ##############################################################################
56 |
57 | ##############################################################################
58 | # Architecture or project specific options
59 | #
60 |
61 | # Stack size to be allocated to the Cortex-M process stack. This stack is
62 | # the stack used by the main() thread.
63 | ifeq ($(USE_PROCESS_STACKSIZE),)
64 | USE_PROCESS_STACKSIZE = 0x400
65 | endif
66 |
67 | # Stack size to the allocated to the Cortex-M main/exceptions stack. This
68 | # stack is used for processing interrupts and exceptions.
69 | ifeq ($(USE_EXCEPTIONS_STACKSIZE),)
70 | USE_EXCEPTIONS_STACKSIZE = 0x400
71 | endif
72 |
73 | # Enables the use of FPU on Cortex-M4 (no, softfp, hard).
74 | ifeq ($(USE_FPU),)
75 | USE_FPU = no
76 | endif
77 |
78 | #
79 | # Architecture or project specific options
80 | ##############################################################################
81 |
82 | ##############################################################################
83 | # Project, sources and paths
84 | #
85 |
86 | # Define project name here
87 | PROJECT = bldc-strip_v2
88 |
89 | # Imported source files and paths
90 | CHIBIOS = ChibiOS
91 | # Startup files.
92 | include $(CHIBIOS)/os/common/ports/ARMCMx/compilers/GCC/mk/startup_stm32f1xx.mk
93 | # HAL-OSAL files (optional).
94 | include $(CHIBIOS)/os/hal/hal.mk
95 | include $(CHIBIOS)/os/hal/ports/STM32/STM32F1xx/platform.mk
96 | include board/board.mk
97 | include $(CHIBIOS)/os/hal/osal/rt/osal.mk
98 | # RTOS files (optional).
99 | include $(CHIBIOS)/os/rt/rt.mk
100 | include $(CHIBIOS)/os/rt/ports/ARMCMx/compilers/GCC/mk/port_v7m.mk
101 | # Other files (optional).
102 | include $(CHIBIOS)/test/rt/test.mk
103 |
104 | # Define linker script file here
105 | LDSCRIPT= $(STARTUPLD)/STM32F103xB.ld
106 |
107 | # C sources that can be compiled in ARM or THUMB mode depending on the global
108 | # setting.
109 | CSRC = $(STARTUPSRC) \
110 | $(KERNSRC) \
111 | $(PORTSRC) \
112 | $(OSALSRC) \
113 | $(HALSRC) \
114 | $(PLATFORMSRC) \
115 | $(BOARDSRC) \
116 | $(TESTSRC) \
117 | $(CHIBIOS)/os/various/evtimer.c \
118 | $(CHIBIOS)/os/various/syscalls.c \
119 | src/main.c \
120 | src/blinky.c \
121 | src/uart_scp.c \
122 | src/obldcpwm.c \
123 | src/obldcadc.c \
124 | src/obldc_catchmotor.c \
125 | src/obldc_can.c
126 |
127 | # C++ sources that can be compiled in ARM or THUMB mode depending on the global
128 | # setting.
129 | CPPSRC =
130 |
131 | # C sources to be compiled in ARM mode regardless of the global setting.
132 | # NOTE: Mixing ARM and THUMB mode enables the -mthumb-interwork compiler
133 | # option that results in lower performance and larger code size.
134 | ACSRC =
135 |
136 | # C++ sources to be compiled in ARM mode regardless of the global setting.
137 | # NOTE: Mixing ARM and THUMB mode enables the -mthumb-interwork compiler
138 | # option that results in lower performance and larger code size.
139 | ACPPSRC =
140 |
141 | # C sources to be compiled in THUMB mode regardless of the global setting.
142 | # NOTE: Mixing ARM and THUMB mode enables the -mthumb-interwork compiler
143 | # option that results in lower performance and larger code size.
144 | TCSRC =
145 |
146 | # C sources to be compiled in THUMB mode regardless of the global setting.
147 | # NOTE: Mixing ARM and THUMB mode enables the -mthumb-interwork compiler
148 | # option that results in lower performance and larger code size.
149 | TCPPSRC =
150 |
151 | # List ASM source files here
152 | ASMSRC = $(STARTUPASM) $(PORTASM) $(OSALASM)
153 |
154 | INCDIR = $(STARTUPINC) $(KERNINC) $(PORTINC) $(OSALINC) \
155 | $(HALINC) $(PLATFORMINC) $(BOARDINC) $(TESTINC) \
156 | $(CHIBIOS)/os/various
157 |
158 |
159 | #
160 | # Project, sources and paths
161 | ##############################################################################
162 |
163 | ##############################################################################
164 | # Compiler settings
165 | #
166 |
167 | MCU = cortex-m3
168 |
169 | #TRGT = arm-elf-
170 | TRGT = arm-none-eabi-
171 | CC = $(TRGT)gcc
172 | CPPC = $(TRGT)g++
173 | # Enable loading with g++ only if you need C++ runtime support.
174 | # NOTE: You can use C++ even without C++ support if you are careful. C++
175 | # runtime support makes code size explode.
176 | LD = $(TRGT)gcc
177 | #LD = $(TRGT)g++
178 | CP = $(TRGT)objcopy
179 | AS = $(TRGT)gcc -x assembler-with-cpp
180 | AR = $(TRGT)ar
181 | OD = $(TRGT)objdump
182 | SZ = $(TRGT)size
183 | HEX = $(CP) -O ihex
184 | BIN = $(CP) -O binary
185 |
186 | # ARM-specific options here
187 | AOPT =
188 |
189 | # THUMB-specific options here
190 | TOPT = -mthumb -DTHUMB
191 |
192 | # Define C warning options here
193 | CWARN = -Wall -Wextra -Wstrict-prototypes
194 |
195 | # Define C++ warning options here
196 | CPPWARN = -Wall -Wextra
197 |
198 | #
199 | # Compiler settings
200 | ##############################################################################
201 |
202 | ##############################################################################
203 | # Start of user section
204 | #
205 |
206 | # List all user C define here, like -D_DEBUG=1
207 | UDEFS =
208 |
209 | # Define ASM defines here
210 | UADEFS =
211 |
212 | # List all user directories here
213 | UINCDIR =
214 |
215 | # List the user directory to look for the libraries here
216 | ULIBDIR =
217 |
218 | # List all user libraries here
219 | ULIBS =
220 |
221 | #
222 | # End of user defines
223 | ##############################################################################
224 |
225 | RULESPATH = $(CHIBIOS)/os/common/ports/ARMCMx/compilers/GCC
226 | include $(RULESPATH)/rules.mk
227 |
--------------------------------------------------------------------------------
/README.md:
--------------------------------------------------------------------------------
1 | bldc-strip
2 | ==========
3 |
4 | Firmware for OpenBLDC "Strip" (STM32F103).
5 |
6 | ## Project description
7 |
8 | Bldc-strip is an open-source project aiming to design an ESC (electronic speed controller) for brushless dc motors. The control software is concurrently developed with a motor controller [hardware](https://github.com/joewa/open-bldc-hardware/tree/master/strip/v0.2) and [simulation models](https://github.com/joewa/open-bldc-modelica) which are used to investigate and test the control algorithms before/while they are implemented to the real controller software and hardware. It is designed to provide a better ESC for the control of small multi-rotor aircraft but should also fit other applications.
9 |
10 | ## Features
11 |
12 | - [x] Open-source control software for STM32F103 32bit microcontroller using [ChibiOS](http://www.chibios.org).
13 | - [x] Sensorless 6-step control method for brushless motors.
14 | - [x] Open loop voltage control to provide (almost) linear "brushed-motor-like" characteristics which is often requested by control systems engineers.
15 | - [x] High frequency PWM from 40 to 200 kHz enabling proper operation of some very small and fast motors.
16 | - [x] Dedicated control methods for fast, slow and very slow to zero rotation speed.
17 | - [x] Seamless 4-quadrant operation with regenerative braking.
18 | - [x] Smooth change of rotation direction.
19 | - [x] Closed loop sensorless position control (proof of concept)
20 | - [ ] Catch start of a rotation motor
21 | - [ ] Adequate protection functions:
22 | - [ ] limitation of motor current
23 | - [ ] limitation of input current
24 | - [ ] seperate limit for regenerative current
25 | - [ ] limitation of reference duty cycle command that would result in a current limitation
26 | - [ ] Software watchdog
27 | - [x] Command/control interface via UART
28 | - [ ] Command/control interface via CAN-bus
29 |
30 | ## Dependencies and references
31 |
32 | Designed and tested with the [OpenBLDC "Strip" V0.2 ESC](https://github.com/joewa/open-bldc-hardware/tree/master/strip/v0.2).
33 |
34 | Using [ChibiOS Real-Time Operating System](http://www.chibios.org).
35 |
36 | Multi-physics, open-source [Modelica simulation models](https://github.com/joewa/open-bldc-modelica) are designed to investigate appropriate motor control methods. In the future, they may be merged with this repository.
37 |
38 | Demo video on [YouTube](https://youtu.be/5QIjhmtY5ok) and [Vimeo](https://vimeo.com/124761289).
39 |
40 | Overview of sensorless 6-step control methods.
41 | Review: [José Carlos Gamazo-Real, Ernesto Vázquez-Sánchez, Jaime Gómez-Gil, "Position and Speed Control of Brushless DC Motors Using Sensorless Techniques and Application Trends", Department of Signal Theory, Communications and Telematic Engineering, University of Valladolid, Sensors 2010, ISSN 1424-8220](http://citeseerx.ist.psu.edu/viewdoc/summary?doi=10.1.1.287.5781)
42 |
43 | ## Status and contribution
44 |
45 | This is a part-time development project and is not dedicated for productive usage. Any contributions preferably [Pull Requests](https://github.com/joewa/bldc-strip/pulls) are always welcome.
46 |
47 | You may report any issues or share ideas by using the [Issues](https://github.com/joewa/bldc-strip/issues) button.
48 |
49 | Additionally, there is a chat room on Gitter:
50 | [](https://gitter.im/joewa/bldc-strip?utm_source=badge&utm_medium=badge&utm_campaign=pr-badge&utm_content=body_badge)
51 |
52 |
53 | ## License
54 |
55 | The project is released under the GNU GENERAL PUBLIC LICENSE - Version 3.
56 |
57 |
--------------------------------------------------------------------------------
/bldc_design_calculations.m:
--------------------------------------------------------------------------------
1 | Ts_ADC1 = 1e-6; % Sample time of ADC1 [s] (All channels ADC_SAMPLE_1P5)
2 | ADC_COMMUTATE_NUM_CHANNELS = 1;
3 | ADC_COMMUTATE_BUF_DEPTH = 50;
4 | f_single = 1 / (Ts_ADC1 * ADC_COMMUTATE_NUM_CHANNELS) % Sample frequency of each channel
5 | T_cb_ADC1 = Ts_ADC1 * ADC_COMMUTATE_NUM_CHANNELS * ADC_COMMUTATE_BUF_DEPTH / 2 % Period of ADC1 streaming callback
6 | f_cb_ADC1 = 1 / T_cb_ADC1
7 |
8 | f_PWM = 20e3;
9 | duty_cycle = 0.6;
10 | t_on = duty_cycle * 1/f_PWM
11 | samples_when_on = t_on * f_single
12 |
13 | disp('Schaltzeiten')
14 | PWM_CLOCK_FREQUENCY = 28e6;
15 | PWM_DEFAULT_FREQUENCY = 100000; % [40e3, 50e3, 62500, 100e3] choose one of these base frequencies [Hz]
16 | PWM_MINIMUM_FREQUENCY = 40000;
17 |
18 | ADC_COMMUTATE_FREQUENCY = 1e6;% // [Hz]
19 | ADC_PWM_DIVIDER = (PWM_CLOCK_FREQUENCY / ADC_COMMUTATE_FREQUENCY);
20 | ADC_PWM_PERIOD = (ADC_COMMUTATE_FREQUENCY / PWM_DEFAULT_FREQUENCY);
21 | PWM_MAXIMUM_PERIOD = (ADC_PWM_DIVIDER * ADC_COMMUTATE_FREQUENCY / PWM_MINIMUM_FREQUENCY);
22 |
23 | d_percent = (1:49) + 49;
24 | pwm_period = fix( ((ADC_PWM_PERIOD * 2500) ./ ((100 .- d_percent) .* d_percent))) .* ADC_PWM_DIVIDER;
25 |
26 | for i=1:length(pwm_period)
27 | if pwm_period(i) > PWM_MAXIMUM_PERIOD
28 | pwm_period(i) = PWM_MAXIMUM_PERIOD;
29 | endif
30 | endfor
31 |
32 | t_on = d_percent ./ 100 .* pwm_period;
33 | t_off = pwm_period - t_on;
34 | plot(d_percent, pwm_period, d_percent, t_off)
35 | % plot(d_percent, t_off)
36 | % Check max samples for linear fit;
37 |
38 |
39 |
40 |
41 |
42 |
--------------------------------------------------------------------------------
/board/board.c:
--------------------------------------------------------------------------------
1 | /*
2 | ChibiOS/RT - Copyright (C) 2006-2013 Giovanni Di Sirio
3 |
4 | Licensed under the Apache License, Version 2.0 (the "License");
5 | you may not use this file except in compliance with the License.
6 | You may obtain a copy of the License at
7 |
8 | http://www.apache.org/licenses/LICENSE-2.0
9 |
10 | Unless required by applicable law or agreed to in writing, software
11 | distributed under the License is distributed on an "AS IS" BASIS,
12 | WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 | See the License for the specific language governing permissions and
14 | limitations under the License.
15 | */
16 |
17 | //#include "ch.h"
18 | #include "hal.h"
19 |
20 | //#include "board.h"
21 |
22 | /**
23 | * @brief PAL setup.
24 | * @details Digital I/O ports static configuration as defined in @p board.h.
25 | * This variable is used by the HAL when initializing the PAL driver.
26 | */
27 | #if HAL_USE_PAL || defined(__DOXYGEN__)
28 | const PALConfig pal_default_config = // from the STM32F1x3 template
29 | {
30 | {VAL_GPIOAODR, VAL_GPIOACRL, VAL_GPIOACRH},
31 | {VAL_GPIOBODR, VAL_GPIOBCRL, VAL_GPIOBCRH},
32 | {VAL_GPIOCODR, VAL_GPIOCCRL, VAL_GPIOCCRH},
33 | {VAL_GPIODODR, VAL_GPIODCRL, VAL_GPIODCRH},
34 | {VAL_GPIOEODR, VAL_GPIOECRL, VAL_GPIOECRH},
35 | };
36 |
37 | /*const PALConfig pal_default_config = // from Kjell's STM32F0x5 setup
38 | {
39 | {VAL_GPIOA_MODER, VAL_GPIOA_OTYPER, VAL_GPIOA_OSPEEDR, VAL_GPIOA_PUPDR,
40 | VAL_GPIOA_ODR, VAL_GPIOA_AFRL, VAL_GPIOA_AFRH},
41 | {VAL_GPIOB_MODER, VAL_GPIOB_OTYPER, VAL_GPIOB_OSPEEDR, VAL_GPIOB_PUPDR,
42 | VAL_GPIOB_ODR, VAL_GPIOB_AFRL, VAL_GPIOB_AFRH},
43 | {VAL_GPIOC_MODER, VAL_GPIOC_OTYPER, VAL_GPIOC_OSPEEDR, VAL_GPIOC_PUPDR,
44 | VAL_GPIOC_ODR, VAL_GPIOC_AFRL, VAL_GPIOC_AFRH},
45 | {VAL_GPIOD_MODER, VAL_GPIOD_OTYPER, VAL_GPIOD_OSPEEDR, VAL_GPIOD_PUPDR,
46 | VAL_GPIOD_ODR, VAL_GPIOD_AFRL, VAL_GPIOD_AFRH},
47 | {VAL_GPIOF_MODER, VAL_GPIOF_OTYPER, VAL_GPIOF_OSPEEDR, VAL_GPIOF_PUPDR,
48 | VAL_GPIOF_ODR, VAL_GPIOF_AFRL, VAL_GPIOF_AFRH}
49 | };*/
50 |
51 | #endif
52 |
53 | /*
54 | * Early initialization code.
55 | * This initialization must be performed just after stack setup and before
56 | * any other initialization.
57 | */
58 | void __early_init(void) {
59 |
60 | stm32_clock_init();
61 | }
62 |
63 | /*
64 | * Board-specific initialization code.
65 | */
66 | void boardInit(void) {
67 | /* Configure PB4 as GPIO. */
68 | AFIO->MAPR |= AFIO_MAPR_SWJ_CFG_NOJNTRST;
69 | /* Make USART1 working */
70 | AFIO->MAPR |= AFIO_MAPR_USART1_REMAP;
71 | /* Remap CH1N, CH2N, CH3N and BKIN to unused pins */
72 | AFIO->MAPR |= AFIO_MAPR_TIM1_REMAP_PARTIALREMAP;
73 | /* Remap CAN1_RX and TX to PB8 and PB9 */
74 | AFIO->MAPR |= AFIO_MAPR_CAN_REMAP_1;
75 | /* Remap USART3 to make PB13 & PB14 available for driver control??? */
76 | //AFIO->MAPR |= AFIO_MAPR_USART3_REMAP_FULLREMAP;
77 | /* Make PA0, PA1, PA2 available for ADC */
78 | //AFIO->MAPR |= AFIO_MAPR_TIM2_REMAP_FULLREMAP; // gruene LED blinkt dann nicht mehr
79 | /* Is PA0... occupied by USART2? */
80 | //AFIO->MAPR |= AFIO_MAPR_USART2_REMAP;
81 | }
82 |
--------------------------------------------------------------------------------
/board/board.c~:
--------------------------------------------------------------------------------
1 | /*
2 | ChibiOS/RT - Copyright (C) 2006-2013 Giovanni Di Sirio
3 |
4 | Licensed under the Apache License, Version 2.0 (the "License");
5 | you may not use this file except in compliance with the License.
6 | You may obtain a copy of the License at
7 |
8 | http://www.apache.org/licenses/LICENSE-2.0
9 |
10 | Unless required by applicable law or agreed to in writing, software
11 | distributed under the License is distributed on an "AS IS" BASIS,
12 | WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 | See the License for the specific language governing permissions and
14 | limitations under the License.
15 | */
16 |
17 | #include "ch.h"
18 | #include "hal.h"
19 |
20 | #include "board.h"
21 |
22 | /**
23 | * @brief PAL setup.
24 | * @details Digital I/O ports static configuration as defined in @p board.h.
25 | * This variable is used by the HAL when initializing the PAL driver.
26 | */
27 | #if HAL_USE_PAL || defined(__DOXYGEN__)
28 | const PALConfig pal_default_config = // from the STM32F1x3 template
29 | {
30 | {VAL_GPIOAODR, VAL_GPIOACRL, VAL_GPIOACRH},
31 | {VAL_GPIOBODR, VAL_GPIOBCRL, VAL_GPIOBCRH},
32 | {VAL_GPIOCODR, VAL_GPIOCCRL, VAL_GPIOCCRH},
33 | {VAL_GPIODODR, VAL_GPIODCRL, VAL_GPIODCRH},
34 | {VAL_GPIOEODR, VAL_GPIOECRL, VAL_GPIOECRH},
35 | };
36 |
37 | /*const PALConfig pal_default_config = // from Kjell's STM32F0x5 setup
38 | {
39 | {VAL_GPIOA_MODER, VAL_GPIOA_OTYPER, VAL_GPIOA_OSPEEDR, VAL_GPIOA_PUPDR,
40 | VAL_GPIOA_ODR, VAL_GPIOA_AFRL, VAL_GPIOA_AFRH},
41 | {VAL_GPIOB_MODER, VAL_GPIOB_OTYPER, VAL_GPIOB_OSPEEDR, VAL_GPIOB_PUPDR,
42 | VAL_GPIOB_ODR, VAL_GPIOB_AFRL, VAL_GPIOB_AFRH},
43 | {VAL_GPIOC_MODER, VAL_GPIOC_OTYPER, VAL_GPIOC_OSPEEDR, VAL_GPIOC_PUPDR,
44 | VAL_GPIOC_ODR, VAL_GPIOC_AFRL, VAL_GPIOC_AFRH},
45 | {VAL_GPIOD_MODER, VAL_GPIOD_OTYPER, VAL_GPIOD_OSPEEDR, VAL_GPIOD_PUPDR,
46 | VAL_GPIOD_ODR, VAL_GPIOD_AFRL, VAL_GPIOD_AFRH},
47 | {VAL_GPIOF_MODER, VAL_GPIOF_OTYPER, VAL_GPIOF_OSPEEDR, VAL_GPIOF_PUPDR,
48 | VAL_GPIOF_ODR, VAL_GPIOF_AFRL, VAL_GPIOF_AFRH}
49 | };*/
50 |
51 | #endif
52 |
53 | /*
54 | * Early initialization code.
55 | * This initialization must be performed just after stack setup and before
56 | * any other initialization.
57 | */
58 | void __early_init(void) {
59 |
60 | stm32_clock_init();
61 | }
62 |
63 | #if HAL_USE_MMC_SPI
64 | /* Board-related functions related to the MMC_SPI driver.*/
65 | bool_t mmc_lld_is_card_inserted(MMCDriver *mmcp) {
66 |
67 | (void)mmcp;
68 | return palReadPad(GPIOC, GPIOC_MMCCP);
69 | }
70 |
71 | bool_t mmc_lld_is_write_protected(MMCDriver *mmcp) {
72 |
73 | (void)mmcp;
74 | return !palReadPad(GPIOC, GPIOC_MMCWP);
75 | }
76 | #endif
77 |
78 | /*
79 | * Board-specific initialization code.
80 | */
81 | void boardInit(void) {
82 | }
83 |
--------------------------------------------------------------------------------
/board/board.mk:
--------------------------------------------------------------------------------
1 | # List of all the board related files.
2 | BOARDSRC = board/board.c
3 |
4 | # Required include directories
5 | BOARDINC = board
6 |
--------------------------------------------------------------------------------
/board/cfg/board.chcfg:
--------------------------------------------------------------------------------
1 |
2 |
3 |
6 |
7 | resources/gencfg/processors/boards/stm32f0xx/templates
8 | ..
9 |
10 | ST STM32F0-Discovery
11 | ST_STM32F0_DISCOVERY
12 |
13 |
15 |
16 |
17 |
25 |
33 |
41 |
49 |
57 |
65 |
73 |
81 |
89 |
97 |
105 |
113 |
121 |
129 |
137 |
145 |
146 |
147 |
155 |
163 |
171 |
179 |
187 |
195 |
203 |
211 |
219 |
227 |
235 |
243 |
251 |
259 |
267 |
275 |
276 |
277 |
285 |
293 |
301 |
309 |
317 |
325 |
333 |
341 |
349 |
357 |
365 |
373 |
381 |
389 |
397 |
405 |
406 |
407 |
415 |
423 |
431 |
439 |
447 |
455 |
463 |
471 |
479 |
487 |
495 |
503 |
511 |
519 |
527 |
535 |
536 |
537 |
545 |
553 |
561 |
569 |
577 |
585 |
593 |
601 |
609 |
617 |
625 |
633 |
641 |
649 |
657 |
665 |
666 |
667 |
668 |
--------------------------------------------------------------------------------
/chconf.h:
--------------------------------------------------------------------------------
1 | /*
2 | ChibiOS/RT - Copyright (C) 2006-2013 Giovanni Di Sirio
3 |
4 | Licensed under the Apache License, Version 2.0 (the "License");
5 | you may not use this file except in compliance with the License.
6 | You may obtain a copy of the License at
7 |
8 | http://www.apache.org/licenses/LICENSE-2.0
9 |
10 | Unless required by applicable law or agreed to in writing, software
11 | distributed under the License is distributed on an "AS IS" BASIS,
12 | WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 | See the License for the specific language governing permissions and
14 | limitations under the License.
15 | */
16 |
17 | /**
18 | * @file templates/chconf.h
19 | * @brief Configuration file template.
20 | * @details A copy of this file must be placed in each project directory, it
21 | * contains the application specific kernel settings.
22 | *
23 | * @addtogroup config
24 | * @details Kernel related settings and hooks.
25 | * @{
26 | */
27 |
28 | #ifndef _CHCONF_H_
29 | #define _CHCONF_H_
30 |
31 | /*===========================================================================*/
32 | /**
33 | * @name System timers settings
34 | * @{
35 | */
36 | /*===========================================================================*/
37 |
38 | /**
39 | * @brief System time counter resolution.
40 | * @note Allowed values are 16 or 32 bits.
41 | */
42 | #define CH_CFG_ST_RESOLUTION 16 // 16
43 |
44 | /**
45 | * @brief System tick frequency.
46 | * @details Frequency of the system timer that drives the system ticks. This
47 | * setting also defines the system tick time unit.
48 | */
49 | #define CH_CFG_ST_FREQUENCY 1000//10000//100000//20000
50 |
51 | /**
52 | * @brief Time delta constant for the tick-less mode.
53 | * @note If this value is zero then the system uses the classic
54 | * periodic tick. This value represents the minimum number
55 | * of ticks that is safe to specify in a timeout directive.
56 | * The value one is not valid, timeouts are rounded up to
57 | * this value.
58 | */
59 | #define CH_CFG_ST_TIMEDELTA 0//32//2 // Tickless mode --> random trouble!!!
60 |
61 | /** @} */
62 |
63 | /*===========================================================================*/
64 | /**
65 | * @name Kernel parameters and options
66 | * @{
67 | */
68 | /*===========================================================================*/
69 |
70 | /**
71 | * @brief Round robin interval.
72 | * @details This constant is the number of system ticks allowed for the
73 | * threads before preemption occurs. Setting this value to zero
74 | * disables the preemption for threads with equal priority and the
75 | * round robin becomes cooperative. Note that higher priority
76 | * threads can still preempt, the kernel is always preemptive.
77 | * @note Disabling the round robin preemption makes the kernel more compact
78 | * and generally faster.
79 | * @note The round robin preemption is not supported in tickless mode and
80 | * must be set to zero in that case.
81 | */
82 | #define CH_CFG_TIME_QUANTUM 0
83 |
84 | /**
85 | * @brief Managed RAM size.
86 | * @details Size of the RAM area to be managed by the OS. If set to zero
87 | * then the whole available RAM is used. The core memory is made
88 | * available to the heap allocator and/or can be used directly through
89 | * the simplified core memory allocator.
90 | *
91 | * @note In order to let the OS manage the whole RAM the linker script must
92 | * provide the @p __heap_base__ and @p __heap_end__ symbols.
93 | * @note Requires @p CH_CFG_USE_MEMCORE.
94 | */
95 | #define CH_CFG_MEMCORE_SIZE 0
96 |
97 | /**
98 | * @brief Idle thread automatic spawn suppression.
99 | * @details When this option is activated the function @p chSysInit()
100 | * does not spawn the idle thread. The application @p main()
101 | * function becomes the idle thread and must implement an
102 | * infinite loop. */
103 | #define CH_CFG_NO_IDLE_THREAD FALSE
104 |
105 | /** @} */
106 |
107 | /*===========================================================================*/
108 | /**
109 | * @name Performance options
110 | * @{
111 | */
112 | /*===========================================================================*/
113 |
114 | /**
115 | * @brief OS optimization.
116 | * @details If enabled then time efficient rather than space efficient code
117 | * is used when two possible implementations exist.
118 | *
119 | * @note This is not related to the compiler optimization options.
120 | * @note The default is @p TRUE.
121 | */
122 | #define CH_CFG_OPTIMIZE_SPEED TRUE
123 |
124 | /** @} */
125 |
126 | /*===========================================================================*/
127 | /**
128 | * @name Subsystem options
129 | * @{
130 | */
131 | /*===========================================================================*/
132 |
133 | /**
134 | * @brief Time Measurement APIs.
135 | * @details If enabled then the time measurement APIs are included in
136 | * the kernel.
137 | *
138 | * @note The default is @p TRUE.
139 | */
140 | #define CH_CFG_USE_TM TRUE
141 |
142 | /**
143 | * @brief Threads registry APIs.
144 | * @details If enabled then the registry APIs are included in the kernel.
145 | *
146 | * @note The default is @p TRUE.
147 | */
148 | #define CH_CFG_USE_REGISTRY TRUE
149 |
150 | /**
151 | * @brief Threads synchronization APIs.
152 | * @details If enabled then the @p chThdWait() function is included in
153 | * the kernel.
154 | *
155 | * @note The default is @p TRUE.
156 | */
157 | #define CH_CFG_USE_WAITEXIT TRUE
158 |
159 | /**
160 | * @brief Semaphores APIs.
161 | * @details If enabled then the Semaphores APIs are included in the kernel.
162 | *
163 | * @note The default is @p TRUE.
164 | */
165 | #define CH_CFG_USE_SEMAPHORES TRUE
166 |
167 | /**
168 | * @brief Semaphores queuing mode.
169 | * @details If enabled then the threads are enqueued on semaphores by
170 | * priority rather than in FIFO order.
171 | *
172 | * @note The default is @p FALSE. Enable this if you have special
173 | * requirements.
174 | * @note Requires @p CH_CFG_USE_SEMAPHORES.
175 | */
176 | #define CH_CFG_USE_SEMAPHORES_PRIORITY FALSE
177 |
178 | /**
179 | * @brief Mutexes APIs.
180 | * @details If enabled then the mutexes APIs are included in the kernel.
181 | *
182 | * @note The default is @p TRUE.
183 | */
184 | #define CH_CFG_USE_MUTEXES TRUE
185 |
186 | /**
187 | * @brief Enables recursive behavior on mutexes.
188 | * @note Recursive mutexes are heavier and have an increased
189 | * memory footprint.
190 | *
191 | * @note The default is @p FALSE.
192 | * @note Requires @p CH_CFG_USE_MUTEXES.
193 | */
194 | #define CH_CFG_USE_MUTEXES_RECURSIVE FALSE
195 |
196 | /**
197 | * @brief Conditional Variables APIs.
198 | * @details If enabled then the conditional variables APIs are included
199 | * in the kernel.
200 | *
201 | * @note The default is @p TRUE.
202 | * @note Requires @p CH_CFG_USE_MUTEXES.
203 | */
204 | #define CH_CFG_USE_CONDVARS TRUE
205 |
206 | /**
207 | * @brief Conditional Variables APIs with timeout.
208 | * @details If enabled then the conditional variables APIs with timeout
209 | * specification are included in the kernel.
210 | *
211 | * @note The default is @p TRUE.
212 | * @note Requires @p CH_CFG_USE_CONDVARS.
213 | */
214 | #define CH_CFG_USE_CONDVARS_TIMEOUT TRUE
215 |
216 | /**
217 | * @brief Events Flags APIs.
218 | * @details If enabled then the event flags APIs are included in the kernel.
219 | *
220 | * @note The default is @p TRUE.
221 | */
222 | #define CH_CFG_USE_EVENTS TRUE
223 |
224 | /**
225 | * @brief Events Flags APIs with timeout.
226 | * @details If enabled then the events APIs with timeout specification
227 | * are included in the kernel.
228 | *
229 | * @note The default is @p TRUE.
230 | * @note Requires @p CH_CFG_USE_EVENTS.
231 | */
232 | #define CH_CFG_USE_EVENTS_TIMEOUT TRUE
233 |
234 | /**
235 | * @brief Synchronous Messages APIs.
236 | * @details If enabled then the synchronous messages APIs are included
237 | * in the kernel.
238 | *
239 | * @note The default is @p TRUE.
240 | */
241 | #define CH_CFG_USE_MESSAGES TRUE
242 |
243 | /**
244 | * @brief Synchronous Messages queuing mode.
245 | * @details If enabled then messages are served by priority rather than in
246 | * FIFO order.
247 | *
248 | * @note The default is @p FALSE. Enable this if you have special
249 | * requirements.
250 | * @note Requires @p CH_CFG_USE_MESSAGES.
251 | */
252 | #define CH_CFG_USE_MESSAGES_PRIORITY FALSE
253 |
254 | /**
255 | * @brief Mailboxes APIs.
256 | * @details If enabled then the asynchronous messages (mailboxes) APIs are
257 | * included in the kernel.
258 | *
259 | * @note The default is @p TRUE.
260 | * @note Requires @p CH_CFG_USE_SEMAPHORES.
261 | */
262 | #define CH_CFG_USE_MAILBOXES TRUE
263 |
264 | /**
265 | * @brief I/O Queues APIs.
266 | * @details If enabled then the I/O queues APIs are included in the kernel.
267 | *
268 | * @note The default is @p TRUE.
269 | */
270 | #define CH_CFG_USE_QUEUES TRUE
271 |
272 | /**
273 | * @brief Core Memory Manager APIs.
274 | * @details If enabled then the core memory manager APIs are included
275 | * in the kernel.
276 | *
277 | * @note The default is @p TRUE.
278 | */
279 | #define CH_CFG_USE_MEMCORE TRUE
280 |
281 | /**
282 | * @brief Heap Allocator APIs.
283 | * @details If enabled then the memory heap allocator APIs are included
284 | * in the kernel.
285 | *
286 | * @note The default is @p TRUE.
287 | * @note Requires @p CH_CFG_USE_MEMCORE and either @p CH_CFG_USE_MUTEXES or
288 | * @p CH_CFG_USE_SEMAPHORES.
289 | * @note Mutexes are recommended.
290 | */
291 | #define CH_CFG_USE_HEAP TRUE
292 |
293 | /**
294 | * @brief Memory Pools Allocator APIs.
295 | * @details If enabled then the memory pools allocator APIs are included
296 | * in the kernel.
297 | *
298 | * @note The default is @p TRUE.
299 | */
300 | #define CH_CFG_USE_MEMPOOLS TRUE
301 |
302 | /**
303 | * @brief Dynamic Threads APIs.
304 | * @details If enabled then the dynamic threads creation APIs are included
305 | * in the kernel.
306 | *
307 | * @note The default is @p TRUE.
308 | * @note Requires @p CH_CFG_USE_WAITEXIT.
309 | * @note Requires @p CH_CFG_USE_HEAP and/or @p CH_CFG_USE_MEMPOOLS.
310 | */
311 | #define CH_CFG_USE_DYNAMIC TRUE
312 |
313 | /** @} */
314 |
315 | /*===========================================================================*/
316 | /**
317 | * @name Debug options
318 | * @{
319 | */
320 | /*===========================================================================*/
321 |
322 | /**
323 | * @brief Debug option, kernel statistics.
324 | *
325 | * @note The default is @p FALSE.
326 | */
327 | #define CH_DBG_STATISTICS FALSE
328 |
329 | /**
330 | * @brief Debug option, system state check.
331 | * @details If enabled the correct call protocol for system APIs is checked
332 | * at runtime.
333 | *
334 | * @note The default is @p FALSE.
335 | */
336 | #define CH_DBG_SYSTEM_STATE_CHECK FALSE
337 |
338 | /**
339 | * @brief Debug option, parameters checks.
340 | * @details If enabled then the checks on the API functions input
341 | * parameters are activated.
342 | *
343 | * @note The default is @p FALSE.
344 | */
345 | #define CH_DBG_ENABLE_CHECKS TRUE
346 |
347 | /**
348 | * @brief Debug option, consistency checks.
349 | * @details If enabled then all the assertions in the kernel code are
350 | * activated. This includes consistency checks inside the kernel,
351 | * runtime anomalies and port-defined checks.
352 | *
353 | * @note The default is @p FALSE.
354 | */
355 | #define CH_DBG_ENABLE_ASSERTS TRUE
356 |
357 | /**
358 | * @brief Debug option, trace buffer.
359 | * @details If enabled then the context switch circular trace buffer is
360 | * activated.
361 | *
362 | * @note The default is @p FALSE.
363 | */
364 | #define CH_DBG_ENABLE_TRACE TRUE
365 |
366 | /**
367 | * @brief Debug option, stack checks.
368 | * @details If enabled then a runtime stack check is performed.
369 | *
370 | * @note The default is @p FALSE.
371 | * @note The stack check is performed in a architecture/port dependent way.
372 | * It may not be implemented or some ports.
373 | * @note The default failure mode is to halt the system with the global
374 | * @p panic_msg variable set to @p NULL.
375 | */
376 | #define CH_DBG_ENABLE_STACK_CHECK TRUE
377 |
378 | /**
379 | * @brief Debug option, stacks initialization.
380 | * @details If enabled then the threads working area is filled with a byte
381 | * value when a thread is created. This can be useful for the
382 | * runtime measurement of the used stack.
383 | *
384 | * @note The default is @p FALSE.
385 | */
386 | #define CH_DBG_FILL_THREADS FALSE
387 |
388 | /**
389 | * @brief Debug option, threads profiling.
390 | * @details If enabled then a field is added to the @p thread_t structure that
391 | * counts the system ticks occurred while executing the thread.
392 | *
393 | * @note The default is @p FALSE.
394 | * @note This debug option is not currently compatible with the
395 | * tickless mode.
396 | */
397 | #define CH_DBG_THREADS_PROFILING FALSE
398 |
399 | /** @} */
400 |
401 | /*===========================================================================*/
402 | /**
403 | * @name Kernel hooks
404 | * @{
405 | */
406 | /*===========================================================================*/
407 |
408 | /**
409 | * @brief Threads descriptor structure extension.
410 | * @details User fields added to the end of the @p thread_t structure.
411 | */
412 | #define CH_CFG_THREAD_EXTRA_FIELDS \
413 | /* Add threads custom fields here.*/
414 |
415 | /**
416 | * @brief Threads initialization hook.
417 | * @details User initialization code added to the @p chThdInit() API.
418 | *
419 | * @note It is invoked from within @p chThdInit() and implicitly from all
420 | * the threads creation APIs.
421 | */
422 | #define CH_CFG_THREAD_INIT_HOOK(tp) { \
423 | /* Add threads initialization code here.*/ \
424 | }
425 |
426 | /**
427 | * @brief Threads finalization hook.
428 | * @details User finalization code added to the @p chThdExit() API.
429 | *
430 | * @note It is inserted into lock zone.
431 | * @note It is also invoked when the threads simply return in order to
432 | * terminate.
433 | */
434 | #define CH_CFG_THREAD_EXIT_HOOK(tp) { \
435 | /* Add threads finalization code here.*/ \
436 | }
437 |
438 | /**
439 | * @brief Context switch hook.
440 | * @details This hook is invoked just before switching between threads.
441 | */
442 | #define CH_CFG_CONTEXT_SWITCH_HOOK(ntp, otp) { \
443 | /* System halt code here.*/ \
444 | }
445 |
446 | /**
447 | * @brief Idle thread enter hook.
448 | * @note This hook is invoked within a critical zone, no OS functions
449 | * should be invoked from here.
450 | * @note This macro can be used to activate a power saving mode.
451 | */
452 | #define CH_CFG_IDLE_ENTER_HOOK() { \
453 | }
454 |
455 | /**
456 | * @brief Idle thread leave hook.
457 | * @note This hook is invoked within a critical zone, no OS functions
458 | * should be invoked from here.
459 | * @note This macro can be used to deactivate a power saving mode.
460 | */
461 | #define CH_CFG_IDLE_LEAVE_HOOK() { \
462 | }
463 |
464 | /**
465 | * @brief Idle Loop hook.
466 | * @details This hook is continuously invoked by the idle thread loop.
467 | */
468 | #define CH_CFG_IDLE_LOOP_HOOK() { \
469 | /* Idle loop code here.*/ \
470 | }
471 |
472 | /**
473 | * @brief System tick event hook.
474 | * @details This hook is invoked in the system tick handler immediately
475 | * after processing the virtual timers queue.
476 | */
477 | #define CH_CFG_SYSTEM_TICK_HOOK() { \
478 | /* System tick event code here.*/ \
479 | }
480 |
481 | /**
482 | * @brief System halt hook.
483 | * @details This hook is invoked in case to a system halting error before
484 | * the system is halted.
485 | */
486 | #define CH_CFG_SYSTEM_HALT_HOOK(reason) { \
487 | /* System halt code here.*/ \
488 | }
489 |
490 | /** @} */
491 |
492 | /*===========================================================================*/
493 | /* Port-specific settings (override port settings defaulted in chcore.h). */
494 | /*===========================================================================*/
495 |
496 | #endif /* _CHCONF_H_ */
497 |
498 | /** @} */
499 |
--------------------------------------------------------------------------------
/chibios-patch/adc_exttrig.patch:
--------------------------------------------------------------------------------
1 | diff -rupN /home/joerg/repos/ChibiOS/os/hal/ports/STM32/STM32F1xx/adc_lld.c ../chibios/os/hal/ports/STM32/STM32F1xx/adc_lld.c
2 | --- /home/joerg/repos/ChibiOS/os/hal/ports/STM32/STM32F1xx/adc_lld.c 2015-02-08 18:34:51.671770178 +0100
3 | +++ ../chibios/os/hal/ports/STM32/STM32F1xx/adc_lld.c 2015-02-08 18:41:37.655784138 +0100
4 | @@ -211,8 +211,8 @@ void adc_lld_start_conversion(ADCDriver
5 | adcp->adc->SQR2 = grpp->sqr2;
6 | adcp->adc->SQR3 = grpp->sqr3;
7 |
8 | - /* ADC start by writing ADC_CR2_ADON a second time.*/
9 | - adcp->adc->CR2 = cr2;
10 | + /* ADC start by writing ADC_CR2_ADON a second time - if EXTTRIG is NOT selected */
11 | + if ((cr2 & (ADC_CR2_EXTTRIG | ADC_CR2_JEXTTRIG)) == 0) adcp->adc->CR2 = cr2;
12 | }
13 |
14 | /**
15 |
--------------------------------------------------------------------------------
/config/config.mk:
--------------------------------------------------------------------------------
1 | # List of all the board related files.
2 | CONFIGSRC = src/config/board.c
3 |
4 | # Required include directories
5 | CONFIGINC = src/config
6 |
--------------------------------------------------------------------------------
/halconf.h:
--------------------------------------------------------------------------------
1 | /*
2 | ChibiOS/RT - Copyright (C) 2006-2013 Giovanni Di Sirio
3 |
4 | Licensed under the Apache License, Version 2.0 (the "License");
5 | you may not use this file except in compliance with the License.
6 | You may obtain a copy of the License at
7 |
8 | http://www.apache.org/licenses/LICENSE-2.0
9 |
10 | Unless required by applicable law or agreed to in writing, software
11 | distributed under the License is distributed on an "AS IS" BASIS,
12 | WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 | See the License for the specific language governing permissions and
14 | limitations under the License.
15 | */
16 |
17 | /**
18 | * @file templates/halconf.h
19 | * @brief HAL configuration header.
20 | * @details HAL configuration file, this file allows to enable or disable the
21 | * various device drivers from your application. You may also use
22 | * this file in order to override the device drivers default settings.
23 | *
24 | * @addtogroup HAL_CONF
25 | * @{
26 | */
27 |
28 | #ifndef _HALCONF_H_
29 | #define _HALCONF_H_
30 |
31 | #include "mcuconf.h"
32 |
33 | /**
34 | * @brief Enables the PAL subsystem.
35 | */
36 | #if !defined(HAL_USE_PAL) || defined(__DOXYGEN__)
37 | #define HAL_USE_PAL TRUE
38 | #endif
39 |
40 | /**
41 | * @brief Enables the ADC subsystem.
42 | */
43 | #if !defined(HAL_USE_ADC) || defined(__DOXYGEN__)
44 | #define HAL_USE_ADC TRUE
45 | #endif
46 |
47 | /**
48 | * @brief Enables the CAN subsystem.
49 | */
50 | #if !defined(HAL_USE_CAN) || defined(__DOXYGEN__)
51 | #define HAL_USE_CAN TRUE
52 | #endif
53 |
54 | /**
55 | * @brief Enables the DAC subsystem.
56 | */
57 | #if !defined(HAL_USE_DAC) || defined(__DOXYGEN__)
58 | #define HAL_USE_DAC FALSE
59 | #endif
60 |
61 | /**
62 | * @brief Enables the EXT subsystem.
63 | */
64 | #if !defined(HAL_USE_EXT) || defined(__DOXYGEN__)
65 | #define HAL_USE_EXT FALSE
66 | #endif
67 |
68 | /**
69 | * @brief Enables the GPT subsystem.
70 | */
71 | #if !defined(HAL_USE_GPT) || defined(__DOXYGEN__)
72 | #define HAL_USE_GPT TRUE
73 | #endif
74 |
75 | /**
76 | * @brief Enables the I2C subsystem.
77 | */
78 | #if !defined(HAL_USE_I2C) || defined(__DOXYGEN__)
79 | #define HAL_USE_I2C FALSE
80 | #endif
81 |
82 | /**
83 | * @brief Enables the I2S subsystem.
84 | */
85 | #if !defined(HAL_USE_I2S) || defined(__DOXYGEN__)
86 | #define HAL_USE_I2S FALSE
87 | #endif
88 |
89 | /**
90 | * @brief Enables the ICU subsystem.
91 | */
92 | #if !defined(HAL_USE_ICU) || defined(__DOXYGEN__)
93 | #define HAL_USE_ICU FALSE
94 | #endif
95 |
96 | /**
97 | * @brief Enables the MAC subsystem.
98 | */
99 | #if !defined(HAL_USE_MAC) || defined(__DOXYGEN__)
100 | #define HAL_USE_MAC FALSE
101 | #endif
102 |
103 | /**
104 | * @brief Enables the MMC_SPI subsystem.
105 | */
106 | #if !defined(HAL_USE_MMC_SPI) || defined(__DOXYGEN__)
107 | #define HAL_USE_MMC_SPI FALSE
108 | #endif
109 |
110 | /**
111 | * @brief Enables the PWM subsystem.
112 | */
113 | #if !defined(HAL_USE_PWM) || defined(__DOXYGEN__)
114 | #define HAL_USE_PWM TRUE
115 | #endif
116 |
117 | /**
118 | * @brief Enables the RTC subsystem.
119 | */
120 | #if !defined(HAL_USE_RTC) || defined(__DOXYGEN__)
121 | #define HAL_USE_RTC FALSE
122 | #endif
123 |
124 | /**
125 | * @brief Enables the SDC subsystem.
126 | */
127 | #if !defined(HAL_USE_SDC) || defined(__DOXYGEN__)
128 | #define HAL_USE_SDC FALSE
129 | #endif
130 |
131 | /**
132 | * @brief Enables the SERIAL subsystem.
133 | */
134 | #if !defined(HAL_USE_SERIAL) || defined(__DOXYGEN__)
135 | #define HAL_USE_SERIAL FALSE
136 | #endif
137 |
138 | /**
139 | * @brief Enables the SERIAL over USB subsystem.
140 | */
141 | #if !defined(HAL_USE_SERIAL_USB) || defined(__DOXYGEN__)
142 | #define HAL_USE_SERIAL_USB FALSE
143 | #endif
144 |
145 | /**
146 | * @brief Enables the SPI subsystem.
147 | */
148 | #if !defined(HAL_USE_SPI) || defined(__DOXYGEN__)
149 | #define HAL_USE_SPI FALSE
150 | #endif
151 |
152 | /**
153 | * @brief Enables the UART subsystem.
154 | */
155 | #if !defined(HAL_USE_UART) || defined(__DOXYGEN__)
156 | #define HAL_USE_UART TRUE
157 | #endif
158 |
159 | /**
160 | * @brief Enables the USB subsystem.
161 | */
162 | #if !defined(HAL_USE_USB) || defined(__DOXYGEN__)
163 | #define HAL_USE_USB FALSE
164 | #endif
165 |
166 | /*===========================================================================*/
167 | /* ADC driver related settings. */
168 | /*===========================================================================*/
169 |
170 | /**
171 | * @brief Enables synchronous APIs.
172 | * @note Disabling this option saves both code and data space.
173 | */
174 | #if !defined(ADC_USE_WAIT) || defined(__DOXYGEN__)
175 | #define ADC_USE_WAIT TRUE
176 | #endif
177 |
178 | /**
179 | * @brief Enables the @p adcAcquireBus() and @p adcReleaseBus() APIs.
180 | * @note Disabling this option saves both code and data space.
181 | */
182 | #if !defined(ADC_USE_MUTUAL_EXCLUSION) || defined(__DOXYGEN__)
183 | #define ADC_USE_MUTUAL_EXCLUSION TRUE
184 | #endif
185 |
186 | /*===========================================================================*/
187 | /* CAN driver related settings. */
188 | /*===========================================================================*/
189 |
190 | /**
191 | * @brief Sleep mode related APIs inclusion switch.
192 | */
193 | #if !defined(CAN_USE_SLEEP_MODE) || defined(__DOXYGEN__)
194 | #define CAN_USE_SLEEP_MODE TRUE
195 | #endif
196 |
197 | /*===========================================================================*/
198 | /* I2C driver related settings. */
199 | /*===========================================================================*/
200 |
201 | /**
202 | * @brief Enables the mutual exclusion APIs on the I2C bus.
203 | */
204 | #if !defined(I2C_USE_MUTUAL_EXCLUSION) || defined(__DOXYGEN__)
205 | #define I2C_USE_MUTUAL_EXCLUSION TRUE
206 | #endif
207 |
208 | /*===========================================================================*/
209 | /* MAC driver related settings. */
210 | /*===========================================================================*/
211 |
212 | /**
213 | * @brief Enables an event sources for incoming packets.
214 | */
215 | #if !defined(MAC_USE_ZERO_COPY) || defined(__DOXYGEN__)
216 | #define MAC_USE_ZERO_COPY FALSE
217 | #endif
218 |
219 | /**
220 | * @brief Enables an event sources for incoming packets.
221 | */
222 | #if !defined(MAC_USE_EVENTS) || defined(__DOXYGEN__)
223 | #define MAC_USE_EVENTS TRUE
224 | #endif
225 |
226 | /*===========================================================================*/
227 | /* MMC_SPI driver related settings. */
228 | /*===========================================================================*/
229 |
230 | /**
231 | * @brief Delays insertions.
232 | * @details If enabled this options inserts delays into the MMC waiting
233 | * routines releasing some extra CPU time for the threads with
234 | * lower priority, this may slow down the driver a bit however.
235 | * This option is recommended also if the SPI driver does not
236 | * use a DMA channel and heavily loads the CPU.
237 | */
238 | #if !defined(MMC_NICE_WAITING) || defined(__DOXYGEN__)
239 | #define MMC_NICE_WAITING TRUE
240 | #endif
241 |
242 | /*===========================================================================*/
243 | /* SDC driver related settings. */
244 | /*===========================================================================*/
245 |
246 | /**
247 | * @brief Number of initialization attempts before rejecting the card.
248 | * @note Attempts are performed at 10mS intervals.
249 | */
250 | #if !defined(SDC_INIT_RETRY) || defined(__DOXYGEN__)
251 | #define SDC_INIT_RETRY 100
252 | #endif
253 |
254 | /**
255 | * @brief Include support for MMC cards.
256 | * @note MMC support is not yet implemented so this option must be kept
257 | * at @p FALSE.
258 | */
259 | #if !defined(SDC_MMC_SUPPORT) || defined(__DOXYGEN__)
260 | #define SDC_MMC_SUPPORT FALSE
261 | #endif
262 |
263 | /**
264 | * @brief Delays insertions.
265 | * @details If enabled this options inserts delays into the MMC waiting
266 | * routines releasing some extra CPU time for the threads with
267 | * lower priority, this may slow down the driver a bit however.
268 | */
269 | #if !defined(SDC_NICE_WAITING) || defined(__DOXYGEN__)
270 | #define SDC_NICE_WAITING TRUE
271 | #endif
272 |
273 | /*===========================================================================*/
274 | /* SERIAL driver related settings. */
275 | /*===========================================================================*/
276 |
277 | /**
278 | * @brief Default bit rate.
279 | * @details Configuration parameter, this is the baud rate selected for the
280 | * default configuration.
281 | */
282 | #if !defined(SERIAL_DEFAULT_BITRATE) || defined(__DOXYGEN__)
283 | #define SERIAL_DEFAULT_BITRATE 38400
284 | #endif
285 |
286 | /**
287 | * @brief Serial buffers size.
288 | * @details Configuration parameter, you can change the depth of the queue
289 | * buffers depending on the requirements of your application.
290 | * @note The default is 64 bytes for both the transmission and receive
291 | * buffers.
292 | */
293 | #if !defined(SERIAL_BUFFERS_SIZE) || defined(__DOXYGEN__)
294 | #define SERIAL_BUFFERS_SIZE 16
295 | #endif
296 |
297 | /*===========================================================================*/
298 | /* SPI driver related settings. */
299 | /*===========================================================================*/
300 |
301 | /**
302 | * @brief Enables synchronous APIs.
303 | * @note Disabling this option saves both code and data space.
304 | */
305 | #if !defined(SPI_USE_WAIT) || defined(__DOXYGEN__)
306 | #define SPI_USE_WAIT TRUE
307 | #endif
308 |
309 | /**
310 | * @brief Enables the @p spiAcquireBus() and @p spiReleaseBus() APIs.
311 | * @note Disabling this option saves both code and data space.
312 | */
313 | #if !defined(SPI_USE_MUTUAL_EXCLUSION) || defined(__DOXYGEN__)
314 | #define SPI_USE_MUTUAL_EXCLUSION TRUE
315 | #endif
316 |
317 | #endif /* _HALCONF_H_ */
318 |
319 | /** @} */
320 |
--------------------------------------------------------------------------------
/mcuconf.h:
--------------------------------------------------------------------------------
1 | /*
2 | ChibiOS/RT - Copyright (C) 2006-2013 Giovanni Di Sirio
3 |
4 | Licensed under the Apache License, Version 2.0 (the "License");
5 | you may not use this file except in compliance with the License.
6 | You may obtain a copy of the License at
7 |
8 | http://www.apache.org/licenses/LICENSE-2.0
9 |
10 | Unless required by applicable law or agreed to in writing, software
11 | distributed under the License is distributed on an "AS IS" BASIS,
12 | WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 | See the License for the specific language governing permissions and
14 | limitations under the License.
15 | */
16 |
17 |
18 | #ifndef _MCUCONF_H_
19 | #define _MCUCONF_H_
20 |
21 | #define STM32F103_MCUCONF
22 |
23 | /*
24 | * STM32F103 drivers configuration.
25 | * The following settings override the default settings present in
26 | * the various device driver implementation headers.
27 | * Note that the settings for each driver only have effect if the whole
28 | * driver is enabled in halconf.h.
29 | *
30 | * IRQ priorities:
31 | * 15...0 Lowest...Highest.
32 | *
33 | * DMA priorities:
34 | * 0...3 Lowest...Highest.
35 | */
36 |
37 | /*
38 | * HAL driver system settings.
39 | */
40 | #define STM32_NO_INIT FALSE
41 | #define STM32_HSI_ENABLED TRUE // 8MHz HSI RC -> 4MHz PLL Source
42 | #define STM32_LSI_ENABLED FALSE
43 | #define STM32_HSE_ENABLED FALSE
44 | #define STM32_LSE_ENABLED FALSE
45 | #define STM32_SW STM32_SW_PLL
46 | #define STM32_PLLSRC STM32_PLLSRC_HSI //STM32_PLLSRC_HSE
47 | #define STM32_PLLXTPRE STM32_PLLXTPRE_DIV1
48 | #define STM32_PLLMUL_VALUE 14 // -> SYSCLK 56MHz; 72MHz ist only possible with external oscillator (HSE); 56MHz chosen to be able to have 14MHz ADC clock
49 | #define STM32_HPRE STM32_HPRE_DIV1 // AHB Prescaler: /1
50 | #define STM32_PPRE1 STM32_PPRE1_DIV2 // APB 1 Prescaler: /2 -> APB1 frequency 28MHz; 36MHz max; to TIM2-7,12-14 etc
51 | #define STM32_PPRE2 STM32_PPRE2_DIV1 // APB 2 Prescaler: /1 -> APB2 frequency 56MHz; 72MHz max (only with HSE); to TIM1,8-11, ADC prescaler etc
52 | #define STM32_ADCPRE STM32_ADCPRE_DIV4 // ADC Prescaler: /4 -> ADC clock frequency 14MHZ; 14MHz max
53 | #define STM32_USB_CLOCK_REQUIRED TRUE
54 | #define STM32_USBPRE STM32_USBPRE_DIV1P5
55 | #define STM32_MCOSEL STM32_MCOSEL_NOCLOCK
56 | #define STM32_RTCSEL STM32_RTCSEL_NOCLOCK //STM32_RTCSEL_LSI //STM32_RTCSEL_HSEDIV
57 | #define STM32_PVD_ENABLE FALSE
58 | #define STM32_PLS STM32_PLS_LEV0
59 |
60 | /*
61 | * ADC driver system settings.
62 | */
63 | #define STM32_ADC_USE_ADC1 TRUE
64 | #define STM32_ADC_ADC1_DMA_PRIORITY 2
65 | #define STM32_ADC_ADC1_IRQ_PRIORITY 5//6
66 |
67 | /*
68 | * CAN driver system settings.
69 | */
70 | #define STM32_CAN_USE_CAN1 TRUE
71 | #define STM32_CAN_CAN1_IRQ_PRIORITY 11
72 |
73 | /*
74 | * EXT driver system settings.
75 | */
76 | #define STM32_EXT_EXTI0_IRQ_PRIORITY 6
77 | #define STM32_EXT_EXTI1_IRQ_PRIORITY 6
78 | #define STM32_EXT_EXTI2_IRQ_PRIORITY 6
79 | #define STM32_EXT_EXTI3_IRQ_PRIORITY 6
80 | #define STM32_EXT_EXTI4_IRQ_PRIORITY 6
81 | #define STM32_EXT_EXTI5_9_IRQ_PRIORITY 6
82 | #define STM32_EXT_EXTI10_15_IRQ_PRIORITY 6
83 | #define STM32_EXT_EXTI16_IRQ_PRIORITY 6
84 | #define STM32_EXT_EXTI17_IRQ_PRIORITY 6
85 | #define STM32_EXT_EXTI18_IRQ_PRIORITY 6
86 | #define STM32_EXT_EXTI19_IRQ_PRIORITY 6
87 |
88 | /*
89 | * GPT driver system settings.
90 | */
91 | #define STM32_GPT_USE_TIM1 FALSE
92 | #define STM32_GPT_USE_TIM2 FALSE
93 | #define STM32_GPT_USE_TIM3 TRUE
94 | #define STM32_GPT_USE_TIM4 TRUE
95 | #define STM32_GPT_USE_TIM5 FALSE
96 | #define STM32_GPT_USE_TIM8 FALSE
97 | #define STM32_GPT_TIM1_IRQ_PRIORITY 7
98 | #define STM32_GPT_TIM2_IRQ_PRIORITY 7
99 | #define STM32_GPT_TIM3_IRQ_PRIORITY 8
100 | #define STM32_GPT_TIM4_IRQ_PRIORITY 7
101 | #define STM32_GPT_TIM5_IRQ_PRIORITY 7
102 | #define STM32_GPT_TIM8_IRQ_PRIORITY 7
103 |
104 | /*
105 | * I2C driver system settings.
106 | */
107 | #define STM32_I2C_USE_I2C1 FALSE
108 | #define STM32_I2C_USE_I2C2 FALSE
109 | #define STM32_I2C_BUSY_TIMEOUT 50
110 | #define STM32_I2C_I2C1_IRQ_PRIORITY 6//5
111 | #define STM32_I2C_I2C2_IRQ_PRIORITY 6//5
112 | #define STM32_I2C_I2C1_DMA_PRIORITY 3
113 | #define STM32_I2C_I2C2_DMA_PRIORITY 3
114 | #define STM32_I2C_DMA_ERROR_HOOK(i2cp) osalSysHalt("DMA failure")
115 |
116 | /*
117 | * ICU driver system settings.
118 | */
119 | #define STM32_ICU_USE_TIM1 FALSE
120 | #define STM32_ICU_USE_TIM2 FALSE
121 | #define STM32_ICU_USE_TIM3 FALSE
122 | #define STM32_ICU_USE_TIM4 FALSE
123 | #define STM32_ICU_USE_TIM5 FALSE
124 | #define STM32_ICU_USE_TIM8 FALSE
125 | #define STM32_ICU_TIM1_IRQ_PRIORITY 7
126 | #define STM32_ICU_TIM2_IRQ_PRIORITY 7
127 | #define STM32_ICU_TIM3_IRQ_PRIORITY 7
128 | #define STM32_ICU_TIM4_IRQ_PRIORITY 7
129 | #define STM32_ICU_TIM5_IRQ_PRIORITY 7
130 | #define STM32_ICU_TIM8_IRQ_PRIORITY 7
131 |
132 | /*
133 | * PWM driver system settings.
134 | */
135 | #define STM32_PWM_USE_ADVANCED FALSE
136 | #define STM32_PWM_USE_TIM1 TRUE
137 | #define STM32_PWM_USE_TIM2 FALSE
138 | #define STM32_PWM_USE_TIM3 FALSE
139 | #define STM32_PWM_USE_TIM4 FALSE
140 | #define STM32_PWM_USE_TIM5 FALSE
141 | #define STM32_PWM_USE_TIM8 FALSE
142 | #define STM32_PWM_TIM1_IRQ_PRIORITY 7
143 | #define STM32_PWM_TIM2_IRQ_PRIORITY 7
144 | #define STM32_PWM_TIM3_IRQ_PRIORITY 7
145 | #define STM32_PWM_TIM4_IRQ_PRIORITY 7
146 | #define STM32_PWM_TIM5_IRQ_PRIORITY 7
147 | #define STM32_PWM_TIM8_IRQ_PRIORITY 7
148 |
149 | /*
150 | * RTC driver system settings.
151 | */
152 | #define STM32_RTC_IRQ_PRIORITY 15
153 |
154 |
155 | /*
156 | * SERIAL driver system settings.
157 | */
158 | #define STM32_SERIAL_USE_USART1 FALSE
159 | #define STM32_SERIAL_USE_USART2 FALSE
160 | #define STM32_SERIAL_USE_USART3 FALSE
161 | #define STM32_SERIAL_USE_UART4 FALSE
162 | #define STM32_SERIAL_USE_UART5 FALSE
163 | #define STM32_SERIAL_USART1_PRIORITY 12
164 | #define STM32_SERIAL_USART2_PRIORITY 12
165 | #define STM32_SERIAL_USART3_PRIORITY 12
166 | #define STM32_SERIAL_UART4_PRIORITY 12
167 | #define STM32_SERIAL_UART5_PRIORITY 12
168 |
169 | /*
170 | * SPI driver system settings.
171 | */
172 | #define STM32_SPI_USE_SPI1 FALSE
173 | #define STM32_SPI_USE_SPI2 FALSE
174 | #define STM32_SPI_USE_SPI3 FALSE
175 | #define STM32_SPI_SPI1_DMA_PRIORITY 1
176 | #define STM32_SPI_SPI2_DMA_PRIORITY 1
177 | #define STM32_SPI_SPI3_DMA_PRIORITY 1
178 | #define STM32_SPI_SPI1_IRQ_PRIORITY 10
179 | #define STM32_SPI_SPI2_IRQ_PRIORITY 10
180 | #define STM32_SPI_SPI3_IRQ_PRIORITY 10
181 | #define STM32_SPI_DMA_ERROR_HOOK(spip) osalSysHalt("DMA failure")
182 |
183 | /*
184 | * ST driver system settings.
185 | */
186 | #define STM32_ST_IRQ_PRIORITY 8
187 | #define STM32_ST_USE_TIMER 2
188 |
189 |
190 |
191 | /*
192 | * UART driver system settings.
193 | */
194 | #define STM32_UART_USE_USART1 TRUE
195 | #define STM32_UART_USE_USART2 FALSE
196 | #define STM32_UART_USE_USART3 FALSE
197 | #define STM32_UART_USART1_IRQ_PRIORITY 12
198 | #define STM32_UART_USART2_IRQ_PRIORITY 12
199 | #define STM32_UART_USART3_IRQ_PRIORITY 12
200 | #define STM32_UART_USART1_DMA_PRIORITY 0
201 | #define STM32_UART_USART2_DMA_PRIORITY 0
202 | #define STM32_UART_USART3_DMA_PRIORITY 0
203 | #define STM32_UART_DMA_ERROR_HOOK(uartp) osalSysHalt("DMA failure")
204 |
205 | /*
206 | * USB driver system settings.
207 | */
208 | #define STM32_USB_USE_USB1 FALSE
209 | #define STM32_USB_LOW_POWER_ON_SUSPEND FALSE
210 | #define STM32_USB_USB1_HP_IRQ_PRIORITY 13
211 | #define STM32_USB_USB1_LP_IRQ_PRIORITY 14
212 |
213 |
214 |
215 | #endif /* _MCUCONF_H_ */
216 |
--------------------------------------------------------------------------------
/python/led.py:
--------------------------------------------------------------------------------
1 | # Kjell H Andersen
2 | # 2014
3 |
4 | # Python script for controlling the BLDC Strip v2 using Chibios firmware through the serial port
5 | # It will only control the LEDs, but may be used as a template for other more useful scripts.
6 | # This script is tested on a RaspberryPi, but it should also work on any computer where pySerial
7 | # can be installed. You need to change the line that initializes the serial port.
8 |
9 |
10 | import serial
11 | import sys
12 |
13 |
14 | def crc8(data_in):
15 | CRC8INIT = 0x00
16 | CRC8POLY = 0x07
17 |
18 | crc = CRC8INIT
19 |
20 | for data in data_in:
21 | bit_counter = 8
22 |
23 | while bit_counter>0:
24 | feedback_bit = (crc ^ data) & 0x01
25 |
26 | if (feedback_bit == 1):
27 | crc = 0xFF & (crc ^ CRC8POLY)
28 |
29 | crc = (crc >> 1) & 0x7F
30 |
31 | if (feedback_bit == 1):
32 | crc = crc | 0x80
33 |
34 | data = data >> 1
35 | bit_counter -= 1
36 |
37 | return crc
38 |
39 |
40 | str = bytearray([0x00,0x00,0x00,0x00,0x00,0x00,0x00])
41 | r = bytearray([0x00,0x00,0x00,0x00,0x00,0x00,0x00])
42 |
43 | if (len(sys.argv) >= 3):
44 | if (sys.argv[1] == "led1"):
45 | str[0] = 0xF0
46 | elif (sys.argv[1] == "led2"):
47 | str[0] = 0xF1
48 | elif (sys.argv[1] == "motorstate"):
49 | str[0] = 0xF2
50 | elif (sys.argv[1] == "dutycycle"):
51 | str[0] = 0xF3
52 | elif (sys.argv[1] == "direction"):
53 | str[0] = 0xF4
54 | elif (sys.argv[1] == "positioncontrol"):
55 | str[0] = 0xF5
56 | elif (sys.argv[1] == "angle"):
57 | str[0] = 0xF6
58 | elif (sys.argv[1] == "signalgenerator_bipolarpwm"):
59 | str[0] = 0xF7
60 |
61 |
62 | else:
63 | print "Argument 1 is not valid, use led1 or led2 or motorstate or dutycycle or direction or positioncontrol or angle or signalgenerator_bipolarpwm";
64 | sys.exit()
65 |
66 | if (sys.argv[2] == "on"):
67 | str[1] = 0xFF
68 | elif (sys.argv[2] == "off"):
69 | str[1] = 0x00
70 | elif (sys.argv[2] == "val"):
71 | if(len(sys.argv) == 4):
72 | str[1] = int( (int(sys.argv[3])/256) ) # Signed value
73 | str[2] = int(int(sys.argv[3])%256)
74 | else:
75 | print "Not correct number of arguments. Provide 3 arguments"
76 | sys.exit()
77 | else:
78 | print "Argument 2 is not valid, use on or off";
79 | sys.exit()
80 | else:
81 | print "Not correct number of arguments. Provide 2 arguments"
82 |
83 | str.append(crc8 (str))
84 |
85 | # Change the device when using this in other platforms than RaspberryPi
86 | # ser = serial.Serial('/dev/ttyAMA0', 9600)
87 | ser = serial.Serial('/dev/ttyUSB0', 9600, timeout=1)
88 | ser.write (str)
89 | print "Read answer";
90 | r = ser.read(8)
91 | result = [ord(b) for b in r]
92 | motorstate = result[1]
93 | delta_t = (result[2]<<8) + (result[3])
94 | u_dc = result[4]
95 | i_dc = result[5] # *21/13
96 | i_dc_ref = result[6]
97 | print "state=%d; delta_t=%d; u_dc=%d; i_dc=%d; i_dc_ref=%d" % (motorstate, delta_t, u_dc, i_dc, i_dc_ref)
98 |
--------------------------------------------------------------------------------
/src/blinky.c:
--------------------------------------------------------------------------------
1 | /*
2 | * blinky.c
3 | *
4 | * Created on: Dec 10, 2013
5 | * Author: kjell
6 | */
7 |
8 | #include "ch.h"
9 | #include "hal.h"
10 | #include "blinky.h"
11 | #include "uart_scp.h"
12 |
13 | uint8_t debugbyte;
14 |
15 | static THD_WORKING_AREA(waBlinkyRed, BLINKY_STACK_SIZE);
16 | static THD_FUNCTION(tBlinkyRed, arg) {
17 | (void)arg;
18 | chRegSetThreadName("BlinkyBlue");
19 |
20 | while (TRUE) {
21 | chThdSleepMilliseconds(250);
22 | // Use this with the strip
23 | //palTogglePad(GPIOB, GPIOB_LEDG);
24 | palTogglePad(GPIOB, GPIOB_LEDR);
25 |
26 | // Use this with the Discovery board
27 | //palTogglePad(GPIOC, GPIOC_LED4);
28 | }
29 | return 0;
30 | }
31 |
32 | void startBlinkyRed(void) {
33 | chThdCreateStatic(waBlinkyRed, sizeof(waBlinkyRed),
34 | NORMALPRIO,
35 | tBlinkyRed, NULL);
36 | }
37 |
38 | static THD_WORKING_AREA(waBlinkyGreen, BLINKY_STACK_SIZE);
39 | static THD_FUNCTION(tBlinkyGreen, arg) {
40 | (void)arg;
41 | chRegSetThreadName("BlinkyGreen");
42 | char sbyte = 77;
43 | uint8_t last_debugbyte=33;
44 | while (TRUE) {
45 | chThdSleepMilliseconds(50);
46 | /*if(debugbyte!=last_debugbyte) {
47 | last_debugbyte = debugbyte;
48 | uartStartSend(&UARTD1, 1, &debugbyte);
49 | }*/
50 | // Use this with the strip
51 | palTogglePad(GPIOB, GPIOB_LEDG);
52 | //palTogglePad(GPIOB, GPIOB_U_NDTS);
53 | //palTogglePad(GPIOB, GPIOB_V_NDTS);
54 | //palTogglePad(GPIOB, GPIOB_W_NDTS);
55 |
56 |
57 | // Use this with the Discovery board
58 | //palTogglePad(GPIOC, GPIOC_LED3);
59 | //uartStartSend(&UARTD1, 1, &sbyte);
60 | }
61 | return 0;
62 | }
63 |
64 | void startBlinkyGreen(void) {
65 | chThdCreateStatic(waBlinkyGreen, sizeof(waBlinkyGreen),
66 | NORMALPRIO,
67 | tBlinkyGreen, NULL);
68 | }
69 |
--------------------------------------------------------------------------------
/src/blinky.h:
--------------------------------------------------------------------------------
1 | /*
2 | * blinky.h
3 | *
4 | * Created on: Dec 10, 2013
5 | * Author: kjell
6 | */
7 |
8 | #ifndef BLINKY_H_
9 | #define BLINKY_H_
10 |
11 | #define BLINKY_STACK_SIZE 128
12 |
13 | extern void startBlinkyRed(void);
14 | extern void startBlinkyGreen(void);
15 |
16 | #endif /* BLINKY_H_ */
17 |
--------------------------------------------------------------------------------
/src/main.c:
--------------------------------------------------------------------------------
1 | #include "ch.h"
2 | #include "hal.h"
3 | #include "blinky.h"
4 | #include "uart_scp.h"
5 | #include "obldcpwm.h"
6 | #include "obldcadc.h"
7 | #include "obldc_catchmotor.h"
8 |
9 | int main(void) {
10 | int temp;
11 | //Start System
12 | halInit();
13 | chSysInit();
14 | //startBlinkyBlue();
15 | startBlinkyGreen();
16 | //startBlinkyRed();
17 | uartSCPInit();
18 | motor_start_timer();
19 | startmyadc();
20 | v_bat_current_conversion();
21 | chThdSleepMicroseconds(500);
22 | temp = get_vbat_sample();//UGLY!!
23 | chThdSleepMicroseconds(500);
24 | temp = catchmotor_setup();
25 | startRampMotorThread();
26 | obldc_can_init(); // Start CAN bus
27 | // Just idle on the main loop
28 | while (TRUE) {
29 | // palTogglePad(GPIOB, GPIOB_LEDG);
30 | // palTogglePad(GPIOB, GPIOB_LEDR);
31 | //uartStartSend(&UARTD1, 13, "Starting...\r\n");
32 | chThdSleepMilliseconds(1000);
33 | //resetadccount();
34 | }
35 | }
36 |
--------------------------------------------------------------------------------
/src/obldc_can.c:
--------------------------------------------------------------------------------
1 | /*
2 | * obldc_can.c
3 | *
4 | * Created on: 27.04.2015
5 | * Author: joerg
6 | */
7 |
8 |
9 | #include "obldc_can.h"
10 | #include "ch.h"
11 | #include "hal.h"
12 |
13 | // Threads
14 |
15 | // Variable definitions
16 | CANRxFrame rxmsg; //static uint8_t can_rx_buffer[256];
17 | static uint8_t can_rx_buffer_last_id;
18 |
19 | /*
20 | * Internal loopback mode, 500KBaud, automatic wakeup, automatic recover
21 | * from abort mode.
22 | * See section 22.7.7 on the STM32 reference manual.
23 | */
24 | static const CANConfig cancfg = {
25 | CAN_MCR_ABOM | CAN_MCR_AWUM | CAN_MCR_TXFP, // , automatic wakeup,
26 | CAN_BTR_LBKM | // Loop back mode - for testing
27 | CAN_BTR_SJW(3) | // Synchronization jump width; must be smaller or equal 4 and smaller than TS1 & TS2
28 | CAN_BTR_TS2(5) | // Time Segment 2;
29 | CAN_BTR_TS1(6) | // Time Segment 1;
30 | CAN_BTR_BRP(1) //CAN_BTR_BRP(1) // BaudRatePrescaler is 2 --> half frequency of APB1(here 28MHz) see Fig 395 "Bit timing"
31 | };
32 | // 24.7.4 seite 655 Each filter bank x consists of two 32-bit registers, CAN_FxR0 and CAN_FxR1.
33 |
34 |
35 |
36 | /*
37 | * Receiver thread.
38 | */
39 | static THD_WORKING_AREA(waCanComThread, 2048);
40 | static THD_FUNCTION(tCanComThread, arg) {
41 | (void)arg;
42 | chRegSetThreadName("CanComThread");
43 |
44 | event_listener_t el;
45 | CANRxFrame rxmsg;
46 | int32_t ind = 0;
47 | int32_t rxbuf_len;
48 | uint8_t crc_low;
49 | uint8_t crc_high;
50 | bool commands_send;
51 |
52 | chEvtRegister(&CAND1.rxfull_event, &el, 0);
53 |
54 | while(!chThdShouldTerminateX()) {
55 | if (chEvtWaitAnyTimeout(ALL_EVENTS, MS2ST(100)) == 0)
56 | continue;
57 | while (canReceive(&CAND1, CAN_ANY_MAILBOX, &rxmsg, TIME_IMMEDIATE) == MSG_OK) {
58 | /* Process message.*/
59 | //palTogglePad(IOPORT3, GPIOC_LED);
60 | palTogglePad(GPIOB, GPIOB_LEDR);
61 | }
62 | }
63 | chEvtUnregister(&CAND1.rxfull_event, &el);
64 | }
65 |
66 |
67 | /*
68 | * Transmitter thread.
69 | */
70 | static THD_WORKING_AREA(can_tx_wa, 256);
71 | static THD_FUNCTION(can_tx, p) {
72 | CANTxFrame txmsg;
73 |
74 | (void)p;
75 | chRegSetThreadName("transmitter");
76 | txmsg.IDE = CAN_IDE_EXT;
77 | txmsg.EID = 0x01234567;
78 | txmsg.RTR = CAN_RTR_DATA;
79 | txmsg.DLC = 8;
80 | txmsg.data32[0] = 0x55AA55AA;
81 | txmsg.data32[1] = 0x00FF00FF;
82 |
83 | while (!chThdShouldTerminateX()) {
84 | canTransmit(&CAND1, CAN_ANY_MAILBOX, &txmsg, MS2ST(10));
85 | chThdSleepMilliseconds(50);
86 | }
87 | }
88 |
89 |
90 | void obldc_can_init(void) {
91 | canStart(&CAND1, &cancfg);
92 |
93 | //chThdCreateStatic(waCanComThread, sizeof(waCanComThread), NORMALPRIO + 7, tCanComThread, NULL);
94 | // Empfangsthread hängt manchmal wenn was empfangen wird
95 |
96 | chThdCreateStatic(can_tx_wa, sizeof(can_tx_wa), NORMALPRIO + 7, can_tx, NULL);
97 |
98 | }
99 |
--------------------------------------------------------------------------------
/src/obldc_can.h:
--------------------------------------------------------------------------------
1 | /*
2 | * obldc_can.h
3 | *
4 | * Created on: 27.04.2015
5 | * Author: joerg
6 | */
7 |
8 | #ifndef OBLDC_CAN_H_
9 | #define OBLDC_CAN_H_
10 |
11 | void obldc_can_init(void);
12 |
13 | #endif /* OBLDC_CAN_H_ */
14 |
--------------------------------------------------------------------------------
/src/obldc_catchmotor.c:
--------------------------------------------------------------------------------
1 | /*
2 | * obldc_catchmotor.c
3 | *
4 | * Created on: 25.08.2014
5 | * Author: joerg
6 | */
7 |
8 |
9 | #include "ch.h"
10 | #include "hal.h"
11 |
12 | #include "obldc_def.h"
13 | #include "obldc_catchmotor.h"
14 | #include "obldcadc.h"
15 | #include "obldcpwm.h"
16 |
17 | extern motor_s motor; // Motor-struct from obldcpwm.c
18 | extern motor_cmd_s motor_cmd, motor_cmd_temp;// Motor-cmd from obldcpwm.c
19 |
20 | static uint8_t halldecode[8];
21 |
22 | // Winkel-Test
23 | uint8_t letzte_winkel[10];
24 | int winkelcount = 0;
25 |
26 | int last_hall_decoded;
27 | int last_halldiff, last_last_halldiff, last_last_last_halldiff, crossing_counter;
28 | int catchcycle(motor_s* m, int voltage_u, int voltage_v, int voltage_w, uint8_t init) {
29 | static int vdiff_last[3]; // Neu
30 | int vdiff[3];
31 | static int vdiff_1_last;
32 | static int vdiff_2_last;
33 | static int vdiff_3_last;
34 | static int last_zero_crossing;
35 | int direction = 0;
36 | static int stopped_count;
37 | int crossing_detected;
38 | int hall_1, hall_2, hall_3;
39 | int hall_code, hall_decoded;
40 | //static int last_hall_decoded;
41 | int halldiff, abshalldiff;
42 |
43 | if (init == 1) {
44 | halldecode[0]=0; halldecode[1]=4; halldecode[2]=2; halldecode[3]=3; halldecode[4]=6; halldecode[5]=5; halldecode[6]=1; halldecode[7]=0;
45 | vdiff_last[0] = 0; vdiff_last[1] = 0; vdiff_last[2] = 0;
46 | vdiff_1_last = 0;//obsolet
47 | vdiff_2_last = 0;
48 | vdiff_3_last = 0;
49 | last_zero_crossing = 0;
50 | direction = 0;
51 | stopped_count = 0;
52 | last_hall_decoded = 0;
53 | last_halldiff = 0; last_last_halldiff = 0; crossing_counter = 0;
54 | } else {
55 | // init run variables
56 | crossing_detected = 0;
57 |
58 | // determine voltage between the phases
59 | int vdiff_1 = voltage_v - voltage_u;
60 | int vdiff_2 = voltage_w - voltage_v;
61 | int vdiff_3 = voltage_u - voltage_w;
62 |
63 | // determine min and max values
64 | int vdiff_max = MAX(MAX(vdiff_1_last, vdiff_2_last), vdiff_3_last);
65 | int vdiff_min = MIN(MIN(vdiff_1_last, vdiff_2_last), vdiff_3_last);
66 |
67 | // when difference between min and max values > "MinCatchVoltage" -> Cond 1 fulfilled
68 | if (vdiff_max - vdiff_min > OBLDC_MIN_CATCH_VOLTAGE) {
69 | // Cond 1 fulfilled
70 | // detect zero crossing of a phase difference voltage
71 | if (((vdiff_1 < 0) && (vdiff_1_last > 0)) || ((vdiff_1 > 0) && (vdiff_1_last < 0))) {
72 | // zero crossing on vdiff_1
73 | if (last_zero_crossing != 1) {
74 | crossing_detected = 1;
75 | last_zero_crossing = 1;
76 | }
77 | }
78 |
79 | if (((vdiff_2 < 0) && (vdiff_2_last > 0)) || ((vdiff_2 > 0) && (vdiff_2_last < 0))) {
80 | // zero crossing on vdiff_2
81 | if (last_zero_crossing != 2) {
82 | crossing_detected = 1;
83 | last_zero_crossing = 2;
84 | }
85 | }
86 | if (((vdiff_3 < 0) && (vdiff_3_last > 0)) || ((vdiff_3 > 0) && (vdiff_3_last < 0))) {
87 | // zero crossing on vdiff_3
88 | if (last_zero_crossing != 3) {
89 | crossing_detected = 1;
90 | last_zero_crossing = 3;
91 | }
92 | }
93 |
94 | if (crossing_detected == 1) {
95 | if (vdiff_1 > 0) {
96 | hall_1 = 1;
97 | } else {
98 | hall_1 = 0;
99 | }
100 | if (vdiff_2 > 0) {
101 | hall_2 = 1;
102 | } else {
103 | hall_2 = 0;
104 | }
105 | if (vdiff_3 > 0) {
106 | hall_3 = 1;
107 | } else {
108 | hall_3 = 0;
109 | }
110 | hall_code = hall_1 + hall_2 * 2 + hall_3 * 4;
111 | hall_decoded = halldecode[hall_code]; // determine motor angle in [1-6]
112 | crossing_detected = 0;
113 | // check if distance to last 'angle' is = 1
114 |
115 | halldiff = (hall_decoded - last_hall_decoded) % 6;
116 | //if ( halldiff >= 3 ) { halldiff -= 6; } // correct difference
117 | if ( halldiff >= 3 ) { halldiff = 6 - halldiff; } // correct difference
118 |
119 | abshalldiff = halldiff;
120 | if (abshalldiff < 0) abshalldiff=-abshalldiff; //ABS
121 |
122 | // check for four consecutive zero crossings to be rock safe!
123 | crossing_counter++;
124 | if (crossing_counter > 4 && last_last_last_halldiff == last_last_halldiff && last_last_halldiff == last_halldiff && halldiff == last_halldiff && abshalldiff == 1 && last_hall_decoded != 0) {
125 | // determine direction of rotation
126 | direction = halldiff;
127 | crossing_counter = 0;
128 | }
129 | last_hall_decoded = hall_decoded;
130 | last_halldiff = halldiff;
131 | last_last_halldiff = last_halldiff;
132 | last_last_last_halldiff = last_last_halldiff;
133 | if (winkelcount<10) {
134 | // Winkel-Test
135 | letzte_winkel[winkelcount] = hall_decoded;
136 | winkelcount++;
137 | }
138 | }
139 |
140 |
141 | } else { // Voltage too small
142 | // count 'elses': if > 10 -> Motor is stopped -> start startup algorithm
143 | stopped_count = stopped_count + 1;
144 | if (stopped_count > 100) {
145 | // start startup algorithm
146 | }
147 | }
148 | vdiff_1_last = vdiff_1;
149 | vdiff_2_last = vdiff_2;
150 | vdiff_3_last = vdiff_3;
151 | // neue adc-messung starten
152 | //catchconversion();
153 | }
154 | motor.dir = direction;
155 | motor.angle = hall_decoded;
156 | return direction;
157 | }
158 |
159 |
160 | /*msg_t myThread(void *arg) {
161 | unsigned i = 10;
162 | while (i > 0) {
163 | palTogglePad(GPIOB, GPIOB_LEDR);
164 | chThdSleepMilliseconds(500);
165 | i--;
166 | }
167 | return (msg_t)i;
168 | }
169 |
170 | thread_t *startMyThread() {
171 | thread_t *tp = chThdCreateFromHeap(NULL, THD_WA_SIZE(256), NORMALPRIO+1, myThread, NULL); // Heap is BAD
172 | if (tp == NULL)
173 | chSysHalt("Memory exausted"); //Memory exausted.
174 | return tp;
175 | }*/
176 |
177 | #define CATCHMOTOR_STACK_SIZE 128
178 | static THD_WORKING_AREA(waCatchMotorThread, CATCHMOTOR_STACK_SIZE);
179 | static THD_FUNCTION(tCatchMotorTread, arg) {
180 | (void)arg;
181 | chRegSetThreadName("CatchMotorThread");
182 | char sbyte = 77;
183 | int catchstate = 0; int catchresult = 0;
184 |
185 | catchcycle(&motor, 0, 0, 0, TRUE); // initialize catch state variables
186 | while (TRUE) {
187 | catchconversion(); // start ADC Converter
188 | chThdSleepMicroseconds(50);
189 | // evaluate last ADC measurement
190 | // determine voltage; for efficiency reasons, we calculating with the ADC value and do not convert to a float for [V]
191 | int voltage_u = getcatchsamples()[0]; // /4095.0 * 3 * 13.6/3.6; // convert to voltage: /4095 ADC resolution, *3 = ADC pin voltage, *13.6/3.6 = phase voltage
192 | int voltage_v = getcatchsamples()[1]; // /4095.0 * 3 * 13.6/3.6;
193 | int voltage_w = getcatchsamples()[2]; // /4095.0 * 3 * 13.6/3.6;
194 | catchstate = catchcycle(&motor, voltage_u, voltage_v, voltage_w, FALSE);
195 | // Write result TODO
196 | if (catchstate != 0) catchresult = catchstate;
197 | }
198 | return 0;
199 | }
200 |
201 | void startCatchMotorThread(void) {
202 | chThdCreateStatic(waCatchMotorThread, sizeof(waCatchMotorThread),
203 | NORMALPRIO, tCatchMotorTread, NULL);
204 | }
205 |
206 |
207 | #define RAMPMOTOR_STACK_SIZE 256
208 | static THD_WORKING_AREA(waRampMotorThread, RAMPMOTOR_STACK_SIZE);
209 | static THD_FUNCTION(tRampMotorTread, arg) {
210 | (void)arg;
211 | chRegSetThreadName("RampMotorThread");
212 |
213 | //int angle = 1;
214 | int acceleration = 3;
215 | int speed = 50; // initial speed
216 | int delta_t = 50;
217 | int64_t temp=0;
218 | int last_angle4, act_angle;
219 |
220 | int catchstate = 0; int catchresult = 0; int catchcount = 0;
221 | //init_motor_struct(&motor);
222 | motor.angle = 4;
223 | //motor.state = OBLDC_STATE_STARTING_SYNC;
224 | motor.state = OBLDC_STATE_OFF;
225 | //motor.pwm_duty_cycle = 0;
226 | //set_bldc_pwm(&motor);
227 | while (true) {
228 | if(motor.state == OBLDC_STATE_OFF) {
229 | adcStopConversion(&ADCD1);
230 | pwmStop(&PWMD1);
231 | palClearPad(GPIOB, GPIOB_U_NDTS);palClearPad(GPIOB, GPIOB_V_NDTS);palClearPad(GPIOB, GPIOB_W_NDTS);
232 | motor.dir = motor_cmd.dir;// Motor stopped, forget direction. TODO remove when tracking works
233 | //motor.dir = 0;
234 | motor.state_inject = 0;
235 | motor.angle = 4;
236 | motor.state_ramp = 0;
237 | motor_cmd_temp.duty_cycle = 0;
238 | chThdSleepMilliseconds(1);
239 | }
240 | if(motor.state == OBLDC_STATE_SIGNALGENERATOR) {
241 | adcStopConversion(&ADCD1);
242 | chThdSleepMilliseconds(2);
243 | }
244 | if(motor.state == OBLDC_STATE_STARTING_SENSE_1) { // Ramp up the motor
245 | // Rotorlageerkennung
246 | chThdSleepMilliseconds(1);
247 | motor.state = OBLDC_STATE_SENSE_INJECT;
248 | motor.pwm_mode = PWM_MODE_ANTIPHASE;
249 | motor.state_inject = 0;
250 | motor.angle = 4;
251 | motor.state_ramp = 0;
252 | motor.state_calibrate_leg = 1;
253 | motor_cmd_temp.duty_cycle = 0; motor_cmd_temp.dir = 0;
254 | motor_set_cmd(&motor, &motor_cmd_temp);
255 | set_bldc_pwm(&motor); // Start position detection by inductance measurement
256 | //motor.state_ramp = 0;
257 | chThdSleepMicroseconds(1000);
258 | //motor.state = OBLDC_STATE_STARTING_SENSE_1; // DEBUG position sensing
259 |
260 | /*
261 | // Einfach und funzt!
262 | motor.noinject = 1;
263 | motor.pwm_mode = PWM_MODE_SINGLEPHASE;
264 | motor.angle = 3;
265 | motor_set_duty_cycle(&motor, 600);// ACHTUNG!!! 1000 geht gerade noch
266 | set_bldc_pwm(&motor); // Position the motor to sync angle
267 | chThdSleepMilliseconds(1000);
268 | catchcount = 0;
269 | motor.state = OBLDC_STATE_RUNNING_SLOW;
270 | motor.pwm_mode = PWM_MODE_ANTIPHASE;
271 | motor.angle = 1;
272 | motor_set_duty_cycle(&motor, 600);// ACHTUNG!!! 1000 geht gerade noch
273 | set_bldc_pwm(&motor); // Start running with back EMF detection
274 | */
275 | }
276 | if(motor.state == OBLDC_STATE_SENSE_INJECT) {
277 | chThdSleepMicroseconds(500);
278 | }
279 | if(motor.state == OBLDC_STATE_RUNNING_SLOW) {
280 | catchcount++;
281 | if(motor.time_zc != temp) {
282 | catchcount = 0; temp = motor.time_zc;
283 | }
284 | /*if(catchcount > 15 && motor.state_reluct == 2) {
285 | motor.inject = 2;
286 | motor.state_reluct = 1;
287 | } else */if(catchcount > 6) {//6 // Lima: 30
288 | motor.inject = 2;//motor.inject = 3;
289 | /*if( (catchcount - 2) % 10 == 0 && motor.state_reluct == 2) { // motor may be in sync position --> re-trigger injection
290 | motor.state_reluct = 1;
291 | }*/
292 | }
293 | if(motor_cmd.newcmd == 1 && catchcount > 10) { // new command was set; Lima: 35
294 | adcStopConversion(&ADCD1);
295 | //schedule_commutate_cb(50);
296 | palTogglePad(GPIOB, GPIOB_LEDR);
297 | increment_angle_functioncall();increment_angle_functioncall();increment_angle_functioncall();increment_angle_functioncall();increment_angle_functioncall();
298 | gptStartOneShot(&GPTD3, 100); // ACHTUNG DIRTY: Könnte schon aufgerufen gewesen sein!
299 | //motor_set_cmd(&motor, &motor_cmd);
300 | //set_bldc_pwm(&motor);
301 | motor_cmd.newcmd = 0;
302 | }
303 |
304 | if(catchcount > 4000) { // Timeout! 2000
305 | pwmStop(&PWMD1);
306 | motor.dir = motor_cmd.dir;// Motor stopped, forget direction. TODO remove when tracking works
307 | //motor.dir = 0;
308 | adcStopConversion(&ADCD1);
309 | catchcount = 0;
310 | motor.delta_t_zc = 0xFFFF;
311 | motor.last_delta_t_zc = 0xFFFF;
312 | motor.state = OBLDC_STATE_STARTING_SENSE_1;
313 | }
314 | if(motor.delta_t_zc < OBLDC_TRANSITION_DEACTIVATE_INJECTION && motor.last_delta_t_zc < OBLDC_TRANSITION_DEACTIVATE_INJECTION) {
315 | motor.inject = 0;
316 | }
317 | if(motor.delta_t_zc < OBLDC_TRANSITION_RUNNING_SLOW_2_RUNNING && motor.last_delta_t_zc < OBLDC_TRANSITION_RUNNING_SLOW_2_RUNNING) {
318 | catchcount=0;
319 | motor.state = OBLDC_STATE_RUNNING;
320 | }
321 | chThdSleepMicroseconds(500);
322 | }
323 | if(motor.state == OBLDC_STATE_RUNNING) { // Motor is fast!
324 | //catchcount++;
325 | if( (motor.delta_t_zc > OBLDC_TRANSITION_RUNNING_2_RUNNING_SLOW && motor.last_delta_t_zc > OBLDC_TRANSITION_RUNNING_2_RUNNING_SLOW)) {
326 | motor.delta_t_zc = 0xFFFF;
327 | motor.last_delta_t_zc = 0xFFFF;
328 | //motor.angle = (motor.angle) % 6 + 1; // Vorwärts immer, rückwärts nimmer!
329 | motor.state = OBLDC_STATE_RUNNING_SLOW; // TODO: Make definitions for these values
330 | }
331 | chThdSleepMicroseconds(500);
332 | }
333 | if(motor.state == OBLDC_STATE_STARTING_SYNC) { // Ramp up the motor
334 | //set_bldc_pwm(angle, 300 + (speed*4)/3, 50); // u/f operation
335 | motor_cmd_temp.duty_cycle = 500 + (speed * 6) / 3; motor_cmd_temp.dir = 1;
336 | motor_set_cmd( &motor, &motor_cmd_temp );
337 | set_bldc_pwm(&motor);
338 | speed = speed + acceleration;
339 | delta_t = 1000000 / speed;
340 | if (speed > 719) { // speed reached --> try to catch motor
341 | motor.state = OBLDC_STATE_CATCHING;
342 | set_bldc_pwm(&motor);
343 | speed = 50;
344 | catchcycle(&motor, 0, 0, 0, TRUE); // initialize catch state variables
345 | }
346 | chThdSleepMicroseconds(delta_t);
347 | motor.angle = (motor.angle) % 6 + 1;
348 | }
349 | if(motor.state == OBLDC_STATE_CATCHING) {
350 | //catchcount++;
351 | catchconversion(); // start ADC Converter
352 | chThdSleepMicroseconds(40);
353 | // evaluate last ADC measurement
354 | // determine voltage; for efficiency reasons, we calculating with the ADC value and do not convert to a float for [V]
355 | int voltage_u = getcatchsamples()[0]; // /4095.0 * 3 * 13.6/3.6; // convert to voltage: /4095 ADC resolution, *3 = ADC pin voltage, *13.6/3.6 = phase voltage
356 | int voltage_v = getcatchsamples()[1]; // /4095.0 * 3 * 13.6/3.6;
357 | int voltage_w = getcatchsamples()[2]; // /4095.0 * 3 * 13.6/3.6;
358 | catchstate = catchcycle(&motor, voltage_u, voltage_v, voltage_w, FALSE);
359 | // Write result TODO
360 | if (1) {//catchstate != 0 && (motor.angle == 3 || motor.angle == 5) ) {
361 | /*
362 | * TODO catchcycle scheint fuer Winkel 3 und 5 ordentlich zu funktionieren.
363 | * --> Ueberarbeiten, damit es fuer alle anderen Winkel auch geht!
364 | */
365 | /*catchresult = catchstate;
366 | uartSendACK(); // Oszilloskop-Trigger auf UART
367 | palClearPad(GPIOB, GPIOB_LEDR);
368 | //adcStopConversion(&ADCD1);
369 | motor.state = OBLDC_STATE_RUNNING;
370 | motor.angle = 1;
371 | motor_set_duty_cycle(&motor, 600);// ACHTUNG!!! 1000 geht gerade noch
372 | set_bldc_pwm(&motor); // Start running with back EMF detection
373 | chThdSleepMilliseconds(5000); chThdSleepMilliseconds(5000);
374 | pwmStop(&PWMD1);
375 | adcStopConversion(&ADCD1);
376 | motor.angle = 3;
377 | motor_set_duty_cycle(&motor, 600);// ACHTUNG!!! 1000 geht gerade noch
378 | set_bldc_pwm(&motor); // Start running with back EMF detection
379 | chThdSleepMilliseconds(5000); chThdSleepMilliseconds(5000);
380 | palSetPad(GPIOB, GPIOB_LEDR);
381 | pwmStop(&PWMD1);
382 | adcStopConversion(&ADCD1);
383 | catchcount = 0;
384 | for (winkelcount=0; winkelcount < 10; winkelcount++) letzte_winkel[winkelcount] = 9;//Winkelcount ist Debug-Kram
385 | winkelcount = 0;
386 | motor.state = OBLDC_STATE_STARTING_SYNC;*/
387 | }
388 | if(catchcount > 10000) { // Timeout!
389 | catchcount = 0;
390 | for (winkelcount=0; winkelcount < 10; winkelcount++) letzte_winkel[winkelcount] = 9;
391 | winkelcount = 0;
392 | motor.state = OBLDC_STATE_STARTING_SYNC;
393 | }
394 | }
395 | }
396 | }
397 |
398 | void startRampMotorThread(void) {
399 | chThdCreateStatic(waRampMotorThread, sizeof(waRampMotorThread),
400 | NORMALPRIO, tRampMotorTread, NULL);
401 | }
402 |
403 |
404 | // ----------- Alternativeloesung mit Virtuellen Timern
405 | virtual_timer_t vt;
406 | int angle = 1;
407 | int acceleration = 3;
408 | int speed = 100; // initial speed
409 | int delta_t = 50;
410 | // Bestimmt die System-Tick-Frequenz: CH_CFG_ST_FREQUENCY. Vielleicht besser den Tickless mode verwenden?
411 | void rampMotorCb(void *p) {
412 | angle = (angle) % 6 + 1;
413 | //set_bldc_pwm(angle, 300 + (speed*4)/3, 50); // u/f operation
414 | speed = speed + acceleration;
415 | delta_t = 1000000 / speed;
416 | if (speed > 700) { // speed reached --> try to catch motor
417 | //set_bldc_pwm(0,0,50);
418 | speed = 100;
419 | delta_t = 2000000;
420 | }
421 | // Restart the timer
422 | chSysLockFromISR();
423 | chVTSetI(&vt, US2ST(delta_t), rampMotorCb, p);
424 | chSysUnlockFromISR();
425 | }
426 |
427 | void startRampMotorCb(void) {
428 | chSysLock();
429 | chVTSetI(&vt, US2ST(1000), rampMotorCb, NULL);
430 | chSysUnlock();
431 | }
432 |
433 |
434 |
--------------------------------------------------------------------------------
/src/obldc_catchmotor.h:
--------------------------------------------------------------------------------
1 | /*
2 | * obldc_catchmotor.h
3 | *
4 | * Created on: 25.08.2014
5 | * Author: joerg
6 | */
7 |
8 | #ifndef OBLDC_CATCHMOTOR_H_
9 | #define OBLDC_CATCHMOTOR_H_
10 |
11 | #define OBLDC_MIN_CATCH_VOLTAGE 360 // 1V minimum voltage to evaluate for motor position catching; /4095 ADC resolution, *3 = ADC pin voltage, *13.6/3.6 = phase voltage TODO: Check max ADC voltage 3V or 3.3V?
12 |
13 |
14 | //msg_t myThread(void *arg);
15 | extern void startCatchMotorThread(void);
16 | extern void startRampMotorThread(void);
17 | extern void startRampMotorCb(void);
18 |
19 | #endif /* OBLDC_CATCHMOTOR_H_ */
20 |
--------------------------------------------------------------------------------
/src/obldc_def.h:
--------------------------------------------------------------------------------
1 | /*
2 | * obldc_def.h
3 | *
4 | * Created on: 25.08.2014
5 | * Author: joerg
6 | */
7 |
8 | #ifndef OBLDC_DEF_H_
9 | #define OBLDC_DEF_H_
10 |
11 | // TODO: Lieber als inline implementieren!
12 | #define MIN(a,b) (((a)<(b))?(a):(b))
13 | #define MAX(a,b) (((a)>(b))?(a):(b))
14 | //#define ABS(a) (((a)>0)?(a):-(a)) // TODO: ACHTUNG KAPUTT!!!
15 |
16 | typedef struct {
17 | int KV; // Voltage constant; scaled with respect to ADC resolution and evaluation method, whatever it will be...
18 | } Motor_t;
19 | /*
20 | * Stores motor parameters and states used in many functions.
21 | * The unit time is microseconds [us]
22 | */
23 |
24 | #endif /* OBLDC_DEF_H_ */
25 |
--------------------------------------------------------------------------------
/src/obldcadc.c:
--------------------------------------------------------------------------------
1 | /*
2 | * obldcadc.c
3 | *
4 | * Created on: 31.05.2014
5 | * Author: joerg
6 | */
7 |
8 |
9 | #include "ch.h"
10 | #include "hal.h"
11 |
12 | #include "obldcadc.h"
13 | #include "obldc_def.h"
14 |
15 | #define ADC_GRP1_NUM_CHANNELS 8
16 | #define ADC_GRP1_BUF_DEPTH 1
17 |
18 | #define ADC_CATCH_NUM_CHANNELS 3
19 | #define ADC_CATCH_BUF_DEPTH 1
20 |
21 |
22 |
23 | static adcsample_t samples1[ADC_GRP1_NUM_CHANNELS * ADC_GRP1_BUF_DEPTH];
24 | static adcsample_t catchsamples[ADC_CATCH_NUM_CHANNELS * ADC_CATCH_BUF_DEPTH];
25 |
26 | uint32_t adccount;
27 | void resetadccount() {
28 | adccount = 0;
29 | }
30 | /*
31 | * ADC streaming callback.
32 | */
33 | static void adccallback(ADCDriver *adcp, adcsample_t *buffer, size_t n) {
34 |
35 | (void)adcp;
36 |
37 | //adcsample_t avg_ch1 = (samples1[0] + samples1[1] + samples1[2] + samples1[3] + samples1[4] + samples1[5] + samples1[6] + samples1[7]) / 8;
38 | //float voltage = avg_ch1/4095.0*3;
39 | adccount++;
40 |
41 | }
42 |
43 | static void adcerrorcallback(ADCDriver *adcp, adcerror_t err) {
44 |
45 | (void)adcp;
46 | (void)err;
47 | }
48 |
49 | /*
50 | * ADC streaming callback for catching mode
51 | */
52 | static void adccatchcallback(ADCDriver *adcp, adcsample_t *buffer, size_t n) {
53 |
54 | (void)adcp;
55 |
56 | //adcsample_t avg_ch1 = (samples1[0] + samples1[1] + samples1[2] + samples1[3] + samples1[4] + samples1[5] + samples1[6] + samples1[7]) / 8;
57 | //float voltage = avg_ch1/4095.0*3;
58 | adccount++;
59 | /*float voltage_u = catchsamples[0]/4095.0 * 3 * 13.6/3.6; // convert to voltage: *3 = ADC pin voltage, *13.6/3.6 = phase voltage
60 | float voltage_v = catchsamples[1]/4095.0 * 3 * 13.6/3.6;
61 | float voltage_w = catchsamples[2]/4095.0 * 3 * 13.6/3.6;
62 |
63 | float vdiff_1 = voltage_v - voltage_u;
64 | float vdiff_2 = voltage_w - voltage_v;
65 | float vdiff_3 = voltage_u - voltage_w;*/
66 |
67 |
68 | }
69 |
70 | static void adccatcherrorcallback(ADCDriver *adcp, adcerror_t err) {
71 |
72 | (void)adcp;
73 | (void)err;
74 | adccount++;
75 | }
76 |
77 | /*
78 | * ADC conversion group.
79 | * Mode: Continuous, 8 samples of 1 channel, SW triggered.
80 | * Channels: IN0.
81 | */
82 | static const ADCConversionGroup adcgrpcfg1 = {
83 | TRUE,
84 | ADC_GRP1_NUM_CHANNELS,
85 | adccallback,
86 | adcerrorcallback,
87 | 0, ADC_CR2_TSVREFE, // ADC_CR1, ADC_CR2; ADC_CR2_TSVREFE = Temperature sensor and V REFINT enable
88 | ADC_SMPR1_SMP_SENSOR(ADC_SAMPLE_239P5) | ADC_SMPR1_SMP_VREF(ADC_SAMPLE_239P5), // ADC sample time register 1 (ADC_SMPR1)
89 | ADC_SMPR2_SMP_AN0(ADC_SAMPLE_41P5) | ADC_SMPR2_SMP_AN1(ADC_SAMPLE_41P5) |
90 | ADC_SMPR2_SMP_AN2(ADC_SAMPLE_41P5) | ADC_SMPR2_SMP_AN3(ADC_SAMPLE_41P5) |
91 | ADC_SMPR2_SMP_AN4(ADC_SAMPLE_41P5) | ADC_SMPR2_SMP_AN5(ADC_SAMPLE_41P5), // SMPR2
92 | ADC_SQR1_NUM_CH(ADC_GRP1_NUM_CHANNELS), // ADC regular sequence register (ADC_SQRx)
93 | ADC_SQR2_SQ8_N(ADC_CHANNEL_SENSOR) | ADC_SQR2_SQ7_N(ADC_CHANNEL_VREFINT),
94 | ADC_SQR3_SQ6_N(ADC_CHANNEL_IN5) | ADC_SQR3_SQ5_N(ADC_CHANNEL_IN4) |
95 | ADC_SQR3_SQ4_N(ADC_CHANNEL_IN3) | ADC_SQR3_SQ3_N(ADC_CHANNEL_IN2) |
96 | ADC_SQR3_SQ2_N(ADC_CHANNEL_IN1) | ADC_SQR3_SQ1_N(ADC_CHANNEL_IN0)
97 | };
98 |
99 | static const ADCConversionGroup adcgrpcfg_example = {
100 | FALSE, // Sets the circular buffer mode for the group.
101 | ADC_GRP1_NUM_CHANNELS, // Enables the circular buffer mode for the group.
102 | NULL, // Callback function associated to the group or NULL.
103 | adcerrorcallback, // Error callback or NULL.
104 | 0, 0, /* CR1, CR2 */
105 | ADC_SMPR1_SMP_AN10(ADC_SAMPLE_1P5),
106 | 0, /* SMPR2 */
107 | ADC_SQR1_NUM_CH(ADC_GRP1_NUM_CHANNELS),
108 | 0, /* SQR2 */
109 | ADC_SQR3_SQ1_N(ADC_CHANNEL_IN10)
110 | };
111 |
112 |
113 | /* static const ADCConversionGroup adcgrpcfg1 = {
114 | TRUE,
115 | ADC_GRP1_NUM_CHANNELS,
116 | adccallback,
117 | adcerrorcallback,
118 | 0, ADC_CR2_TSVREFE, // ADC_CR1, ADC_CR2; ADC_CR2_TSVREFE = Temperature sensor and V REFINT enable
119 | 0, // ADC sample time register 1 (ADC_SMPR1)
120 | ADC_SMPR2_SMP_AN0(ADC_SAMPLE_1P5), // SMPR2
121 | ADC_SQR1_NUM_CH(ADC_GRP1_NUM_CHANNELS), // ADC regular sequence register (ADC_SQRx)
122 | 0,
123 | ADC_SQR3_SQ1_N(ADC_CHANNEL_IN0)
124 | };*/
125 |
126 | static void testcallback(ADCDriver *adcp, adcsample_t *buffer, size_t n) {
127 |
128 | (void)adcp;
129 | adccount++;
130 | //adcsample_t avg_ch1 = (samples1[0] + samples1[1] + samples1[2] + samples1[3] + samples1[4] + samples1[5] + samples1[6] + samples1[7]) / 8;
131 | //float voltage = avg_ch1/4095.0*3;
132 |
133 | }
134 |
135 | /*
136 | * ADC conversion configuration for catching mode
137 | */
138 | static const ADCConversionGroup adccatchgroup = {
139 | FALSE, // linear mode
140 | ADC_CATCH_NUM_CHANNELS,
141 | testcallback, //adccatchcallback,
142 | adccatcherrorcallback,
143 | 0, // ADC_CR1
144 | 0, // ADC_CR2
145 | 0, // ADC_SMPR1
146 | ADC_SMPR2_SMP_AN0(ADC_SAMPLE_239P5) | ADC_SMPR2_SMP_AN1(ADC_SAMPLE_239P5) | ADC_SMPR2_SMP_AN2(ADC_SAMPLE_239P5), // ADC_SMPR2
147 | ADC_SQR1_NUM_CH(ADC_CATCH_NUM_CHANNELS), // ADC_SQR1
148 | 0, // ADC_SQR2
149 | ADC_SQR3_SQ3_N(ADC_CHANNEL_IN2) | ADC_SQR3_SQ2_N(ADC_CHANNEL_IN1) | ADC_SQR3_SQ1_N(ADC_CHANNEL_IN0) // ADC_SQR3
150 | };
151 |
152 | static const ADCConversionGroup adccatchgroup_simple = {
153 | FALSE, // linear mode
154 | ADC_CATCH_NUM_CHANNELS,
155 | NULL, // no callback and end of conversion
156 | adccatcherrorcallback,
157 | 0, // ADC_CR1
158 | 0, // ADC_CR2
159 | 0, // ADC_SMPR1
160 | ADC_SMPR2_SMP_AN0(ADC_SAMPLE_239P5) | ADC_SMPR2_SMP_AN1(ADC_SAMPLE_239P5) | ADC_SMPR2_SMP_AN2(ADC_SAMPLE_239P5), // ADC_SMPR2
161 | ADC_SQR1_NUM_CH(ADC_CATCH_NUM_CHANNELS), // ADC_SQR1
162 | 0, // ADC_SQR2
163 | ADC_SQR3_SQ3_N(ADC_CHANNEL_IN2) | ADC_SQR3_SQ2_N(ADC_CHANNEL_IN1) | ADC_SQR3_SQ1_N(ADC_CHANNEL_IN0) // ADC_SQR3
164 | };
165 |
166 |
167 |
168 |
169 |
170 | void catchconversion(void) {
171 | //adcConvert(&ADCD1, &adccatchgroup, catchsamples, ADC_CATCH_BUF_DEPTH);// kehrt nicht zurueck
172 | adcStartConversion(&ADCD1, &adccatchgroup_simple, catchsamples, ADC_CATCH_BUF_DEPTH);// adccatchgroup
173 | //adcStartConversion(&ADCD1, &adccatchgroup, catchsamples, ADC_CATCH_BUF_DEPTH);
174 | //adcStartConversion(&ADCD1, &adcgrpcfg1, samples1, ADC_GRP1_BUF_DEPTH);
175 | }
176 |
177 | int catchmotor_setup(void) {
178 | // Set disable signal to open all switches
179 | palClearPad(GPIOB, GPIOB_U_NDTS);
180 | palClearPad(GPIOB, GPIOB_V_NDTS);
181 | palClearPad(GPIOB, GPIOB_W_NDTS);
182 | return 1; // TODO: Do sth useful
183 | }
184 |
185 | adcsample_t* getcatchsamples(void) {
186 | return catchsamples;
187 | }
188 |
--------------------------------------------------------------------------------
/src/obldcadc.h:
--------------------------------------------------------------------------------
1 | /*
2 | * obldcadc.h
3 | *
4 | * Created on: 31.05.2014
5 | * Author: joerg
6 | */
7 |
8 | #ifndef OBLDCADC_H_
9 | #define OBLDCADC_H_
10 |
11 | //TODO: Zusammenfuehren mit obldpwm.c
12 |
13 | #include "obldcpwm.h"
14 |
15 | void startmyadc(void);
16 | void resetadccount(void);
17 | void catchconversion(void);
18 |
19 | adcsample_t* getcatchsamples(void);
20 |
21 | int catchmotor_setup(void);
22 |
23 | #endif /* OBLDCADC_H_ */
24 |
--------------------------------------------------------------------------------
/src/obldcpwm.c:
--------------------------------------------------------------------------------
1 | /*
2 | * pwm.c
3 | *
4 | * Created on: 22.05.2014
5 | * Author: joerg
6 | */
7 |
8 | #include "ch.h"
9 | #include "hal.h"
10 | #include "uart.h"
11 | #include "uart_scp.h"
12 | #include "pwm.h"
13 |
14 | #include "obldc_def.h"
15 | #include "obldcpwm.h"
16 | #include "ringbuffer.h"
17 |
18 | inline int mod(int a, int b)
19 | {
20 | int r = a % b;
21 | return r < 0 ? r + b : r;
22 | }
23 |
24 | extern uint8_t debugbyte;
25 |
26 | motor_s motor; // Stores all motor data
27 | motor_cmd_s motor_cmd, motor_cmd_temp;
28 |
29 | //#define ADC_COMMUTATE_NUM_CHANNELS 5
30 | //#define ADC_COMMUTATE_BUF_DEPTH 8
31 | //f_single = 2.0000e+05
32 | //T_cb_ADC1 = 2.0000e-05
33 | //f_cb_ADC1 = 5.0000e+04
34 |
35 | #define ADC_COMMUTATE_NUM_CHANNELS 1
36 | #define ADC_COMMUTATE_BUF_DEPTH 50
37 | #define NREG 8 // Number of samples for a valid regression
38 | #define DROPNOISYSAMPLES 1 // "Drop samples with switching noise
39 |
40 | typedef struct {
41 | int16_t size;
42 | int16_t start;
43 | int16_t end;
44 | int16_t elems[NREG+1];
45 | } commutate_Buffer;
46 |
47 | commutate_Buffer ibuf, ubuf, ybuf;
48 |
49 |
50 | static adcsample_t commutatesamples[ADC_COMMUTATE_NUM_CHANNELS * ADC_COMMUTATE_BUF_DEPTH];
51 |
52 | /*
53 | * Ganzzahlige Teiler von ADC_COMMUTATE_FREQUENCY=1e6:
54 | * 25, 20, 16, 10, 8, 5
55 | */
56 |
57 | #define PWM_CLOCK_FREQUENCY 28e6 //2e6 //14e6 // [Hz]
58 | #define PWM_DEFAULT_FREQUENCY 100000 // [40000, 50000, 62500, 100000, 125000] choose one of these base frequencies [Hz] Lima+Nema34: 40000
59 | #define PWM_MINIMUM_FREQUENCY 40000
60 |
61 | #define ADC_COMMUTATE_FREQUENCY 1e6 // [Hz]
62 | #define ADC_PWM_DIVIDER (PWM_CLOCK_FREQUENCY / ADC_COMMUTATE_FREQUENCY)
63 | #define ADC_PWM_PERIOD (ADC_COMMUTATE_FREQUENCY / PWM_DEFAULT_FREQUENCY)
64 | #define PWM_MAXIMUM_PERIOD (ADC_PWM_DIVIDER * ADC_COMMUTATE_FREQUENCY / PWM_MINIMUM_FREQUENCY)
65 |
66 | #define ADC_VBAT_CURRENT_NUM_CHANNELS 3
67 | #define ADC_VBAT_CURRENT_BUF_DEPTH 4
68 | #define ADC_VBAT_CURRENT_EXTTRIG_NUM_CHANNELS 2
69 | #define ADC_VBAT_CURRENT_EXTTRIG_BUF_DEPTH 12
70 |
71 |
72 | //static adcsample_t vbat_current_samples[ADC_VBAT_CURRENT_NUM_CHANNELS * ADC_VBAT_CURRENT_BUF_DEPTH];
73 | static adcsample_t vbat_current_samples[ADC_COMMUTATE_NUM_CHANNELS * ADC_COMMUTATE_BUF_DEPTH];// ist das noetig???
74 |
75 |
76 | void startmyadc(void) {
77 | adcStart(&ADCD1, NULL);
78 | }
79 |
80 |
81 | //uint8_t table_angle2leg[7];
82 | //uint8_t table_angle2leg2[7];
83 | motor_s* get_motor_ptr(void) {
84 | return &motor;
85 | }
86 |
87 | void init_motor_struct(motor_s* motor) {
88 | motor->state = OBLDC_STATE_OFF;
89 | motor->pwm_mode = PWM_MODE_ANTIPHASE; //PWM_MODE_SINGLEPHASE;
90 | motor->pwm_t_on = 0;
91 | motor->pwm_period = PWM_CLOCK_FREQUENCY / PWM_DEFAULT_FREQUENCY; // in ticks
92 | motor->offset_leg[0] = 0;
93 | motor->offset_leg[1] = 0;
94 | motor->offset_leg[2] = 0;
95 | motor->u_dc = 0;
96 | motor->i_dc = 0;
97 | motor->i_dc_ref = 0;
98 | motor->u_dc_filt = 0;
99 | motor->i_dc_filt = 0;
100 | motor->i_dc_sum = 0;
101 | motor->last_angle = 0;
102 | motor->angle = 0;
103 | motor->angle_sum = 0;
104 | motor->positioncontrol = 0;
105 | motor->P_position = 70; // P-gain of position controller
106 | motor->dir = 0;
107 | motor->dirjustchanged = 0;
108 | motor->dir_v_range = OBLDC_DIR_V_RANGE;
109 | motor->time = 0;
110 | motor->time_zc = 0;
111 | motor->time_last_zc = 0;
112 | motor->time_next_commutate_cb = 0;
113 | motor->delta_t_zc = 0xFFFF;
114 | motor->last_delta_t_zc = 0xFFFF;
115 | motor->inject = 0;
116 | motor->last_angle4 = 0;
117 | motor_cmd.duty_cycle = 0; //1000;
118 | motor_cmd.dir = 1;
119 | motor_cmd.newcmd = 0;
120 |
121 | bufferInitStatic(ubuf, 6);
122 | bufferInitStatic(ibuf, 6);
123 | //motor->sumx=0; motor->sumx2=0; motor->sumxy=0; motor->sumy=0; motor->sumy2=0;
124 | /*table_angle2leg[0]=0; table_angle2leg2[0]=0; // 0, 0, 0, 0 SenseBridgeSign
125 | table_angle2leg[1]=0; table_angle2leg2[0]=1; // 1, 1, -1, 0 -1
126 | table_angle2leg[2]=2; table_angle2leg2[0]=1; // 2, 0, -1, 1 1
127 | table_angle2leg[3]=2; table_angle2leg2[0]=0; // 3, -1, 0, 1 -1
128 | table_angle2leg[4]=1; table_angle2leg2[0]=0; // 4, -1, 1, 0 1
129 | table_angle2leg[5]=1; table_angle2leg2[0]=2; // 5, 0, 1, -1 -1
130 | table_angle2leg[6]=0; table_angle2leg2[0]=2; // 6, 1, 0, -1 1*/
131 | }
132 |
133 | static inline void increment_angle(void) {
134 | //motor.angle = ((motor.angle - 1 + motor.dir) % 6) + 1; WARUM GEHT DAS NICHT!? Weil Modulo nicht Rest der ganzzahligen Division ist...
135 | if(motor.dir == 1) {
136 | motor.angle = (motor.angle) % 6 + 1;
137 | } else if(motor.dir == -1) {
138 | motor.angle = (motor.angle + 4) % 6 + 1;
139 | }
140 | }
141 |
142 | void increment_angle_functioncall(void) {
143 | increment_angle();
144 | }
145 |
146 |
147 | static inline void count_angle4control(void) {
148 | int16_t r = (motor.angle - motor.last_angle) % 6;
149 | if(r > 3) { // wird groeszer
150 | motor.angle_sum += r - 6;
151 | //motor.angle_sum -= 1;
152 | } else if(r < -2) { // wird kleiner
153 | motor.angle_sum += 6 + r;
154 | //motor.angle_sum += 1;
155 | } else {
156 | motor.angle_sum += r; // Quick'n dirty
157 | }
158 | motor.last_angle = motor.angle;
159 | //uint8_t debugbyte=motor.angle; uartStartSendI(&UARTD1, 1, &debugbyte );// TODO Debug!
160 | // TODO: motor.angle auf serielle schnittstelle zum debuggen schreiben - sieht gut aus.
161 | }
162 |
163 | void motor_set_cmd(motor_s* m, motor_cmd_s* cmd) {
164 | int d_percent;
165 | if(cmd->dir == m->dir) {
166 | m->pwm_d = cmd->duty_cycle;
167 | } else {
168 | m->pwm_d = -cmd->duty_cycle;
169 | }
170 | //m->dir = cmd->dir;
171 | d_percent = (5000 + m->pwm_d / 2) / 100;
172 | //TODO: Limitation of duty cycle to prevent over current using motor speed (and resistance)
173 | if(m->state == OBLDC_STATE_STARTING_SENSE_1) { // Ramp up the motor
174 | m->pwm_mode = PWM_MODE_SINGLEPHASE;
175 | m->pwm_period = PWM_CLOCK_FREQUENCY / PWM_DEFAULT_FREQUENCY; // in ticks
176 | // No zero crossing occurred yet
177 | m->time_zc = 0;
178 | m->time_last_zc = 0;
179 | m->time_next_commutate_cb = 0;
180 | m->delta_t_zc = 0xFFFF;
181 | m->last_delta_t_zc = 0xFFFF;
182 | }
183 | else {
184 | m->pwm_mode = PWM_MODE_ANTIPHASE;
185 | }
186 | if(m->pwm_mode == PWM_MODE_SINGLEPHASE)
187 | m->pwm_t_on = m->pwm_period * m->pwm_d / 10000;
188 | else {//PWM_MODE_ANTIPHASE
189 | eval_vbat_idc(); // Evaluate from last cycle. New external triggered!
190 | if(d_percent > 0 && d_percent < 100)// Adaptive PWM period. TODO: Test this!
191 | m->pwm_period = ADC_PWM_DIVIDER * (int)((ADC_PWM_PERIOD * 2500) / ((100 - d_percent) * d_percent));
192 | else
193 | m->pwm_period = PWM_CLOCK_FREQUENCY / PWM_DEFAULT_FREQUENCY;
194 | if(m->pwm_period > PWM_MAXIMUM_PERIOD)
195 | m->pwm_period = PWM_MAXIMUM_PERIOD;
196 | m->pwm_t_on = m->pwm_period * (5000 + m->pwm_d / 2) / 10000;
197 | }
198 | m->pwm_t_on_ADC = m->pwm_t_on / ADC_PWM_DIVIDER;
199 | m->pwm_period_ADC = m->pwm_period / ADC_PWM_DIVIDER;
200 |
201 | if(m->state_reluct == 3 && m->state != OBLDC_STATE_SENSE_INJECT) {//
202 | m->state_reluct = 0; // Unknown
203 | }
204 | //m->sumx=0; m->sumx2=0; m->sumxy=0; m->sumy=0; m->sumy2=0;
205 | m->sumy=0;
206 |
207 | if(m->dir == -1)
208 | m->invSenseSign = (m->angle + 1) % 2;
209 | else
210 | m->invSenseSign = m->angle % 2;
211 |
212 | //get_vbat_sample(); // not external triggered
213 | bufferInitStatic(ybuf, NREG);
214 | }
215 |
216 | // TODO: void motor_set_period(motor_s* m, int period)
217 | // TODO: void motor_set_pwm_mode(motor_s* m, obldc_pwm_mode pwm_mode)
218 |
219 | uint32_t k_cb_commutate; // Counts how often the ADC callback was called
220 | inline void reset_adc_commutate_count(void) {
221 | k_cb_commutate = 0;
222 | }
223 |
224 |
225 | static const ADCConversionGroup adc_vbat_current_group = {
226 | FALSE, // linear mode
227 | ADC_VBAT_CURRENT_NUM_CHANNELS,
228 | NULL, // no callback and end of conversion
229 | NULL,
230 | 0, // ADC_CR1
231 | 0, // ADC_CR2
232 | 0, // ADC_SMPR1
233 | ADC_SMPR2_SMP_AN3(ADC_SAMPLE_1P5) | ADC_SMPR2_SMP_AN4(ADC_SAMPLE_1P5) | ADC_SMPR2_SMP_AN5(ADC_SAMPLE_1P5), // ADC_SMPR2
234 | ADC_SQR1_NUM_CH(ADC_VBAT_CURRENT_NUM_CHANNELS), // ADC_SQR1
235 | 0, // ADC_SQR2
236 | ADC_SQR3_SQ1_N(ADC_CHANNEL_IN3) | ADC_SQR3_SQ2_N(ADC_CHANNEL_IN4) | ADC_SQR3_SQ3_N(ADC_CHANNEL_IN5) // ADC_SQR3
237 | };
238 |
239 | static ADCConversionGroup adc_vbat_current_exttrig_group = {
240 | FALSE, // linear mode
241 | ADC_VBAT_CURRENT_EXTTRIG_NUM_CHANNELS,
242 | NULL, // no callback and end of conversion
243 | NULL,
244 | 0, // ADC_CR1
245 | 0, // ADC_CR2
246 | 0, // ADC_SMPR1
247 | ADC_SMPR2_SMP_AN3(ADC_SAMPLE_1P5) | ADC_SMPR2_SMP_AN4(ADC_SAMPLE_1P5), // ADC_SMPR2
248 | ADC_SQR1_NUM_CH(ADC_VBAT_CURRENT_EXTTRIG_NUM_CHANNELS), // ADC_SQR1
249 | 0, // ADC_SQR2
250 | ADC_SQR3_SQ1_N(ADC_CHANNEL_IN3) | ADC_SQR3_SQ2_N(ADC_CHANNEL_IN4) // ADC_SQR3
251 | };
252 |
253 | static PWMConfig genpwmcfg= {
254 | PWM_CLOCK_FREQUENCY, /* PWM clock frequency */
255 | PWM_CLOCK_FREQUENCY / PWM_DEFAULT_FREQUENCY, /* PWM period */
256 | NULL, /* No callback */
257 | {
258 | {PWM_OUTPUT_ACTIVE_HIGH, NULL},
259 | {PWM_OUTPUT_ACTIVE_HIGH, NULL},
260 | {PWM_OUTPUT_ACTIVE_HIGH, NULL},
261 | {PWM_OUTPUT_DISABLED, NULL},
262 | },
263 | 0,//TIM_CR2_MMS_1, // 010: Update - The update event is selected as trigger output (TRGO). //TIM_CR2_MMS_2, // TIM CR2 register initialization data, OC1REF signal is used as trigger output (TRGO)
264 | 0 // TIM DIER register initialization data, "should normally be zero"
265 | };
266 |
267 |
268 |
269 | inline int64_t motortime_now(void) {
270 | return (motor.time + gptGetCounterX(&GPTD4));
271 | }
272 |
273 | static inline void motortime_zc(int64_t t) {
274 | motor.time_last_zc = motor.time_zc;
275 | motor.time_zc = t;//motortime_now();
276 | motor.last_delta_t_zc = motor.delta_t_zc;
277 | motor.delta_t_zc = motor.time_zc - motor.time_last_zc; // TODO: state machine dass kein ueberlauf auftreten kann
278 | }
279 |
280 |
281 | static void commutatetimercb(GPTDriver *gptp) {
282 | msg_t msg;
283 |
284 | (void)gptp;
285 | //chSysLockFromISR();
286 | adcStopConversionI(&ADCD1);
287 | if(motor.state == OBLDC_STATE_RUNNING_SLOW || motor.state == OBLDC_STATE_RUNNING) {
288 | motor_cmd.newcmd = 0;
289 | increment_angle();
290 | //BEGIN Position controller
291 | if(motor.positioncontrol) {
292 | count_angle4control();
293 | motor_cmd.duty_cycle = motor.P_position * (motor_cmd.angle - motor.angle_sum); // P-position-controller
294 | if(motor_cmd.duty_cycle < 0) {
295 | motor_cmd.duty_cycle = -motor_cmd.duty_cycle;
296 | motor_cmd.dir = -1;
297 | } else {
298 | motor_cmd.dir = 1;
299 | }
300 |
301 | if(motor_cmd.duty_cycle > 1000) {
302 | motor_cmd.duty_cycle = 1000;
303 | }
304 | }
305 | //END Position controller
306 | motor_set_cmd(&motor, &motor_cmd);
307 | set_bldc_pwm(&motor);
308 | //pwmStop(&PWMD1);
309 | //palTogglePad(GPIOB, GPIOB_LEDR);
310 | }
311 | else if(motor.state == OBLDC_STATE_SENSE_INJECT) {
312 | if(motor.state_reluct == 3) {
313 | motor.angle = (motor.angle + 1) % 6 + 1;
314 | } else {
315 | if(motor_cmd.dir == -1) {
316 | motor.angle = (motor.angle + 1) % 6 + 1;
317 | } else {
318 | motor.angle = (motor.angle + 1) % 6 + 1;
319 | }
320 | //increment_angle(); increment_angle(); increment_angle(); increment_angle();
321 | }
322 | //increment_angle();increment_angle(); // Beide richtugen
323 | motor_cmd_temp.duty_cycle = 0; motor_cmd_temp.dir = motor_cmd.dir;
324 | motor_set_cmd(&motor, &motor_cmd_temp);
325 | //motor_set_cmd(&motor, &motor_cmd);
326 | set_bldc_pwm(&motor);
327 | }
328 | //chSysUnlockFromISR();
329 | }
330 |
331 |
332 | /*static void gpttimercb(GPTDriver *gptp) {
333 | msg_t msg;
334 |
335 | (void)gptp;
336 | gptcnt_t gpt_time_now;
337 | int64_t time2fire;
338 | chSysLockFromISR();
339 | //palTogglePad(GPIOB, GPIOB_LEDR);
340 | motor.time += TIMER_CB_PERIOD;
341 | time2fire = motor.time_next_commutate_cb - motor.time;
342 | if(time2fire < 100) time2fire=100;
343 | if(motor.time < motor.time_next_commutate_cb && (gptcnt_t)time2fire < TIMER_CB_PERIOD) {
344 | // Schedule next commutatetimercb
345 | //gptStartOneShotI(&GPTD4, (gptcnt_t)time2fire);
346 | }
347 | chSysUnlockFromISR();
348 | }*/
349 |
350 | static const GPTConfig gptcommutatecfg = {
351 | 1000000, /* 1MHz timer clock.*/
352 | commutatetimercb, /* Timer callback.*/
353 | 0,
354 | 0
355 | };
356 |
357 | /*static const GPTConfig gptcfg3 = {
358 | 1000000, // 1MHz timer clock.
359 | gpttimercb, // Timer callback.
360 | 0,
361 | 0
362 | };*/
363 |
364 | static inline void schedule_commutate_cb(gptcnt_t time2fire) {
365 | motor.time_next_commutate_cb = motor.time_zc + time2fire;//motor.time_next_commutate_cb = t;
366 | //if(time2fire < TIMER_CB_PERIOD) {
367 | // Schedule next commutatetimercb
368 | gptStartOneShotI(&GPTD3, time2fire);
369 | //adcStartConversionI(&ADCD1, &adc_vbat_current_group, vbat_current_samples, ADC_VBAT_CURRENT_BUF_DEPTH); // Now, not triggered
370 | // TODO: call this only when running whithout injection
371 | if(motor.state == OBLDC_STATE_RUNNING || (motor.state == OBLDC_STATE_RUNNING_SLOW) ) {
372 | adcStartConversionI(&ADCD1, &adc_vbat_current_exttrig_group, vbat_current_samples, ADC_VBAT_CURRENT_EXTTRIG_BUF_DEPTH); // triggered
373 | }
374 | //}
375 | //} // TODO: Else something went terribly wrong. Stop!
376 | }
377 |
378 | void motor_start_timer(void) {
379 | motor.time = 0;
380 | motor.time_zc = 0;
381 | motor.time_last_zc = 0;
382 | motor.time_next_commutate_cb = 0;
383 | //gptStart(&GPTD4, &gptcfg3);
384 | //gptStartContinuous(&GPTD4, TIMER_CB_PERIOD);
385 | //pwmEnableChannel(&PWMD3, 0, 1000); // to start the counter
386 | gptStart(&GPTD3, &gptcommutatecfg);
387 | //gptStartOneShot(&GPTD4, 40000);
388 | }
389 |
390 | /*
391 | * ADC streaming callback.
392 | */
393 |
394 | uint16_t yreg[(ADC_COMMUTATE_NUM_CHANNELS * ADC_COMMUTATE_BUF_DEPTH) / 2 + 1]; //[NREG+1]
395 | uint16_t* csamples;
396 | //uint16_t xreg[(ADC_COMMUTATE_NUM_CHANNELS * ADC_COMMUTATE_BUF_DEPTH) / 2 + 1]; //[NREG+1]
397 |
398 | /*
399 | * The rotor (magnets) have a permeability which causes an emf in the open phase.
400 | * The emf is zero when the rotor angle is where either no torque (e.g. 0°) is produced or the torque is maximum (e.g. at 90°).
401 | * The current ripple (determined by observing the power consumption of the ESC) is minimal at maximum torque.
402 | * At a battery voltage of 11.5V the maximal V-pp is about 3.0V
403 | */
404 |
405 | void decode_inject_pattern(void) {
406 | uint8_t u,v,w;// Is NOT u,v,w phases of the motor
407 | if(motor.dir >= 0) {
408 | u = motor.sense_inject_pattern[0]; v = motor.sense_inject_pattern[1]; w = motor.sense_inject_pattern[2];
409 | } else {// Injection sequence was called in reversed order
410 | //u = motor.sense_inject_pattern[1]; v = motor.sense_inject_pattern[2]; w = motor.sense_inject_pattern[0];
411 | u = motor.sense_inject_pattern[0]; v = motor.sense_inject_pattern[1]; w = motor.sense_inject_pattern[2];
412 | //u = motor.sense_inject_pattern[0]; v = motor.sense_inject_pattern[2]; w = motor.sense_inject_pattern[1];
413 | }
414 | if(u == 2) {
415 | if(v == 1) {
416 | if(w == 3) motor.angle4 = 1; else motor.angle4 = 0; // D
417 | } else if(v == 3) {
418 | if(w == 1) motor.angle4 = 7; else motor.angle4 = 0; // Q
419 | }
420 | } else if(v == 2) {
421 | if(u == 1) {
422 | if(w == 3) motor.angle4 = 3; else motor.angle4 = 0; // Q
423 | } else if(u == 3) {
424 | if(w == 1) motor.angle4 = 9; else motor.angle4 = 0;// D
425 | }
426 | } else if(w == 2) {
427 | if(v == 1) {
428 | if(u == 3) motor.angle4 = 11; else motor.angle4 = 0;// Q
429 | } else if(v == 3) {
430 | if(u == 1) motor.angle4 = 5; else motor.angle4 = 0; // D
431 | }
432 | } else if(u == 1) {
433 | if(v == 1) {
434 | if(w == 3) motor.angle4 = 2; else motor.angle4 = 0;
435 | } else if(v == 3) {
436 | if(w == 1) {
437 | motor.angle4 = 6;
438 | } else if(w == 3) {
439 | motor.angle4 = 4;
440 | } else motor.angle4 = 0;
441 | }
442 | } else if(u == 3) {
443 | if(v == 3) {
444 | if(w == 1) motor.angle4 = 8; else motor.angle4 = 0;
445 | } else if(v == 1) {
446 | if(w == 1) {
447 | motor.angle4 = 10;
448 | } else if(w == 3) {
449 | motor.angle4 = 12;
450 | } else motor.angle4 = 0;
451 | }
452 | }
453 | /*
454 | * When motor.dir == -1 the results of sense_inject_pattern are inverted, i.e. 1 is 3 and 3 is 1.
455 | * To get same motor.angle4 in both directions, it must be shifted by 90 deg.
456 | */
457 | if(motor.dir < 0) motor.angle4 = (motor.angle4 + 5) % 12 + 1;
458 | }
459 |
460 | int16_t y_on, y_off, sample_cnt_t_on, sample_cnt_t_off, x_old, y_old;
461 | /*
462 | * adc_commutate_inject_cb implements a 2-per-rev position detection method based on PWM injection and inductance measurement.
463 | */
464 | static void adc_commutate_inject_cb(ADCDriver *adcp, adcsample_t *buffer, size_t n) {
465 | (void)adcp;
466 | csamples = yreg;
467 | int i;
468 | uint32_t k_sample, k_zc; // Sample in the present commutation cycle
469 | uint16_t k_pwm_period;//Indicates if the pwm sample occurred at pwm-on
470 |
471 | chSysLockFromISR();
472 | sample_cnt_t_on = 0; sample_cnt_t_off = 0; y_on = 0; y_off = 0;
473 |
474 | k_sample = (ADC_COMMUTATE_BUF_DEPTH / 2) * k_cb_commutate;
475 | if(k_cb_commutate > 1) {
476 | adcStopConversionI(&ADCD1);
477 | //pwmStop(&PWMD1);
478 | for (i=0; i<(ADC_COMMUTATE_NUM_CHANNELS * ADC_COMMUTATE_BUF_DEPTH) / 2; i++ ) {// halbe puffertiefe
479 | k_pwm_period = k_sample % motor.pwm_period_ADC;
480 | if ( k_pwm_period > DROPNOISYSAMPLES && k_pwm_period < motor.pwm_t_on_ADC) { // Samples during t_on!!!
481 | sample_cnt_t_on++;
482 | y_on += buffer[i];
483 | }
484 | //else if (k_pwm_period > motor.pwm_t_on_ADC + 1 + DROPNOISYSAMPLES && k_pwm_period < motor.pwm_period_ADC) {// Samples during t_off
485 | else if (k_pwm_period > motor.pwm_t_on_ADC + DROPNOISYSAMPLES && k_pwm_period < motor.pwm_period_ADC) {// Samples during t_off
486 | sample_cnt_t_off++;
487 | y_off += buffer[i]; // Sensebridgesign
488 | }
489 | k_sample++;
490 | //csamples[i] = buffer[i]; // For debugging
491 | }
492 |
493 | if(motor.state_calibrate_leg) { //Ugly
494 | motor.u_dc = motor.u_dc2;
495 | }
496 | if (motor.invSenseSign) {
497 | y_on = -(y_on / sample_cnt_t_on - motor.u_dc);
498 | y_off = -(y_off / sample_cnt_t_off - motor.u_dc);
499 | }
500 | else {
501 | y_on = y_on / sample_cnt_t_on - motor.u_dc;
502 | y_off = y_off / sample_cnt_t_off - motor.u_dc;
503 | }
504 |
505 | if(motor.state_calibrate_leg) {
506 | //HIER den u_dc vom Anfang (Startup) nehmen!
507 | motor.offset_leg[motor.legoff] = y_on + y_off;
508 | }
509 |
510 | if(y_on + motor.dir_v_range < y_off) {
511 | motor.sense_inject_pattern[motor.state_inject] = 3;
512 | }
513 | else if(y_on > y_off + motor.dir_v_range) {
514 | motor.sense_inject_pattern[motor.state_inject] = 1;
515 | }
516 | else {
517 | motor.sense_inject_pattern[motor.state_inject] = 2;
518 | }
519 | motor.state_inject++;
520 |
521 | if(motor.state_inject < 3) {
522 | if(motor.state_inject == 1) {// reset last angle because the actual angle is unknown
523 | motor.last_angle4 = 0;
524 | }
525 | gptStartOneShotI(&GPTD3, 8);
526 | }
527 | else {
528 | // Put breakpoint here to check if motor.offset_leg[0..2] is close to zero. If not tune gain for u_dc
529 | motor.state_calibrate_leg = 0; // If this was an initial calibration, it is finished now!
530 | decode_inject_pattern();
531 | //increment_angle(); increment_angle();// Beide richtungen?
532 | motor.angle = (motor.angle + 1) % 6 + 1; // restore initial rotor position. Nur für motor.dir == 1 !!!
533 | //motor.angle=1;
534 | motor.angle4 = ((motor.angle4 - 1) + (motor.angle - 1) * 4) % 12 + 1; // correction of result of decode_inject_pattern
535 | if(motor.angle4 != 0) {// Winkel ist gültig; 50% chance dass das klappt
536 | if(motor.state_ramp == 0) { // Injection was called for the first time and the result may be wrong
537 | // The correct equation is motor.angle = ((motor.angle4 + 5) / 4) % 3 + 2; but motor.angle is incremented by 1 in schedule_commutate_cb
538 | //motor.angle = ((motor.angle4 + 5) / 4) % 3 + 1; // Nur für motor.dir == 1 !!!
539 | //motor.angle = ((motor.angle4 + 5) / 4 - 1) % 3 + 1; increment_angle(); // Worked!
540 | if(motor.dir == 1) { // fine tuning...
541 | motor.angle = ((motor.angle4 + 6) / 4 - 1) % 3 + 1; increment_angle();
542 | } else {
543 | motor.angle = ((motor.angle4 + 4) / 4 - 1) % 3 + 1; increment_angle();
544 | }
545 | motor.state = OBLDC_STATE_RUNNING_SLOW;
546 | gptStartOneShotI(&GPTD3, 8);
547 | } else if(motor.state_ramp <= 1){// Injection was called for the second time and we can check weather the first guess was good or bad
548 | if( (motor.angle4 - 1) % 4 != 0 ) { // good, angle is at Q-axis
549 | //motor.state = OBLDC_STATE_RUNNING_SLOW;
550 | //schedule_commutate_cb(5);
551 | //gptStartOneShotI(&GPTD3, 8);
552 | //TODO motor.dir = sign(pwm_duty_Cycle)
553 | //motor.dir = 1;
554 | } else { // bad, angle is at D-axis
555 | //motor.angle = (motor.angle) % 6 + 1; //Nur für motor.dir == 1 !!!
556 | increment_angle();//R
557 | }
558 | motor.state = OBLDC_STATE_RUNNING_SLOW;
559 | //schedule_commutate_cb(5);
560 | gptStartOneShotI(&GPTD3, 8);
561 | } else { // motor.state_ramp > 1 : Injection, do tracking
562 | /*
563 | * *** Position tracking method ***
564 | * Depending on the commanded and actual spinning direction one of the following conditions are triggered
565 | * in case the actual direction changes. This is tracked by setting motor.dir to the new spinning direction.
566 | * Note: In case the direction is changed while adc_commutate_cb is in the state motor.state_reluct == 1,
567 | * the motor probably stops since adc_commutate_inject_cb is only called when motor.state_reluct becomes 2.
568 | * This may sometimes occur if motor_cmd.dir != motor.dir
569 | */
570 | // Calculate true difference between angle4 and angle
571 | if(motor.dir == 1) {
572 | motor.something = ( (motor.angle4 - 1) - ((motor.angle - 1) % 3) * 4 ) % 12;
573 | motor.delta_angle4 = mod(motor.angle4 - motor.last_angle4, 12); // ACHTUNG!
574 | } else {
575 | motor.something = ( ((motor.angle - 1) % 3) * 4 - (motor.angle4 - 1) ) % 12;
576 | motor.delta_angle4 = mod(motor.last_angle4 - motor.angle4, 12); // ACHTUNG!
577 | }
578 | if(motor.something >= 6) motor.something -= 12;
579 | if(motor.delta_angle4 >= 6) motor.delta_angle4 -= 12;
580 |
581 | //if(motor.delta_angle4 < -8) motor.state = OBLDC_STATE_OFF; // KANN nicht passieren
582 |
583 | if(motor.state_reluct == 3) {// Injection was called at the end of a commutation cycle
584 | // Positive --> negative direction when positive was commanded
585 | if(motor_cmd.dir == 1 && motor.something > -4 && motor.dir == 1) {
586 | if(motor.something < 0) {
587 | motor.dir = -1; motor.dirjustchanged = 1;
588 | } else {// May this really occur???
589 | //motor.dir = -1; increment_angle();
590 | }
591 | } // Negative --> positive direction when negative was commanded
592 | else if(motor_cmd.dir == -1 && motor.something > -4 && motor.something < 0 && motor.dir == -1) {
593 | if(motor.something < 0) {
594 | motor.dir = 1; motor.dirjustchanged = 1;
595 | }
596 | } // Negative --> positive direction when positive was commanded
597 | else if(motor_cmd.dir == 1 && motor.something > -4 && motor.something < 0 && motor.dir == -1) {
598 | if(motor.something < 0) {
599 | increment_angle();increment_angle();
600 | motor.dir = 1; motor.dirjustchanged = 1;
601 | } else {
602 | //increment_angle();increment_angle();increment_angle(); motor.dir = 1;
603 | }
604 | } // Positive --> negative direction when negative was commanded
605 | else if(motor_cmd.dir == -1 && motor.something > -4 && motor.something < 0 && motor.dir == 1) {
606 | if(motor.something < 0) {
607 | increment_angle();increment_angle();
608 | motor.dir = -1; motor.dirjustchanged = 1;
609 | } else {
610 | //increment_angle();increment_angle();increment_angle();motor.dir = -1;
611 | }
612 | }
613 | else {
614 | motor.dirjustchanged = 0;
615 | }
616 | } else if(motor.state_reluct == 2 && motor.inject == 2) {// Injection was called at a zero crossing during a commutation cycle
617 | //motor.inject = 3;
618 | if(motor_cmd.dir == 1 && motor.delta_angle4 > 0 && motor.something == 0 && motor.dir == -1 && motor.dirjustchanged == 1) {
619 | // Motor is stuck in synchronous position.
620 | motor.angle = (motor.angle) % 6 + 1; motor.state_reluct = 3;
621 | motor.dirjustchanged = 0;
622 | //motor.state = OBLDC_STATE_OFF;
623 | } else if(motor_cmd.dir == 1 && motor.delta_angle4 == 0 && motor.something == 0 && motor.dir == 1 && motor.dirjustchanged == 0) {
624 | // Motor is stuck in synchronous position.
625 | //motor.angle = (motor.angle) % 6 + 1;
626 | motor.state_reluct = 3;
627 | motor.dirjustchanged = 0;
628 | //motor.state = OBLDC_STATE_OFF;
629 | } else if(motor_cmd.dir == 1 && motor.delta_angle4 <= 0 && motor.something == 0 && motor.dir == -1) {
630 | // Drehrichtng wechseln und kommutierne. motor.something == 0 vielleicht überflüssig!
631 | if(1){//motor.dirjustchanged == 0) {
632 | increment_angle();
633 | motor.dir = 1; motor.state_reluct = 3;
634 | motor.dirjustchanged = 1;
635 | }
636 | //motor.state = OBLDC_STATE_OFF;
637 | } else if(motor_cmd.dir == -1 && motor.delta_angle4 > 0 && motor.something == 0 && motor.dir == 1 && motor.dirjustchanged == 1) {
638 | // Motor is stuck in synchronous position.
639 | motor.angle = (motor.angle + 4) % 6 + 1; motor.state_reluct = 3;
640 | motor.dirjustchanged = 0;
641 | //motor.state = OBLDC_STATE_OFF;
642 | } else if(motor_cmd.dir == -1 && motor.delta_angle4 <= 0 && motor.something == 0 && motor.dir == 1) {
643 | // Drehrichtng wechseln und kommutierne. motor.something == 0 vielleicht überflüssig!
644 | if(1){//motor.dirjustchanged == 0) {
645 | increment_angle();
646 | motor.dir = -1; motor.state_reluct = 3;
647 | motor.dirjustchanged = 1;
648 | }
649 | //motor.state = OBLDC_STATE_OFF;
650 | } else {
651 | motor.dirjustchanged = 0;
652 | }
653 | // Injection beim 0-durchgang; bei callback winkel nicht erhöhen
654 | increment_angle();increment_angle();increment_angle();increment_angle();increment_angle();
655 | }
656 |
657 | /*if( (motor.angle4 - 1) % 4 == 0 ) {
658 | motor.angle = (motor.angle + 5) % 6 + 1;
659 | }*/
660 | motor.last_angle4 = motor.angle4;
661 |
662 | if(motor.state != OBLDC_STATE_OFF) {
663 | motor.state = OBLDC_STATE_RUNNING_SLOW;
664 | gptStartOneShotI(&GPTD3, 8);
665 | }
666 | }
667 | } else { // decode_inject_pattern returned motor.angle4 == 0 --> Invalid angle!!!
668 | /*
669 | * Plenty of invalid angles are read when motor_cmd.dir == 1 while everything is fine when motor_cmd.dir == -1
670 | * TODO Investigate whats wrong there...
671 | */
672 | //motor.state = OBLDC_STATE_STARTING_SENSE_1;
673 | //motor.state = OBLDC_STATE_OFF;
674 | if(motor.state_reluct == 3) {
675 | } else if(motor.state_reluct == 2 && motor.inject == 2) {
676 | increment_angle();increment_angle();increment_angle();increment_angle();increment_angle();
677 | }
678 | /*if(motor.dir == 1) { // guess that the motor keeps spinning
679 | motor.last_angle4 = (motor.last_angle4 % 12) + 1;
680 | } else {
681 | motor.last_angle4 = ((motor.last_angle4 + 10)% 12) + 1;
682 | }*/
683 | motor.state = OBLDC_STATE_RUNNING_SLOW;
684 | gptStartOneShotI(&GPTD3, 8);
685 | }
686 | }
687 | }//if(k_cb_commutate > 1)
688 |
689 | k_cb_commutate++; // k_cb_ADC++; PUT BREAKPOINT HERE
690 | chSysUnlockFromISR();
691 | }
692 |
693 |
694 | static void adc_commutate_cb(ADCDriver *adcp, adcsample_t *buffer, size_t n) {
695 | (void)adcp;
696 | csamples = yreg;
697 | int i;
698 | uint32_t k_sample, k_zc; // Sample in the present commutation cycle
699 | uint16_t k_pwm_period;//Indicates if the pwm sample occurred at pwm-on
700 |
701 | chSysLockFromISR();
702 | sample_cnt_t_on = 0; sample_cnt_t_off = 0; y_on = 0; y_off = 0;
703 |
704 | k_sample = (ADC_COMMUTATE_BUF_DEPTH / 2) * k_cb_commutate;
705 | if(k_cb_commutate > 1) { // evaluate only if k_pwm_period > DROPSTARTCOMMUTATIONSAMPLES to allow current at sensed phase to become zero
706 | for (i=0; i<(ADC_COMMUTATE_NUM_CHANNELS * ADC_COMMUTATE_BUF_DEPTH) / 2; i++ ) {// halbe puffertiefe
707 | k_pwm_period = k_sample % motor.pwm_period_ADC;
708 | if ( k_pwm_period > DROPNOISYSAMPLES && k_pwm_period < motor.pwm_t_on_ADC) { // Samples during t_on!!!
709 | sample_cnt_t_on++;
710 | y_on += buffer[i];
711 | }
712 | //else if (k_pwm_period > motor.pwm_t_on_ADC + 1 + DROPNOISYSAMPLES && k_pwm_period < motor.pwm_period_ADC) {// Samples during t_off
713 | else if (k_pwm_period > motor.pwm_t_on_ADC + DROPNOISYSAMPLES && k_pwm_period < motor.pwm_period_ADC) {// Samples during t_off
714 | sample_cnt_t_off++;
715 | y_off += buffer[i]; // Sensebridgesign
716 | }
717 | k_sample++;
718 | //csamples[i] = buffer[i]; // For debugging
719 | }
720 |
721 | if (motor.invSenseSign) {
722 | //y_on = -(buffer[i] - motor.u_dc); // Sensebridgesign
723 | y_on = -(y_on / sample_cnt_t_on - motor.u_dc);
724 | y_off = -(y_off / sample_cnt_t_off - motor.u_dc);
725 | }
726 | else {
727 | //y_on = buffer[i] - motor.u_dc;
728 | y_on = y_on / sample_cnt_t_on - motor.u_dc;
729 | y_off = y_off / sample_cnt_t_off - motor.u_dc;
730 | }
731 | /*
732 | * Low-Speed-Sensorless-Commutation-Method:
733 | * 1. Voltage is applied to the motor; i.e. the motor is in synchronous position
734 | * 2. The angle is incremented by 2, e.g. from 1 to 3
735 | * 3. The following states will be detected sequentially:
736 | * 0.: y_on > y_off + margin; motor is before maximum torque position --> go to state 1
737 | * 1.: y_on and y_off are within margin; Motor is at maximum torque position --> go to state 2
738 | * 2.: y_on+margin < y_off; motor has passed the maximum torque position
739 | * 4. Now immediately increment the angle by 1 and repeat...
740 | */
741 | if(y_on + motor.dir_v_range < y_off) {// Detect zero crossing here
742 | if(motor.state_reluct == 2) {
743 | motor.state_reluct = 3;
744 | adcStopConversionI(&ADCD1); // OK, commutate!
745 | if(motor.inject > 1) { //if(motor.state_ramp < 2) {
746 | if(motor.state_ramp < 2) motor.state_ramp++;
747 | //trigger injection sequence at the two other phases to check if angle4 refers to a D- or a Q-Axis position
748 | motor.state = OBLDC_STATE_SENSE_INJECT;
749 | motor.sense_inject_pattern[0] = 3; // Keep actually measured value // Keep zero crossing at the the actual phase
750 | motor.state_inject = 1; // Skip actual phase
751 | }
752 | motortime_zc(motor.time_next_commutate_cb + k_sample); // Write time of zero crossing - hier eigentlich zu spaet - dann stimmt aber der speed
753 | schedule_commutate_cb(50);
754 | // Problem: delta_t ist zu groß: prüfe mit Oszi!
755 | //motor.time_next_commutate_cb += k_sample - k_zc;// set correct time: add time from zero crossing to now
756 | }
757 | } else if( (y_on > y_off + motor.dir_v_range + 200) && motor.state_reluct == 2 && motor.inject == 2 && motor.state_ramp >= 2 && motor.dirjustchanged == 0) {
758 | /*
759 | * Becomes true in case the direction is reversed when zero crossing already occurred. If the motor continues in the new direction,
760 | * the next zero crossing will occur in a d-axis position and the
761 | */
762 | motor.state_reluct = 1;
763 | motor.persist_in_state_recluct_2_count = 0;
764 | adcStopConversionI(&ADCD1); //motor.state = OBLDC_STATE_OFF;
765 | if(motor.dir == 1) motor.dir = -1; else motor.dir = 1;
766 | increment_angle(); increment_angle(); increment_angle();
767 | motor.state_reluct = 3; motor.dirjustchanged = 1;
768 | schedule_commutate_cb(50);
769 | // TODO: TEST if this actually works!!!!!!!!!!!!
770 | } else if(y_on > y_off + motor.dir_v_range) {
771 | if(motor.state_reluct == 0) {
772 | motor.state_reluct = 1;
773 | }
774 | } else if (motor.persist_in_state_recluct_2_count > 1600) { // Too long in state_reluct==2 --> re-trigger injection
775 | motor.persist_in_state_recluct_2_count = 0; motor.state_reluct = 1;
776 | //adcStopConversionI(&ADCD1); motor.state = OBLDC_STATE_OFF; // Use this line to see if this is actually triggered
777 | } else {// Found zero crossing
778 | if(motor.state_reluct == 1) { // Zero crossing happened HERE!
779 | // if(motor.state_reluct == 1 && y_on < y_off) { // Zero crossing happened HERE! --> Threshold removed because it is sometimes not crossed when the motor is at standstill
780 | motor.persist_in_state_recluct_2_count = 0;
781 | motor.state_reluct = 2;
782 | //motor.u_dc2 = (y_on + y_off) / 2;
783 | k_zc = k_sample;
784 | //motortime_zc(motor.time_next_commutate_cb + k_sample); // Write time of zero crossing
785 | //if(motor.inject == 2) {
786 | //if(motor.state_ramp < 1 && motor.inject == 2) {
787 | if(motor.state_ramp < 1 || motor.inject == 2) {
788 | if(motor.state_ramp < 2) {motor.state_ramp++;}//motor.state_ramp++; // Call this sequence only once
789 | adcStopConversionI(&ADCD1);
790 | //pwmStop(&PWMD1);
791 | //trigger injection sequence at the two other phases to check if angle4 refers to a D- or a Q-Axis position
792 | motor.state = OBLDC_STATE_SENSE_INJECT;
793 | motor.sense_inject_pattern[0] = 2;// Keep zero crossing at the the actual phase
794 | motor.state_inject = 1; // Skip actual phase
795 | gptStartOneShotI(&GPTD3, 8);
796 | /*
797 | // Jetzt injection-messung machen:
798 | // ...
799 | if (...) {
800 | // wenn der winkel Richtig ist, dann alles gut und motor.angle um 1 erhöhen
801 | } else {
802 | // wenn der winkel falsch ist, dann motor.angle = (motor.angle4 + 5) / 4 + 2;
803 | motor.angle = motor.angle + 1;
804 | }
805 | */
806 | }
807 | } else if (motor.state_reluct == 2 && motor.state_ramp > 1 && motor.inject == 2) {
808 | // Count up how many cycles state_reluct==2 is active
809 | //motor.persist_in_state_recluct_2_count++;
810 | }
811 | }
812 |
813 | }//if(k_cb_commutate > 1)
814 |
815 | k_cb_commutate++; // k_cb_ADC++; PUT BREAKPOINT HERE
816 | chSysUnlockFromISR();
817 | }
818 |
819 |
820 | static void adc_commutate_fast_cb(ADCDriver *adcp, adcsample_t *buffer, size_t n) {
821 | (void)adcp;
822 |
823 | csamples = yreg;
824 | int i;
825 | uint32_t k_sample; // Sample in the present commutation cycle
826 | uint16_t k_pwm_period;//Indicates if the pwm sample occurred at pwm-on
827 |
828 | int64_t m_reg, b_reg, reg_den, k_zc;
829 |
830 | commutate_Buffer* xbuf_ptr;
831 | commutate_Buffer* ybuf_ptr;
832 |
833 | chSysLockFromISR();
834 | sample_cnt_t_on = 0; sample_cnt_t_off = 0; y_on = 0; y_off = 0;
835 | //u_dc_int = get_vbat_sample();
836 |
837 | ybuf_ptr = &ybuf;
838 | //k_start = (ADC_COMMUTATE_BUF_DEPTH / 2) * k_cb_commutate;
839 | //k_end = k_start + (ADC_COMMUTATE_NUM_CHANNELS * ADC_COMMUTATE_BUF_DEPTH) / 2;
840 | k_sample = (ADC_COMMUTATE_BUF_DEPTH / 2) * k_cb_commutate;
841 | //motor.sumy = 0; // ENTFERNEN!! Nur zum probieren!
842 | if(k_cb_commutate > 1) // evaluate only if k_pwm_period > DROPSTARTCOMMUTATIONSAMPLES to allow current at sensed phase to become zero WAR 1
843 | for (i=0; i<(ADC_COMMUTATE_NUM_CHANNELS * ADC_COMMUTATE_BUF_DEPTH) / 2; i++ ) {// halbe puffertiefe
844 | k_pwm_period = k_sample % motor.pwm_period_ADC;
845 | if ( k_pwm_period > DROPNOISYSAMPLES && k_pwm_period < motor.pwm_t_on_ADC) { // Samples during t_on!!!
846 | if (isBufferFull(ybuf_ptr)) {
847 | bufferRead(ybuf_ptr, y_old);
848 | // Decrement obsolete buffer values from sums
849 | motor.sumy -= y_old;
850 | }
851 | if (motor.invSenseSign)
852 | y_on = -(buffer[i] - motor.u_dc); // Sensebridgesign
853 | else
854 | y_on = buffer[i] - motor.u_dc;
855 | //bufferWrite(ybuf_ptr, buffer[i]);
856 | bufferWrite(ybuf_ptr, y_on);
857 | motor.sumy += y_on;
858 | }
859 | if( motor.sumy < -50 && isBufferFull(ybuf_ptr)) {// Detect zero crossing here
860 | //if(motor.state_reluct == 2 || motor.state_reluct == 1) {
861 | motor.state_reluct = 3;
862 | //motortime_zc();
863 | adcStopConversionI(&ADCD1); // OK, commutate!
864 | //pwmStop(&PWMD1);
865 | motortime_zc(motor.time_next_commutate_cb + k_sample);
866 |
867 | y_off=0;
868 | //schedule_commutate_cb( (motor.delta_t_zc + motor.last_delta_t_zc) * 2 / 5 );
869 | schedule_commutate_cb( (motor.delta_t_zc + motor.last_delta_t_zc) / 4 - 25); // Orig 10
870 | return;
871 | }
872 | k_sample++;
873 | //csamples[i] = buffer[i];
874 | }
875 | // Check for timeout
876 | if(k_sample > 10000000) {//(k_sample > 1000000) { // TIMEOUT
877 | k_sample++;
878 | adcStopConversionI(&ADCD1); // HERE breakpoint
879 | chSysUnlockFromISR();
880 | return;
881 | }
882 |
883 | k_cb_commutate++; // k_cb_ADC++; PUT BREAKPOINT HERE
884 | chSysUnlockFromISR();
885 | }
886 |
887 |
888 | static void adc_commutate_err_cb(ADCDriver *adcp, adcerror_t err) {
889 | (void)adcp;
890 | (void)err;
891 | //adc_commutate_count++;
892 | }
893 |
894 |
895 | static uint8_t halldecode[8];
896 |
897 |
898 |
899 |
900 | /**
901 | * adc_commutate_group is used for back-emf sensing to determine when the motor shall commutate.
902 | */
903 | /*static const ADCConversionGroup adc_commutate_group = {
904 | TRUE, // linear mode
905 | ADC_COMMUTATE_NUM_CHANNELS,
906 | adc_commutate_cb,
907 | adc_commutate_err_cb,
908 | 0, // ADC_CR1
909 | //0, // ADC_CR2
910 | //ADC_CR2_EXTTRIG | ADC_CR2_EXTSEL_2, // ADC_CR2: use ext event | select Timer3 TRGO event
911 | ADC_CR2_EXTTRIG, // | ADC_CR2_EXTSEL_2 | ADC_CR2_EXTSEL_1 | ADC_CR2_EXTSEL_0, // ADC_CR2: use ext event | select SWSTART event
912 | 0, // ADC_SMPR1
913 | ADC_SMPR2_SMP_AN0(ADC_SAMPLE_1P5) | ADC_SMPR2_SMP_AN1(ADC_SAMPLE_1P5) | ADC_SMPR2_SMP_AN2(ADC_SAMPLE_1P5) | ADC_SMPR2_SMP_AN4(ADC_SAMPLE_1P5) | ADC_SMPR2_SMP_AN5(ADC_SAMPLE_1P5), // ADC_SMPR2
914 | ADC_SQR1_NUM_CH(ADC_COMMUTATE_NUM_CHANNELS), // ADC_SQR1
915 | 0, // ADC_SQR2
916 | // ADC regular sequence register 3 (ADC_SQR3): U_VOLTAGE, V_VOLTAGE, W_VOLTAGE, CURRENT, CURRENTREF (see schematic)
917 | ADC_SQR3_SQ1_N(ADC_CHANNEL_IN0) | ADC_SQR3_SQ2_N(ADC_CHANNEL_IN1) | ADC_SQR3_SQ3_N(ADC_CHANNEL_IN2) | ADC_SQR3_SQ4_N(ADC_CHANNEL_IN4) | ADC_SQR3_SQ5_N(ADC_CHANNEL_IN5)// ADC_SQR3
918 | };*/
919 |
920 | static ADCConversionGroup adc_commutate_group = {
921 | TRUE, // circular mode
922 | ADC_COMMUTATE_NUM_CHANNELS,
923 | adc_commutate_cb,
924 | adc_commutate_err_cb,
925 | 0, // ADC_CR1
926 | ADC_CR2_EXTTRIG | ADC_CR2_CONT, // ADC_CR2: use ext event | select TIM1_CC1 event | Cont-mode (start once, always run)
927 | 0, // ADC_SMPR1
928 | ADC_SMPR2_SMP_AN0(ADC_SAMPLE_1P5), // ADC_SMPR2
929 | ADC_SQR1_NUM_CH(ADC_COMMUTATE_NUM_CHANNELS), // ADC_SQR1
930 | 0, // ADC_SQR2
931 | // ADC regular sequence register 3 (ADC_SQR3): U_VOLTAGE, V_VOLTAGE, W_VOLTAGE, CURRENT, CURRENTREF (see schematic)
932 | ADC_SQR3_SQ1_N(ADC_CHANNEL_IN0)// ADC_SQR3
933 | };
934 |
935 |
936 | void v_bat_current_conversion(void) {
937 | init_motor_struct(&motor); // v_bat_current_conversion wird nur aus main aufgerufen TODO: Eigene Funktion machen!
938 | adcStartConversion(&ADCD1, &adc_vbat_current_group, vbat_current_samples, ADC_VBAT_CURRENT_BUF_DEPTH);
939 | }
940 |
941 | adcsample_t* get_vbat_current_samples(void) {
942 | return vbat_current_samples;
943 | }
944 |
945 | adcsample_t get_vbat_sample(void) { // value scaled to be 50% of phase voltage sample
946 | // /4095.0 * 3 * 13.6/3.6; // convert to voltage: /4095 ADC resolution, *3 = ADC pin voltage, *13.6/3.6 = phase voltage
947 | // the voltage divider at v_bat is 1.5 and 10 kOhm
948 | // So, the transformation is 115*36 / (15*136)
949 | int i,v_scaled;
950 | int u_raw=0;
951 | int i_raw=0;
952 | int i_raw_ref=0;
953 | for(i=0; i < ADC_VBAT_CURRENT_NUM_CHANNELS*ADC_VBAT_CURRENT_BUF_DEPTH; i+=ADC_VBAT_CURRENT_NUM_CHANNELS) {
954 | u_raw += vbat_current_samples[i];
955 | i_raw += vbat_current_samples[i+1] - vbat_current_samples[i+2];
956 | i_raw_ref += vbat_current_samples[i+2];
957 | }
958 | //v_scaled = u_raw / ADC_VBAT_CURRENT_BUF_DEPTH * 4140 / 2040 / 2; // aus Bauteilen
959 | v_scaled = u_raw / ADC_VBAT_CURRENT_BUF_DEPTH * 4210 / 2040 / 2; // Nach Kalibrierung mit state_calibrate_leg
960 | motor.u_dc = v_scaled; // UGLY!
961 | motor.u_dc2 = v_scaled;
962 | motor.i_dc = i_raw / ADC_VBAT_CURRENT_BUF_DEPTH;
963 | motor.i_dc_ref = i_raw_ref / ADC_VBAT_CURRENT_BUF_DEPTH;
964 | return (adcsample_t)v_scaled;
965 | }
966 |
967 |
968 | void eval_vbat_idc(void) { // value scaled to be 50% of phase voltage sample TODO MUSS NOCH GETESTET WERDEN
969 | // /4095.0 * 3 * 13.6/3.6; // convert to voltage: /4095 ADC resolution, *3 = ADC pin voltage, *13.6/3.6 = phase voltage
970 | // the voltage divider at v_bat is 1.5 and 10 kOhm
971 | // So, the transformation is 115*36 / (15*136)
972 | int i;
973 | int u_raw_on=0;
974 | int u_raw_off=0;
975 | int i_raw_on=0;
976 | int i_raw_off=0;
977 | int16_t i_old;
978 | commutate_Buffer* ibuf_ptr;
979 | ibuf_ptr = &ibuf;
980 |
981 | sample_cnt_t_on = 0; sample_cnt_t_off = 0;
982 | for (i=0; i<(ADC_VBAT_CURRENT_EXTTRIG_NUM_CHANNELS*ADC_VBAT_CURRENT_EXTTRIG_BUF_DEPTH); i+=ADC_VBAT_CURRENT_EXTTRIG_NUM_CHANNELS ) {// halbe puffertiefe
983 | if ( i > DROPNOISYSAMPLES && i < motor.pwm_t_on_ADC) { // Samples during t_on!!!
984 | sample_cnt_t_on++;
985 | u_raw_on += vbat_current_samples[i];
986 | i_raw_on += vbat_current_samples[i+1] - motor.i_dc_ref;
987 | }
988 | else if (i > motor.pwm_t_on_ADC + DROPNOISYSAMPLES && i < motor.pwm_period_ADC) {// Samples during t_off
989 | sample_cnt_t_off++;
990 | u_raw_off += vbat_current_samples[i];
991 | i_raw_off += vbat_current_samples[i+1] - motor.i_dc_ref;
992 | }
993 | //csamples[i] = buffer[i]; // For debugging
994 | }
995 | //motor.u_dc = u_raw_on / sample_cnt_t_on * 4140 / 2040 / 2;
996 | motor.u_dc = u_raw_on / sample_cnt_t_on * 4210 / 2040 / 2;
997 | motor.i_dc = i_raw_on / sample_cnt_t_on;
998 |
999 | if (isBufferFull(ibuf_ptr)) {
1000 | bufferRead(ibuf_ptr, i_old);
1001 | // Decrement obsolete buffer values from sums
1002 | motor.i_dc_sum -= i_old;
1003 | }
1004 | bufferWrite(ibuf_ptr, motor.i_dc);
1005 | motor.i_dc_sum += motor.i_dc;
1006 | motor.i_dc_filt = motor.i_dc_sum / 6;
1007 | }
1008 |
1009 |
1010 | /*
1011 | * Generic PWM for BLDC motor operation.
1012 | * duty_cycle in percent * 100
1013 | * Period in microseconds
1014 | */
1015 | static const uint8_t pin_leg_enable[3] = {
1016 | GPIOB_U_NDTS, GPIOB_V_NDTS, GPIOB_W_NDTS
1017 | };
1018 | void set_bldc_pwm(motor_s* m) { // Mache neu mit motor_struct (pointer)
1019 | int angle, t_on, period, inv_duty_cycle;
1020 | uint8_t legp, legn, legoff; // Positive and negative PWM leg
1021 | angle = m->angle;
1022 | t_on = m->pwm_t_on;
1023 | period = m->pwm_period;
1024 |
1025 | adcStopConversion(&ADCD1);
1026 | //palClearPad(GPIOB, GPIOB_U_NDTS); palClearPad(GPIOB, GPIOB_V_NDTS); palClearPad(GPIOB, GPIOB_W_NDTS);
1027 | //pwmStop(&PWMD1);
1028 |
1029 | if (m->state == OBLDC_STATE_RUNNING) {
1030 | adc_commutate_group.end_cb = adc_commutate_fast_cb;
1031 | }
1032 | else if(m->state == OBLDC_STATE_RUNNING_SLOW) {
1033 | adc_commutate_group.end_cb = adc_commutate_cb;
1034 | }
1035 | else if(m->state == OBLDC_STATE_SENSE_INJECT) {
1036 | adc_commutate_group.end_cb = adc_commutate_inject_cb;
1037 | }
1038 | else if (m->state == OBLDC_STATE_OFF || m->state == OBLDC_STATE_CATCHING) { // PWM OFF!
1039 | angle = 0;
1040 | }
1041 | else if(m->state == OBLDC_STATE_STARTING_SENSE_1) {
1042 | }
1043 | else {
1044 | angle = 0;
1045 | }
1046 | //genpwmcfg.period = PWM_CLOCK_FREQUENCY / frequency
1047 | //genpwmcfg.CR1 |= TIM_CR1_CMS_0;
1048 | if (angle < 1 || angle > 6) { // no angle --> all legs to gnd
1049 | //pwmStart(&PWMD1, &genpwmcfg); // PWM signal generation
1050 | //pwmEnableChannel(&PWMD1, 0, PWM_PERCENTAGE_TO_WIDTH(&PWMD1, 10000));
1051 | legp = 3;
1052 | legn = 3;
1053 | palClearPad(GPIOB, GPIOB_U_NDTS);
1054 | //pwmEnableChannel(&PWMD1, 1, PWM_PERCENTAGE_TO_WIDTH(&PWMD1, 10000));
1055 | palClearPad(GPIOB, GPIOB_V_NDTS);
1056 | //pwmEnableChannel(&PWMD1, 2, PWM_PERCENTAGE_TO_WIDTH(&PWMD1, 10000));
1057 | palClearPad(GPIOB, GPIOB_W_NDTS);
1058 | pwmStop(&PWMD1);
1059 | } else {
1060 | if (angle == 1) { // sample W_VOLTAGE, triggered by U_PWM
1061 | adc_commutate_group.cr2 = ADC_CR2_EXTTRIG | ADC_CR2_CONT; // ADC_CR2: select TIM1_CC1 event
1062 | adc_commutate_group.smpr2 = ADC_SMPR2_SMP_AN2(ADC_SAMPLE_1P5);
1063 | adc_commutate_group.sqr3 = ADC_SQR3_SQ1_N(ADC_CHANNEL_IN2); // W_VOLTAGE
1064 | legp = 0; legn = 1; legoff=2;
1065 | } else if (angle == 2) { // sample U_VOLTAGE, triggered by W_PWM
1066 | adc_commutate_group.cr2 = ADC_CR2_EXTTRIG | ADC_CR2_EXTSEL_1 | ADC_CR2_CONT; //ADC_CR2: select TIM1_CC3 event
1067 | adc_commutate_group.smpr2 = ADC_SMPR2_SMP_AN0(ADC_SAMPLE_1P5);
1068 | adc_commutate_group.sqr3 = ADC_SQR3_SQ1_N(ADC_CHANNEL_IN0); // U_VOLTAGE
1069 | legp = 2; legn = 1; legoff=0;
1070 | } else if (angle == 3) { // sample V_VOLTAGE, triggered by W_PWM
1071 | adc_commutate_group.cr2 = ADC_CR2_EXTTRIG | ADC_CR2_EXTSEL_1 | ADC_CR2_CONT; //ADC_CR2: select TIM1_CC3 event
1072 | adc_commutate_group.smpr2 = ADC_SMPR2_SMP_AN1(ADC_SAMPLE_1P5);
1073 | adc_commutate_group.sqr3 = ADC_SQR3_SQ1_N(ADC_CHANNEL_IN1); // V_VOLTAGE
1074 | legp = 2; legn = 0; legoff=1;
1075 | } else if (angle == 4) { // sample W_VOLTAGE, triggered by V_PWM
1076 | adc_commutate_group.cr2 = ADC_CR2_EXTTRIG | ADC_CR2_EXTSEL_0 | ADC_CR2_CONT; //ADC_CR2: select TIM1_CC2 event
1077 | adc_commutate_group.smpr2 = ADC_SMPR2_SMP_AN2(ADC_SAMPLE_1P5);
1078 | adc_commutate_group.sqr3 = ADC_SQR3_SQ1_N(ADC_CHANNEL_IN2); // W_VOLTAGE
1079 | legp = 1; legn = 0; legoff=2;
1080 | } else if (angle == 5) { // sample U_VOLTAGE, triggered by V_PWM
1081 | adc_commutate_group.cr2 = ADC_CR2_EXTTRIG | ADC_CR2_EXTSEL_0 | ADC_CR2_CONT; //ADC_CR2: select TIM1_CC2 event
1082 | adc_commutate_group.smpr2 = ADC_SMPR2_SMP_AN0(ADC_SAMPLE_1P5);
1083 | adc_commutate_group.sqr3 = ADC_SQR3_SQ1_N(ADC_CHANNEL_IN0); // U_VOLTAGE
1084 | legp = 1; legn = 2; legoff=0;
1085 | } else if (angle == 6) { // sample V_VOLTAGE, triggered by U_PWM
1086 | adc_commutate_group.cr2 = ADC_CR2_EXTTRIG | ADC_CR2_CONT; //ADC_CR2: select TIM1_CC1 event
1087 | adc_commutate_group.smpr2 = ADC_SMPR2_SMP_AN1(ADC_SAMPLE_1P5);
1088 | adc_commutate_group.sqr3 = ADC_SQR3_SQ1_N(ADC_CHANNEL_IN1); // V_VOLTAGE
1089 | legp = 0; legn = 2; legoff=1;
1090 | }
1091 | m->legoff = legoff; // this leg is used for sensing now
1092 | adc_vbat_current_exttrig_group.cr2 = adc_commutate_group.cr2;
1093 |
1094 | //adcStart(&ADCD1, &adc_commutate_group);
1095 | int i,x;
1096 | genpwmcfg.channels[legp].mode = PWM_OUTPUT_ACTIVE_HIGH;
1097 | if (m->pwm_mode == PWM_MODE_ANTIPHASE)
1098 | genpwmcfg.channels[legn].mode = PWM_OUTPUT_ACTIVE_LOW;
1099 | else
1100 | genpwmcfg.channels[legn].mode = PWM_OUTPUT_ACTIVE_HIGH;
1101 |
1102 | palClearPad(GPIOB, GPIOB_U_NDTS); palClearPad(GPIOB, GPIOB_V_NDTS); palClearPad(GPIOB, GPIOB_W_NDTS);
1103 | pwmStop(&PWMD1);
1104 | if (m->state == OBLDC_STATE_RUNNING || m->state == OBLDC_STATE_RUNNING_SLOW || m->state == OBLDC_STATE_SENSE_INJECT) {
1105 | k_cb_commutate = 0;
1106 | genpwmcfg.period = period;
1107 | //BEGIN TEST
1108 | /* Test configuration: sample the PWM on the active leg
1109 | adc_commutate_group.cr2 = ADC_CR2_EXTTRIG | ADC_CR2_CONT; // ADC_CR2: use ext event | select TIM1_CC1 event
1110 | adc_commutate_group.smpr2 = ADC_SMPR2_SMP_AN0(ADC_SAMPLE_1P5);
1111 | adc_commutate_group.sqr3 = ADC_SQR3_SQ1_N(ADC_CHANNEL_IN0); // U_VOLTAGE
1112 | genpwmcfg.channels[0].mode = PWM_OUTPUT_ACTIVE_HIGH;*/
1113 | //END TEST
1114 | adcStartConversion(&ADCD1, &adc_commutate_group, commutatesamples, ADC_COMMUTATE_BUF_DEPTH);
1115 | //pwmStart(&PWMD1, &genpwmcfg); // PWM signal generation
1116 | //pwmEnableChannel(&PWMD1, 0, t_on); // TEST
1117 | if (m->pwm_mode == PWM_MODE_ANTIPHASE) {
1118 | pwmStart(&PWMD1, &genpwmcfg); // PWM signal generation
1119 | pwmEnableChannel(&PWMD1, legp, t_on);
1120 | pwmEnableChannel(&PWMD1, legn, t_on);
1121 | } // PWM_MODE_SINGLEPHASE not supported in STATE_RUNNING
1122 | //ADC1->CR2 = ADC1->CR2 | ADC_CR2_SWSTART; // Software trigger ADC conversion (NOT WORKING YET)
1123 | } else if (m->state == OBLDC_STATE_STARTING_SYNC || m->state == OBLDC_STATE_STARTING_SENSE_1) {
1124 | genpwmcfg.period = PWM_CLOCK_FREQUENCY / PWM_DEFAULT_FREQUENCY;
1125 | //inv_duty_cycle = 10000-duty_cycle;
1126 | if (m->pwm_mode == PWM_MODE_ANTIPHASE) {
1127 | pwmStart(&PWMD1, &genpwmcfg); // PWM signal generation
1128 | pwmEnableChannel(&PWMD1, legp, t_on);
1129 | pwmEnableChannel(&PWMD1, legn, t_on);
1130 | } else if (m->pwm_mode == PWM_MODE_SINGLEPHASE) {
1131 | pwmStart(&PWMD1, &genpwmcfg); // PWM signal generation
1132 | pwmEnableChannel(&PWMD1, legp, t_on);
1133 | }
1134 | //pwmStart(&PWMD1, &genpwmcfg); // PWM signal generation
1135 | } else {
1136 | //pwmEnableChannel(&PWMD1, table_angle2leg[angle], PWM_PERCENTAGE_TO_WIDTH(&PWMD1, 0));
1137 | }
1138 | palSetPad(GPIOB, pin_leg_enable[legp]);
1139 | palSetPad(GPIOB, pin_leg_enable[legn]);
1140 | }
1141 | }
1142 |
1143 |
1144 | void set_pwm_antiphase(int t_on, uint8_t legp, uint8_t legn) {
1145 | genpwmcfg.channels[legp].mode = PWM_OUTPUT_ACTIVE_HIGH;
1146 | genpwmcfg.channels[legn].mode = PWM_OUTPUT_ACTIVE_LOW;
1147 | pwmStart(&PWMD1, &genpwmcfg); // PWM signal generation
1148 | pwmEnableChannel(&PWMD1, legp, t_on);
1149 | pwmEnableChannel(&PWMD1, legn, t_on);
1150 | palSetPad(GPIOB, pin_leg_enable[legp]);
1151 | palSetPad(GPIOB, pin_leg_enable[legn]);
1152 | }
1153 |
--------------------------------------------------------------------------------
/src/obldcpwm.h:
--------------------------------------------------------------------------------
1 | /*
2 | * pwm.h
3 | *
4 | * Created on: 22.05.2014
5 | * Author: joerg
6 | */
7 |
8 | #ifndef OBLDCPWM_H_
9 | #define OBLDCPWM_H_
10 |
11 | #include "obldcadc.h"
12 |
13 | // besser aufgehoben im reglerteil -> simulation
14 |
15 |
16 |
17 | typedef enum {
18 | OBLDC_STATE_OFF = 0,
19 | OBLDC_STATE_STARTING_SYNC,
20 | OBLDC_STATE_STARTING_SENSE_1,
21 | OBLDC_STATE_CATCHING,
22 | OBLDC_STATE_SENSE_INJECT,
23 | //OBLDC_STATE_RUNNING_INJECT,
24 | OBLDC_STATE_RUNNING_SLOW,
25 | OBLDC_STATE_RUNNING,
26 | OBLDC_STATE_SIGNALGENERATOR
27 | } obldc_state;
28 |
29 | typedef enum {
30 | PWM_MODE_SINGLEPHASE, // one phase pulses, one phase low side on, one phase open: DANGEROUS when braking and zero crossings
31 | PWM_MODE_ANTIPHASE, // inverted pulses to two phases, one phase open
32 | PWM_MODE_ONEPULSE // One pulse per commutation, appropriate for very high motor speeds
33 | } obldc_pwm_mode;
34 |
35 | typedef enum {
36 | FAULT_NONE = 0,
37 | FAULT_OVER_VOLTAGE,
38 | FAULT_UNDER_VOLTAGE,
39 | FAULT_OVER_CURRENT
40 | } obldc_fault_code;
41 |
42 | typedef struct {
43 | int16_t duty_cycle; // Duty cycle 100%=10000
44 | int16_t dir;
45 | int16_t dir_control;
46 | int16_t angle; // When positioncontrol == true
47 | int8_t newcmd;
48 | } motor_cmd_s;
49 |
50 | typedef struct {
51 | obldc_state state;
52 | obldc_pwm_mode pwm_mode;
53 | int pwm_d; // Duty cycle -10000 < d < 10000
54 | int pwm_t_on; // in timer clock ticks
55 | int pwm_period; // in timer clock ticks
56 | int pwm_t_on_ADC; // in ADC clock ticks
57 | int pwm_period_ADC;
58 | int16_t angle, angle4, last_angle4, delta_angle4;
59 | int16_t last_angle; // used for proper counting of angle_sum (quick'n dirty)
60 | int32_t angle_sum; // absolute angle used for position control loops
61 | uint8_t positioncontrol; // True when position control is enabled
62 | int16_t P_position; // Gain of the position controller
63 | int dir;
64 | uint8_t dirjustchanged;
65 | int16_t dir_v_range;
66 | uint8_t sense_inject_pattern[3];
67 | uint8_t state_inject, state_ramp, inject;
68 | int16_t u_dc, u_dc2, u_dc_filt;
69 | int16_t i_dc, i_dc_ref, i_dc_filt, i_dc_sum;
70 | uint8_t legoff; // id of the inverter leg which is used fo sensing now
71 | int16_t offset_leg[3]; // calibration of the voltage sensors
72 | uint8_t state_calibrate_leg; // do voltage divider calibration when 1 (motor must be at standstill)
73 | uint8_t state_reluct; // 0=unknown
74 | uint16_t persist_in_state_recluct_2_count;
75 | int64_t time; // Motor time in usec
76 | int64_t time_zc, time_last_zc;
77 | int64_t time_next_commutate_cb;
78 | uint16_t delta_t_zc, last_delta_t_zc;
79 | int32_t sumy;
80 | //int64_t sumx, sumx2, sumxy, sumy, sumy2;
81 | uint8_t invSenseSign;// True when voltage must be inverted
82 | int16_t something;
83 | } motor_s;
84 |
85 | #define OBLDC_DIR_V_RANGE 300 // Range for detection of voltage zero crossing in the inductance measurement
86 | //#define OBLDC_DIR_V_RANGE 80 // Threshold for Lima
87 | //#define OBLDC_DIR_V_RANGE 40 // Threshold for Nema 34, 3-phase stepper motor
88 | //#define OBLDC_DIR_V_RANGE 700 // Threshold for Hacker A200-8
89 | //#define OBLDC_DIR_V_RANGE 160 // Threshold for amaxrc.de AMAX GOLD G2822-1200kV
90 |
91 | #define OBLDC_TRANSITION_RUNNING_SLOW_2_RUNNING 500 // Lima: 10000
92 | #define OBLDC_TRANSITION_RUNNING_2_RUNNING_SLOW 600
93 | #define OBLDC_TRANSITION_DEACTIVATE_INJECTION 2000 // Lima: 12000
94 |
95 |
96 | #define OBLDC_PWM_SWITCH_FREQUENCY_MIN 50000 // lowest switching frequency [Hz]
97 | #define OBLDC_PWM_SWITCH_FREQUENCY_MAX 40000 // highest switching frequency [Hz]
98 | #define OBLDC_PWM_PWM_MODE PWM_MODE_SINGLEPHASE // Default PWM mode
99 | #define OBLDC_PWM_MIN_DUTY_CYCLE 0.02 // Minimum duty cycle
100 | #define OBLDC_PWM_MAX_DUTY_CYCLE 8000 // Maximum duty cycle
101 |
102 | #define OBLDC_MIN_CATCH_VOLTAGE_OBSOLETE 360 // 1V minimum voltage to evaluate for motor position catching; /4095 ADC resolution, *3 = ADC pin voltage, *13.6/3.6 = phase voltage TODO: Check max ADC voltage 3V or 3.3V?
103 |
104 |
105 |
106 |
107 |
108 | void motor_start_timer(void);
109 | inline int64_t motortime_now(void);
110 | motor_s* get_motor_ptr(void);
111 | void set_bldc_pwm(motor_s* m);
112 | void motor_set_cmd(motor_s* m, motor_cmd_s* cmd);
113 | void set_bldc_pwm_adc(int angle, int duty_cycle, int period);
114 | void startcatchmodePWM(void);
115 | void init_motor_struct(motor_s* motor);
116 | void decode_inject_pattern(void);
117 | void v_bat_current_conversion(void);
118 | adcsample_t get_vbat_sample(void);
119 | void eval_vbat_idc(void);
120 |
121 | void increment_angle_functioncall(void);
122 | void set_pwm_antiphase(int t_on, uint8_t legp, uint8_t legn);
123 |
124 |
125 | #endif /* OBLDCPWM_H_ */
126 |
--------------------------------------------------------------------------------
/src/ringbuffer.h:
--------------------------------------------------------------------------------
1 | /* Philip Thrasher's Crazy Awesome Ring Buffer Macros!
2 | *
3 | * Below you will find some naughty macros for easy owning and manipulating
4 | * generic ring buffers. Yes, they are slightly evil in readability, but they
5 | * are really fast, and they work great.
6 | *
7 | * Example usage:
8 | *
9 | * #include
10 | *
11 | * // So we can use this in any method, this gives us a typedef
12 | * // named 'intBuffer'.
13 | * ringBuffer_typedef(int, intBuffer);
14 | *
15 | * int main() {
16 | * // Declare vars.
17 | * intBuffer myBuffer;
18 | *
19 | * bufferInit(myBuffer,1024,int);
20 | *
21 | * // We must have the pointer. All of the macros deal with the pointer.
22 | * // (except for init.)
23 | * intBuffer* myBuffer_ptr;
24 | * myBuffer_ptr = &myBuffer;
25 | *
26 | * // Write two values.
27 | * bufferWrite(myBuffer_ptr,37);
28 | * bufferWrite(myBuffer_ptr,72);
29 | *
30 | * // Read a value into a local variable.
31 | * int first;
32 | * bufferRead(myBuffer_ptr,first);
33 | * assert(first == 37); // true
34 | *
35 | * int second;
36 | * bufferRead(myBuffer_ptr,second);
37 | * assert(second == 72); // true
38 | *
39 | * return 0;
40 | * }
41 | *
42 | */
43 |
44 | #ifndef _ringbuffer_h
45 | #define _ringbuffer_h
46 |
47 | #define ringBuffer_typedef(T, NAME) \
48 | typedef struct { \
49 | int size; \
50 | int start; \
51 | int end; \
52 | T* elems; \
53 | } NAME
54 |
55 | #define bufferInit(BUF, S, T) \
56 | BUF.size = S+1; \
57 | BUF.start = 0; \
58 | BUF.end = 0; \
59 | BUF.elems = (T*)calloc(BUF.size, sizeof(T))
60 |
61 | #define bufferInitStatic(BUF, S) \
62 | BUF.size = S+1; \
63 | BUF.start = 0; \
64 | BUF.end = 0
65 |
66 | #define bufferDestroy(BUF) free(BUF->elems)
67 | #define nextStartIndex(BUF) ((BUF->start + 1) % BUF->size)
68 | #define nextEndIndex(BUF) ((BUF->end + 1) % BUF->size)
69 | #define isBufferEmpty(BUF) (BUF->end == BUF->start)
70 | #define isBufferFull(BUF) (nextEndIndex(BUF) == BUF->start)
71 |
72 | #define bufferWrite(BUF, ELEM) \
73 | BUF->elems[BUF->end] = ELEM; \
74 | BUF->end = (BUF->end + 1) % BUF->size; \
75 | if (isBufferEmpty(BUF)) { \
76 | BUF->start = nextStartIndex(BUF); \
77 | }
78 |
79 | #define bufferRead(BUF, ELEM) \
80 | ELEM = BUF->elems[BUF->start]; \
81 | BUF->start = nextStartIndex(BUF);
82 |
83 | #endif
84 |
--------------------------------------------------------------------------------
/src/uart_scp.c:
--------------------------------------------------------------------------------
1 | /*
2 | * uart_scp.c
3 | *
4 | * Created on: Jan 4, 2014
5 | * Author: kjell
6 | */
7 |
8 | #include "ch.h"
9 | #include "hal.h"
10 | #include "uart.h"
11 | #include "uart_scp.h"
12 | #include "obldcpwm.h"
13 |
14 | uint8_t rxBuffer[SCP_PACKET_LENGTH];
15 | uint8_t txBuffer[SCP_PACKET_LENGTH];
16 |
17 | extern motor_s motor; // Motor-struct from obldcpwm.c
18 | extern motor_cmd_s motor_cmd;
19 |
20 | uint8_t crc8(uint8_t *data_in, uint8_t number_of_bytes_to_read) {
21 | uint8_t crc;
22 | uint8_t loop_count;
23 | uint8_t bit_counter;
24 | uint8_t data;
25 | uint8_t feedback_bit;
26 |
27 | crc = CRC8INIT;
28 |
29 | for (loop_count = 0; loop_count != number_of_bytes_to_read; loop_count++) {
30 | data = data_in[loop_count];
31 |
32 | bit_counter = 8;
33 | do {
34 | feedback_bit = (crc ^ data) & 0x01;
35 |
36 | if (feedback_bit == 0x01) {
37 | crc = crc ^ CRC8POLY;
38 | }
39 | crc = (crc >> 1) & 0x7F;
40 | if (feedback_bit == 0x01) {
41 | crc = crc | 0x80;
42 | }
43 |
44 | data = data >> 1;
45 | bit_counter--;
46 |
47 | } while (bit_counter > 0);
48 | }
49 |
50 | return crc;
51 | }
52 |
53 | /*
54 | * This callback is invoked when a transmission buffer has been completely
55 | * read by the driver.
56 | */
57 | static void txend1(UARTDriver *uartp) {
58 | (void)uartp;
59 | }
60 |
61 | /*
62 | * This callback is invoked when a transmission has physically completed.
63 | */
64 | static void txend2(UARTDriver *uartp) {
65 | (void)uartp;
66 | }
67 |
68 | /*
69 | * This callback is invoked on a receive error, the errors mask is passed
70 | * as parameter.
71 | */
72 | static void rxerr(UARTDriver *uartp, uartflags_t e) {
73 | (void)uartp;
74 | (void)e;
75 | }
76 |
77 | /*
78 | * This callback is invoked when a character is received but the application
79 | * was not ready to receive it, the character is passed as parameter.
80 | */
81 | static void rxchar(UARTDriver *uartp, uint16_t c) {
82 | (void)uartp;
83 | (void)c;
84 | }
85 |
86 | /*
87 | * This callback is invoked when a receive buffer has been completely written.
88 | */
89 | static void rxend(UARTDriver *uartp) {
90 | (void)uartp;
91 |
92 | //chSysLockFromISR(); // commutation is disturbed when called
93 | uint16_t temp_uint16;
94 | uint8_t crc = crc8(rxBuffer, SCP_PACKET_LENGTH - 1);
95 |
96 |
97 | if (crc == rxBuffer[7]) {
98 | switch (rxBuffer[0]) {
99 |
100 | case SCP_LEDRED:
101 | if (rxBuffer[1] == 0x00) {
102 | //palClearPad(GPIOC, GPIOC_LED4); //STM32F0Discovery
103 | palClearPad(GPIOB, GPIOB_LEDR); //Strip v2
104 | txBuffer[0] = SCP_ACK;
105 | }
106 | else if (rxBuffer[1] == 0xFF) {
107 | //palSetPad(GPIOC, GPIOC_LED4); //STM32F0Discovery
108 | palSetPad(GPIOB, GPIOB_LEDR); //Strip v2
109 | txBuffer[0] = SCP_ACK;
110 | }
111 | else {
112 | txBuffer[0] = SCP_NACK;
113 | }
114 | break;
115 |
116 | case SCP_LEDGREEN:
117 | if (rxBuffer[1] == 0x00) {
118 | //palClearPad(GPIOC, GPIOC_LED3); //STM32F0Discovery
119 | palClearPad(GPIOB, GPIOB_LEDG); //Strip v2
120 | txBuffer[0] = SCP_ACK;
121 | }
122 | else if (rxBuffer[1] == 0xFF) {
123 | //palSetPad(GPIOC, GPIOC_LED3); //STM32F0Discovery
124 | palSetPad(GPIOB, GPIOB_LEDG); //Strip v2
125 | txBuffer[0] = SCP_ACK;
126 | }
127 | else {
128 | txBuffer[0] = SCP_NACK;
129 | }
130 | break;
131 | case SCP_SIGNALGENERATOR_BIPOLARPWM:
132 | if(motor.state == OBLDC_STATE_OFF || OBLDC_STATE_SIGNALGENERATOR) {
133 | motor.state = OBLDC_STATE_SIGNALGENERATOR;
134 | temp_uint16 = (uint16_t)(rxBuffer[1] << 8) + rxBuffer[2];
135 | if(temp_uint16 > OBLDC_PWM_MAX_DUTY_CYCLE) {
136 | motor_cmd.duty_cycle = OBLDC_PWM_MAX_DUTY_CYCLE;
137 | }
138 | else {
139 | motor_cmd.duty_cycle = temp_uint16;
140 | }
141 | motor_cmd.dir = 1;
142 | motor_set_cmd( &motor, &motor_cmd );
143 | set_pwm_antiphase(motor.pwm_t_on, 0, 1);
144 | }
145 | txBuffer[0] = SCP_ACK;
146 | break;
147 | case SCP_MOTORSTATE:
148 | if (rxBuffer[1] == 0x00) {
149 | motor.state = OBLDC_STATE_OFF;
150 | } else {
151 | if(motor.state == OBLDC_STATE_OFF) {
152 | motor.state = OBLDC_STATE_STARTING_SENSE_1;
153 | }
154 | }
155 | txBuffer[0] = SCP_ACK;
156 | txBuffer[1] = (uint8_t)motor.state;
157 | //txBuffer[1] = (uint8_t)motor.dirjustchanged;
158 | //txBuffer[1] = (uint8_t)motor.state_reluct;
159 | txBuffer[2] = (uint8_t)(motor.delta_t_zc >> 8); // High byte
160 | txBuffer[3] = (uint8_t)(motor.delta_t_zc); // Low byte
161 | txBuffer[4] = (uint8_t)(motor.u_dc/10);//((motor.u_dc*100)/1630);
162 | //txBuffer[4] = (uint8_t)(motor.dir+1);//((motor.u_dc*100)/1630);
163 | if (motor.u_dc2<0) motor.u_dc2 = -motor.u_dc2;
164 | //txBuffer[5] = (uint8_t)(motor.u_dc2);//((motor.u_dc*100)/1630);
165 | //txBuffer[5] = (uint8_t)(motor.i_dc_filt / 4);
166 | txBuffer[5] = (uint8_t)(motor.delta_angle4+20);
167 | //txBuffer[6] = (uint8_t)(motor.i_dc_ref / 4);
168 | //txBuffer[6] = (uint8_t)(motor.u_dc);
169 | break;
170 | case SCP_SETDUTYCYCLE:
171 | //if(rxBuffer[1]>7) rxBuffer[1] = 7;
172 | //motor.dir = 1;
173 | motor.dir_v_range = OBLDC_DIR_V_RANGE;
174 | temp_uint16 = (uint16_t)(rxBuffer[1] << 8) + rxBuffer[2];
175 | /*if(temp_uint16 >= 0) {
176 | motor.dir = 1;// motor.dir = 1; //TODO: bis das python script geht
177 | } else {
178 | motor.dir = -1;
179 | temp_int16 = -temp_int16;
180 | }*/
181 | if(temp_uint16 > OBLDC_PWM_MAX_DUTY_CYCLE) {
182 | motor_cmd.duty_cycle = OBLDC_PWM_MAX_DUTY_CYCLE;
183 | }
184 | else {
185 | motor_cmd.duty_cycle = temp_uint16;
186 | }
187 |
188 | if(motor.dir == 0) {
189 | motor.dir = motor_cmd.dir;
190 | }
191 |
192 | txBuffer[0] = SCP_ACK;
193 | break;
194 | case SCP_DIRECTION:
195 | if (rxBuffer[1] == 0x00) {
196 | motor_cmd.dir = -1;
197 | motor_cmd.dir_control = -1;
198 | txBuffer[0] = SCP_ACK;
199 | }
200 | else if (rxBuffer[1] == 0xFF) {
201 | motor_cmd.dir = 1;
202 | motor_cmd.dir_control = 1;
203 | txBuffer[0] = SCP_ACK;
204 | }
205 | else {
206 | txBuffer[0] = SCP_NACK;
207 | }
208 | break;
209 | case SCP_POSITIONCONTROL:
210 | if (rxBuffer[1] == 0x00) {
211 | motor.positioncontrol = 0;
212 | txBuffer[0] = SCP_ACK;
213 | }
214 | else if (rxBuffer[1] == 0xFF) {
215 | motor.positioncontrol = 1;
216 | txBuffer[0] = SCP_ACK;
217 | motor_cmd.angle = 0;
218 | motor_cmd.dir_control = motor_cmd.dir;
219 | motor.angle_sum = 0;
220 | motor_cmd.angle = 0;
221 | }
222 | else {
223 | txBuffer[0] = SCP_NACK;
224 | }
225 | break;
226 | case SCP_ANGLE:
227 | motor_cmd.newcmd = 1; // Wird in obldc_catchmotor ausgewertet. Funzt noch nicht.
228 | temp_uint16 = (uint16_t)(rxBuffer[1] << 8) + rxBuffer[2];
229 | if(temp_uint16 > 30000) {
230 | motor_cmd.angle = 30000;
231 | }
232 | else {
233 | motor_cmd.angle = temp_uint16;
234 | }
235 | if(motor.dir == 0) {
236 | motor.dir = motor_cmd.dir;
237 | }
238 | txBuffer[0] = SCP_ACK;
239 | break;
240 | }
241 |
242 |
243 | txBuffer[7] = crc8(txBuffer, SCP_PACKET_LENGTH - 1);
244 | uartStartSendI(&UARTD1, SCP_PACKET_LENGTH, txBuffer);
245 | uartStartReceiveI(&UARTD1, SCP_PACKET_LENGTH, rxBuffer);
246 |
247 | //chSysUnlockFromISR();
248 | }
249 | }
250 |
251 | /*
252 | * UART driver configuration structure.
253 | */
254 | static UARTConfig uart_cfg_1 = {txend1, txend2, rxend, rxchar, rxerr, 9600, 0,
255 | USART_CR2_LINEN, 0};
256 |
257 | void uartSendACK(void) {
258 | txBuffer[0] = SCP_ACK;
259 | uartStartSend(&UARTD1, 1, txBuffer);
260 | }
261 |
262 |
263 | void uartSCPInit(void) {
264 | /*
265 | * * Activates the serial driver 1
266 | * */
267 | //palSetPadMode(GPIOB, GPIOB_USART_TX, PAL_MODE_ALTERNATE(0));
268 | //palSetPadMode(GPIOB, GPIOB_USART_RX, PAL_MODE_ALTERNATE(0));
269 | uartStart(&UARTD1, &uart_cfg_1);
270 | /*
271 | * * Initiate RX and wait for message
272 | * */
273 | uartStartReceive(&UARTD1, SCP_PACKET_LENGTH, &rxBuffer[0]);
274 | }
275 |
--------------------------------------------------------------------------------
/src/uart_scp.h:
--------------------------------------------------------------------------------
1 | /*
2 | * uart_scp.h
3 | *
4 | * Created on: Jan 4, 2014
5 | * Author: kjell
6 | */
7 |
8 | /*
9 | * Packet structure
10 | *
11 | * Byte 0: Command
12 | * Byte 1: User0
13 | * Byte 2: User1
14 | * Byte 3: User2
15 | * Byte 4: User3
16 | * Byte 5: User4
17 | * Byte 6: User5
18 | * Byte 7: CRC8
19 | */
20 |
21 | #ifndef UART_SCP_H_
22 | #define UART_SCP_H_
23 |
24 | #define CRC8INIT 0x00
25 | #define CRC8POLY 0x07
26 |
27 | #define SCP_ACK_TIMEOUT_MS 100
28 | #define SCP_PACKET_LENGTH 8
29 |
30 | #define SCP_STATUS 0x00
31 | #define SCP_ACK 0x01
32 | #define SCP_NACK 0x02
33 |
34 | /*
35 | * User0 is used to indicate Led on or off
36 | * User0 = 0x00 : OFF
37 | * User0 = 0xFF : ON
38 | */
39 | #define SCP_LEDRED 0xF0
40 | #define SCP_LEDGREEN 0xF1
41 | #define SCP_MOTORSTATE 0xF2
42 | #define SCP_SETDUTYCYCLE 0xF3
43 | #define SCP_DIRECTION 0xF4
44 | #define SCP_POSITIONCONTROL 0xF5
45 | #define SCP_ANGLE 0xF6
46 | #define SCP_SIGNALGENERATOR_BIPOLARPWM 0xF7
47 |
48 | void uartSendACK(void);
49 | void uartSCPInit(void);
50 |
51 | #endif /* UART_SCP_H_ */
52 |
--------------------------------------------------------------------------------