file transfer commit

This commit is contained in:
Blizzard Finnegan 2021-12-16 20:39:50 -05:00
commit 7659668b1f
99 changed files with 10717 additions and 0 deletions

View file

@ -0,0 +1,4 @@
V_FRICTION=0.2595;
SYS_A=2491.5;
SYS_B=8.333;
D_DRAG=6.54e-7;

Binary file not shown.

After

Width:  |  Height:  |  Size: 56 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 1.8 MiB

View file

@ -0,0 +1,33 @@
\relax
\@writefile{toc}{\contentsline {section}{\numberline {I}Introduction}{1}{}\protected@file@percent }
\@writefile{toc}{\contentsline {section}{\numberline {II}Parts and Materials}{1}{}\protected@file@percent }
\@writefile{toc}{\contentsline {section}{\numberline {III}Results}{1}{}\protected@file@percent }
\@writefile{toc}{\contentsline {subsection}{\numberline {\mbox {III-A}}Lab 1}{1}{}\protected@file@percent }
\@writefile{toc}{\contentsline {subsection}{\numberline {\mbox {III-B}}Lab 2}{1}{}\protected@file@percent }
\@writefile{toc}{\contentsline {subsection}{\numberline {\mbox {III-C}}Lab 3}{1}{}\protected@file@percent }
\@writefile{toc}{\contentsline {subsection}{\numberline {\mbox {III-D}}Lab 4}{1}{}\protected@file@percent }
\@writefile{toc}{\contentsline {subsection}{\numberline {\mbox {III-E}}Lab 5}{2}{}\protected@file@percent }
\@writefile{toc}{\contentsline {section}{\numberline {IV}Discussion and Summary}{2}{}\protected@file@percent }
\@writefile{toc}{\contentsline {section}{Appendix\nobreakspace A: Equations and Calculations}{2}{}\protected@file@percent }
\@writefile{toc}{\contentsline {subsection}{\numberline {\mbox {A-A}}Equations}{2}{}\protected@file@percent }
\newlabel{equation:timeConstant}{{1}{2}}
\newlabel{calculation:motorBlock}{{2}{2}}
\@writefile{toc}{\contentsline {section}{Appendix\nobreakspace B: Tables}{2}{}\protected@file@percent }
\newlabel{table:vars}{{B}{2}}
\@writefile{lot}{\contentsline {table}{\numberline {I}{\ignorespaces Values for variables in Figure\nobreakspace {}7\hbox {}}}{2}{}\protected@file@percent }
\@writefile{toc}{\contentsline {section}{Appendix\nobreakspace C: Images}{2}{}\protected@file@percent }
\@writefile{lof}{\contentsline {figure}{\numberline {1}{\ignorespaces The completed physical system.}}{2}{}\protected@file@percent }
\newlabel{fig:finishedBuild}{{1}{2}}
\@writefile{lof}{\contentsline {figure}{\numberline {2}{\ignorespaces Motor response to a steady 2.5V input}}{3}{}\protected@file@percent }
\newlabel{fig:ramp}{{2}{3}}
\@writefile{lof}{\contentsline {figure}{\numberline {3}{\ignorespaces Comparison of open-loop, closed-loop, and feed-forward systems.}}{3}{}\protected@file@percent }
\newlabel{fig:loopFF}{{3}{3}}
\@writefile{lof}{\contentsline {figure}{\numberline {4}{\ignorespaces Trapezoidal reference signal input and output with proportional control.}}{3}{}\protected@file@percent }
\newlabel{fig:decouple}{{4}{3}}
\@writefile{lof}{\contentsline {figure}{\numberline {5}{\ignorespaces Trapezoidal reference signal with PI control.}}{3}{}\protected@file@percent }
\newlabel{fig:PI}{{5}{3}}
\@writefile{lof}{\contentsline {figure}{\numberline {6}{\ignorespaces Static position response curve for the motor.}}{3}{}\protected@file@percent }
\newlabel{fig:pos}{{6}{3}}
\@writefile{lof}{\contentsline {figure}{\numberline {7}{\ignorespaces General block diagram for a Ball-On-Beam system}}{3}{}\protected@file@percent }
\newlabel{fig:block}{{7}{3}}
\gdef \@abspage@last{3}

File diff suppressed because it is too large Load diff

View file

@ -0,0 +1,393 @@
This is pdfTeX, Version 3.141592653-2.6-1.40.22 (TeX Live 2022/dev/Debian) (preloaded format=pdflatex 2021.12.12) 12 DEC 2021 17:23
entering extended mode
\write18 enabled.
file:line:error style messages enabled.
%&-line parsing enabled.
**finalPortfolio.tex
(./finalPortfolio.tex
LaTeX2e <2021-11-15>
L3 programming layer <2021-11-22>
(/usr/share/texlive/texmf-dist/tex/latex/ieeetran/IEEEtran.cls
Document Class: IEEEtran 2015/08/26 V1.8b by Michael Shell
-- See the "IEEEtran_HOWTO" manual for usage information.
-- http://www.michaelshell.org/tex/ieeetran/
\@IEEEtrantmpdimenA=\dimen138
\@IEEEtrantmpdimenB=\dimen139
\@IEEEtrantmpdimenC=\dimen140
\@IEEEtrantmpcountA=\count183
\@IEEEtrantmpcountB=\count184
\@IEEEtrantmpcountC=\count185
\@IEEEtrantmptoksA=\toks16
LaTeX Font Info: Trying to load font information for OT1+ptm on input line 5
03.
(/usr/share/texlive/texmf-dist/tex/latex/psnfss/ot1ptm.fd
File: ot1ptm.fd 2001/06/04 font definitions for OT1/ptm.
)
-- Using 8.5in x 11in (letter) paper.
-- Using PDF output.
\@IEEEnormalsizeunitybaselineskip=\dimen141
-- This is a 10 point document.
\CLASSINFOnormalsizebaselineskip=\dimen142
\CLASSINFOnormalsizeunitybaselineskip=\dimen143
\IEEEnormaljot=\dimen144
LaTeX Font Info: Font shape `OT1/ptm/bx/n' in size <5> not available
(Font) Font shape `OT1/ptm/b/n' tried instead on input line 1090.
LaTeX Font Info: Font shape `OT1/ptm/bx/it' in size <5> not available
(Font) Font shape `OT1/ptm/b/it' tried instead on input line 1090.
LaTeX Font Info: Font shape `OT1/ptm/bx/n' in size <7> not available
(Font) Font shape `OT1/ptm/b/n' tried instead on input line 1090.
LaTeX Font Info: Font shape `OT1/ptm/bx/it' in size <7> not available
(Font) Font shape `OT1/ptm/b/it' tried instead on input line 1090.
LaTeX Font Info: Font shape `OT1/ptm/bx/n' in size <8> not available
(Font) Font shape `OT1/ptm/b/n' tried instead on input line 1090.
LaTeX Font Info: Font shape `OT1/ptm/bx/it' in size <8> not available
(Font) Font shape `OT1/ptm/b/it' tried instead on input line 1090.
LaTeX Font Info: Font shape `OT1/ptm/bx/n' in size <9> not available
(Font) Font shape `OT1/ptm/b/n' tried instead on input line 1090.
LaTeX Font Info: Font shape `OT1/ptm/bx/it' in size <9> not available
(Font) Font shape `OT1/ptm/b/it' tried instead on input line 1090.
LaTeX Font Info: Font shape `OT1/ptm/bx/n' in size <10> not available
(Font) Font shape `OT1/ptm/b/n' tried instead on input line 1090.
LaTeX Font Info: Font shape `OT1/ptm/bx/it' in size <10> not available
(Font) Font shape `OT1/ptm/b/it' tried instead on input line 1090.
LaTeX Font Info: Font shape `OT1/ptm/bx/n' in size <11> not available
(Font) Font shape `OT1/ptm/b/n' tried instead on input line 1090.
LaTeX Font Info: Font shape `OT1/ptm/bx/it' in size <11> not available
(Font) Font shape `OT1/ptm/b/it' tried instead on input line 1090.
LaTeX Font Info: Font shape `OT1/ptm/bx/n' in size <12> not available
(Font) Font shape `OT1/ptm/b/n' tried instead on input line 1090.
LaTeX Font Info: Font shape `OT1/ptm/bx/it' in size <12> not available
(Font) Font shape `OT1/ptm/b/it' tried instead on input line 1090.
LaTeX Font Info: Font shape `OT1/ptm/bx/n' in size <17> not available
(Font) Font shape `OT1/ptm/b/n' tried instead on input line 1090.
LaTeX Font Info: Font shape `OT1/ptm/bx/it' in size <17> not available
(Font) Font shape `OT1/ptm/b/it' tried instead on input line 1090.
LaTeX Font Info: Font shape `OT1/ptm/bx/n' in size <20> not available
(Font) Font shape `OT1/ptm/b/n' tried instead on input line 1090.
LaTeX Font Info: Font shape `OT1/ptm/bx/it' in size <20> not available
(Font) Font shape `OT1/ptm/b/it' tried instead on input line 1090.
LaTeX Font Info: Font shape `OT1/ptm/bx/n' in size <24> not available
(Font) Font shape `OT1/ptm/b/n' tried instead on input line 1090.
LaTeX Font Info: Font shape `OT1/ptm/bx/it' in size <24> not available
(Font) Font shape `OT1/ptm/b/it' tried instead on input line 1090.
\IEEEquantizedlength=\dimen145
\IEEEquantizedlengthdiff=\dimen146
\IEEEquantizedtextheightdiff=\dimen147
\IEEEilabelindentA=\dimen148
\IEEEilabelindentB=\dimen149
\IEEEilabelindent=\dimen150
\IEEEelabelindent=\dimen151
\IEEEdlabelindent=\dimen152
\IEEElabelindent=\dimen153
\IEEEiednormlabelsep=\dimen154
\IEEEiedmathlabelsep=\dimen155
\IEEEiedtopsep=\skip47
\c@section=\count186
\c@subsection=\count187
\c@subsubsection=\count188
\c@paragraph=\count189
\c@IEEEsubequation=\count190
\abovecaptionskip=\skip48
\belowcaptionskip=\skip49
\c@figure=\count191
\c@table=\count192
\@IEEEeqnnumcols=\count193
\@IEEEeqncolcnt=\count194
\@IEEEsubeqnnumrollback=\count195
\@IEEEquantizeheightA=\dimen156
\@IEEEquantizeheightB=\dimen157
\@IEEEquantizeheightC=\dimen158
\@IEEEquantizeprevdepth=\dimen159
\@IEEEquantizemultiple=\count196
\@IEEEquantizeboxA=\box50
\@IEEEtmpitemindent=\dimen160
\IEEEPARstartletwidth=\dimen161
\c@IEEEbiography=\count197
\@IEEEtranrubishbin=\box51
) (/usr/share/texlive/texmf-dist/tex/latex/amsmath/amsmath.sty
Package: amsmath 2021/10/15 v2.17l AMS math features
\@mathmargin=\skip50
For additional information on amsmath, use the `?' option.
(/usr/share/texlive/texmf-dist/tex/latex/amsmath/amstext.sty
Package: amstext 2021/08/26 v2.01 AMS text
(/usr/share/texlive/texmf-dist/tex/latex/amsmath/amsgen.sty
File: amsgen.sty 1999/11/30 v2.0 generic functions
\@emptytoks=\toks17
\ex@=\dimen162
))
(/usr/share/texlive/texmf-dist/tex/latex/amsmath/amsbsy.sty
Package: amsbsy 1999/11/29 v1.2d Bold Symbols
\pmbraise@=\dimen163
)
(/usr/share/texlive/texmf-dist/tex/latex/amsmath/amsopn.sty
Package: amsopn 2021/08/26 v2.02 operator names
)
\inf@bad=\count198
LaTeX Info: Redefining \frac on input line 234.
\uproot@=\count199
\leftroot@=\count266
LaTeX Info: Redefining \overline on input line 399.
\classnum@=\count267
\DOTSCASE@=\count268
LaTeX Info: Redefining \ldots on input line 496.
LaTeX Info: Redefining \dots on input line 499.
LaTeX Info: Redefining \cdots on input line 620.
\Mathstrutbox@=\box52
\strutbox@=\box53
\big@size=\dimen164
LaTeX Font Info: Redeclaring font encoding OML on input line 743.
LaTeX Font Info: Redeclaring font encoding OMS on input line 744.
\macc@depth=\count269
\c@MaxMatrixCols=\count270
\dotsspace@=\muskip16
\c@parentequation=\count271
\dspbrk@lvl=\count272
\tag@help=\toks18
\row@=\count273
\column@=\count274
\maxfields@=\count275
\andhelp@=\toks19
\eqnshift@=\dimen165
\alignsep@=\dimen166
\tagshift@=\dimen167
\tagwidth@=\dimen168
\totwidth@=\dimen169
\lineht@=\dimen170
\@envbody=\toks20
\multlinegap=\skip51
\multlinetaggap=\skip52
\mathdisplay@stack=\toks21
LaTeX Info: Redefining \[ on input line 2938.
LaTeX Info: Redefining \] on input line 2939.
)
(/usr/share/texlive/texmf-dist/tex/latex/url/url.sty
\Urlmuskip=\muskip17
Package: url 2013/09/16 ver 3.4 Verb mode for urls, etc.
)
(/usr/share/texlive/texmf-dist/tex/latex/graphics/graphicx.sty
Package: graphicx 2021/09/16 v1.2d Enhanced LaTeX Graphics (DPC,SPQR)
(/usr/share/texlive/texmf-dist/tex/latex/graphics/keyval.sty
Package: keyval 2014/10/28 v1.15 key=value parser (DPC)
\KV@toks@=\toks22
)
(/usr/share/texlive/texmf-dist/tex/latex/graphics/graphics.sty
Package: graphics 2021/03/04 v1.4d Standard LaTeX Graphics (DPC,SPQR)
(/usr/share/texlive/texmf-dist/tex/latex/graphics/trig.sty
Package: trig 2021/08/11 v1.11 sin cos tan (DPC)
)
(/usr/share/texlive/texmf-dist/tex/latex/graphics-cfg/graphics.cfg
File: graphics.cfg 2016/06/04 v1.11 sample graphics configuration
)
Package graphics Info: Driver file: pdftex.def on input line 107.
(/usr/share/texlive/texmf-dist/tex/latex/graphics-def/pdftex.def
File: pdftex.def 2020/10/05 v1.2a Graphics/color driver for pdftex
))
\Gin@req@height=\dimen171
\Gin@req@width=\dimen172
)
(/usr/share/texlive/texmf-dist/tex/latex/float/float.sty
Package: float 2001/11/08 v1.3d Float enhancements (AL)
\c@float@type=\count276
\float@exts=\toks23
\float@box=\box54
\@float@everytoks=\toks24
\@floatcapt=\box55
)
(/usr/share/texlive/texmf-dist/tex/latex/l3backend/l3backend-pdftex.def
File: l3backend-pdftex.def 2021-10-18 L3 backend support: PDF output (pdfTeX)
\l__color_backend_stack_int=\count277
\l__pdf_internal_box=\box56
)
(./finalPortfolio.aux)
\openout1 = `finalPortfolio.aux'.
LaTeX Font Info: Checking defaults for OML/cmm/m/it on input line 47.
LaTeX Font Info: ... okay on input line 47.
LaTeX Font Info: Checking defaults for OMS/cmsy/m/n on input line 47.
LaTeX Font Info: ... okay on input line 47.
LaTeX Font Info: Checking defaults for OT1/cmr/m/n on input line 47.
LaTeX Font Info: ... okay on input line 47.
LaTeX Font Info: Checking defaults for T1/cmr/m/n on input line 47.
LaTeX Font Info: ... okay on input line 47.
LaTeX Font Info: Checking defaults for TS1/cmr/m/n on input line 47.
LaTeX Font Info: ... okay on input line 47.
LaTeX Font Info: Checking defaults for OMX/cmex/m/n on input line 47.
LaTeX Font Info: ... okay on input line 47.
LaTeX Font Info: Checking defaults for U/cmr/m/n on input line 47.
LaTeX Font Info: ... okay on input line 47.
-- Lines per column: 58 (exact).
(/usr/share/texlive/texmf-dist/tex/context/base/mkii/supp-pdf.mkii
[Loading MPS to PDF converter (version 2006.09.02).]
\scratchcounter=\count278
\scratchdimen=\dimen173
\scratchbox=\box57
\nofMPsegments=\count279
\nofMParguments=\count280
\everyMPshowfont=\toks25
\MPscratchCnt=\count281
\MPscratchDim=\dimen174
\MPnumerator=\count282
\makeMPintoPDFobject=\count283
\everyMPtoPDFconversion=\toks26
) (/usr/share/texlive/texmf-dist/tex/latex/epstopdf-pkg/epstopdf-base.sty
Package: epstopdf-base 2020-01-24 v2.11 Base part for package epstopdf
Package epstopdf-base Info: Redefining graphics rule for `.eps' on input line 4
85.
(/usr/share/texlive/texmf-dist/tex/latex/latexconfig/epstopdf-sys.cfg
File: epstopdf-sys.cfg 2010/07/13 v1.3 Configuration of (r)epstopdf for TeX Liv
e
))
Underfull \hbox (badness 10000) in paragraph at lines 69--78
[]
LaTeX Font Info: Trying to load font information for OT1+pcr on input line 8
3.
(/usr/share/texlive/texmf-dist/tex/latex/psnfss/ot1pcr.fd
File: ot1pcr.fd 2001/06/04 font definitions for OT1/pcr.
)
Underfull \hbox (badness 10000) in paragraph at lines 80--92
[]
[1{/var/lib/texmf/fonts/map/pdftex/updmap/pdftex.map}
]
Underfull \hbox (badness 3849) in paragraph at lines 132--139
[]\OT1/ptm/m/n/10 There were some er-rors in the di-rec-tions pro-vided
[]
Underfull \hbox (badness 1715) in paragraph at lines 132--139
\OT1/ptm/m/n/10 by the pro-fes-sor. This re-sulted in some un-cer-tainty as
[]
Underfull \hbox (badness 1577) in paragraph at lines 132--139
\OT1/ptm/m/n/10 to how to pro-ceed, the most glar-ing of which was a
[]
Underfull \hbox (badness 10000) in paragraph at lines 132--139
[]
Underfull \hbox (badness 10000) in paragraph at lines 140--142
[]
Underfull \hbox (badness 10000) in paragraph at lines 143--148
[]
Underfull \hbox (badness 4168) in paragraph at lines 149--153
\OT1/ptm/m/n/10 in-cor-rectly, par-tic-u-larly the beam length mis-cal-cu-la-ti
on
[]
Underfull \hbox (badness 1655) in paragraph at lines 149--153
\OT1/ptm/m/n/10 ques-tions about their sys-tem did I re-al-ize I made the
[]
Underfull \hbox (badness 10000) in paragraph at lines 149--153
[]
<constructedSystem.jpg, id=15, 4047.12pt x 1967.35pt>
File: constructedSystem.jpg Graphic file (type jpg)
<use constructedSystem.jpg>
Package pdftex.def Info: constructedSystem.jpg used on input line 206.
(pdftex.def) Requested size: 232.19843pt x 112.87259pt.
<motorSpeedRamp.png, id=16, 946.53625pt x 531.9875pt>
File: motorSpeedRamp.png Graphic file (type png)
<use motorSpeedRamp.png>
Package pdftex.def Info: motorSpeedRamp.png used on input line 214.
(pdftex.def) Requested size: 232.19843pt x 130.49637pt.
[2 <./constructedSystem.jpg>]
<lab2FinalGraph.png, id=28, 361.35pt x 217.5628pt>
File: lab2FinalGraph.png Graphic file (type png)
<use lab2FinalGraph.png>
Package pdftex.def Info: lab2FinalGraph.png used on input line 222.
(pdftex.def) Requested size: 232.19843pt x 139.80406pt.
<lab3VelocityGraph.png, id=29, 674.52pt x 474.27188pt>
File: lab3VelocityGraph.png Graphic file (type png)
<use lab3VelocityGraph.png>
Package pdftex.def Info: lab3VelocityGraph.png used on input line 230.
(pdftex.def) Requested size: 232.19843pt x 163.26213pt.
<lab4TunedPlot.png, id=30, 958.58125pt x 525.965pt>
File: lab4TunedPlot.png Graphic file (type png)
<use lab4TunedPlot.png>
Package pdftex.def Info: lab4TunedPlot.png used on input line 238.
(pdftex.def) Requested size: 232.19843pt x 127.39787pt.
Underfull \vbox (badness 10000) has occurred while \output is active []
<lab5PositionTunedPlot.png, id=31, 484.81125pt x 292.09125pt>
File: lab5PositionTunedPlot.png Graphic file (type png)
<use lab5PositionTunedPlot.png>
Package pdftex.def Info: lab5PositionTunedPlot.png used on input line 246.
(pdftex.def) Requested size: 232.19843pt x 139.89912pt.
<completeSystemBlockDiagram.jpg, id=32, 963.6pt x 264.23718pt>
File: completeSystemBlockDiagram.jpg Graphic file (type jpg)
<use completeSystemBlockDiagram.jpg>
Package pdftex.def Info: completeSystemBlockDiagram.jpg used on input line 254
.
(pdftex.def) Requested size: 232.19843pt x 63.67223pt.
[3 <./motorSpeedRamp.png> <./lab2FinalGraph.png> <./lab3VelocityGraph.png> <./
lab4TunedPlot.png> <./lab5PositionTunedPlot.png> <./completeSystemBlockDiagram.
jpg>]
(./finalPortfolio.aux) )
Here is how much of TeX's memory you used:
3056 strings out of 478353
51379 string characters out of 5850634
370428 words of memory out of 5000000
21166 multiletter control sequences out of 15000+600000
442064 words of font info for 94 fonts, out of 8000000 for 9000
1144 hyphenation exceptions out of 8191
55i,16n,62p,265b,259s stack positions out of 5000i,500n,10000p,200000b,80000s
{/usr/share/texlive/texmf-dist/fonts/enc/dvips/base/8r.
enc}</usr/share/texlive/texmf-dist/fonts/type1/public/amsfonts/cm/cmex10.pfb></
usr/share/texlive/texmf-dist/fonts/type1/public/amsfonts/cm/cmmi10.pfb></usr/sh
are/texlive/texmf-dist/fonts/type1/public/amsfonts/cm/cmmi6.pfb></usr/share/tex
live/texmf-dist/fonts/type1/public/amsfonts/cm/cmmi7.pfb></usr/share/texlive/te
xmf-dist/fonts/type1/public/amsfonts/cm/cmmi8.pfb></usr/share/texlive/texmf-dis
t/fonts/type1/public/amsfonts/cm/cmr10.pfb></usr/share/texlive/texmf-dist/fonts
/type1/public/amsfonts/cm/cmr5.pfb></usr/share/texlive/texmf-dist/fonts/type1/p
ublic/amsfonts/cm/cmr7.pfb></usr/share/texlive/texmf-dist/fonts/type1/public/am
sfonts/cm/cmr8.pfb></usr/share/texlive/texmf-dist/fonts/type1/public/amsfonts/c
m/cmsy10.pfb></usr/share/texlive/texmf-dist/fonts/type1/public/amsfonts/cm/cmsy
7.pfb></usr/share/texlive/texmf-dist/fonts/type1/urw/courier/ucrr8a.pfb></usr/s
hare/texlive/texmf-dist/fonts/type1/urw/times/utmb8a.pfb></usr/share/texlive/te
xmf-dist/fonts/type1/urw/times/utmbi8a.pfb></usr/share/texlive/texmf-dist/fonts
/type1/urw/times/utmr8a.pfb></usr/share/texlive/texmf-dist/fonts/type1/urw/time
s/utmri8a.pfb>
Output written on finalPortfolio.pdf (3 pages, 2267492 bytes).
PDF statistics:
106 PDF objects out of 1000 (max. 8388607)
58 compressed objects within 1 object stream
0 named destinations out of 1000 (max. 500000)
36 words of extra memory for PDF output out of 10000 (max. 10000000)

Binary file not shown.

View file

@ -0,0 +1,88 @@
<?xml version="1.0" standalone="yes"?>
<!-- logreq request file -->
<!-- logreq version 1.0 / dtd version 1.0 -->
<!-- Do not edit this file! -->
<!DOCTYPE requests [
<!ELEMENT requests (internal | external)*>
<!ELEMENT internal (generic, (provides | requires)*)>
<!ELEMENT external (generic, cmdline?, input?, output?, (provides | requires)*)>
<!ELEMENT cmdline (binary, (option | infile | outfile)*)>
<!ELEMENT input (file)+>
<!ELEMENT output (file)+>
<!ELEMENT provides (file)+>
<!ELEMENT requires (file)+>
<!ELEMENT generic (#PCDATA)>
<!ELEMENT binary (#PCDATA)>
<!ELEMENT option (#PCDATA)>
<!ELEMENT infile (#PCDATA)>
<!ELEMENT outfile (#PCDATA)>
<!ELEMENT file (#PCDATA)>
<!ATTLIST requests
version CDATA #REQUIRED
>
<!ATTLIST internal
package CDATA #REQUIRED
priority (9) #REQUIRED
active (0 | 1) #REQUIRED
>
<!ATTLIST external
package CDATA #REQUIRED
priority (1 | 2 | 3 | 4 | 5 | 6 | 7 | 8) #REQUIRED
active (0 | 1) #REQUIRED
>
<!ATTLIST provides
type (static | dynamic | editable) #REQUIRED
>
<!ATTLIST requires
type (static | dynamic | editable) #REQUIRED
>
<!ATTLIST file
type CDATA #IMPLIED
>
]>
<requests version="1.0">
<internal package="biblatex" priority="9" active="1">
<generic>latex</generic>
<provides type="dynamic">
<file>finalPortfolio.bcf</file>
</provides>
<requires type="dynamic">
<file>finalPortfolio.bbl</file>
</requires>
<requires type="static">
<file>blx-dm.def</file>
<file>blx-compat.def</file>
<file>biblatex.def</file>
<file>standard.bbx</file>
<file>numeric.bbx</file>
<file>numeric-comp.bbx</file>
<file>ieee.bbx</file>
<file>numeric-comp.cbx</file>
<file>ieee.cbx</file>
<file>biblatex.cfg</file>
<file>english.lbx</file>
</requires>
</internal>
<external package="biblatex" priority="5" active="1">
<generic>biber</generic>
<cmdline>
<binary>biber</binary>
<infile>finalPortfolio</infile>
</cmdline>
<input>
<file>finalPortfolio.bcf</file>
</input>
<output>
<file>finalPortfolio.bbl</file>
</output>
<provides type="dynamic">
<file>finalPortfolio.bbl</file>
</provides>
<requires type="dynamic">
<file>finalPortfolio.bcf</file>
</requires>
<requires type="editable">
<file>example_bib.bib</file>
</requires>
</external>
</requests>

Binary file not shown.

View file

@ -0,0 +1,260 @@
%% This is a skeleton file demonstrating the use of IEEEtran.cls
%% (requires IEEEtran.cls version 1.8b or later) with an IEEE
%% journal paper.
%%
%% Support sites:
%% http://www.michaelshell.org/tex/ieeetran/
%% http://www.ctan.org/pkg/ieeetran
%% and
%% http://www.ieee.org/
%%*************************************************************************
%% Legal Notice:
%% This code is offered as-is without any warranty either expressed or
%% implied; without even the implied warranty of MERCHANTABILITY or
%% FITNESS FOR A PARTICULAR PURPOSE!
%% User assumes all risk.
%% In no event shall the IEEE or any contributor to this code be liable for
%% any damages or losses, including, but not limited to, incidental,
%% consequential, or any other damages, resulting from the use or misuse
%% of any information contained here.
%%
%% All comments are the opinions of their respective authors and are not
%% necessarily endorsed by the IEEE.
%%
%% This work is distributed under the LaTeX Project Public License (LPPL)
%% ( http://www.latex-project.org/ ) version 1.3, and may be freely used,
%% distributed and modified. A copy of the LPPL, version 1.3, is included
%% in the base LaTeX documentation of all distributions of LaTeX released
%% 2003/12/01 or later.
%% Retain all contribution notices and credits.
%% ** Modified files should be clearly indicated as such, including **
%% ** renaming them and changing author support contact information. **
%%*************************************************************************
\documentclass[journal]{IEEEtran}
% *** MATH PACKAGES ***
\usepackage{amsmath}
% *** PDF, URL AND HYPERLINK PACKAGES ***
\usepackage{url}
% correct bad hyphenation here: (DON'T ADD BLANK LINE AFTER THIS COMMAND)
\hyphenation{op-tical net-works semi-conduc-tor}
\usepackage{graphicx} %needed to include png, eps figures
\usepackage{float} % used to fix location of images i.e.\begin{figure}[H]
\begin{document}
% paper title
\title{Final Lab Portfolio\\ \small{EEET--427--01: Controls Systems Lab}}
% author names
\author{Blizzard MacDougall, rmm3470}% <-this % stops a space
% The report headers
\markboth{EEET--427--01 Lab Portfolio; Dec. 2021} %Don't remove next line
{Shell}
% make the title area
\maketitle
\begin{abstract}
In an effort to further understanding of controls systems,
students were instructed to construct a system capable of balancing a ball on a beam.
This system was to be able to react to outside stimuli, and keep the ball as stable as possible.
\end{abstract}
\section{Introduction}
\IEEEPARstart{T}{he} purpose of these experiments was to provide real-world experience in implementing the controls systems concepts described in lecture.
In addition, the labs also provided experience with troubleshooting both systems and Arduino code.
Background knowledge necessary for this lab includes basic calculus skills and physics (specifically two-dimensional motion and forces).
These labs make extensive use of an Arduino (purchased at the start of the course), primarily to control a motor.
This is done using code provided by the instructor, which is modified to suit each students particular hardware.
The labs also make use of soldering skills, as well as basic hot-glue and foam-core working skills.
Each portion of the lab received a brief description, and were roughly based off of the work in lecture that week.
Moreover, each lab built upon the previous lab.
The final lab project is pictured in Figure~\ref{fig:finishedBuild}.\\
\section{Parts and Materials}
There are several major components in this lab.
First and foremost, the RoboRED YourDuino board (hereafter referred to as "the Arduino"), which is the microcontroller the labs are based in.
This board controls all of the following devices, either directly or indirectly.
The primary motor used in these labs is the DFRobot \verb|FIT0450| DC motor (hereafter referred to a "the motor").
The ultimate goal of the motor is to control the beam on which a ball will balance.
The motor is controlled by a Seeed studio \verb|MIX1508| H-Bridge Motor Driver (hereafter referred to as "the motor driver" or "the motor driver board").
This motor driver takes power from a steady power source, and controls the motor based on PWM signals sent from the Arduino.
The power for the motor driver in all labs is provided by an AC-to-USB power supply.
In later labs, a Pololu carrier board containing a STMicro \verb|VL53L1X| Time-of-Flight sensor (hereafter referred to as "the TOF sensor" or "the time-of-flight sensor") is used.
This is used to find the ball's position on the balancing beam.
The lab also makes use of foam core and hot glue, for the balancing beam and for connecting components.
All code for each lab was provided by the professor at the beginning of lab.\\
\newpage
\section{Results}
\subsection{Lab 1}
The first lab's instructions were to create a standard transfer function and block diagram for the motor distributed at the beginning of lab.
This was done by sending a constant voltage to the motor, and graphing its velocity over time, as seen in Figure~\ref{fig:ramp}.
Values of $a$ and $b$ can be found in Table~\ref{table:vars}.
The transfer function for the motor can be represented as $\frac{a}{s+b}$ in Figure~\ref{fig:block}, and is calculated in Equation~\ref{calculation:motorBlock}.
These values are key for all following labs, as every subsequent lab's code uses these values to control the motor.
\subsection{Lab 2}
This lab's purpose was to compare different ways of controlling the motor.
This was done by giving the motor a trapezoidal reference signal, and comparing the response with different control schemes.
The control schemes tested in this lab were using closed-loop feedback and feed-forward.
The graph in Figure~\ref{fig:loopFF} shows the final comparison of all of these control mechanisms.
This lab found that using both closed-loop feedback and feed-forward in conjunction gave the fastest response time with the most accurate steady-state speed.
\subsection{Lab 3}
The purpose of this lab was to introduce how to decouple the input, and how to ensure that the motor works properly when programmed to turn backwards.
This used an expanded version of the trapezoidal reference signal used in the previous lab, including a negative portion of the signal.
Figure~\ref{fig:decouple} shows both the input reference signal, and that the output signal is close to the same path.
In addition, this lab ensured that the motor never tried to use more power than was available (in this case, $5V$).
This can be seen in the yellow line in Figure~\ref{fig:decouple}.
\subsection{Lab 4}
This lab's instructions were to take the previous control schemes, and add integral control on top of them.
This used the same trapezoidal reference signal as in Lab 3.
This resulted in a motor response curve that was more accurate to the input signal, and was more accurate in position.
Using the control system consisting only of proportional control and feed-forward produced an error in speed of $35.49rad/sec$,
while the control system including integral control produced an error of only $11.82rad/sec$.
This can be seen in comparing Figure~\ref{fig:decouple} and Figure~\ref{fig:PI}, and comparing each \verb|motorspeed| plot with the \verb|refVel| or \verb|Wref| plots.
\subsection{Lab 5}
In this lab, students moved from tuning the velocity error to tuning the position error.
This is crucial, as a high error in the position of the motor will mean an even higher error in the beam's position, making it impossible to balance the ball properly.
To do this, the control system was given a constant position, and the motor's position over time was plotted.
After tuning, the motor's error in position was reduced to $1.20rad$, with a response time of $<500ms$, as shown in Figure~\ref{fig:pos}.
\section{Discussion and Summary}
%%Yes, I know, there's a break in writing style here. Its to fill a requirement and hopefully pass the course.
There were some errors in the directions provided by the professor.
This resulted in some uncertainty as to how to proceed, the most glaring of which was a discrepancy between
the completed system the professor would periodically demonstrate and the specifications for correctly building the system.
More specifically, the length of the beam on which the ball sits was significantly longer than the base that supported it.
To solve this issue, I shortened the beam to fit the base.
This resulted in needing to modify most of the code given by the professor, to account for the differing ratio between beam length
and the range of motion of the motor.\\
A majority of the time, I was working outside of my comfort zone, as the last time I had worked with Arduino code previous to this lab was almost two years ago.
This encouraged me to relearn C++ outside of class, and pushed me to learn more languages in preparation for the future to mitigate problems caused by inexperience.\\
Most of my physical mechanical skills came in handy in this course.
Particularly, small arts-and-crafts skills like use of foam core and hot glue.
This helped when it came time to troubleshoot the mis-sized beam, as I not only had to change the length of the beam itself,
but also account for the beam in the lifting arm.
This can be seen in Figure~\ref{fig:finishedBuild} in the triangular notch cut out of the lifting arm on the right side of the device, allowing full range of motion for the motor.\\
Overall, I learned that I find errors I've made by helping others.
There were several times in the process of physically building the system that I had made some measurement incorrectly, particularly the beam length miscalculation mentioned previously.
Only by other students asking me questions about their system did I realize I made the measurement error.
Overall, I've found that I tend to work best in a small group of people, where we collectively share information back to the larger group.\\
By the end of this course, I had a good grasp on most first-order system concepts.
In addition, I also understood how to control said systems, both mathematically and in Arduino code.
\newpage
\appendices
\section{Equations and Calculations}
\subsection{Equations}
\begin{equation}
\frac1b=\tau=t_{65\%steady-state}
\label{equation:timeConstant}
\end{equation}
\begin{equation}
\begin{split}
\omega_{mtr;steady-state}\approx750rad/s\\
V_{arm}=2.5V\\
\frac{\omega_{mtr}}{V_{arm}}\approx299\frac{rad}{sV}\\
0.65*\omega_{mtr;steady-state}=450rad/s\\
t_{65\%steady-state}\approx120ms\\
b=\frac{1}{\tau}=\frac{1}{0.12s}=8.\overline3Hz\\
\frac{a}{s+b}@\ steady-state=\frac ab\\
299\frac{rad}{sV}=\frac{a}{b}\\
a=\left(299\frac{rad}{sV}\right)(8.\overline3Hz)\\
a=2491.5\frac{rad}{s^2V}
\end{split}
\label{calculation:motorBlock}
\end{equation}
\section{Tables}
\begin{table}[!ht] %[H]
\centering
\label{table:vars}
\begin{tabular}{c|r|l}
Variable & value & unit\\ \hline
$a$ & $2491.5$ & $\frac{rad}{s^2V}$\\\hline
$b$ & $9.\overline{3}$ & $Hz$\\\hline
$g$ & $9.81$ & $m/s$\\\hline
$L_{arm}$ & $10$ & $cm$\\\hline
$L_{beam}$ & $36$ & $cm$\\\hline
$C_{beam}$ & $5.625$\\\hline
$D_{beam}$ & $20$\\\hline
$C_{ball}$ & $1$\\\hline
$D_{ball}$ & $6$\\\hline
$K_{p,arm}$ & $0.1$ & $\frac{Vs}{rad}$\\\hline
$K_{p,ball}$ & $1$ & $\frac{rad}{m}$\\
\end{tabular}
\caption{Values for variables in Figure~\ref{fig:block}}
\end{table}
\section{Images}
\begin{figure}[H]%[!ht]
\begin {center}
\includegraphics[width=0.45\textwidth]{constructedSystem.jpg}
\caption{The completed physical system.}
\label{fig:finishedBuild}
\end{center}
\end{figure}
\begin{figure}[H]%[!ht]
\begin {center}
\includegraphics[width=0.45\textwidth]{motorSpeedRamp.png}
\caption{Motor response to a steady 2.5V input}
\label{fig:ramp}
\end{center}
\end{figure}
\begin{figure}[H]%[!ht]
\begin {center}
\includegraphics[width=0.45\textwidth]{lab2FinalGraph.png}
\caption{Comparison of open-loop, closed-loop, and feed-forward systems.}
\label{fig:loopFF}
\end {center}
\end{figure}
\begin{figure}[H]%[!ht]
\begin {center}
\includegraphics[width=0.45\textwidth]{lab3VelocityGraph.png}
\caption{Trapezoidal reference signal input and output with proportional control.}
\label{fig:decouple}
\end {center}
\end{figure}
\begin{figure}[H]%[!ht]
\begin {center}
\includegraphics[width=0.45\textwidth]{lab4TunedPlot.png}
\caption{Trapezoidal reference signal with PI control.}
\label{fig:PI}
\end {center}
\end{figure}
\begin{figure}[H]%[!ht]
\begin {center}
\includegraphics[width=0.45\textwidth]{lab5PositionTunedPlot.png}
\caption{Static position response curve for the motor.}
\label{fig:pos}
\end {center}
\end{figure}
\begin{figure}[H]%[!ht]
\begin {center}
\includegraphics[width=0.45\textwidth]{completeSystemBlockDiagram.jpg}
\caption{General block diagram for a Ball-On-Beam system}
\label{fig:block}
\end {center}
\end{figure}
\end{document}

Binary file not shown.

After

Width:  |  Height:  |  Size: 14 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 45 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 60 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 12 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 27 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 31 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 2.1 MiB

Binary file not shown.

85
lab0/lab0/lab1.ino Normal file
View file

@ -0,0 +1,85 @@
#include <Wire.h>
#include <VL53L1X.h>
uint8_t width, height;
uint8_t center;
boolean firstPrint = true;
int x,y;
VL53L1X sensor;
int i=0;
void setup() {
Serial.begin(115200);
Wire.begin();
Wire.setClock(400000);
sensor.setTimeout(500);
if (!sensor.init())
{
Serial.println("Failed to detect and initialize sensor!");
while(1);
}
//use long distance mode, allowing for 50000us (50ms) for a measurements.
//minimum value for budget is 33ms; 200ms works well
sensor.setDistanceMode(VL53L1X::Long);
sensor.setMeasurementTimingBudget(50000);
}
void loop()
{
sensor.readSingle(true);
//printLotsOfStats();
//printIndexAndPeakSignal();
printPlottermm();
delay(10);
i++;
if (sensor.timeoutOccurred())
{
Serial.print(" TIMEOUT");
}
}
void printPlottermm()
{
if(firstPrint)
{
Serial.print("Range (mm):");
Serial.println();
firstPrint = false;
}
Serial.print("\t");
Serial.print(sensor.ranging_data.range_mm);
Serial.println();
}
void printIndexandPeakSignal()
{
if(firstPrint) {
Serial.print("index:");
Serial.print("index:");
Serial.print("index:");
Serial.print("index:");
Serial.print("index:");
Serial.println();
firstPrint = false;
}
Serial.print(i); Serial.print("\t");
Serial.print(sensor.ranging_data.range_mm); Serial.print("\t");
Serial.print(sensor.ranging_data.peak_signal_count_rate_MCPS); Serial.print("\t");
Serial.print(sensor.rangeStatusToString(sensor.ranging_data.range_status)); Serial.print("\t");
Serial.print(sensor.ranging_data.ambient_count_rate_MCPS);
Serial.println();
}
void printLotsOfStats()
{
Serial.print("Index:\t"); Serial.print(i);
Serial.print("\tRange:"); Serial.print(sensor.ranging_data.range_mm);
Serial.print("\tPeak:"); Serial.print(sensor.ranging_data.peak_signal_count_rate_MCPS);
Serial.print("\tAmbient:"); Serial.print(sensor.ranging_data.ambient_count_rate_MCPS);
Serial.print("\tStatus: "); Serial.print(VL53L1X::rangeStatusToString(sensor.ranging_data.range_status));
Serial.println();
}

BIN
lab0/lab0Report/graph1.png Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 40 KiB

View file

@ -0,0 +1,2 @@
\relax
\gdef \@abspage@last{1}

1277
lab0/lab0Report/labSetup.log Normal file

File diff suppressed because it is too large Load diff

Binary file not shown.

Binary file not shown.

View file

@ -0,0 +1,103 @@
% File: labSetup.tex
% Created: 14:12:01 Thu, 02 Sep 2021 EDT
% Last Change: 14:12:01 Thu, 02 Sep 2021 EDT
%
\documentclass[letterpaper]{article}
\usepackage{amsmath}
\usepackage{graphicx}
\usepackage{cancel}
\usepackage{amssymb}
\usepackage{listings}
\usepackage[shortlabels]{enumitem}
\usepackage{lipsum}
\usepackage{soul}
\usepackage{geometry}
\usepackage{tikz}
\usepackage{pgfplots}
\pgfplotsset{compat=newest, compat/show suggested version=false}
\geometry{portrait, margin=1in}
\date{09/02/2021}
\title{%
Lab 1 Report\\
\large EEET-427-01: Control Systems}
\author{Blizzard MacDougall}
\begin{document}
\maketitle
\pagenumbering{arabic}
The distance sensor is accurate to within $\pm1cm$ between a distance of $0cm$ and $~375cm$.
\begin{center}
\begin{tabular}{|c|c|c|}
\hline
Actual Value (mm) & Minimum Measurement (mm) & Maximum Measurement (mm)\\
\hline \hline
0 & 0 & 1\\
\hline
500 & 498 & 506\\
\hline
1000 & 997 & 1003\\
\hline
1500 & 1497 & 1503\\
\hline
2000 & 1998 & 2008\\
\hline
2500 & 2495 & 2503\\
\hline
3000 & 2999 & 3010\\
\hline
3500 & 3550 & 3560\\
\hline
4000 & 3994 & 4036\\
\hline
\end{tabular}
\end{center}
\begin{center}
\begin{tikzpicture}
\begin{axis}
[
title=Defined vs Measured Distances
scatter/classes=
{
a={mark=o,draw=black}
},
xlabel={Defined Distance (cm)},
ylabel={Measured Distance (cm)},
xmin=0, xmax=400,
ymin=0, ymax=400,
xtick={0, 50, 100, 150, 200, 250, 300, 350, 400},
ytick={0, 50, 100, 150, 200, 250, 300, 350, 400},
ymajorgrids=true,
xmajorgrids=true,
grid style=dashed,
]
\addplot
[
domain=0:400,
samples=10,
color=red,
]
{x};
\addplot[scatter,only marks, scatter src=explicit symbolic]
table
{
x y
0 0.05
50.0 50.2
100.0 100.0
150.0 150.0
200.0 200.3
250.0 249.9
300.0 300.45
350.0 350.5
400.0 402.5
};
\end{axis}
\end{tikzpicture}
\end{center}
One possible use of this is for redundancy in a liquid level measurement system. (The system would most likely already be using a float as its main measurement system. In the event that the sensor for the float failed, the distance sensor could measure the distance the float moves to determine the level of fluid in the tank, as a back-up measurement system).
\end{document}

Binary file not shown.

BIN
lab1/Untitled 1.ods Normal file

Binary file not shown.

484
lab1/lab1/lab1.ino Normal file
View file

@ -0,0 +1,484 @@
/* Click in this box, then
CTRL-A to select all
CTRL-C to copy
CTRL-V to paste into Arduino IDE
File: Lab1_motor_step_v3
Written: Aug 31, 2020, Clark Hochgraf
Revised: Jan 30, 2021
Desc:
This program demonstrates the response a dc motor to a voltage step input.
Speed of the motor is measured using a quadrature encoder.
*/
volatile byte quadratureCode, oldquadratureCode;
volatile float quadPos = 0.0;
float lastquadPos = 0;
float motorspeedRPS = 0;
bool isModuleEn = false;
bool prevModuleEn = false;
const byte TSAMP_MSEC = 20;
long timeElapsedTicks = 0;
const float TSAMP = 0.001 * TSAMP_MSEC;
int TOTAL_RUN_TIME_MSEC = 2000; // in millisec
volatile float adcReading = 0;
float pwm_value_commanded;// command supplied to the motor PWM value.
const int ENC2 = A2; // d16, PC2 PCINT10 (green wire)
const int ENC3 = A3; // d17, PC3 PCINT11 (blue wire
const int PWM_M1A_PIN = 3; // d3, PD3 PCINT19 digital output OCR2B (green wire)
const int PWM_M1B_PIN = 11; // d11, PB4 digital output OCR2A (blue wire)
const float VOLTS_PER_PWM = 5.0 / 255.0; // motor drive voltage per pwm command
const float RADPERSEC_PERVOLT = 356.0; // from datasheet calculations
const float PWM_VALUE= 128;
float Wref = PWM_VALUE * VOLTS_PER_PWM * RADPERSEC_PERVOLT;
// ##################################################################
void setup()
{
Serial.begin(115200);//Initialize the serial port ** Set Serial Monitor to same 115200
Serial.println(F("Lab 1 Motor Step Response v3"));
Serial.println(F("runs for two seconds and then stops"));
displayMenu();
initMotorPins();
initEncoderInterrupts();
initPWMtimer2();
}
// ##################################################################
void loop()
{ manageMenu();
syncSample();
if (isModuleEn) {
float DCgain=1.24;
pwm_value_commanded = DCgain*PWM_VALUE; // Change this value to change motor speed
sendPWMvalueToMotor(pwm_value_commanded);
printResults(); // only print while motor running
}
else { //send zero voltage command to pwm if not enabled
pwm_value_commanded = 0;
sendPWMvalueToMotor(pwm_value_commanded);
}
if (timeElapsedTicks * TSAMP_MSEC > TOTAL_RUN_TIME_MSEC) //stop motor after 2 seconds
{
isModuleEn = false;
}
prevModuleEn = isModuleEn;
} // End main loop
// ##################################################################
//********************************************************************
void sendPWMvalueToMotor(int pwm_command)
{
if (pwm_command < 0) { // negative case -- set direction CW
pwm_command = - int(pwm_command);
OCR2B = 0;
OCR2A = constrain(pwm_command, 0, 255); //Serial.println(OCR2A);
}
else
{ //positive case -- set direction CW
pwm_command = int(pwm_command);
OCR2A = 0;
OCR2B = constrain(pwm_command, 0, 255); //Serial.println(OCR2B);
}
}
//********************************************************************
void printResults(void)
{ if (isModuleEn != prevModuleEn)
{
//print header
Serial.print("time (msec): "); Serial.print(",");
Serial.print("motorspeed: (rad/sec) "); Serial.print(",");
Serial.print("quadPos: (rad) "); Serial.print(",");
Serial.print("pwm_command: () "); Serial.print(",");
Serial.print("Varm (V) "); Serial.print(",");
Serial.print("Wref (rad/sec)");
Serial.println();
quadPos = 0;
lastquadPos = quadPos;
}
motorspeedRPS = -(lastquadPos - quadPos) / (TSAMP_MSEC * 0.001); // radians per time interval (rad/sec)
lastquadPos = quadPos;
Serial.print(timeElapsedTicks * TSAMP_MSEC); Serial.print(",");
Serial.print(motorspeedRPS); Serial.print(",");
Serial.print(quadPos); Serial.print(",");
Serial.print(pwm_value_commanded); Serial.print(",");
Serial.print(pwm_value_commanded * VOLTS_PER_PWM); Serial.print(",");
Serial.print(Wref);
Serial.println();
timeElapsedTicks++;
}
//********************************************************************
void displayMenu()
{
Serial.println("\nEnter 'e' to toggle module enable.");
}
//********************************************************************
void manageMenu()
{
char inChar = Serial.read();
if (inChar == 'e')
{
isModuleEn = !isModuleEn;
if (isModuleEn) {
Serial.println(F("Module ENABLED"));
timeElapsedTicks = 0;
}
else Serial.println(F("Module DISABLED"));
}
}
//********************************************************************
void initMotorPins()
{ // configure pins as input or output
pinMode(ENC2, INPUT); // Encoder A
pinMode(ENC3, INPUT); // Encoder B
pinMode(PWM_M1A_PIN, OUTPUT); // set motor PWM signal to output
pinMode(PWM_M1B_PIN, OUTPUT); // set motor direction pin to output
}
//********************************************************************
void initEncoderInterrupts(void)
{
// Position encoder ISR setup
// PCINT1_vect ISR triggered for enabled bit changes on PCMSK1
cli(); // disable global interrupts
PCMSK1 = 0b00001100; // ENC3,2,1,0 -> A3,A2,A1,A0 -> d17,16,15,14
PCICR = (1 << PCIE1); // enable pin change interrupts 8..14
sei(); // enable global interrupts
}
//********************************************************************
void initPWMtimer2(void)
{
//-----------------------------------------------------------------
// Use Timer 2 for direct motor drive PWM generation.
// Prescale = 1, FAST PWM, 8-bit (Mode 3) -> 62.5 kHz PWM
// Output pins OC2B (d3~) and OC2A (d11~) driven by counter hardware.
cli();
TCCR2B = 0;
TCCR2A = 0;
TCCR2B = (0 << WGM22); // start FAST PWM mode 3 setup
TCCR2A = (1 << WGM21) | (1 << WGM20); // finish FAST PWM setup
TCCR2B |= (0 << CS22) | (0 << CS21) | (1 << CS20); // clock prescale = 1
TCCR2A |= (1 << COM2B1) | (0 << COM2B0); // OCR2B pin (d3~) noninverting PWM
TCCR2A |= (1 << COM2A1) | (0 << COM2A0); // OCR2A pin (d11~) noninverting PWM
OCR2B = 1; OCR2A = 1;
sei();
}
//********************************************************************
void decodeEncoder32(void) // 2 bit quad decoder
{
const float MTR_RAD_PER_TICK = TWO_PI / 32;
static byte oldquadratureCode = 0;
oldquadratureCode = quadratureCode;
quadratureCode = (PINC & 0b00001100);
// Quadrature sequence: 0,8,12,4 (update ?CW facing end)
switch (quadratureCode)
{
case 0:
if (oldquadratureCode == 4) quadPos += MTR_RAD_PER_TICK;
if (oldquadratureCode == 8) quadPos -= MTR_RAD_PER_TICK;
break;
case 8:
if (oldquadratureCode == 0) quadPos += MTR_RAD_PER_TICK;
if (oldquadratureCode == 12) quadPos -= MTR_RAD_PER_TICK;
break;
case 12:
if (oldquadratureCode == 8) quadPos += MTR_RAD_PER_TICK;
if (oldquadratureCode == 4) quadPos -= MTR_RAD_PER_TICK;
break;
case 4:
if (oldquadratureCode == 12) quadPos += MTR_RAD_PER_TICK;
if (oldquadratureCode == 0) quadPos -= MTR_RAD_PER_TICK;
break;
}
} // decodeEncoder32( )
//********************************************************************
void syncSample() // set the sample rate for ADC and therefore for the main loop
{ // sample interval time is set by TSAMP_MSEC
const unsigned long TIC_USEC = TSAMP_MSEC * 1000UL;
const byte ADCSRA_ISR = 0b11101111; // auto ISR, clkdiv = 128
static unsigned long tic, stake = 0;
static boolean first_run = true;
if (first_run) {
stake = micros(); // only runs first time to set stake
first_run = false;
}
while ((tic - stake) < TIC_USEC) tic = micros(); // wait here until
stake = tic;
ADCSRA = ADCSRA_ISR; // start oversample-average series
}
//********************************************************************
ISR(PCINT1_vect) // if pin change occurs, update quadrature decoder
{
decodeEncoder32();
}
//********************************************************************
ISR (ADC_vect)
{
const byte N_ADC_AVE = 80;
const float INV_N_ADC = 1.0 / N_ADC_AVE;
static byte nConv = 0;
static unsigned int loAccum = 0, hiAccum = 0;
//SET_TP0_HI;
loAccum += ADCL; // lower 8 bits: must read before ADCH per Atmel
hiAccum += ADCH; // upper 2 bits
if (++nConv >= N_ADC_AVE)
{
//SET_TP1_HI;
adcReading = INV_N_ADC * (256UL * hiAccum + loAccum);
hiAccum = 0; loAccum = 0;
nConv = 0;
ADCSRA &= ~bit(ADIE); // stop auto conversions
//SET_TP1_LO;
}
//SET_TP0_LO;
} // end of ADC_vect

View file

@ -0,0 +1,8 @@
\relax
\@writefile{toc}{\contentsline {section}{\numberline {1}Section 1}{1}{}\protected@file@percent }
\@writefile{toc}{\contentsline {section}{\numberline {2}Section 2}{1}{}\protected@file@percent }
\@writefile{toc}{\contentsline {section}{\numberline {3}Section 3}{1}{}\protected@file@percent }
\@writefile{toc}{\contentsline {section}{\numberline {4}Section 4}{1}{}\protected@file@percent }
\@writefile{toc}{\contentsline {section}{\numberline {5}Section 5}{1}{}\protected@file@percent }
\@writefile{toc}{\contentsline {section}{\numberline {6}Section 6}{1}{}\protected@file@percent }
\gdef \@abspage@last{1}

View file

@ -0,0 +1,760 @@
This is pdfTeX, Version 3.141592653-2.6-1.40.22 (TeX Live 2022/dev/Debian) (preloaded format=pdflatex 2021.12.7) 8 DEC 2021 17:53
entering extended mode
\write18 enabled.
file:line:error style messages enabled.
%&-line parsing enabled.
**lab2Report.tex
(./lab2Report.tex
LaTeX2e <2021-11-15>
L3 programming layer <2021-11-22>
(/usr/share/texlive/texmf-dist/tex/latex/base/article.cls
Document Class: article 2021/10/04 v1.4n Standard LaTeX document class
(/usr/share/texlive/texmf-dist/tex/latex/base/size10.clo
File: size10.clo 2021/10/04 v1.4n Standard LaTeX file (size option)
)
\c@part=\count183
\c@section=\count184
\c@subsection=\count185
\c@subsubsection=\count186
\c@paragraph=\count187
\c@subparagraph=\count188
\c@figure=\count189
\c@table=\count190
\abovecaptionskip=\skip47
\belowcaptionskip=\skip48
\bibindent=\dimen138
)
(/usr/share/texlive/texmf-dist/tex/latex/amsmath/amsmath.sty
Package: amsmath 2021/10/15 v2.17l AMS math features
\@mathmargin=\skip49
For additional information on amsmath, use the `?' option.
(/usr/share/texlive/texmf-dist/tex/latex/amsmath/amstext.sty
Package: amstext 2021/08/26 v2.01 AMS text
(/usr/share/texlive/texmf-dist/tex/latex/amsmath/amsgen.sty
File: amsgen.sty 1999/11/30 v2.0 generic functions
\@emptytoks=\toks16
\ex@=\dimen139
))
(/usr/share/texlive/texmf-dist/tex/latex/amsmath/amsbsy.sty
Package: amsbsy 1999/11/29 v1.2d Bold Symbols
\pmbraise@=\dimen140
)
(/usr/share/texlive/texmf-dist/tex/latex/amsmath/amsopn.sty
Package: amsopn 2021/08/26 v2.02 operator names
)
\inf@bad=\count191
LaTeX Info: Redefining \frac on input line 234.
\uproot@=\count192
\leftroot@=\count193
LaTeX Info: Redefining \overline on input line 399.
\classnum@=\count194
\DOTSCASE@=\count195
LaTeX Info: Redefining \ldots on input line 496.
LaTeX Info: Redefining \dots on input line 499.
LaTeX Info: Redefining \cdots on input line 620.
\Mathstrutbox@=\box50
\strutbox@=\box51
\big@size=\dimen141
LaTeX Font Info: Redeclaring font encoding OML on input line 743.
LaTeX Font Info: Redeclaring font encoding OMS on input line 744.
\macc@depth=\count196
\c@MaxMatrixCols=\count197
\dotsspace@=\muskip16
\c@parentequation=\count198
\dspbrk@lvl=\count199
\tag@help=\toks17
\row@=\count266
\column@=\count267
\maxfields@=\count268
\andhelp@=\toks18
\eqnshift@=\dimen142
\alignsep@=\dimen143
\tagshift@=\dimen144
\tagwidth@=\dimen145
\totwidth@=\dimen146
\lineht@=\dimen147
\@envbody=\toks19
\multlinegap=\skip50
\multlinetaggap=\skip51
\mathdisplay@stack=\toks20
LaTeX Info: Redefining \[ on input line 2938.
LaTeX Info: Redefining \] on input line 2939.
)
(/usr/share/texlive/texmf-dist/tex/latex/graphics/graphicx.sty
Package: graphicx 2021/09/16 v1.2d Enhanced LaTeX Graphics (DPC,SPQR)
(/usr/share/texlive/texmf-dist/tex/latex/graphics/keyval.sty
Package: keyval 2014/10/28 v1.15 key=value parser (DPC)
\KV@toks@=\toks21
)
(/usr/share/texlive/texmf-dist/tex/latex/graphics/graphics.sty
Package: graphics 2021/03/04 v1.4d Standard LaTeX Graphics (DPC,SPQR)
(/usr/share/texlive/texmf-dist/tex/latex/graphics/trig.sty
Package: trig 2021/08/11 v1.11 sin cos tan (DPC)
)
(/usr/share/texlive/texmf-dist/tex/latex/graphics-cfg/graphics.cfg
File: graphics.cfg 2016/06/04 v1.11 sample graphics configuration
)
Package graphics Info: Driver file: pdftex.def on input line 107.
(/usr/share/texlive/texmf-dist/tex/latex/graphics-def/pdftex.def
File: pdftex.def 2020/10/05 v1.2a Graphics/color driver for pdftex
))
\Gin@req@height=\dimen148
\Gin@req@width=\dimen149
)
(/usr/share/texlive/texmf-dist/tex/latex/cancel/cancel.sty
Package: cancel 2013/04/12 v2.2 Cancel math terms
)
(/usr/share/texlive/texmf-dist/tex/latex/amsfonts/amssymb.sty
Package: amssymb 2013/01/14 v3.01 AMS font symbols
(/usr/share/texlive/texmf-dist/tex/latex/amsfonts/amsfonts.sty
Package: amsfonts 2013/01/14 v3.01 Basic AMSFonts support
\symAMSa=\mathgroup4
\symAMSb=\mathgroup5
LaTeX Font Info: Redeclaring math symbol \hbar on input line 98.
LaTeX Font Info: Overwriting math alphabet `\mathfrak' in version `bold'
(Font) U/euf/m/n --> U/euf/b/n on input line 106.
))
(/usr/share/texlive/texmf-dist/tex/latex/listings/listings.sty
\lst@mode=\count269
\lst@gtempboxa=\box52
\lst@token=\toks22
\lst@length=\count270
\lst@currlwidth=\dimen150
\lst@column=\count271
\lst@pos=\count272
\lst@lostspace=\dimen151
\lst@width=\dimen152
\lst@newlines=\count273
\lst@lineno=\count274
\lst@maxwidth=\dimen153
(/usr/share/texlive/texmf-dist/tex/latex/listings/lstmisc.sty
File: lstmisc.sty 2020/03/24 1.8d (Carsten Heinz)
\c@lstnumber=\count275
\lst@skipnumbers=\count276
\lst@framebox=\box53
)
(/usr/share/texlive/texmf-dist/tex/latex/listings/listings.cfg
File: listings.cfg 2020/03/24 1.8d listings configuration
))
Package: listings 2020/03/24 1.8d (Carsten Heinz)
(/usr/share/texlive/texmf-dist/tex/latex/enumitem/enumitem.sty
Package: enumitem 2019/06/20 v3.9 Customized lists
\labelindent=\skip52
\enit@outerparindent=\dimen154
\enit@toks=\toks23
\enit@inbox=\box54
\enit@count@id=\count277
\enitdp@description=\count278
)
(/usr/share/texlive/texmf-dist/tex/latex/lipsum/lipsum.sty
(/usr/share/texlive/texmf-dist/tex/latex/l3packages/l3keys2e/l3keys2e.sty
(/usr/share/texlive/texmf-dist/tex/latex/l3kernel/expl3.sty
Package: expl3 2021-11-22 L3 programming layer (loader)
(/usr/share/texlive/texmf-dist/tex/latex/l3backend/l3backend-pdftex.def
File: l3backend-pdftex.def 2021-10-18 L3 backend support: PDF output (pdfTeX)
\l__color_backend_stack_int=\count279
\l__pdf_internal_box=\box55
))
Package: l3keys2e 2021-11-12 LaTeX2e option processing using LaTeX3 keys
)
Package: lipsum 2021-09-20 v2.7 150 paragraphs of Lorem Ipsum dummy text
\g__lipsum_par_int=\count280
\l__lipsum_a_int=\count281
\l__lipsum_b_int=\count282
(/usr/share/texlive/texmf-dist/tex/latex/lipsum/lipsum.ltd.tex))
(/usr/share/texlive/texmf-dist/tex/generic/soul/soul.sty
Package: soul 2003/11/17 v2.4 letterspacing/underlining (mf)
\SOUL@word=\toks24
\SOUL@lasttoken=\toks25
\SOUL@cmds=\toks26
\SOUL@buffer=\toks27
\SOUL@token=\toks28
\SOUL@spaceskip=\skip53
\SOUL@ttwidth=\dimen155
\SOUL@uldp=\dimen156
\SOUL@ulht=\dimen157
)
(/usr/share/texlive/texmf-dist/tex/latex/geometry/geometry.sty
Package: geometry 2020/01/02 v5.9 Page Geometry
(/usr/share/texlive/texmf-dist/tex/generic/iftex/ifvtex.sty
Package: ifvtex 2019/10/25 v1.7 ifvtex legacy package. Use iftex instead.
(/usr/share/texlive/texmf-dist/tex/generic/iftex/iftex.sty
Package: iftex 2020/03/06 v1.0d TeX engine tests
))
\Gm@cnth=\count283
\Gm@cntv=\count284
\c@Gm@tempcnt=\count285
\Gm@bindingoffset=\dimen158
\Gm@wd@mp=\dimen159
\Gm@odd@mp=\dimen160
\Gm@even@mp=\dimen161
\Gm@layoutwidth=\dimen162
\Gm@layoutheight=\dimen163
\Gm@layouthoffset=\dimen164
\Gm@layoutvoffset=\dimen165
\Gm@dimlist=\toks29
)
(/usr/share/texlive/texmf-dist/tex/latex/pgf/frontendlayer/tikz.sty
(/usr/share/texlive/texmf-dist/tex/latex/pgf/basiclayer/pgf.sty
(/usr/share/texlive/texmf-dist/tex/latex/pgf/utilities/pgfrcs.sty
(/usr/share/texlive/texmf-dist/tex/generic/pgf/utilities/pgfutil-common.tex
\pgfutil@everybye=\toks30
\pgfutil@tempdima=\dimen166
\pgfutil@tempdimb=\dimen167
(/usr/share/texlive/texmf-dist/tex/generic/pgf/utilities/pgfutil-common-lists.t
ex)) (/usr/share/texlive/texmf-dist/tex/generic/pgf/utilities/pgfutil-latex.def
\pgfutil@abb=\box56
) (/usr/share/texlive/texmf-dist/tex/generic/pgf/utilities/pgfrcs.code.tex
(/usr/share/texlive/texmf-dist/tex/generic/pgf/pgf.revision.tex)
Package: pgfrcs 2021/05/15 v3.1.9a (3.1.9a)
))
Package: pgf 2021/05/15 v3.1.9a (3.1.9a)
(/usr/share/texlive/texmf-dist/tex/latex/pgf/basiclayer/pgfcore.sty
(/usr/share/texlive/texmf-dist/tex/latex/pgf/systemlayer/pgfsys.sty
(/usr/share/texlive/texmf-dist/tex/generic/pgf/systemlayer/pgfsys.code.tex
Package: pgfsys 2021/05/15 v3.1.9a (3.1.9a)
(/usr/share/texlive/texmf-dist/tex/generic/pgf/utilities/pgfkeys.code.tex
\pgfkeys@pathtoks=\toks31
\pgfkeys@temptoks=\toks32
(/usr/share/texlive/texmf-dist/tex/generic/pgf/utilities/pgfkeysfiltered.code.t
ex
\pgfkeys@tmptoks=\toks33
))
\pgf@x=\dimen168
\pgf@y=\dimen169
\pgf@xa=\dimen170
\pgf@ya=\dimen171
\pgf@xb=\dimen172
\pgf@yb=\dimen173
\pgf@xc=\dimen174
\pgf@yc=\dimen175
\pgf@xd=\dimen176
\pgf@yd=\dimen177
\w@pgf@writea=\write3
\r@pgf@reada=\read2
\c@pgf@counta=\count286
\c@pgf@countb=\count287
\c@pgf@countc=\count288
\c@pgf@countd=\count289
\t@pgf@toka=\toks34
\t@pgf@tokb=\toks35
\t@pgf@tokc=\toks36
\pgf@sys@id@count=\count290
(/usr/share/texlive/texmf-dist/tex/generic/pgf/systemlayer/pgf.cfg
File: pgf.cfg 2021/05/15 v3.1.9a (3.1.9a)
)
Driver file for pgf: pgfsys-pdftex.def
(/usr/share/texlive/texmf-dist/tex/generic/pgf/systemlayer/pgfsys-pdftex.def
File: pgfsys-pdftex.def 2021/05/15 v3.1.9a (3.1.9a)
(/usr/share/texlive/texmf-dist/tex/generic/pgf/systemlayer/pgfsys-common-pdf.de
f
File: pgfsys-common-pdf.def 2021/05/15 v3.1.9a (3.1.9a)
)))
(/usr/share/texlive/texmf-dist/tex/generic/pgf/systemlayer/pgfsyssoftpath.code.
tex
File: pgfsyssoftpath.code.tex 2021/05/15 v3.1.9a (3.1.9a)
\pgfsyssoftpath@smallbuffer@items=\count291
\pgfsyssoftpath@bigbuffer@items=\count292
)
(/usr/share/texlive/texmf-dist/tex/generic/pgf/systemlayer/pgfsysprotocol.code.
tex
File: pgfsysprotocol.code.tex 2021/05/15 v3.1.9a (3.1.9a)
)) (/usr/share/texlive/texmf-dist/tex/latex/xcolor/xcolor.sty
Package: xcolor 2021/10/31 v2.13 LaTeX color extensions (UK)
(/usr/share/texlive/texmf-dist/tex/latex/graphics-cfg/color.cfg
File: color.cfg 2016/01/02 v1.6 sample color configuration
)
Package xcolor Info: Driver file: pdftex.def on input line 227.
Package xcolor Info: Model `cmy' substituted by `cmy0' on input line 1352.
Package xcolor Info: Model `hsb' substituted by `rgb' on input line 1356.
Package xcolor Info: Model `RGB' extended on input line 1368.
Package xcolor Info: Model `HTML' substituted by `rgb' on input line 1370.
Package xcolor Info: Model `Hsb' substituted by `hsb' on input line 1371.
Package xcolor Info: Model `tHsb' substituted by `hsb' on input line 1372.
Package xcolor Info: Model `HSB' substituted by `hsb' on input line 1373.
Package xcolor Info: Model `Gray' substituted by `gray' on input line 1374.
Package xcolor Info: Model `wave' substituted by `hsb' on input line 1375.
)
(/usr/share/texlive/texmf-dist/tex/generic/pgf/basiclayer/pgfcore.code.tex
Package: pgfcore 2021/05/15 v3.1.9a (3.1.9a)
(/usr/share/texlive/texmf-dist/tex/generic/pgf/math/pgfmath.code.tex
(/usr/share/texlive/texmf-dist/tex/generic/pgf/math/pgfmathcalc.code.tex
(/usr/share/texlive/texmf-dist/tex/generic/pgf/math/pgfmathutil.code.tex)
(/usr/share/texlive/texmf-dist/tex/generic/pgf/math/pgfmathparser.code.tex
\pgfmath@dimen=\dimen178
\pgfmath@count=\count293
\pgfmath@box=\box57
\pgfmath@toks=\toks37
\pgfmath@stack@operand=\toks38
\pgfmath@stack@operation=\toks39
)
(/usr/share/texlive/texmf-dist/tex/generic/pgf/math/pgfmathfunctions.code.tex
(/usr/share/texlive/texmf-dist/tex/generic/pgf/math/pgfmathfunctions.basic.code
.tex)
(/usr/share/texlive/texmf-dist/tex/generic/pgf/math/pgfmathfunctions.trigonomet
ric.code.tex)
(/usr/share/texlive/texmf-dist/tex/generic/pgf/math/pgfmathfunctions.random.cod
e.tex)
(/usr/share/texlive/texmf-dist/tex/generic/pgf/math/pgfmathfunctions.comparison
.code.tex)
(/usr/share/texlive/texmf-dist/tex/generic/pgf/math/pgfmathfunctions.base.code.
tex)
(/usr/share/texlive/texmf-dist/tex/generic/pgf/math/pgfmathfunctions.round.code
.tex)
(/usr/share/texlive/texmf-dist/tex/generic/pgf/math/pgfmathfunctions.misc.code.
tex)
(/usr/share/texlive/texmf-dist/tex/generic/pgf/math/pgfmathfunctions.integerari
thmetics.code.tex)))
(/usr/share/texlive/texmf-dist/tex/generic/pgf/math/pgfmathfloat.code.tex
\c@pgfmathroundto@lastzeros=\count294
))
(/usr/share/texlive/texmf-dist/tex/generic/pgf/math/pgfint.code.tex)
(/usr/share/texlive/texmf-dist/tex/generic/pgf/basiclayer/pgfcorepoints.code.te
x
File: pgfcorepoints.code.tex 2021/05/15 v3.1.9a (3.1.9a)
\pgf@picminx=\dimen179
\pgf@picmaxx=\dimen180
\pgf@picminy=\dimen181
\pgf@picmaxy=\dimen182
\pgf@pathminx=\dimen183
\pgf@pathmaxx=\dimen184
\pgf@pathminy=\dimen185
\pgf@pathmaxy=\dimen186
\pgf@xx=\dimen187
\pgf@xy=\dimen188
\pgf@yx=\dimen189
\pgf@yy=\dimen190
\pgf@zx=\dimen191
\pgf@zy=\dimen192
)
(/usr/share/texlive/texmf-dist/tex/generic/pgf/basiclayer/pgfcorepathconstruct.
code.tex
File: pgfcorepathconstruct.code.tex 2021/05/15 v3.1.9a (3.1.9a)
\pgf@path@lastx=\dimen193
\pgf@path@lasty=\dimen194
)
(/usr/share/texlive/texmf-dist/tex/generic/pgf/basiclayer/pgfcorepathusage.code
.tex
File: pgfcorepathusage.code.tex 2021/05/15 v3.1.9a (3.1.9a)
\pgf@shorten@end@additional=\dimen195
\pgf@shorten@start@additional=\dimen196
)
(/usr/share/texlive/texmf-dist/tex/generic/pgf/basiclayer/pgfcorescopes.code.te
x
File: pgfcorescopes.code.tex 2021/05/15 v3.1.9a (3.1.9a)
\pgfpic=\box58
\pgf@hbox=\box59
\pgf@layerbox@main=\box60
\pgf@picture@serial@count=\count295
)
(/usr/share/texlive/texmf-dist/tex/generic/pgf/basiclayer/pgfcoregraphicstate.c
ode.tex
File: pgfcoregraphicstate.code.tex 2021/05/15 v3.1.9a (3.1.9a)
\pgflinewidth=\dimen197
)
(/usr/share/texlive/texmf-dist/tex/generic/pgf/basiclayer/pgfcoretransformation
s.code.tex
File: pgfcoretransformations.code.tex 2021/05/15 v3.1.9a (3.1.9a)
\pgf@pt@x=\dimen198
\pgf@pt@y=\dimen199
\pgf@pt@temp=\dimen256
)
(/usr/share/texlive/texmf-dist/tex/generic/pgf/basiclayer/pgfcorequick.code.tex
File: pgfcorequick.code.tex 2021/05/15 v3.1.9a (3.1.9a)
)
(/usr/share/texlive/texmf-dist/tex/generic/pgf/basiclayer/pgfcoreobjects.code.t
ex
File: pgfcoreobjects.code.tex 2021/05/15 v3.1.9a (3.1.9a)
)
(/usr/share/texlive/texmf-dist/tex/generic/pgf/basiclayer/pgfcorepathprocessing
.code.tex
File: pgfcorepathprocessing.code.tex 2021/05/15 v3.1.9a (3.1.9a)
)
(/usr/share/texlive/texmf-dist/tex/generic/pgf/basiclayer/pgfcorearrows.code.te
x
File: pgfcorearrows.code.tex 2021/05/15 v3.1.9a (3.1.9a)
\pgfarrowsep=\dimen257
)
(/usr/share/texlive/texmf-dist/tex/generic/pgf/basiclayer/pgfcoreshade.code.tex
File: pgfcoreshade.code.tex 2021/05/15 v3.1.9a (3.1.9a)
\pgf@max=\dimen258
\pgf@sys@shading@range@num=\count296
\pgf@shadingcount=\count297
)
(/usr/share/texlive/texmf-dist/tex/generic/pgf/basiclayer/pgfcoreimage.code.tex
File: pgfcoreimage.code.tex 2021/05/15 v3.1.9a (3.1.9a)
(/usr/share/texlive/texmf-dist/tex/generic/pgf/basiclayer/pgfcoreexternal.code.
tex
File: pgfcoreexternal.code.tex 2021/05/15 v3.1.9a (3.1.9a)
\pgfexternal@startupbox=\box61
))
(/usr/share/texlive/texmf-dist/tex/generic/pgf/basiclayer/pgfcorelayers.code.te
x
File: pgfcorelayers.code.tex 2021/05/15 v3.1.9a (3.1.9a)
)
(/usr/share/texlive/texmf-dist/tex/generic/pgf/basiclayer/pgfcoretransparency.c
ode.tex
File: pgfcoretransparency.code.tex 2021/05/15 v3.1.9a (3.1.9a)
)
(/usr/share/texlive/texmf-dist/tex/generic/pgf/basiclayer/pgfcorepatterns.code.
tex
File: pgfcorepatterns.code.tex 2021/05/15 v3.1.9a (3.1.9a)
)
(/usr/share/texlive/texmf-dist/tex/generic/pgf/basiclayer/pgfcorerdf.code.tex
File: pgfcorerdf.code.tex 2021/05/15 v3.1.9a (3.1.9a)
)))
(/usr/share/texlive/texmf-dist/tex/generic/pgf/modules/pgfmoduleshapes.code.tex
File: pgfmoduleshapes.code.tex 2021/05/15 v3.1.9a (3.1.9a)
\pgfnodeparttextbox=\box62
) (/usr/share/texlive/texmf-dist/tex/generic/pgf/modules/pgfmoduleplot.code.tex
File: pgfmoduleplot.code.tex 2021/05/15 v3.1.9a (3.1.9a)
)
(/usr/share/texlive/texmf-dist/tex/latex/pgf/compatibility/pgfcomp-version-0-65
.sty
Package: pgfcomp-version-0-65 2021/05/15 v3.1.9a (3.1.9a)
\pgf@nodesepstart=\dimen259
\pgf@nodesepend=\dimen260
)
(/usr/share/texlive/texmf-dist/tex/latex/pgf/compatibility/pgfcomp-version-1-18
.sty
Package: pgfcomp-version-1-18 2021/05/15 v3.1.9a (3.1.9a)
)) (/usr/share/texlive/texmf-dist/tex/latex/pgf/utilities/pgffor.sty
(/usr/share/texlive/texmf-dist/tex/latex/pgf/utilities/pgfkeys.sty
(/usr/share/texlive/texmf-dist/tex/generic/pgf/utilities/pgfkeys.code.tex))
(/usr/share/texlive/texmf-dist/tex/latex/pgf/math/pgfmath.sty
(/usr/share/texlive/texmf-dist/tex/generic/pgf/math/pgfmath.code.tex))
(/usr/share/texlive/texmf-dist/tex/generic/pgf/utilities/pgffor.code.tex
Package: pgffor 2021/05/15 v3.1.9a (3.1.9a)
(/usr/share/texlive/texmf-dist/tex/generic/pgf/math/pgfmath.code.tex)
\pgffor@iter=\dimen261
\pgffor@skip=\dimen262
\pgffor@stack=\toks40
\pgffor@toks=\toks41
))
(/usr/share/texlive/texmf-dist/tex/generic/pgf/frontendlayer/tikz/tikz.code.tex
Package: tikz 2021/05/15 v3.1.9a (3.1.9a)
(/usr/share/texlive/texmf-dist/tex/generic/pgf/libraries/pgflibraryplothandlers
.code.tex
File: pgflibraryplothandlers.code.tex 2021/05/15 v3.1.9a (3.1.9a)
\pgf@plot@mark@count=\count298
\pgfplotmarksize=\dimen263
)
\tikz@lastx=\dimen264
\tikz@lasty=\dimen265
\tikz@lastxsaved=\dimen266
\tikz@lastysaved=\dimen267
\tikz@lastmovetox=\dimen268
\tikz@lastmovetoy=\dimen269
\tikzleveldistance=\dimen270
\tikzsiblingdistance=\dimen271
\tikz@figbox=\box63
\tikz@figbox@bg=\box64
\tikz@tempbox=\box65
\tikz@tempbox@bg=\box66
\tikztreelevel=\count299
\tikznumberofchildren=\count300
\tikznumberofcurrentchild=\count301
\tikz@fig@count=\count302
(/usr/share/texlive/texmf-dist/tex/generic/pgf/modules/pgfmodulematrix.code.tex
File: pgfmodulematrix.code.tex 2021/05/15 v3.1.9a (3.1.9a)
\pgfmatrixcurrentrow=\count303
\pgfmatrixcurrentcolumn=\count304
\pgf@matrix@numberofcolumns=\count305
)
\tikz@expandcount=\count306
(/usr/share/texlive/texmf-dist/tex/generic/pgf/frontendlayer/tikz/libraries/tik
zlibrarytopaths.code.tex
File: tikzlibrarytopaths.code.tex 2021/05/15 v3.1.9a (3.1.9a)
)))
(/usr/share/texlive/texmf-dist/tex/latex/circuitikz/circuitikz.sty
Package: circuitikz 2021/10/31{} The CircuiTikz circuit drawing package version
1.4.4
(/usr/share/texlive/texmf-dist/tex/generic/pgf/frontendlayer/tikz/libraries/tik
zlibrarycalc.code.tex
File: tikzlibrarycalc.code.tex 2021/05/15 v3.1.9a (3.1.9a)
)
(/usr/share/texlive/texmf-dist/tex/generic/pgf/libraries/pgflibraryarrows.meta.
code.tex
File: pgflibraryarrows.meta.code.tex 2021/05/15 v3.1.9a (3.1.9a)
\pgfarrowinset=\dimen272
\pgfarrowlength=\dimen273
\pgfarrowwidth=\dimen274
\pgfarrowlinewidth=\dimen275
)
(/usr/share/texlive/texmf-dist/tex/generic/pgf/frontendlayer/tikz/libraries/tik
zlibrarybending.code.tex
File: tikzlibrarybending.code.tex 2021/05/15 v3.1.9a (3.1.9a)
(/usr/share/texlive/texmf-dist/tex/generic/pgf/modules/pgfmodulebending.code.te
x
File: pgfmodulebending.code.tex 2021/05/15 v3.1.9a (3.1.9a)
(/usr/share/texlive/texmf-dist/tex/generic/pgf/modules/pgfmodulenonlineartransf
ormations.code.tex
File: pgfmodulenonlineartransformations.code.tex 2021/05/15 v3.1.9a (3.1.9a)
\pgftransformnonlinearflatness=\dimen276
)
(/usr/share/texlive/texmf-dist/tex/generic/pgf/libraries/pgflibrarycurvilinear.
code.tex
File: pgflibrarycurvilinear.code.tex 2021/05/15 v3.1.9a (3.1.9a)
\pgf@curvilinear@time@a=\dimen277
\pgf@curvilinear@length@a=\dimen278
\pgf@curvilinear@length@b=\dimen279
\pgf@curvilinear@length@c=\dimen280
\pgf@curvilinear@length@d=\dimen281
)
\pgf@arrows@the@rigidity=\dimen282
))
(/usr/share/texlive/texmf-dist/tex/generic/pgf/frontendlayer/tikz/libraries/tik
zlibraryfpu.code.tex
(/usr/share/texlive/texmf-dist/tex/generic/pgf/libraries/pgflibraryfpu.code.tex
)) (/usr/share/texlive/texmf-dist/tex/generic/circuitikz/pgfcirc.defines.tex
\pgf@circ@count@a=\count307
\pgf@circ@count@b=\count308
\pgf@circ@count@c=\count309
\pgf@circ@res@up=\dimen283
\pgf@circ@res@down=\dimen284
\pgf@circ@res@zero=\dimen285
\pgf@circ@res@left=\dimen286
\pgf@circ@res@right=\dimen287
\pgf@circ@res@other=\dimen288
\pgf@circ@res@step=\dimen289
\pgf@circ@res@temp=\dimen290
\pgf@circ@Rlen=\dimen291
\pgf@circ@scaled@Rlen=\dimen292
\pgfstartlinewidth=\dimen293
)
(/usr/share/texlive/texmf-dist/tex/generic/circuitikz/pgfcircutils.tex
\ctikz@scratchbox=\box67
)
(/usr/share/texlive/texmf-dist/tex/generic/circuitikz/pgfcircpath.tex)
(/usr/share/texlive/texmf-dist/tex/generic/circuitikz/pgfcircshapes.tex)
(/usr/share/texlive/texmf-dist/tex/generic/circuitikz/pgfcircmonopoles.tex)
(/usr/share/texlive/texmf-dist/tex/generic/circuitikz/pgfcircbipoles.tex)
(/usr/share/texlive/texmf-dist/tex/generic/circuitikz/pgfcirctripoles.tex
\pgf@circ@res@count=\count310
)
(/usr/share/texlive/texmf-dist/tex/generic/circuitikz/pgfcircquadpoles.tex)
(/usr/share/texlive/texmf-dist/tex/generic/circuitikz/pgfcircmultipoles.tex)
(/usr/share/texlive/texmf-dist/tex/generic/circuitikz/pgfcirclabel.tex)
(/usr/share/texlive/texmf-dist/tex/generic/circuitikz/pgfcircvoltage.tex
\pgfcirc@labelshift=\dimen294
)
(/usr/share/texlive/texmf-dist/tex/generic/circuitikz/pgfcirccurrent.tex)
(/usr/share/texlive/texmf-dist/tex/generic/circuitikz/pgfcircflow.tex))
(/usr/share/texlive/texmf-dist/tex/generic/pgf/frontendlayer/tikz/libraries/tik
zlibraryshapes.code.tex
File: tikzlibraryshapes.code.tex 2021/05/15 v3.1.9a (3.1.9a)
(/usr/share/texlive/texmf-dist/tex/generic/pgf/frontendlayer/tikz/libraries/tik
zlibraryshapes.geometric.code.tex
File: tikzlibraryshapes.geometric.code.tex 2021/05/15 v3.1.9a (3.1.9a)
(/usr/share/texlive/texmf-dist/tex/generic/pgf/libraries/shapes/pgflibraryshape
s.geometric.code.tex
File: pgflibraryshapes.geometric.code.tex 2021/05/15 v3.1.9a (3.1.9a)
))
(/usr/share/texlive/texmf-dist/tex/generic/pgf/frontendlayer/tikz/libraries/tik
zlibraryshapes.misc.code.tex
File: tikzlibraryshapes.misc.code.tex 2021/05/15 v3.1.9a (3.1.9a)
(/usr/share/texlive/texmf-dist/tex/generic/pgf/libraries/shapes/pgflibraryshape
s.misc.code.tex
File: pgflibraryshapes.misc.code.tex 2021/05/15 v3.1.9a (3.1.9a)
))
(/usr/share/texlive/texmf-dist/tex/generic/pgf/frontendlayer/tikz/libraries/tik
zlibraryshapes.symbols.code.tex
File: tikzlibraryshapes.symbols.code.tex 2021/05/15 v3.1.9a (3.1.9a)
(/usr/share/texlive/texmf-dist/tex/generic/pgf/libraries/shapes/pgflibraryshape
s.symbols.code.tex
File: pgflibraryshapes.symbols.code.tex 2021/05/15 v3.1.9a (3.1.9a)
))
(/usr/share/texlive/texmf-dist/tex/generic/pgf/frontendlayer/tikz/libraries/tik
zlibraryshapes.arrows.code.tex
File: tikzlibraryshapes.arrows.code.tex 2021/05/15 v3.1.9a (3.1.9a)
(/usr/share/texlive/texmf-dist/tex/generic/pgf/libraries/shapes/pgflibraryshape
s.arrows.code.tex
File: pgflibraryshapes.arrows.code.tex 2021/05/15 v3.1.9a (3.1.9a)
))
(/usr/share/texlive/texmf-dist/tex/generic/pgf/frontendlayer/tikz/libraries/tik
zlibraryshapes.callouts.code.tex
(/usr/share/texlive/texmf-dist/tex/generic/pgf/libraries/shapes/pgflibraryshape
s.callouts.code.tex))
(/usr/share/texlive/texmf-dist/tex/generic/pgf/frontendlayer/tikz/libraries/tik
zlibraryshapes.multipart.code.tex
File: tikzlibraryshapes.multipart.code.tex 2021/05/15 v3.1.9a (3.1.9a)
(/usr/share/texlive/texmf-dist/tex/generic/pgf/libraries/shapes/pgflibraryshape
s.multipart.code.tex
File: pgflibraryshapes.multipart.code.tex 2021/05/15 v3.1.9a (3.1.9a)
\pgfnodepartlowerbox=\box68
\pgfnodeparttwobox=\box69
\pgfnodepartthreebox=\box70
\pgfnodepartfourbox=\box71
\pgfnodeparttwentybox=\box72
\pgfnodepartnineteenbox=\box73
\pgfnodeparteighteenbox=\box74
\pgfnodepartseventeenbox=\box75
\pgfnodepartsixteenbox=\box76
\pgfnodepartfifteenbox=\box77
\pgfnodepartfourteenbox=\box78
\pgfnodepartthirteenbox=\box79
\pgfnodeparttwelvebox=\box80
\pgfnodepartelevenbox=\box81
\pgfnodeparttenbox=\box82
\pgfnodepartninebox=\box83
\pgfnodeparteightbox=\box84
\pgfnodepartsevenbox=\box85
\pgfnodepartsixbox=\box86
\pgfnodepartfivebox=\box87
)))
(/usr/share/texlive/texmf-dist/tex/generic/pgf/frontendlayer/tikz/libraries/tik
zlibraryarrows.code.tex
File: tikzlibraryarrows.code.tex 2021/05/15 v3.1.9a (3.1.9a)
(/usr/share/texlive/texmf-dist/tex/generic/pgf/libraries/pgflibraryarrows.code.
tex
File: pgflibraryarrows.code.tex 2021/05/15 v3.1.9a (3.1.9a)
\arrowsize=\dimen295
))
No file lab2Report.aux.
\openout1 = `lab2Report.aux'.
LaTeX Font Info: Checking defaults for OML/cmm/m/it on input line 27.
LaTeX Font Info: ... okay on input line 27.
LaTeX Font Info: Checking defaults for OMS/cmsy/m/n on input line 27.
LaTeX Font Info: ... okay on input line 27.
LaTeX Font Info: Checking defaults for OT1/cmr/m/n on input line 27.
LaTeX Font Info: ... okay on input line 27.
LaTeX Font Info: Checking defaults for T1/cmr/m/n on input line 27.
LaTeX Font Info: ... okay on input line 27.
LaTeX Font Info: Checking defaults for TS1/cmr/m/n on input line 27.
LaTeX Font Info: ... okay on input line 27.
LaTeX Font Info: Checking defaults for OMX/cmex/m/n on input line 27.
LaTeX Font Info: ... okay on input line 27.
LaTeX Font Info: Checking defaults for U/cmr/m/n on input line 27.
LaTeX Font Info: ... okay on input line 27.
(/usr/share/texlive/texmf-dist/tex/context/base/mkii/supp-pdf.mkii
[Loading MPS to PDF converter (version 2006.09.02).]
\scratchcounter=\count311
\scratchdimen=\dimen296
\scratchbox=\box88
\nofMPsegments=\count312
\nofMParguments=\count313
\everyMPshowfont=\toks42
\MPscratchCnt=\count314
\MPscratchDim=\dimen297
\MPnumerator=\count315
\makeMPintoPDFobject=\count316
\everyMPtoPDFconversion=\toks43
) (/usr/share/texlive/texmf-dist/tex/latex/epstopdf-pkg/epstopdf-base.sty
Package: epstopdf-base 2020-01-24 v2.11 Base part for package epstopdf
Package epstopdf-base Info: Redefining graphics rule for `.eps' on input line 4
85.
(/usr/share/texlive/texmf-dist/tex/latex/latexconfig/epstopdf-sys.cfg
File: epstopdf-sys.cfg 2010/07/13 v1.3 Configuration of (r)epstopdf for TeX Liv
e
))
\c@lstlisting=\count317
*geometry* driver: auto-detecting
*geometry* detected driver: pdftex
*geometry* verbose mode - [ preamble ] result:
* driver: pdftex
* paper: letterpaper
* layout: <same size as paper>
* layoutoffset:(h,v)=(0.0pt,0.0pt)
* modes:
* h-part:(L,W,R)=(72.26999pt, 469.75502pt, 72.26999pt)
* v-part:(T,H,B)=(72.26999pt, 650.43001pt, 72.26999pt)
* \paperwidth=614.295pt
* \paperheight=794.96999pt
* \textwidth=469.75502pt
* \textheight=650.43001pt
* \oddsidemargin=0.0pt
* \evensidemargin=0.0pt
* \topmargin=-37.0pt
* \headheight=12.0pt
* \headsep=25.0pt
* \topskip=10.0pt
* \footskip=30.0pt
* \marginparwidth=65.0pt
* \marginparsep=11.0pt
* \columnsep=10.0pt
* \skip\footins=9.0pt plus 4.0pt minus 2.0pt
* \hoffset=0.0pt
* \voffset=0.0pt
* \mag=1000
* \@twocolumnfalse
* \@twosidefalse
* \@mparswitchfalse
* \@reversemarginfalse
* (1in=72.27pt=25.4mm, 1cm=28.453pt)
LaTeX Font Info: Trying to load font information for U+msa on input line 28.
(/usr/share/texlive/texmf-dist/tex/latex/amsfonts/umsa.fd
File: umsa.fd 2013/01/14 v3.01 AMS symbols A
)
LaTeX Font Info: Trying to load font information for U+msb on input line 28.
(/usr/share/texlive/texmf-dist/tex/latex/amsfonts/umsb.fd
File: umsb.fd 2013/01/14 v3.01 AMS symbols B
) [1
{/var/lib/texmf/fonts/map/pdftex/updmap/pdftex.map}] (./lab2Report.aux) )
Here is how much of TeX's memory you used:
32637 strings out of 478353
815223 string characters out of 5850635
1445697 words of memory out of 5000000
50388 multiletter control sequences out of 15000+600000
411159 words of font info for 58 fonts, out of 8000000 for 9000
1141 hyphenation exceptions out of 8191
84i,16n,89p,414b,834s stack positions out of 5000i,500n,10000p,200000b,80000s
</usr/
share/texlive/texmf-dist/fonts/type1/public/amsfonts/cm/cmbx12.pfb></usr/share/
texlive/texmf-dist/fonts/type1/public/amsfonts/cm/cmmi10.pfb></usr/share/texliv
e/texmf-dist/fonts/type1/public/amsfonts/cm/cmmi7.pfb></usr/share/texlive/texmf
-dist/fonts/type1/public/amsfonts/cm/cmr10.pfb></usr/share/texlive/texmf-dist/f
onts/type1/public/amsfonts/cm/cmr12.pfb></usr/share/texlive/texmf-dist/fonts/ty
pe1/public/amsfonts/cm/cmr17.pfb></usr/share/texlive/texmf-dist/fonts/type1/pub
lic/amsfonts/cm/cmr5.pfb></usr/share/texlive/texmf-dist/fonts/type1/public/amsf
onts/cm/cmr7.pfb></usr/share/texlive/texmf-dist/fonts/type1/public/amsfonts/cm/
cmtt10.pfb>
Output written on lab2Report.pdf (1 page, 97459 bytes).
PDF statistics:
56 PDF objects out of 1000 (max. 8388607)
34 compressed objects within 1 object stream
0 named destinations out of 1000 (max. 500000)
13 words of extra memory for PDF output out of 10000 (max. 10000000)

Binary file not shown.

Binary file not shown.

View file

@ -0,0 +1,89 @@
% File: lab2Report.tex
% Created: 10:22:13 Sat, 04 Sep 2021 EDT
% Last Change: 10:22:13 Sat, 04 Sep 2021 EDT
%
\documentclass[letterpaper]{article}
\usepackage{amsmath}
\usepackage{graphicx}
\usepackage{cancel}
\usepackage{amssymb}
\usepackage{listings}
\usepackage[shortlabels]{enumitem}
\usepackage{lipsum}
\usepackage{soul}
\usepackage{geometry}
\usepackage{tikz}
\usepackage{circuitikz}
\usetikzlibrary{shapes,arrows}
\geometry{portrait, margin=1in}
\date{09/04/2021}
\title{%
Lab 2 Report\\
\large EEET-427-01: Control Systems}
\author{Blizzard MacDougall}
\begin{document}
\maketitle
\pagenumbering{arabic}
\tikzstyle{int}=[draw, fill=blue!20, minimum size=2em]
\section{Section 1}
\begin{equation}
\begin{split}
\omega_{mtr}=750rad/s\\
\frac{\omega_{mtr}}{V_{arm}}=299\frac{rad}{sV}
\end{split}
\end{equation}
\section{Section 2}
\begin{equation}
\tau=0.12s
\end{equation}
\section{Section 3}
\begin{equation}
\frac{\omega_{mtr}}{V_{arm}}=\frac{a}{s+b}=\frac{2491.5\frac{rad}{s^2V}}{(s+8.\overline 3)Hz}
\end{equation}
\section{Section 4}
\begin{center}
\begin{tikzpicture}[node distance=2.5cm,auto,>=latex']
\node (a) [coordinate] {b};
\node [int] (b) [right of=a] {$\frac{2491.5}{s+8.\overline 3}$};
\node [coordinate] (end) [right of=b]{};
\path[->] (a) edge node {$V_{arm}$} (b);
\draw[->] (b) edge node {$\omega_{mtr}$} (end) ;
\end{tikzpicture}
\end{center}
\section{Section 5}
\begin{equation}
\begin{split}
\omega_{mtr}=750rad/s\\
\frac{\omega_{mtr}}{\omega_{ref}}=0.8399=83.99\%\\
\tau=0.12s\\
\frac{\omega_{mtr}}{\omega_{ref}}=\frac{a}{s+b}=\frac{6.999rad/s}{(s+8.\overline3)rad/s}
\end{split}
\end{equation}
\begin{center}
\begin{tikzpicture}[node distance=2.5cm,auto]
\node (a) [coordinate] {b};
\node [int] (b) [right of=a]{$\frac{6.999rad/s}{(s+8.\overline3)rad/s}$};
\node [coordinate] (end) [right of=b] {};
\path[->] (a) edge node {$\omega_{ref}$} (b);
\draw[->] (b) edge node {$\omega_{mtr}$} (end);
\end{tikzpicture}
\end{center}
\section{Section 6}
\begin{center}
\begin{verbatim}
DCgain=1.24
\end{verbatim}
\end{center}
\end{document}

Binary file not shown.

After

Width:  |  Height:  |  Size: 14 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 5.6 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 7.4 KiB

BIN
lab1/motorSpeedRamp.png Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 14 KiB

Binary file not shown.

View file

@ -0,0 +1,320 @@
/* Click in this box, then
CTRL-A to select all
CTRL-C to copy
CTRL-V to paste into Arduino IDE
File: Lab2_closed_loop_vel_STARTER_1
Written: Aug 31, 2020, Clark Hochgraf
Revised: Sep 10, 2021
Desc:
Closed loop speed control of dc motor.
Speed of the motor is measured using a quadrature encoder.
Assumes fixed 5v 2amp power supply on Motor Driver
*/
volatile byte quadratureCode, oldquadratureCode;
volatile float quadPos = 0.0;
float lastquadPos = 0;
float motorspeedRPS = 0;
bool isModuleEn = false;
bool prevModuleEn = false;
const byte TSAMP_MSEC = 20;
long timeElapsedTicks = 0;
const float TSAMP = 0.001 * TSAMP_MSEC;
int TOTAL_RUN_TIME_MSEC = 2000; // in millisec
volatile float adcReading = 0;
float pwm_value_commanded;// command supplied to the motor PWM value.
const int ENC2 = A2; // d16, PC2 PCINT10 (green wire)
const int ENC3 = A3; // d17, PC3 PCINT11 (blue wire
const int PWM_M1A_PIN = 3; // d3, PD3 PCINT19 digital output OCR2B (green wire)
const int PWM_M1B_PIN = 11; // d11, PB4 digital output OCR2A (blue wire)
const float VOLTS_PER_PWM = 5.0 / 255.0; // motor drive voltage per pwm command
const float PWM_PER_VOLT = 1 / VOLTS_PER_PWM; // pwm value to achieve 1 volt output
const float RADPERSEC_PERVOLT = 356.0; // from datasheet calculations
float Wref = 0;
//---------------------------------------------------------------------
// Motor constants: DF robot motor with encoder model FIT0458
const float K_EMF = 0.00285; //(V/(160*120))*60.0/TWO_PI; // V/rad/sec from V/1000RPM
const float K_TRQ = 0.008 / 2.8; // N-m/Amp
const float R_ARM = 2.14; // ohms
const float D_DRAG = 0e-6;
const float SYS_A = 1;
const float SYS_B = 1;
const float V_FRICTION = 0.15;
float Varm;
float mtrVel = 0.0, mtrPos = 0.0, errVel = 0.0, errPos = 0.0;
float refAcc = 0.0, refVel = 0.0, refPos = 0.0;
// ##################################################################
void setup()
{
Serial.begin(115200);//Initialize the serial port ** Set Serial Monitor to same 115200
Serial.println(F("Lab2_closed_loop_vel_v1"));
Serial.println(F("runs for two seconds and then stops"));
displayMenu();
initMotorPins();
initEncoderInterrupts();
initPWMtimer2();
}
// ##################################################################
void loop()
{ manageMenu();
syncSample();
if (isModuleEn) {
stepRefVel(500); // input is velocity in radians per sec
Wref = refVel; // set reference velocity for motor
// calculate motor velocity from change in motor position
mtrVel = (quadPos - lastquadPos) / (TSAMP_MSEC * 0.001); // radians per time interval (rad/sec)
lastquadPos = quadPos; // update most recent position value
// ADD LINE OF CODE HERE TO CALCULATE errVel which is equal to reference Velocity minus motor vel
errVel=refVel-mtrVel;
float kp=0.00125;// sets proportional feedback gain
// ADD LINE OF CODE HERE TO CALCULATE Varm which is equal to Kp gain times the error in velocity
Varm=kp*errVel;
//Varm = closedLoopVelP(errVel, 0.00125); // error signal, Kp gain // closed loop control
//Varm = refVel * K_EMF; // uncomment for open loop speed control
//Varm = refVel * K_EMF + V_FRICTION; // uncomment for open loop speed control
//Varm = refVel * K_EMF + V_FRICTION + mtrVel * D_DRAG * R_ARM / K_TRQ; // uncomment for open loop speed control
//Varm = Varm + closedLoopVelP(errVel, 0.0125);
driveMotorVolts(Varm);
printResults(); // only print while motor running
}
else { //send zero voltage command to pwm if not enabled
Varm = 0;
driveMotorVolts(Varm);
}
if (timeElapsedTicks * TSAMP_MSEC > TOTAL_RUN_TIME_MSEC) //stop motor after 2 seconds
{
isModuleEn = false;
}
prevModuleEn = isModuleEn;
} // End main loop
// ##################################################################
float closedLoopVelP(float errorIn, float Kp)
{
return Kp * errorIn;
}
//*********************************************************************
void stepRefVel(float vel_rad_per_sec) // step input velocity reference levels
{
if (timeElapsedTicks < 0) refVel = 0.0;
else if (timeElapsedTicks < 400) refVel = vel_rad_per_sec;
else if (timeElapsedTicks < 800) refVel = -vel_rad_per_sec;
else if (timeElapsedTicks < 1000) refVel = 0.0;
else isModuleEn = false;
}
//********************************************************************
void calculateError(void)
{
mtrVel = (quadPos - lastquadPos) / (TSAMP_MSEC * 0.001); // radians per time interval (rad/sec)
lastquadPos = quadPos;
errVel = refVel - mtrVel;
}
//********************************************************************
void driveMotorVolts(float Vmotor)
{
int pwm_command = (int)(Vmotor * PWM_PER_VOLT);
if (pwm_command < 0) { // negative case -- set direction CW
pwm_command = - int(pwm_command);
OCR2B = 0;
OCR2A = constrain(pwm_command, 0, 255); //Serial.println(OCR2A);
}
else
{ //positive case -- set direction CW
pwm_command = int(pwm_command);
OCR2A = 0;
OCR2B = constrain(pwm_command, 0, 255); //Serial.println(OCR2B);
}
}
//********************************************************************
void printResults(void)
{ if (isModuleEn != prevModuleEn)
{
//print header
Serial.print("time (msec): "); Serial.print(",");
Serial.print("motorspeed: (rad/sec) "); Serial.print(",");
Serial.print("quadPos: (rad) "); Serial.print(",");
Serial.print("pwm_command: () "); Serial.print(",");
Serial.print("Varm (V) "); Serial.print(",");
Serial.print("Wref (rad/sec)");
Serial.println();
quadPos = 0;
lastquadPos = quadPos;
}
motorspeedRPS = mtrVel;
Serial.print(timeElapsedTicks * TSAMP_MSEC); Serial.print(",");
Serial.print(motorspeedRPS); Serial.print(",");
Serial.print(quadPos); Serial.print(",");
Serial.print(pwm_value_commanded); Serial.print(",");
Serial.print(Varm); Serial.print(",");
Serial.print(Wref);
Serial.println();
timeElapsedTicks++;
}
//********************************************************************
void displayMenu()
{
Serial.println("\nEnter 'e' to toggle module enable.");
}
//********************************************************************
void manageMenu()
{
char inChar = Serial.read();
if (inChar == 'e')
{
isModuleEn = !isModuleEn;
if (isModuleEn) {
Serial.println(F("Module ENABLED"));
timeElapsedTicks = 0;
}
else Serial.println(F("Module DISABLED"));
}
}
//********************************************************************
void initMotorPins()
{ // configure pins as input or output
pinMode(ENC2, INPUT); // Encoder A
pinMode(ENC3, INPUT); // Encoder B
pinMode(PWM_M1A_PIN, OUTPUT); // set motor PWM signal to output
pinMode(PWM_M1B_PIN, OUTPUT); // set motor direction pin to output
}
//********************************************************************
void initEncoderInterrupts(void)
{
// Position encoder ISR setup
// PCINT1_vect ISR triggered for enabled bit changes on PCMSK1
cli(); // disable global interrupts
PCMSK1 = 0b00001100; // ENC3,2,1,0 -> A3,A2,A1,A0 -> d17,16,15,14
PCICR = (1 << PCIE1); // enable pin change interrupts 8..14
sei(); // enable global interrupts
}
//********************************************************************
void initPWMtimer2(void)
{
//-----------------------------------------------------------------
// Use Timer 2 for direct motor drive PWM generation.
// Prescale = 1, FAST PWM, 8-bit (Mode 3) -> 62.5 kHz PWM
// Output pins OC2B (d3~) and OC2A (d11~) driven by counter hardware.
cli();
TCCR2B = 0;
TCCR2A = 0;
TCCR2B = (0 << WGM22); // start FAST PWM mode 3 setup
TCCR2A = (1 << WGM21) | (1 << WGM20); // finish FAST PWM setup
TCCR2B |= (0 << CS22) | (0 << CS21) | (1 << CS20); // clock prescale = 1
TCCR2A |= (1 << COM2B1) | (0 << COM2B0); // OCR2B pin (d3~) noninverting PWM
TCCR2A |= (1 << COM2A1) | (0 << COM2A0); // OCR2A pin (d11~) noninverting PWM
OCR2B = 1; OCR2A = 1;
sei();
}
//********************************************************************
void decodeEncoder32(void) // 2 bit quad decoder
{
const float MTR_RAD_PER_TICK = TWO_PI / 32;
static byte oldquadratureCode = 0;
oldquadratureCode = quadratureCode;
quadratureCode = (PINC & 0b00001100);
// Quadrature sequence: 0,8,12,4 (update ?CW facing end)
switch (quadratureCode)
{
case 0:
if (oldquadratureCode == 4) quadPos += MTR_RAD_PER_TICK;
if (oldquadratureCode == 8) quadPos -= MTR_RAD_PER_TICK;
break;
case 8:
if (oldquadratureCode == 0) quadPos += MTR_RAD_PER_TICK;
if (oldquadratureCode == 12) quadPos -= MTR_RAD_PER_TICK;
break;
case 12:
if (oldquadratureCode == 8) quadPos += MTR_RAD_PER_TICK;
if (oldquadratureCode == 4) quadPos -= MTR_RAD_PER_TICK;
break;
case 4:
if (oldquadratureCode == 12) quadPos += MTR_RAD_PER_TICK;
if (oldquadratureCode == 0) quadPos -= MTR_RAD_PER_TICK;
break;
}
} // decodeEncoder32( )
//********************************************************************
void syncSample() // set the sample rate for ADC and therefore for the main loop
{ // sample interval time is set by TSAMP_MSEC
const unsigned long TIC_USEC = TSAMP_MSEC * 1000UL;
const byte ADCSRA_ISR = 0b11101111; // auto ISR, clkdiv = 128
static unsigned long tic, stake = 0;
static boolean first_run = true;
if (first_run) {
stake = micros(); // only runs first time to set stake
first_run = false;
}
while ((tic - stake) < TIC_USEC) tic = micros(); // wait here until
stake = tic;
ADCSRA = ADCSRA_ISR; // start oversample-average series
}
//********************************************************************
ISR(PCINT1_vect) // if pin change occurs, update quadrature decoder
{
decodeEncoder32();
}
//********************************************************************
ISR (ADC_vect)
{
const byte N_ADC_AVE = 80;
const float INV_N_ADC = 1.0 / N_ADC_AVE;
static byte nConv = 0;
static unsigned int loAccum = 0, hiAccum = 0;
//SET_TP0_HI;
loAccum += ADCL; // lower 8 bits: must read before ADCH per Atmel
hiAccum += ADCH; // upper 2 bits
if (++nConv >= N_ADC_AVE)
{
//SET_TP1_HI;
adcReading = INV_N_ADC * (256UL * hiAccum + loAccum);
hiAccum = 0; loAccum = 0;
nConv = 0;
ADCSRA &= ~bit(ADIE); // stop auto conversions
//SET_TP1_LO;
}
//SET_TP0_LO;
} // end of ADC_vect

View file

@ -0,0 +1,308 @@
/* Click in this box, then
CTRL-A to select all
CTRL-C to copy
CTRL-V to paste into Arduino IDE
File: Lab2_motor_step_v1
Written: Aug 31, 2020, Clark Hochgraf
Revised: Feb 8, 2021
Desc:
Closed loop speed control of dc motor.
Speed of the motor is measured using a quadrature encoder.
Assumes fixed 5v 2amp power supply on Motor Driver
*/
volatile byte quadratureCode, oldquadratureCode;
volatile float quadPos = 0.0;
float lastquadPos = 0;
float motorspeedRPS = 0;
bool isModuleEn = false;
bool prevModuleEn = false;
const byte TSAMP_MSEC = 20;
long timeElapsedTicks = 0;
const float TSAMP = 0.001 * TSAMP_MSEC;
int TOTAL_RUN_TIME_MSEC = 2000; // in millisec
volatile float adcReading = 0;
float pwm_value_commanded;// command supplied to the motor PWM value.
const int ENC2 = A2; // d16, PC2 PCINT10 (green wire)
const int ENC3 = A3; // d17, PC3 PCINT11 (blue wire
const int PWM_M1A_PIN = 3; // d3, PD3 PCINT19 digital output OCR2B (green wire)
const int PWM_M1B_PIN = 11; // d11, PB4 digital output OCR2A (blue wire)
const float VOLTS_PER_PWM = 5.0 / 255.0; // motor drive voltage per pwm command
const float PWM_PER_VOLT = 1 / VOLTS_PER_PWM; // pwm value to achieve 1 volt output
const float RADPERSEC_PERVOLT = 356.0; // from datasheet calculations
float Wref = 0;
//---------------------------------------------------------------------
// Motor constants: DF robot motor with encoder model FIT0458
const float K_EMF = 0.00285; //(V/(160*120))*60.0/TWO_PI; // V/rad/sec from V/1000RPM
const float K_TRQ = 0.008 / 2.8; // N-m/Amp
const float R_ARM = 2.14; // ohms
const float D_DRAG = 0e-6;
const float SYS_A = 1;
const float SYS_B = 1;
const float V_FRICTION = 0.15;
float Varm;
float mtrVel = 0.0, mtrPos = 0.0, errVel = 0.0, errPos = 0.0;
float refAcc = 0.0, refVel = 0.0, refPos = 0.0;
// ##################################################################
void setup()
{
Serial.begin(115200);//Initialize the serial port ** Set Serial Monitor to same 115200
Serial.println(F("Lab2_closed_loop_vel_v1"));
Serial.println(F("runs for two seconds and then stops"));
displayMenu();
initMotorPins();
initEncoderInterrupts();
initPWMtimer2();
}
// ##################################################################
void loop()
{ manageMenu();
syncSample();
if (isModuleEn) {
stepRefVel(500); // input is velocity in radians per sec
Wref = refVel;
calculateError();
Varm = closedLoopVelP(errVel, 0.0125); // error signal, Kp gain // closed loop control
//Varm = refVel * K_EMF; // uncomment for open loop speed control
Varm = refVel * K_EMF + V_FRICTION; // uncomment for open loop speed control
//Varm = refVel * K_EMF + V_FRICTION + mtrVel * D_DRAG * R_ARM / K_TRQ; // uncomment for open loop speed control
//Varm = Varm + closedLoopVelP(errVel, 0.0125);
driveMotorVolts(Varm);
printResults(); // only print while motor running
}
else { //send zero voltage command to pwm if not enabled
Varm = 0;
driveMotorVolts(Varm);
}
if (timeElapsedTicks * TSAMP_MSEC > TOTAL_RUN_TIME_MSEC) //stop motor after 2 seconds
{
isModuleEn = false;
}
prevModuleEn = isModuleEn;
} // End main loop
// ##################################################################
float closedLoopVelP(float errorIn, float Kp)
{
return Kp * errorIn;
}
//*********************************************************************
void stepRefVel(float vel_rad_per_sec) // step input velocity reference levels
{
if (timeElapsedTicks < 0) refVel = 0.0;
else if (timeElapsedTicks < 400) refVel = vel_rad_per_sec;
else if (timeElapsedTicks < 800) refVel = -vel_rad_per_sec;
else if (timeElapsedTicks < 1000) refVel = 0.0;
else isModuleEn = false;
}
//********************************************************************
void calculateError(void)
{
mtrVel = (quadPos - lastquadPos) / (TSAMP_MSEC * 0.001); // radians per time interval (rad/sec)
lastquadPos = quadPos;
errVel = refVel - mtrVel;
}
//********************************************************************
void driveMotorVolts(float Vmotor)
{
int pwm_command = (int)(Vmotor * PWM_PER_VOLT);
if (pwm_command < 0) { // negative case -- set direction CW
pwm_command = - int(pwm_command);
OCR2B = 0;
OCR2A = constrain(pwm_command, 0, 255); //Serial.println(OCR2A);
}
else
{ //positive case -- set direction CW
pwm_command = int(pwm_command);
OCR2A = 0;
OCR2B = constrain(pwm_command, 0, 255); //Serial.println(OCR2B);
}
}
//********************************************************************
void printResults(void)
{ if (isModuleEn != prevModuleEn)
{
//print header
Serial.print("time (msec): "); Serial.print(",");
Serial.print("motorspeed: (rad/sec) "); Serial.print(",");
Serial.print("quadPos: (rad) "); Serial.print(",");
Serial.print("pwm_command: () "); Serial.print(",");
Serial.print("Varm (V) "); Serial.print(",");
Serial.print("Wref (rad/sec)");
Serial.println();
quadPos = 0;
lastquadPos = quadPos;
}
motorspeedRPS = mtrVel;
Serial.print(timeElapsedTicks * TSAMP_MSEC); Serial.print(",");
Serial.print(motorspeedRPS); Serial.print(",");
Serial.print(quadPos); Serial.print(",");
Serial.print(pwm_value_commanded); Serial.print(",");
Serial.print(Varm); Serial.print(",");
Serial.print(Wref);
Serial.println();
timeElapsedTicks++;
}
//********************************************************************
void displayMenu()
{
Serial.println("\nEnter 'e' to toggle module enable.");
}
//********************************************************************
void manageMenu()
{
char inChar = Serial.read();
if (inChar == 'e')
{
isModuleEn = !isModuleEn;
if (isModuleEn) {
Serial.println(F("Module ENABLED"));
timeElapsedTicks = 0;
}
else Serial.println(F("Module DISABLED"));
}
}
//********************************************************************
void initMotorPins()
{ // configure pins as input or output
pinMode(ENC2, INPUT); // Encoder A
pinMode(ENC3, INPUT); // Encoder B
pinMode(PWM_M1A_PIN, OUTPUT); // set motor PWM signal to output
pinMode(PWM_M1B_PIN, OUTPUT); // set motor direction pin to output
}
//********************************************************************
void initEncoderInterrupts(void)
{
// Position encoder ISR setup
// PCINT1_vect ISR triggered for enabled bit changes on PCMSK1
cli(); // disable global interrupts
PCMSK1 = 0b00001100; // ENC3,2,1,0 -> A3,A2,A1,A0 -> d17,16,15,14
PCICR = (1 << PCIE1); // enable pin change interrupts 8..14
sei(); // enable global interrupts
}
//********************************************************************
void initPWMtimer2(void)
{
//-----------------------------------------------------------------
// Use Timer 2 for direct motor drive PWM generation.
// Prescale = 1, FAST PWM, 8-bit (Mode 3) -> 62.5 kHz PWM
// Output pins OC2B (d3~) and OC2A (d11~) driven by counter hardware.
cli();
TCCR2B = 0;
TCCR2A = 0;
TCCR2B = (0 << WGM22); // start FAST PWM mode 3 setup
TCCR2A = (1 << WGM21) | (1 << WGM20); // finish FAST PWM setup
TCCR2B |= (0 << CS22) | (0 << CS21) | (1 << CS20); // clock prescale = 1
TCCR2A |= (1 << COM2B1) | (0 << COM2B0); // OCR2B pin (d3~) noninverting PWM
TCCR2A |= (1 << COM2A1) | (0 << COM2A0); // OCR2A pin (d11~) noninverting PWM
OCR2B = 1; OCR2A = 1;
sei();
}
//********************************************************************
void decodeEncoder32(void) // 2 bit quad decoder
{
const float MTR_RAD_PER_TICK = TWO_PI / 32;
static byte oldquadratureCode = 0;
oldquadratureCode = quadratureCode;
quadratureCode = (PINC & 0b00001100);
// Quadrature sequence: 0,8,12,4 (update ?CW facing end)
switch (quadratureCode)
{
case 0:
if (oldquadratureCode == 4) quadPos += MTR_RAD_PER_TICK;
if (oldquadratureCode == 8) quadPos -= MTR_RAD_PER_TICK;
break;
case 8:
if (oldquadratureCode == 0) quadPos += MTR_RAD_PER_TICK;
if (oldquadratureCode == 12) quadPos -= MTR_RAD_PER_TICK;
break;
case 12:
if (oldquadratureCode == 8) quadPos += MTR_RAD_PER_TICK;
if (oldquadratureCode == 4) quadPos -= MTR_RAD_PER_TICK;
break;
case 4:
if (oldquadratureCode == 12) quadPos += MTR_RAD_PER_TICK;
if (oldquadratureCode == 0) quadPos -= MTR_RAD_PER_TICK;
break;
}
} // decodeEncoder32( )
//********************************************************************
void syncSample() // set the sample rate for ADC and therefore for the main loop
{ // sample interval time is set by TSAMP_MSEC
const unsigned long TIC_USEC = TSAMP_MSEC * 1000UL;
const byte ADCSRA_ISR = 0b11101111; // auto ISR, clkdiv = 128
static unsigned long tic, stake = 0;
static boolean first_run = true;
if (first_run) {
stake = micros(); // only runs first time to set stake
first_run = false;
}
while ((tic - stake) < TIC_USEC) tic = micros(); // wait here until
stake = tic;
ADCSRA = ADCSRA_ISR; // start oversample-average series
}
//********************************************************************
ISR(PCINT1_vect) // if pin change occurs, update quadrature decoder
{
decodeEncoder32();
}
//********************************************************************
ISR (ADC_vect)
{
const byte N_ADC_AVE = 80;
const float INV_N_ADC = 1.0 / N_ADC_AVE;
static byte nConv = 0;
static unsigned int loAccum = 0, hiAccum = 0;
//SET_TP0_HI;
loAccum += ADCL; // lower 8 bits: must read before ADCH per Atmel
hiAccum += ADCH; // upper 2 bits
if (++nConv >= N_ADC_AVE)
{
//SET_TP1_HI;
adcReading = INV_N_ADC * (256UL * hiAccum + loAccum);
hiAccum = 0; loAccum = 0;
nConv = 0;
ADCSRA &= ~bit(ADIE); // stop auto conversions
//SET_TP1_LO;
}
//SET_TP0_LO;
} // end of ADC_vect

BIN
lab2/finalGraph.png Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 14 KiB

View file

@ -0,0 +1,7 @@
\relax
\@writefile{toc}{\contentsline {section}{\numberline {1}Section 1}{1}{}\protected@file@percent }
\@writefile{toc}{\contentsline {section}{\numberline {2}Section 2}{1}{}\protected@file@percent }
\@writefile{toc}{\contentsline {section}{\numberline {3}Section 3}{1}{}\protected@file@percent }
\@writefile{toc}{\contentsline {section}{\numberline {4}Section 4}{2}{}\protected@file@percent }
\@writefile{toc}{\contentsline {section}{\numberline {5}Section 5}{3}{}\protected@file@percent }
\gdef \@abspage@last{3}

View file

@ -0,0 +1,331 @@
This is pdfTeX, Version 3.141592653-2.6-1.40.22 (TeX Live 2022/dev/Debian) (preloaded format=pdflatex 2021.12.7) 8 DEC 2021 17:53
entering extended mode
\write18 enabled.
file:line:error style messages enabled.
%&-line parsing enabled.
**lab2Report.tex
(./lab2Report.tex
LaTeX2e <2021-11-15>
L3 programming layer <2021-11-22>
(/usr/share/texlive/texmf-dist/tex/latex/base/article.cls
Document Class: article 2021/10/04 v1.4n Standard LaTeX document class
(/usr/share/texlive/texmf-dist/tex/latex/base/size10.clo
File: size10.clo 2021/10/04 v1.4n Standard LaTeX file (size option)
)
\c@part=\count183
\c@section=\count184
\c@subsection=\count185
\c@subsubsection=\count186
\c@paragraph=\count187
\c@subparagraph=\count188
\c@figure=\count189
\c@table=\count190
\abovecaptionskip=\skip47
\belowcaptionskip=\skip48
\bibindent=\dimen138
)
(/usr/share/texlive/texmf-dist/tex/latex/amsmath/amsmath.sty
Package: amsmath 2021/10/15 v2.17l AMS math features
\@mathmargin=\skip49
For additional information on amsmath, use the `?' option.
(/usr/share/texlive/texmf-dist/tex/latex/amsmath/amstext.sty
Package: amstext 2021/08/26 v2.01 AMS text
(/usr/share/texlive/texmf-dist/tex/latex/amsmath/amsgen.sty
File: amsgen.sty 1999/11/30 v2.0 generic functions
\@emptytoks=\toks16
\ex@=\dimen139
))
(/usr/share/texlive/texmf-dist/tex/latex/amsmath/amsbsy.sty
Package: amsbsy 1999/11/29 v1.2d Bold Symbols
\pmbraise@=\dimen140
)
(/usr/share/texlive/texmf-dist/tex/latex/amsmath/amsopn.sty
Package: amsopn 2021/08/26 v2.02 operator names
)
\inf@bad=\count191
LaTeX Info: Redefining \frac on input line 234.
\uproot@=\count192
\leftroot@=\count193
LaTeX Info: Redefining \overline on input line 399.
\classnum@=\count194
\DOTSCASE@=\count195
LaTeX Info: Redefining \ldots on input line 496.
LaTeX Info: Redefining \dots on input line 499.
LaTeX Info: Redefining \cdots on input line 620.
\Mathstrutbox@=\box50
\strutbox@=\box51
\big@size=\dimen141
LaTeX Font Info: Redeclaring font encoding OML on input line 743.
LaTeX Font Info: Redeclaring font encoding OMS on input line 744.
\macc@depth=\count196
\c@MaxMatrixCols=\count197
\dotsspace@=\muskip16
\c@parentequation=\count198
\dspbrk@lvl=\count199
\tag@help=\toks17
\row@=\count266
\column@=\count267
\maxfields@=\count268
\andhelp@=\toks18
\eqnshift@=\dimen142
\alignsep@=\dimen143
\tagshift@=\dimen144
\tagwidth@=\dimen145
\totwidth@=\dimen146
\lineht@=\dimen147
\@envbody=\toks19
\multlinegap=\skip50
\multlinetaggap=\skip51
\mathdisplay@stack=\toks20
LaTeX Info: Redefining \[ on input line 2938.
LaTeX Info: Redefining \] on input line 2939.
)
(/usr/share/texlive/texmf-dist/tex/latex/graphics/graphicx.sty
Package: graphicx 2021/09/16 v1.2d Enhanced LaTeX Graphics (DPC,SPQR)
(/usr/share/texlive/texmf-dist/tex/latex/graphics/keyval.sty
Package: keyval 2014/10/28 v1.15 key=value parser (DPC)
\KV@toks@=\toks21
)
(/usr/share/texlive/texmf-dist/tex/latex/graphics/graphics.sty
Package: graphics 2021/03/04 v1.4d Standard LaTeX Graphics (DPC,SPQR)
(/usr/share/texlive/texmf-dist/tex/latex/graphics/trig.sty
Package: trig 2021/08/11 v1.11 sin cos tan (DPC)
)
(/usr/share/texlive/texmf-dist/tex/latex/graphics-cfg/graphics.cfg
File: graphics.cfg 2016/06/04 v1.11 sample graphics configuration
)
Package graphics Info: Driver file: pdftex.def on input line 107.
(/usr/share/texlive/texmf-dist/tex/latex/graphics-def/pdftex.def
File: pdftex.def 2020/10/05 v1.2a Graphics/color driver for pdftex
))
\Gin@req@height=\dimen148
\Gin@req@width=\dimen149
)
(/usr/share/texlive/texmf-dist/tex/latex/cancel/cancel.sty
Package: cancel 2013/04/12 v2.2 Cancel math terms
)
(/usr/share/texlive/texmf-dist/tex/latex/amsfonts/amssymb.sty
Package: amssymb 2013/01/14 v3.01 AMS font symbols
(/usr/share/texlive/texmf-dist/tex/latex/amsfonts/amsfonts.sty
Package: amsfonts 2013/01/14 v3.01 Basic AMSFonts support
\symAMSa=\mathgroup4
\symAMSb=\mathgroup5
LaTeX Font Info: Redeclaring math symbol \hbar on input line 98.
LaTeX Font Info: Overwriting math alphabet `\mathfrak' in version `bold'
(Font) U/euf/m/n --> U/euf/b/n on input line 106.
))
(/usr/share/texlive/texmf-dist/tex/latex/listings/listings.sty
\lst@mode=\count269
\lst@gtempboxa=\box52
\lst@token=\toks22
\lst@length=\count270
\lst@currlwidth=\dimen150
\lst@column=\count271
\lst@pos=\count272
\lst@lostspace=\dimen151
\lst@width=\dimen152
\lst@newlines=\count273
\lst@lineno=\count274
\lst@maxwidth=\dimen153
(/usr/share/texlive/texmf-dist/tex/latex/listings/lstmisc.sty
File: lstmisc.sty 2020/03/24 1.8d (Carsten Heinz)
\c@lstnumber=\count275
\lst@skipnumbers=\count276
\lst@framebox=\box53
)
(/usr/share/texlive/texmf-dist/tex/latex/listings/listings.cfg
File: listings.cfg 2020/03/24 1.8d listings configuration
))
Package: listings 2020/03/24 1.8d (Carsten Heinz)
(/usr/share/texlive/texmf-dist/tex/latex/enumitem/enumitem.sty
Package: enumitem 2019/06/20 v3.9 Customized lists
\labelindent=\skip52
\enit@outerparindent=\dimen154
\enit@toks=\toks23
\enit@inbox=\box54
\enit@count@id=\count277
\enitdp@description=\count278
)
(/usr/share/texlive/texmf-dist/tex/latex/lipsum/lipsum.sty
(/usr/share/texlive/texmf-dist/tex/latex/l3packages/l3keys2e/l3keys2e.sty
(/usr/share/texlive/texmf-dist/tex/latex/l3kernel/expl3.sty
Package: expl3 2021-11-22 L3 programming layer (loader)
(/usr/share/texlive/texmf-dist/tex/latex/l3backend/l3backend-pdftex.def
File: l3backend-pdftex.def 2021-10-18 L3 backend support: PDF output (pdfTeX)
\l__color_backend_stack_int=\count279
\l__pdf_internal_box=\box55
))
Package: l3keys2e 2021-11-12 LaTeX2e option processing using LaTeX3 keys
)
Package: lipsum 2021-09-20 v2.7 150 paragraphs of Lorem Ipsum dummy text
\g__lipsum_par_int=\count280
\l__lipsum_a_int=\count281
\l__lipsum_b_int=\count282
(/usr/share/texlive/texmf-dist/tex/latex/lipsum/lipsum.ltd.tex))
(/usr/share/texlive/texmf-dist/tex/generic/soul/soul.sty
Package: soul 2003/11/17 v2.4 letterspacing/underlining (mf)
\SOUL@word=\toks24
\SOUL@lasttoken=\toks25
\SOUL@cmds=\toks26
\SOUL@buffer=\toks27
\SOUL@token=\toks28
\SOUL@spaceskip=\skip53
\SOUL@ttwidth=\dimen155
\SOUL@uldp=\dimen156
\SOUL@ulht=\dimen157
)
(/usr/share/texlive/texmf-dist/tex/latex/geometry/geometry.sty
Package: geometry 2020/01/02 v5.9 Page Geometry
(/usr/share/texlive/texmf-dist/tex/generic/iftex/ifvtex.sty
Package: ifvtex 2019/10/25 v1.7 ifvtex legacy package. Use iftex instead.
(/usr/share/texlive/texmf-dist/tex/generic/iftex/iftex.sty
Package: iftex 2020/03/06 v1.0d TeX engine tests
))
\Gm@cnth=\count283
\Gm@cntv=\count284
\c@Gm@tempcnt=\count285
\Gm@bindingoffset=\dimen158
\Gm@wd@mp=\dimen159
\Gm@odd@mp=\dimen160
\Gm@even@mp=\dimen161
\Gm@layoutwidth=\dimen162
\Gm@layoutheight=\dimen163
\Gm@layouthoffset=\dimen164
\Gm@layoutvoffset=\dimen165
\Gm@dimlist=\toks29
)
No file lab2Report.aux.
\openout1 = `lab2Report.aux'.
LaTeX Font Info: Checking defaults for OML/cmm/m/it on input line 23.
LaTeX Font Info: ... okay on input line 23.
LaTeX Font Info: Checking defaults for OMS/cmsy/m/n on input line 23.
LaTeX Font Info: ... okay on input line 23.
LaTeX Font Info: Checking defaults for OT1/cmr/m/n on input line 23.
LaTeX Font Info: ... okay on input line 23.
LaTeX Font Info: Checking defaults for T1/cmr/m/n on input line 23.
LaTeX Font Info: ... okay on input line 23.
LaTeX Font Info: Checking defaults for TS1/cmr/m/n on input line 23.
LaTeX Font Info: ... okay on input line 23.
LaTeX Font Info: Checking defaults for OMX/cmex/m/n on input line 23.
LaTeX Font Info: ... okay on input line 23.
LaTeX Font Info: Checking defaults for U/cmr/m/n on input line 23.
LaTeX Font Info: ... okay on input line 23.
(/usr/share/texlive/texmf-dist/tex/context/base/mkii/supp-pdf.mkii
[Loading MPS to PDF converter (version 2006.09.02).]
\scratchcounter=\count286
\scratchdimen=\dimen166
\scratchbox=\box56
\nofMPsegments=\count287
\nofMParguments=\count288
\everyMPshowfont=\toks30
\MPscratchCnt=\count289
\MPscratchDim=\dimen167
\MPnumerator=\count290
\makeMPintoPDFobject=\count291
\everyMPtoPDFconversion=\toks31
) (/usr/share/texlive/texmf-dist/tex/latex/epstopdf-pkg/epstopdf-base.sty
Package: epstopdf-base 2020-01-24 v2.11 Base part for package epstopdf
Package epstopdf-base Info: Redefining graphics rule for `.eps' on input line 4
85.
(/usr/share/texlive/texmf-dist/tex/latex/latexconfig/epstopdf-sys.cfg
File: epstopdf-sys.cfg 2010/07/13 v1.3 Configuration of (r)epstopdf for TeX Liv
e
))
\c@lstlisting=\count292
*geometry* driver: auto-detecting
*geometry* detected driver: pdftex
*geometry* verbose mode - [ preamble ] result:
* driver: pdftex
* paper: letterpaper
* layout: <same size as paper>
* layoutoffset:(h,v)=(0.0pt,0.0pt)
* modes:
* h-part:(L,W,R)=(72.26999pt, 469.75502pt, 72.26999pt)
* v-part:(T,H,B)=(72.26999pt, 650.43001pt, 72.26999pt)
* \paperwidth=614.295pt
* \paperheight=794.96999pt
* \textwidth=469.75502pt
* \textheight=650.43001pt
* \oddsidemargin=0.0pt
* \evensidemargin=0.0pt
* \topmargin=-37.0pt
* \headheight=12.0pt
* \headsep=25.0pt
* \topskip=10.0pt
* \footskip=30.0pt
* \marginparwidth=65.0pt
* \marginparsep=11.0pt
* \columnsep=10.0pt
* \skip\footins=9.0pt plus 4.0pt minus 2.0pt
* \hoffset=0.0pt
* \voffset=0.0pt
* \mag=1000
* \@twocolumnfalse
* \@twosidefalse
* \@mparswitchfalse
* \@reversemarginfalse
* (1in=72.27pt=25.4mm, 1cm=28.453pt)
LaTeX Font Info: Trying to load font information for U+msa on input line 24.
(/usr/share/texlive/texmf-dist/tex/latex/amsfonts/umsa.fd
File: umsa.fd 2013/01/14 v3.01 AMS symbols A
)
LaTeX Font Info: Trying to load font information for U+msb on input line 24.
(/usr/share/texlive/texmf-dist/tex/latex/amsfonts/umsb.fd
File: umsb.fd 2013/01/14 v3.01 AMS symbols B
)
Underfull \hbox (badness 10000) in paragraph at lines 48--49
[]
[1
{/var/lib/texmf/fonts/map/pdftex/updmap/pdftex.map}]
<section3.png, id=14, 466.8642pt x 278.9622pt>
File: section3.png Graphic file (type png)
<use section3.png>
Package pdftex.def Info: section3.png used on input line 60.
(pdftex.def) Requested size: 466.86305pt x 278.96152pt.
[2 <./section3.png>]
[3] (./lab2Report.aux) )
Here is how much of TeX's memory you used:
5448 strings out of 478353
85132 string characters out of 5850635
482075 words of memory out of 5000000
23526 multiletter control sequences out of 15000+600000
411159 words of font info for 58 fonts, out of 8000000 for 9000
1141 hyphenation exceptions out of 8191
68i,15n,77p,297b,339s stack positions out of 5000i,500n,10000p,200000b,80000s
</usr/share/texlive/texmf-dist/fonts/type1/public/amsfo
nts/cm/cmbx12.pfb></usr/share/texlive/texmf-dist/fonts/type1/public/amsfonts/cm
/cmmi10.pfb></usr/share/texlive/texmf-dist/fonts/type1/public/amsfonts/cm/cmmi7
.pfb></usr/share/texlive/texmf-dist/fonts/type1/public/amsfonts/cm/cmr10.pfb></
usr/share/texlive/texmf-dist/fonts/type1/public/amsfonts/cm/cmr12.pfb></usr/sha
re/texlive/texmf-dist/fonts/type1/public/amsfonts/cm/cmr17.pfb></usr/share/texl
ive/texmf-dist/fonts/type1/public/amsfonts/cm/cmsy10.pfb></usr/share/texlive/te
xmf-dist/fonts/type1/public/amsfonts/cm/cmtt10.pfb>
Output written on lab2Report.pdf (3 pages, 120572 bytes).
PDF statistics:
56 PDF objects out of 1000 (max. 8388607)
32 compressed objects within 1 object stream
0 named destinations out of 1000 (max. 500000)
6 words of extra memory for PDF output out of 10000 (max. 10000000)

Binary file not shown.

Binary file not shown.

View file

@ -0,0 +1,102 @@
% File: lab2Report.tex
% Created: 14:38:48 Fri, 10 Sep 2021 EDT
% Last Change: 14:38:48 Fri, 10 Sep 2021 EDT
%
\documentclass[letterpaper]{article}
\usepackage{amsmath}
\usepackage{graphicx}
\usepackage{cancel}
\usepackage{amssymb}
\usepackage{listings}
\usepackage[shortlabels]{enumitem}
\usepackage{lipsum}
\usepackage{soul}
\usepackage{geometry}
\geometry{portrait, margin=1in}
\date{09/10/2021}
\title{%
Lab 2 Report\\
\large EEET-427-01:Controls Systems}
\author{Blizzard MacDougall}
\begin{document}
\maketitle
\pagenumbering{arabic}
\section{Section 1}
\begin{enumerate}
\item When $K_p=0.1$, plot the speed step response. What undesirable behavior is seen in the actual speed signal?\\
The output speed exceeds the reference speed, making the system unstable.
\item Looking at the $V_{arm}$ signal that represents the voltage the control system wants to apply to the motor, why didn't the time constant of the control system keep getting smaller as $K_p$ went from $0.025$ to $0.1$?\\
The initial slope of the curve remains consistent. This is because the motor has a max acceleration that it can achieve.
\item Plot the signal $V_{arm}$ given $K_p=0.005$ and $K_p=0.0025$. What do you notice about the shape of $V_{arm}$? How does this relate to the faster response of the motor system when K has each of the above values?\\
The initial voltage response in $K_p=0.005$ is faster, but the voltage response of $K_p=0.0025$ is smoother.
\end{enumerate}
\section{Section 2}
\begin{enumerate}
\item What was your value of \verb|V_FRICTION|?
0.2595
\item Why didn't the intercept of the trendline change even when you added \verb|V_FRICTION|?\\
The intercept didn't change because that's a characteristic of the motor.
\item Why was the motor able to spin at low speeds with \verb|V_FRICTION| added, but not when \verb|V_FRICTION| was excluded?\\
This is because at low speeds, the motor has a friction to begin moving. Without compensating for that, the motor would not move at all. \verb|V_FRICTION| allows us to avoid this problem by increasing the baseline amount of voltage sent to the motor.
\end{enumerate}
\section{Section 3}
\begin{enumerate}
\item Using the slope of the trendline slope of $\omega_{mtr}$ vs $V_{arm}$ from section 2, find \verb|D_DRAG|.\\
\begin{equation}
\begin{split}
K_{eff}=K_e+\frac R{K_t}D_{drag}\\
D_{drag}=\frac{R}{K_t}(K_{eff}-K_e)\\
D_{drag}=\frac{0.0028}{2.14}(0.0033-0.0028)\\
D_{drag}=6.54_E-7
\end{split}
\end{equation}
\newpage
\item Plot the step response for $\omega_{ref}=700rad/sec$, label each axis with units, and give the plot a descriptive title.\\
\begin{figure}[h!]
\includegraphics{section3.png}
\end{figure}
\item What is the time constant of the response for a reference motor speed of $700rad/sec$ when \verb|D_DRAG| compensation is included?
\begin{equation}
\tau=138.4ms
\end{equation}
\item Was the time constant with compensation much faster, about the same, or much slower than without drag compensation?
The time constant with compensation was much faster. This is because the motor will continue to request more power for a longer period of time.
\item Was the steady state speed percent error with compensation much lower, about the same, or much higher than without drag compensation?
The steady state speed error was smaller with the compensation. This is because the compensation effectively shifts the
\end{enumerate}
\section{Section 4}
\begin{enumerate}
\item Calculate the motor steady state speed error. What is the percent steady state error with closed loop feedback and compensation for \verb|D_Drag| and \verb|V_friction|?
\begin{equation}
error=0.3\%
\end{equation}
\item Calculate the time constant of the closed loop response. What is the time constant in milliseconds with closed loop feedback and compensation for \verb|D_Drag| and \verb|V_friction|?
\begin{equation}
\tau=37.7ms
\end{equation}
\newpage
\item Was the time constant with compensation much faster, about the same, or slower than the original feedback control loop without compensation?\\
The time constant with compensation is much faster than the original feedback loop without compensation because the feedback speeds up the reaction time.
\item Was the steady state speed percent error with compensation much lower, about the same, or much higher than the original feedback control loop without compensation?\\
The error with compensation is lower than without compensation because the values get significantly closer to the reference speed.
\item What steady state speed percent error would you expect if the \verb|Kp| gain was reduced to \verb|0.00125|?
$40-60\%$ I'd expect the error to still be bad, as with the open loop no-feed-forward. However, I would expect it to be better than that model, but worse than if Kp is high.
\item What time constant would you expect if the \verb|Kp| gain was reduced to \verb|0.00125|? Try this and see what the actual motor speed is.
\end{enumerate}
\section{Section 5}
\begin{enumerate}
\item What is the notable difference between closed loop feedback control compared to open loop control, regardless of whether feed-forward is included?\\
The closed feedback loops nearly instantaneously reach their steady-state values.
\item What is the notable difference between using feed-forward control compared to not using feed-forward control, regardless of whether the control is open or closed loop?\\
The feed-forward loops appear to essentially be the non-feed-forward loops shifted vertically.
\end{enumerate}
\end{document}

Binary file not shown.

After

Width:  |  Height:  |  Size: 17 KiB

BIN
lab2/lab2spreadsheet.xlsx Normal file

Binary file not shown.

318
lab2/starter1/starter1.ino Normal file
View file

@ -0,0 +1,318 @@
/* Click in this box, then
CTRL-A to select all
CTRL-C to copy
CTRL-V to paste into Arduino IDE
File: Lab2_closed_loop_vel_STARTER_1
Written: Aug 31, 2020, Clark Hochgraf
Revised: Sept 17, 2021 - slowed down PWM frequency to 2kHz
Revised: Sep 10, 2021
Desc:
Closed loop speed control of dc motor.
Speed of the motor is measured using a quadrature encoder.
Assumes fixed 5v 2amp power supply on Motor Driver
*/
volatile byte quadratureCode, oldquadratureCode;
volatile float quadPos = 0.0;
float lastquadPos = 0;
float motorspeedRPS = 0;
bool isModuleEn = false;
bool prevModuleEn = false;
const byte TSAMP_MSEC = 20;
long timeElapsedTicks = 0;
const float TSAMP = 0.001 * TSAMP_MSEC;
int TOTAL_RUN_TIME_MSEC = 2000; // in millisec
volatile float adcReading = 0;
float pwm_value_commanded;// command supplied to the motor PWM value.
const int ENC2 = A2; // d16, PC2 PCINT10 (green wire)
const int ENC3 = A3; // d17, PC3 PCINT11 (blue wire
const int PWM_M1A_PIN = 3; // d3, PD3 PCINT19 digital output OCR2B (green wire)
const int PWM_M1B_PIN = 11; // d11, PB4 digital output OCR2A (blue wire)
const float VOLTS_PER_PWM = 5.0 / 255.0; // motor drive voltage per pwm command
const float PWM_PER_VOLT = 1 / VOLTS_PER_PWM; // pwm value to achieve 1 volt output
const float RADPERSEC_PERVOLT = 356.0; // from datasheet calculations
float Wref = 0;
//---------------------------------------------------------------------
// Motor constants: DF robot motor with encoder model FIT0458
const float K_EMF = 0.00285; //(V/(160*120))*60.0/TWO_PI; // V/rad/sec from V/1000RPM
const float K_TRQ = 0.008 / 2.8; // N-m/Amp
const float R_ARM = 2.14; // ohms
const float D_DRAG = 0e-6;
const float SYS_A = 1;
const float SYS_B = 1;
const float V_FRICTION = 0.15;
float Varm;
float mtrVel = 0.0, mtrPos = 0.0, errVel = 0.0, errPos = 0.0;
float refAcc = 0.0, refVel = 0.0, refPos = 0.0;
// ##################################################################
void setup()
{
Serial.begin(115200);//Initialize the serial port ** Set Serial Monitor to same 115200
Serial.println(F("Lab2_closed_loop_vel_v1"));
Serial.println(F("runs for two seconds and then stops"));
displayMenu();
initMotorPins();
initEncoderInterrupts();
initPWMtimer2();
}
// ##################################################################
void loop()
{ manageMenu();
syncSample();
if (isModuleEn) {
stepRefVel(500); // input is velocity in radians per sec
Wref = refVel; // set reference velocity for motor
// calculate motor velocity from change in motor position
mtrVel = (quadPos - lastquadPos) / (TSAMP_MSEC * 0.001); // radians per time interval (rad/sec)
lastquadPos = quadPos; // update most recent position value
// ADD LINE OF CODE HERE TO CALCULATE errVel which is equal to reference Velocity minus motor vel
errVel=refVel-mtrVel;
float kp=0.00125;// sets proportional feedback gain
// ADD LINE OF CODE HERE TO CALCULATE Varm which is equal to Kp gain times the error in velocity
Varm=kp*errVel;
Varm = closedLoopVelP(errVel, 0.00125); // error signal, Kp gain // closed loop control
//Varm = refVel * K_EMF; // uncomment for open loop speed control
//Varm = refVel * K_EMF + V_FRICTION; // uncomment for open loop speed control
//Varm = refVel * K_EMF + V_FRICTION + mtrVel * D_DRAG * R_ARM / K_TRQ; // uncomment for open loop speed control
//Varm = Varm + closedLoopVelP(errVel, 0.0125);
driveMotorVolts(Varm);
printResults(); // only print while motor running
}
else { //send zero voltage command to pwm if not enabled
Varm = 0;
driveMotorVolts(Varm);
}
if (timeElapsedTicks * TSAMP_MSEC > TOTAL_RUN_TIME_MSEC) //stop motor after 2 seconds
{
isModuleEn = false;
}
prevModuleEn = isModuleEn;
} // End main loop
// ##################################################################
float closedLoopVelP(float errorIn, float Kp)
{
return Kp * errorIn;
}
//*********************************************************************
void stepRefVel(float vel_rad_per_sec) // step input velocity reference levels
{
if (timeElapsedTicks < 0) refVel = 0.0;
else if (timeElapsedTicks < 400) refVel = vel_rad_per_sec;
else if (timeElapsedTicks < 800) refVel = -vel_rad_per_sec;
else if (timeElapsedTicks < 1000) refVel = 0.0;
else isModuleEn = false;
}
//********************************************************************
void calculateError(void)
{
mtrVel = (quadPos - lastquadPos) / (TSAMP_MSEC * 0.001); // radians per time interval (rad/sec)
lastquadPos = quadPos;
errVel = refVel - mtrVel;
}
//********************************************************************
void driveMotorVolts(float Vmotor)
{
int pwm_command = (int)(Vmotor * PWM_PER_VOLT);
if (pwm_command < 0) { // negative case -- set direction CW
pwm_command = - int(pwm_command);
OCR2B = 0;
OCR2A = constrain(pwm_command, 0, 255); //Serial.println(OCR2A);
}
else
{ //positive case -- set direction CW
pwm_command = int(pwm_command);
OCR2A = 0;
OCR2B = constrain(pwm_command, 0, 255); //Serial.println(OCR2B);
}
}
//********************************************************************
void printResults(void)
{ if (isModuleEn != prevModuleEn)
{
//print header
Serial.print("time (msec): "); Serial.print(",");
Serial.print("motorspeed: (rad/sec) "); Serial.print(",");
Serial.print("quadPos: (rad) "); Serial.print(",");
Serial.print("pwm_command: () "); Serial.print(",");
Serial.print("Varm (V) "); Serial.print(",");
Serial.print("Wref (rad/sec)");
Serial.println();
quadPos = 0;
lastquadPos = quadPos;
}
motorspeedRPS = mtrVel;
Serial.print(timeElapsedTicks * TSAMP_MSEC); Serial.print(",");
Serial.print(motorspeedRPS); Serial.print(",");
Serial.print(quadPos); Serial.print(",");
Serial.print(pwm_value_commanded); Serial.print(",");
Serial.print(Varm); Serial.print(",");
Serial.print(Wref);
Serial.println();
timeElapsedTicks++;
}
//********************************************************************
void displayMenu()
{
Serial.println("\nEnter 'e' to toggle module enable.");
}
//********************************************************************
void manageMenu()
{
char inChar = Serial.read();
if (inChar == 'e')
{
isModuleEn = !isModuleEn;
if (isModuleEn) {
Serial.println(F("Module ENABLED"));
timeElapsedTicks = 0;
}
else Serial.println(F("Module DISABLED"));
}
}
//********************************************************************
void initMotorPins()
{ // configure pins as input or output
pinMode(ENC2, INPUT); // Encoder A
pinMode(ENC3, INPUT); // Encoder B
pinMode(PWM_M1A_PIN, OUTPUT); // set motor PWM signal to output
pinMode(PWM_M1B_PIN, OUTPUT); // set motor direction pin to output
}
//********************************************************************
void initEncoderInterrupts(void)
{
// Position encoder ISR setup
// PCINT1_vect ISR triggered for enabled bit changes on PCMSK1
cli(); // disable global interrupts
PCMSK1 = 0b00001100; // ENC3,2,1,0 -> A3,A2,A1,A0 -> d17,16,15,14
PCICR = (1 << PCIE1); // enable pin change interrupts 8..14
sei(); // enable global interrupts
}
//********************************************************************
void initPWMtimer2(void)
{
//-----------------------------------------------------------------
// Use Timer 2 for direct motor drive PWM generation.
// Prescale = 1, FAST PWM, 8-bit (Mode 3) -> 62.5 kHz PWM
// Output pins OC2B (d3~) and OC2A (d11~) driven by counter hardware.
cli();
TCCR2B = 0;
TCCR2A = 0;
TCCR2B = (0 << WGM22); // start FAST PWM mode 3 setup
TCCR2A = (1 << WGM21) | (1 << WGM20); // finish FAST PWM setup
// TCCR2B |= (0 << CS22) | (0 << CS21) | (1 << CS20); // clock prescale = 1 (problem for PWM driver board)
TCCR2B |= (0 << CS22) | (1 << CS21) | (1 << CS20); // clock prescale = 32
TCCR2A |= (1 << COM2B1) | (0 << COM2B0); // OCR2B pin (d3~) noninverting PWM
TCCR2A |= (1 << COM2A1) | (0 << COM2A0); // OCR2A pin (d11~) noninverting PWM
OCR2B = 1; OCR2A = 1;
sei();
}
//********************************************************************
void decodeEncoder32(void) // 2 bit quad decoder
{
const float MTR_RAD_PER_TICK = TWO_PI / 32;
static byte oldquadratureCode = 0;
oldquadratureCode = quadratureCode;
quadratureCode = (PINC & 0b00001100);
// Quadrature sequence: 0,8,12,4 (update ?CW facing end)
switch (quadratureCode)
{
case 0:
if (oldquadratureCode == 4) quadPos += MTR_RAD_PER_TICK;
if (oldquadratureCode == 8) quadPos -= MTR_RAD_PER_TICK;
break;
case 8:
if (oldquadratureCode == 0) quadPos += MTR_RAD_PER_TICK;
if (oldquadratureCode == 12) quadPos -= MTR_RAD_PER_TICK;
break;
case 12:
if (oldquadratureCode == 8) quadPos += MTR_RAD_PER_TICK;
if (oldquadratureCode == 4) quadPos -= MTR_RAD_PER_TICK;
break;
case 4:
if (oldquadratureCode == 12) quadPos += MTR_RAD_PER_TICK;
if (oldquadratureCode == 0) quadPos -= MTR_RAD_PER_TICK;
break;
}
} // decodeEncoder32( )
//********************************************************************
void syncSample() // set the sample rate for ADC and therefore for the main loop
{ // sample interval time is set by TSAMP_MSEC
const unsigned long TIC_USEC = TSAMP_MSEC * 1000UL;
const byte ADCSRA_ISR = 0b11101111; // auto ISR, clkdiv = 128
static unsigned long tic, stake = 0;
static boolean first_run = true;
if (first_run) {
stake = micros(); // only runs first time to set stake
first_run = false;
}
while ((tic - stake) < TIC_USEC) tic = micros(); // wait here until
stake = tic;
ADCSRA = ADCSRA_ISR; // start oversample-average series
}
//********************************************************************
ISR(PCINT1_vect) // if pin change occurs, update quadrature decoder
{
decodeEncoder32();
}
//********************************************************************
ISR (ADC_vect)
{
const byte N_ADC_AVE = 80;
const float INV_N_ADC = 1.0 / N_ADC_AVE;
static byte nConv = 0;
static unsigned int loAccum = 0, hiAccum = 0;
//SET_TP0_HI;
loAccum += ADCL; // lower 8 bits: must read before ADCH per Atmel
hiAccum += ADCH; // upper 2 bits
if (++nConv >= N_ADC_AVE)
{
//SET_TP1_HI;
adcReading = INV_N_ADC * (256UL * hiAccum + loAccum);
hiAccum = 0; loAccum = 0;
nConv = 0;
ADCSRA &= ~bit(ADIE); // stop auto conversions
//SET_TP1_LO;
}
//SET_TP0_LO;
} // end of ADC_vect

309
lab2/starter2/starter2.ino Normal file
View file

@ -0,0 +1,309 @@
/* Click in this box, then
CTRL-A to select all
CTRL-C to copy
CTRL-V to paste into Arduino IDE
File: Lab2_motor_step_v1
Written: Aug 31, 2020, Clark Hochgraf
Revised: Sept 17, 2021 - slowed down PWM frequency to 2kHz
Revised: Feb 8, 2021
Desc:
Closed loop speed control of dc motor.
Speed of the motor is measured using a quadrature encoder.
Assumes fixed 5v 2amp power supply on Motor Driver
*/
volatile byte quadratureCode, oldquadratureCode;
volatile float quadPos = 0.0;
float lastquadPos = 0;
float motorspeedRPS = 0;
bool isModuleEn = false;
bool prevModuleEn = false;
const byte TSAMP_MSEC = 20;
long timeElapsedTicks = 0;
const float TSAMP = 0.001 * TSAMP_MSEC;
int TOTAL_RUN_TIME_MSEC = 2000; // in millisec
volatile float adcReading = 0;
float pwm_value_commanded;// command supplied to the motor PWM value.
const int ENC2 = A2; // d16, PC2 PCINT10 (green wire)
const int ENC3 = A3; // d17, PC3 PCINT11 (blue wire
const int PWM_M1A_PIN = 3; // d3, PD3 PCINT19 digital output OCR2B (green wire)
const int PWM_M1B_PIN = 11; // d11, PB4 digital output OCR2A (blue wire)
const float VOLTS_PER_PWM = 5.0 / 255.0; // motor drive voltage per pwm command
const float PWM_PER_VOLT = 1 / VOLTS_PER_PWM; // pwm value to achieve 1 volt output
const float RADPERSEC_PERVOLT = 356.0; // from datasheet calculations
float Wref = 0;
//---------------------------------------------------------------------
// Motor constants: DF robot motor with encoder model FIT0458
const float K_EMF = 0.00285; //(V/(160*120))*60.0/TWO_PI; // V/rad/sec from V/1000RPM
const float K_TRQ = 0.008 / 2.8; // N-m/Amp
const float R_ARM = 2.14; // ohms
const float D_DRAG = 6.54e-7;
const float SYS_A = 1;
const float SYS_B = 1;
const float V_FRICTION = 0.2595;
float Varm;
float mtrVel = 0.0, mtrPos = 0.0, errVel = 0.0, errPos = 0.0;
float refAcc = 0.0, refVel = 0.0, refPos = 0.0;
// ##################################################################
void setup()
{
Serial.begin(115200);//Initialize the serial port ** Set Serial Monitor to same 115200
Serial.println(F("Lab2_closed_loop_vel_v1"));
Serial.println(F("runs for two seconds and then stops"));
displayMenu();
initMotorPins();
initEncoderInterrupts();
initPWMtimer2();
}
// ##################################################################
void loop()
{ manageMenu();
syncSample();
if (isModuleEn) {
stepRefVel(500); // input is velocity in radians per sec
Wref = refVel;
calculateError();
//Varm = closedLoopVelP(errVel, 0.1); // error signal, Kp gain // closed loop control
//Varm = refVel * K_EMF; // uncomment for open loop speed control
Varm = refVel * K_EMF + V_FRICTION; // uncomment for open loop speed control
//Varm = refVel * K_EMF + V_FRICTION + mtrVel * D_DRAG * R_ARM / K_TRQ; // uncomment for open loop speed control
//Varm = Varm + closedLoopVelP(errVel, 0.0125);
driveMotorVolts(Varm);
printResults(); // only print while motor running
}
else { //send zero voltage command to pwm if not enabled
Varm = 0;
driveMotorVolts(Varm);
}
if (timeElapsedTicks * TSAMP_MSEC > TOTAL_RUN_TIME_MSEC) //stop motor after 2 seconds
{
isModuleEn = false;
}
prevModuleEn = isModuleEn;
} // End main loop
// ##################################################################
float closedLoopVelP(float errorIn, float Kp)
{
return Kp * errorIn;
}
//*********************************************************************
void stepRefVel(float vel_rad_per_sec) // step input velocity reference levels
{
if (timeElapsedTicks < 0) refVel = 0.0;
else if (timeElapsedTicks < 400) refVel = vel_rad_per_sec;
else if (timeElapsedTicks < 800) refVel = -vel_rad_per_sec;
else if (timeElapsedTicks < 1000) refVel = 0.0;
else isModuleEn = false;
}
//********************************************************************
void calculateError(void)
{
mtrVel = (quadPos - lastquadPos) / (TSAMP_MSEC * 0.001); // radians per time interval (rad/sec)
lastquadPos = quadPos;
errVel = refVel - mtrVel;
}
//********************************************************************
void driveMotorVolts(float Vmotor)
{
int pwm_command = (int)(Vmotor * PWM_PER_VOLT);
if (pwm_command < 0) { // negative case -- set direction CW
pwm_command = - int(pwm_command);
OCR2B = 0;
OCR2A = constrain(pwm_command, 0, 255); //Serial.println(OCR2A);
}
else
{ //positive case -- set direction CW
pwm_command = int(pwm_command);
OCR2A = 0;
OCR2B = constrain(pwm_command, 0, 255); //Serial.println(OCR2B);
}
}
//********************************************************************
void printResults(void)
{ if (isModuleEn != prevModuleEn)
{
//print header
Serial.print("time (msec): "); Serial.print(",");
Serial.print("motorspeed: (rad/sec) "); Serial.print(",");
Serial.print("quadPos: (rad) "); Serial.print(",");
Serial.print("pwm_command: () "); Serial.print(",");
Serial.print("Varm (V) "); Serial.print(",");
Serial.print("Wref (rad/sec)");
Serial.println();
quadPos = 0;
lastquadPos = quadPos;
}
motorspeedRPS = mtrVel;
Serial.print(timeElapsedTicks * TSAMP_MSEC); Serial.print(",");
Serial.print(motorspeedRPS); Serial.print(",");
Serial.print(quadPos); Serial.print(",");
Serial.print(pwm_value_commanded); Serial.print(",");
Serial.print(Varm); Serial.print(",");
Serial.print(Wref);
Serial.println();
timeElapsedTicks++;
}
//********************************************************************
void displayMenu()
{
Serial.println("\nEnter 'e' to toggle module enable.");
}
//********************************************************************
void manageMenu()
{
char inChar = Serial.read();
if (inChar == 'e')
{
isModuleEn = !isModuleEn;
if (isModuleEn) {
Serial.println(F("Module ENABLED"));
timeElapsedTicks = 0;
}
else Serial.println(F("Module DISABLED"));
}
}
//********************************************************************
void initMotorPins()
{ // configure pins as input or output
pinMode(ENC2, INPUT); // Encoder A
pinMode(ENC3, INPUT); // Encoder B
pinMode(PWM_M1A_PIN, OUTPUT); // set motor PWM signal to output
pinMode(PWM_M1B_PIN, OUTPUT); // set motor direction pin to output
}
//********************************************************************
void initEncoderInterrupts(void)
{
// Position encoder ISR setup
// PCINT1_vect ISR triggered for enabled bit changes on PCMSK1
cli(); // disable global interrupts
PCMSK1 = 0b00001100; // ENC3,2,1,0 -> A3,A2,A1,A0 -> d17,16,15,14
PCICR = (1 << PCIE1); // enable pin change interrupts 8..14
sei(); // enable global interrupts
}
//********************************************************************
void initPWMtimer2(void)
{
//-----------------------------------------------------------------
// Use Timer 2 for direct motor drive PWM generation.
// Prescale = 1, FAST PWM, 8-bit (Mode 3) -> 62.5 kHz PWM
// Output pins OC2B (d3~) and OC2A (d11~) driven by counter hardware.
cli();
TCCR2B = 0;
TCCR2A = 0;
TCCR2B = (0 << WGM22); // start FAST PWM mode 3 setup
TCCR2A = (1 << WGM21) | (1 << WGM20); // finish FAST PWM setup
// TCCR2B |= (0 << CS22) | (0 << CS21) | (1 << CS20); // clock prescale = 1 (problem for PWM driver board)
TCCR2B |= (0 << CS22) | (1 << CS21) | (1 << CS20); // clock prescale = 32
TCCR2A |= (1 << COM2B1) | (0 << COM2B0); // OCR2B pin (d3~) noninverting PWM
TCCR2A |= (1 << COM2A1) | (0 << COM2A0); // OCR2A pin (d11~) noninverting PWM
OCR2B = 1; OCR2A = 1;
sei();
}
//********************************************************************
void decodeEncoder32(void) // 2 bit quad decoder
{
const float MTR_RAD_PER_TICK = TWO_PI / 32;
static byte oldquadratureCode = 0;
oldquadratureCode = quadratureCode;
quadratureCode = (PINC & 0b00001100);
// Quadrature sequence: 0,8,12,4 (update ?CW facing end)
switch (quadratureCode)
{
case 0:
if (oldquadratureCode == 4) quadPos += MTR_RAD_PER_TICK;
if (oldquadratureCode == 8) quadPos -= MTR_RAD_PER_TICK;
break;
case 8:
if (oldquadratureCode == 0) quadPos += MTR_RAD_PER_TICK;
if (oldquadratureCode == 12) quadPos -= MTR_RAD_PER_TICK;
break;
case 12:
if (oldquadratureCode == 8) quadPos += MTR_RAD_PER_TICK;
if (oldquadratureCode == 4) quadPos -= MTR_RAD_PER_TICK;
break;
case 4:
if (oldquadratureCode == 12) quadPos += MTR_RAD_PER_TICK;
if (oldquadratureCode == 0) quadPos -= MTR_RAD_PER_TICK;
break;
}
} // decodeEncoder32( )
//********************************************************************
void syncSample() // set the sample rate for ADC and therefore for the main loop
{ // sample interval time is set by TSAMP_MSEC
const unsigned long TIC_USEC = TSAMP_MSEC * 1000UL;
const byte ADCSRA_ISR = 0b11101111; // auto ISR, clkdiv = 128
static unsigned long tic, stake = 0;
static boolean first_run = true;
if (first_run) {
stake = micros(); // only runs first time to set stake
first_run = false;
}
while ((tic - stake) < TIC_USEC) tic = micros(); // wait here until
stake = tic;
ADCSRA = ADCSRA_ISR; // start oversample-average series
}
//********************************************************************
ISR(PCINT1_vect) // if pin change occurs, update quadrature decoder
{
decodeEncoder32();
}
//********************************************************************
ISR (ADC_vect)
{
const byte N_ADC_AVE = 80;
const float INV_N_ADC = 1.0 / N_ADC_AVE;
static byte nConv = 0;
static unsigned int loAccum = 0, hiAccum = 0;
//SET_TP0_HI;
loAccum += ADCL; // lower 8 bits: must read before ADCH per Atmel
hiAccum += ADCH; // upper 2 bits
if (++nConv >= N_ADC_AVE)
{
//SET_TP1_HI;
adcReading = INV_N_ADC * (256UL * hiAccum + loAccum);
hiAccum = 0; loAccum = 0;
nConv = 0;
ADCSRA &= ~bit(ADIE); // stop auto conversions
//SET_TP1_LO;
}
//SET_TP0_LO;
} // end of ADC_vect

Binary file not shown.

Binary file not shown.

Binary file not shown.

View file

@ -0,0 +1,320 @@
/* Click in this box, then
CTRL-A to select all
CTRL-C to copy
CTRL-V to paste into Arduino IDE
File: Lab2_closed_loop_vel_STARTER_1
Written: Aug 31, 2020, Clark Hochgraf
Revised: Sep 10, 2021
Desc:
Closed loop speed control of dc motor.
Speed of the motor is measured using a quadrature encoder.
Assumes fixed 5v 2amp power supply on Motor Driver
*/
volatile byte quadratureCode, oldquadratureCode;
volatile float quadPos = 0.0;
float lastquadPos = 0;
float motorspeedRPS = 0;
bool isModuleEn = false;
bool prevModuleEn = false;
const byte TSAMP_MSEC = 20;
long timeElapsedTicks = 0;
const float TSAMP = 0.001 * TSAMP_MSEC;
int TOTAL_RUN_TIME_MSEC = 2000; // in millisec
volatile float adcReading = 0;
float pwm_value_commanded;// command supplied to the motor PWM value.
const int ENC2 = A2; // d16, PC2 PCINT10 (green wire)
const int ENC3 = A3; // d17, PC3 PCINT11 (blue wire
const int PWM_M1A_PIN = 3; // d3, PD3 PCINT19 digital output OCR2B (green wire)
const int PWM_M1B_PIN = 11; // d11, PB4 digital output OCR2A (blue wire)
const float VOLTS_PER_PWM = 5.0 / 255.0; // motor drive voltage per pwm command
const float PWM_PER_VOLT = 1 / VOLTS_PER_PWM; // pwm value to achieve 1 volt output
const float RADPERSEC_PERVOLT = 356.0; // from datasheet calculations
float Wref = 0;
//---------------------------------------------------------------------
// Motor constants: DF robot motor with encoder model FIT0458
const float K_EMF = 0.00285; //(V/(160*120))*60.0/TWO_PI; // V/rad/sec from V/1000RPM
const float K_TRQ = 0.008 / 2.8; // N-m/Amp
const float R_ARM = 2.14; // ohms
const float D_DRAG = 0e-6;
const float SYS_A = 1;
const float SYS_B = 1;
const float V_FRICTION = 0.15;
float Varm;
float mtrVel = 0.0, mtrPos = 0.0, errVel = 0.0, errPos = 0.0;
float refAcc = 0.0, refVel = 0.0, refPos = 0.0;
// ##################################################################
void setup()
{
Serial.begin(115200);//Initialize the serial port ** Set Serial Monitor to same 115200
Serial.println(F("Lab2_closed_loop_vel_v1"));
Serial.println(F("runs for two seconds and then stops"));
displayMenu();
initMotorPins();
initEncoderInterrupts();
initPWMtimer2();
}
// ##################################################################
void loop()
{ manageMenu();
syncSample();
if (isModuleEn) {
stepRefVel(500); // input is velocity in radians per sec
Wref = refVel; // set reference velocity for motor
// calculate motor velocity from change in motor position
mtrVel = (quadPos - lastquadPos) / (TSAMP_MSEC * 0.001); // radians per time interval (rad/sec)
lastquadPos = quadPos; // update most recent position value
// ADD LINE OF CODE HERE TO CALCULATE errVel which is equal to reference Velocity minus motor vel
errVel=refVel-mtrVel;
float kp=0.00125;// sets proportional feedback gain
// ADD LINE OF CODE HERE TO CALCULATE Varm which is equal to Kp gain times the error in velocity
Varm=kp*errVel;
//Varm = closedLoopVelP(errVel, 0.00125); // error signal, Kp gain // closed loop control
//Varm = refVel * K_EMF; // uncomment for open loop speed control
//Varm = refVel * K_EMF + V_FRICTION; // uncomment for open loop speed control
//Varm = refVel * K_EMF + V_FRICTION + mtrVel * D_DRAG * R_ARM / K_TRQ; // uncomment for open loop speed control
//Varm = Varm + closedLoopVelP(errVel, 0.0125);
driveMotorVolts(Varm);
printResults(); // only print while motor running
}
else { //send zero voltage command to pwm if not enabled
Varm = 0;
driveMotorVolts(Varm);
}
if (timeElapsedTicks * TSAMP_MSEC > TOTAL_RUN_TIME_MSEC) //stop motor after 2 seconds
{
isModuleEn = false;
}
prevModuleEn = isModuleEn;
} // End main loop
// ##################################################################
float closedLoopVelP(float errorIn, float Kp)
{
return Kp * errorIn;
}
//*********************************************************************
void stepRefVel(float vel_rad_per_sec) // step input velocity reference levels
{
if (timeElapsedTicks < 0) refVel = 0.0;
else if (timeElapsedTicks < 400) refVel = vel_rad_per_sec;
else if (timeElapsedTicks < 800) refVel = -vel_rad_per_sec;
else if (timeElapsedTicks < 1000) refVel = 0.0;
else isModuleEn = false;
}
//********************************************************************
void calculateError(void)
{
mtrVel = (quadPos - lastquadPos) / (TSAMP_MSEC * 0.001); // radians per time interval (rad/sec)
lastquadPos = quadPos;
errVel = refVel - mtrVel;
}
//********************************************************************
void driveMotorVolts(float Vmotor)
{
int pwm_command = (int)(Vmotor * PWM_PER_VOLT);
if (pwm_command < 0) { // negative case -- set direction CW
pwm_command = - int(pwm_command);
OCR2B = 0;
OCR2A = constrain(pwm_command, 0, 255); //Serial.println(OCR2A);
}
else
{ //positive case -- set direction CW
pwm_command = int(pwm_command);
OCR2A = 0;
OCR2B = constrain(pwm_command, 0, 255); //Serial.println(OCR2B);
}
}
//********************************************************************
void printResults(void)
{ if (isModuleEn != prevModuleEn)
{
//print header
Serial.print("time (msec): "); Serial.print(",");
Serial.print("motorspeed: (rad/sec) "); Serial.print(",");
Serial.print("quadPos: (rad) "); Serial.print(",");
Serial.print("pwm_command: () "); Serial.print(",");
Serial.print("Varm (V) "); Serial.print(",");
Serial.print("Wref (rad/sec)");
Serial.println();
quadPos = 0;
lastquadPos = quadPos;
}
motorspeedRPS = mtrVel;
Serial.print(timeElapsedTicks * TSAMP_MSEC); Serial.print(",");
Serial.print(motorspeedRPS); Serial.print(",");
Serial.print(quadPos); Serial.print(",");
Serial.print(pwm_value_commanded); Serial.print(",");
Serial.print(Varm); Serial.print(",");
Serial.print(Wref);
Serial.println();
timeElapsedTicks++;
}
//********************************************************************
void displayMenu()
{
Serial.println("\nEnter 'e' to toggle module enable.");
}
//********************************************************************
void manageMenu()
{
char inChar = Serial.read();
if (inChar == 'e')
{
isModuleEn = !isModuleEn;
if (isModuleEn) {
Serial.println(F("Module ENABLED"));
timeElapsedTicks = 0;
}
else Serial.println(F("Module DISABLED"));
}
}
//********************************************************************
void initMotorPins()
{ // configure pins as input or output
pinMode(ENC2, INPUT); // Encoder A
pinMode(ENC3, INPUT); // Encoder B
pinMode(PWM_M1A_PIN, OUTPUT); // set motor PWM signal to output
pinMode(PWM_M1B_PIN, OUTPUT); // set motor direction pin to output
}
//********************************************************************
void initEncoderInterrupts(void)
{
// Position encoder ISR setup
// PCINT1_vect ISR triggered for enabled bit changes on PCMSK1
cli(); // disable global interrupts
PCMSK1 = 0b00001100; // ENC3,2,1,0 -> A3,A2,A1,A0 -> d17,16,15,14
PCICR = (1 << PCIE1); // enable pin change interrupts 8..14
sei(); // enable global interrupts
}
//********************************************************************
void initPWMtimer2(void)
{
//-----------------------------------------------------------------
// Use Timer 2 for direct motor drive PWM generation.
// Prescale = 1, FAST PWM, 8-bit (Mode 3) -> 62.5 kHz PWM
// Output pins OC2B (d3~) and OC2A (d11~) driven by counter hardware.
cli();
TCCR2B = 0;
TCCR2A = 0;
TCCR2B = (0 << WGM22); // start FAST PWM mode 3 setup
TCCR2A = (1 << WGM21) | (1 << WGM20); // finish FAST PWM setup
TCCR2B |= (0 << CS22) | (0 << CS21) | (1 << CS20); // clock prescale = 1
TCCR2A |= (1 << COM2B1) | (0 << COM2B0); // OCR2B pin (d3~) noninverting PWM
TCCR2A |= (1 << COM2A1) | (0 << COM2A0); // OCR2A pin (d11~) noninverting PWM
OCR2B = 1; OCR2A = 1;
sei();
}
//********************************************************************
void decodeEncoder32(void) // 2 bit quad decoder
{
const float MTR_RAD_PER_TICK = TWO_PI / 32;
static byte oldquadratureCode = 0;
oldquadratureCode = quadratureCode;
quadratureCode = (PINC & 0b00001100);
// Quadrature sequence: 0,8,12,4 (update ?CW facing end)
switch (quadratureCode)
{
case 0:
if (oldquadratureCode == 4) quadPos += MTR_RAD_PER_TICK;
if (oldquadratureCode == 8) quadPos -= MTR_RAD_PER_TICK;
break;
case 8:
if (oldquadratureCode == 0) quadPos += MTR_RAD_PER_TICK;
if (oldquadratureCode == 12) quadPos -= MTR_RAD_PER_TICK;
break;
case 12:
if (oldquadratureCode == 8) quadPos += MTR_RAD_PER_TICK;
if (oldquadratureCode == 4) quadPos -= MTR_RAD_PER_TICK;
break;
case 4:
if (oldquadratureCode == 12) quadPos += MTR_RAD_PER_TICK;
if (oldquadratureCode == 0) quadPos -= MTR_RAD_PER_TICK;
break;
}
} // decodeEncoder32( )
//********************************************************************
void syncSample() // set the sample rate for ADC and therefore for the main loop
{ // sample interval time is set by TSAMP_MSEC
const unsigned long TIC_USEC = TSAMP_MSEC * 1000UL;
const byte ADCSRA_ISR = 0b11101111; // auto ISR, clkdiv = 128
static unsigned long tic, stake = 0;
static boolean first_run = true;
if (first_run) {
stake = micros(); // only runs first time to set stake
first_run = false;
}
while ((tic - stake) < TIC_USEC) tic = micros(); // wait here until
stake = tic;
ADCSRA = ADCSRA_ISR; // start oversample-average series
}
//********************************************************************
ISR(PCINT1_vect) // if pin change occurs, update quadrature decoder
{
decodeEncoder32();
}
//********************************************************************
ISR (ADC_vect)
{
const byte N_ADC_AVE = 80;
const float INV_N_ADC = 1.0 / N_ADC_AVE;
static byte nConv = 0;
static unsigned int loAccum = 0, hiAccum = 0;
//SET_TP0_HI;
loAccum += ADCL; // lower 8 bits: must read before ADCH per Atmel
hiAccum += ADCH; // upper 2 bits
if (++nConv >= N_ADC_AVE)
{
//SET_TP1_HI;
adcReading = INV_N_ADC * (256UL * hiAccum + loAccum);
hiAccum = 0; loAccum = 0;
nConv = 0;
ADCSRA &= ~bit(ADIE); // stop auto conversions
//SET_TP1_LO;
}
//SET_TP0_LO;
} // end of ADC_vect

View file

@ -0,0 +1,308 @@
/* Click in this box, then
CTRL-A to select all
CTRL-C to copy
CTRL-V to paste into Arduino IDE
File: Lab2_motor_step_v1
Written: Aug 31, 2020, Clark Hochgraf
Revised: Feb 8, 2021
Desc:
Closed loop speed control of dc motor.
Speed of the motor is measured using a quadrature encoder.
Assumes fixed 5v 2amp power supply on Motor Driver
*/
volatile byte quadratureCode, oldquadratureCode;
volatile float quadPos = 0.0;
float lastquadPos = 0;
float motorspeedRPS = 0;
bool isModuleEn = false;
bool prevModuleEn = false;
const byte TSAMP_MSEC = 20;
long timeElapsedTicks = 0;
const float TSAMP = 0.001 * TSAMP_MSEC;
int TOTAL_RUN_TIME_MSEC = 2000; // in millisec
volatile float adcReading = 0;
float pwm_value_commanded;// command supplied to the motor PWM value.
const int ENC2 = A2; // d16, PC2 PCINT10 (green wire)
const int ENC3 = A3; // d17, PC3 PCINT11 (blue wire
const int PWM_M1A_PIN = 3; // d3, PD3 PCINT19 digital output OCR2B (green wire)
const int PWM_M1B_PIN = 11; // d11, PB4 digital output OCR2A (blue wire)
const float VOLTS_PER_PWM = 5.0 / 255.0; // motor drive voltage per pwm command
const float PWM_PER_VOLT = 1 / VOLTS_PER_PWM; // pwm value to achieve 1 volt output
const float RADPERSEC_PERVOLT = 356.0; // from datasheet calculations
float Wref = 0;
//---------------------------------------------------------------------
// Motor constants: DF robot motor with encoder model FIT0458
const float K_EMF = 0.00285; //(V/(160*120))*60.0/TWO_PI; // V/rad/sec from V/1000RPM
const float K_TRQ = 0.008 / 2.8; // N-m/Amp
const float R_ARM = 2.14; // ohms
const float D_DRAG = 0e-6;
const float SYS_A = 1;
const float SYS_B = 1;
const float V_FRICTION = 0.15;
float Varm;
float mtrVel = 0.0, mtrPos = 0.0, errVel = 0.0, errPos = 0.0;
float refAcc = 0.0, refVel = 0.0, refPos = 0.0;
// ##################################################################
void setup()
{
Serial.begin(115200);//Initialize the serial port ** Set Serial Monitor to same 115200
Serial.println(F("Lab2_closed_loop_vel_v1"));
Serial.println(F("runs for two seconds and then stops"));
displayMenu();
initMotorPins();
initEncoderInterrupts();
initPWMtimer2();
}
// ##################################################################
void loop()
{ manageMenu();
syncSample();
if (isModuleEn) {
stepRefVel(500); // input is velocity in radians per sec
Wref = refVel;
calculateError();
Varm = closedLoopVelP(errVel, 0.0125); // error signal, Kp gain // closed loop control
//Varm = refVel * K_EMF; // uncomment for open loop speed control
Varm = refVel * K_EMF + V_FRICTION; // uncomment for open loop speed control
//Varm = refVel * K_EMF + V_FRICTION + mtrVel * D_DRAG * R_ARM / K_TRQ; // uncomment for open loop speed control
//Varm = Varm + closedLoopVelP(errVel, 0.0125);
driveMotorVolts(Varm);
printResults(); // only print while motor running
}
else { //send zero voltage command to pwm if not enabled
Varm = 0;
driveMotorVolts(Varm);
}
if (timeElapsedTicks * TSAMP_MSEC > TOTAL_RUN_TIME_MSEC) //stop motor after 2 seconds
{
isModuleEn = false;
}
prevModuleEn = isModuleEn;
} // End main loop
// ##################################################################
float closedLoopVelP(float errorIn, float Kp)
{
return Kp * errorIn;
}
//*********************************************************************
void stepRefVel(float vel_rad_per_sec) // step input velocity reference levels
{
if (timeElapsedTicks < 0) refVel = 0.0;
else if (timeElapsedTicks < 400) refVel = vel_rad_per_sec;
else if (timeElapsedTicks < 800) refVel = -vel_rad_per_sec;
else if (timeElapsedTicks < 1000) refVel = 0.0;
else isModuleEn = false;
}
//********************************************************************
void calculateError(void)
{
mtrVel = (quadPos - lastquadPos) / (TSAMP_MSEC * 0.001); // radians per time interval (rad/sec)
lastquadPos = quadPos;
errVel = refVel - mtrVel;
}
//********************************************************************
void driveMotorVolts(float Vmotor)
{
int pwm_command = (int)(Vmotor * PWM_PER_VOLT);
if (pwm_command < 0) { // negative case -- set direction CW
pwm_command = - int(pwm_command);
OCR2B = 0;
OCR2A = constrain(pwm_command, 0, 255); //Serial.println(OCR2A);
}
else
{ //positive case -- set direction CW
pwm_command = int(pwm_command);
OCR2A = 0;
OCR2B = constrain(pwm_command, 0, 255); //Serial.println(OCR2B);
}
}
//********************************************************************
void printResults(void)
{ if (isModuleEn != prevModuleEn)
{
//print header
Serial.print("time (msec): "); Serial.print(",");
Serial.print("motorspeed: (rad/sec) "); Serial.print(",");
Serial.print("quadPos: (rad) "); Serial.print(",");
Serial.print("pwm_command: () "); Serial.print(",");
Serial.print("Varm (V) "); Serial.print(",");
Serial.print("Wref (rad/sec)");
Serial.println();
quadPos = 0;
lastquadPos = quadPos;
}
motorspeedRPS = mtrVel;
Serial.print(timeElapsedTicks * TSAMP_MSEC); Serial.print(",");
Serial.print(motorspeedRPS); Serial.print(",");
Serial.print(quadPos); Serial.print(",");
Serial.print(pwm_value_commanded); Serial.print(",");
Serial.print(Varm); Serial.print(",");
Serial.print(Wref);
Serial.println();
timeElapsedTicks++;
}
//********************************************************************
void displayMenu()
{
Serial.println("\nEnter 'e' to toggle module enable.");
}
//********************************************************************
void manageMenu()
{
char inChar = Serial.read();
if (inChar == 'e')
{
isModuleEn = !isModuleEn;
if (isModuleEn) {
Serial.println(F("Module ENABLED"));
timeElapsedTicks = 0;
}
else Serial.println(F("Module DISABLED"));
}
}
//********************************************************************
void initMotorPins()
{ // configure pins as input or output
pinMode(ENC2, INPUT); // Encoder A
pinMode(ENC3, INPUT); // Encoder B
pinMode(PWM_M1A_PIN, OUTPUT); // set motor PWM signal to output
pinMode(PWM_M1B_PIN, OUTPUT); // set motor direction pin to output
}
//********************************************************************
void initEncoderInterrupts(void)
{
// Position encoder ISR setup
// PCINT1_vect ISR triggered for enabled bit changes on PCMSK1
cli(); // disable global interrupts
PCMSK1 = 0b00001100; // ENC3,2,1,0 -> A3,A2,A1,A0 -> d17,16,15,14
PCICR = (1 << PCIE1); // enable pin change interrupts 8..14
sei(); // enable global interrupts
}
//********************************************************************
void initPWMtimer2(void)
{
//-----------------------------------------------------------------
// Use Timer 2 for direct motor drive PWM generation.
// Prescale = 1, FAST PWM, 8-bit (Mode 3) -> 62.5 kHz PWM
// Output pins OC2B (d3~) and OC2A (d11~) driven by counter hardware.
cli();
TCCR2B = 0;
TCCR2A = 0;
TCCR2B = (0 << WGM22); // start FAST PWM mode 3 setup
TCCR2A = (1 << WGM21) | (1 << WGM20); // finish FAST PWM setup
TCCR2B |= (0 << CS22) | (0 << CS21) | (1 << CS20); // clock prescale = 1
TCCR2A |= (1 << COM2B1) | (0 << COM2B0); // OCR2B pin (d3~) noninverting PWM
TCCR2A |= (1 << COM2A1) | (0 << COM2A0); // OCR2A pin (d11~) noninverting PWM
OCR2B = 1; OCR2A = 1;
sei();
}
//********************************************************************
void decodeEncoder32(void) // 2 bit quad decoder
{
const float MTR_RAD_PER_TICK = TWO_PI / 32;
static byte oldquadratureCode = 0;
oldquadratureCode = quadratureCode;
quadratureCode = (PINC & 0b00001100);
// Quadrature sequence: 0,8,12,4 (update ?CW facing end)
switch (quadratureCode)
{
case 0:
if (oldquadratureCode == 4) quadPos += MTR_RAD_PER_TICK;
if (oldquadratureCode == 8) quadPos -= MTR_RAD_PER_TICK;
break;
case 8:
if (oldquadratureCode == 0) quadPos += MTR_RAD_PER_TICK;
if (oldquadratureCode == 12) quadPos -= MTR_RAD_PER_TICK;
break;
case 12:
if (oldquadratureCode == 8) quadPos += MTR_RAD_PER_TICK;
if (oldquadratureCode == 4) quadPos -= MTR_RAD_PER_TICK;
break;
case 4:
if (oldquadratureCode == 12) quadPos += MTR_RAD_PER_TICK;
if (oldquadratureCode == 0) quadPos -= MTR_RAD_PER_TICK;
break;
}
} // decodeEncoder32( )
//********************************************************************
void syncSample() // set the sample rate for ADC and therefore for the main loop
{ // sample interval time is set by TSAMP_MSEC
const unsigned long TIC_USEC = TSAMP_MSEC * 1000UL;
const byte ADCSRA_ISR = 0b11101111; // auto ISR, clkdiv = 128
static unsigned long tic, stake = 0;
static boolean first_run = true;
if (first_run) {
stake = micros(); // only runs first time to set stake
first_run = false;
}
while ((tic - stake) < TIC_USEC) tic = micros(); // wait here until
stake = tic;
ADCSRA = ADCSRA_ISR; // start oversample-average series
}
//********************************************************************
ISR(PCINT1_vect) // if pin change occurs, update quadrature decoder
{
decodeEncoder32();
}
//********************************************************************
ISR (ADC_vect)
{
const byte N_ADC_AVE = 80;
const float INV_N_ADC = 1.0 / N_ADC_AVE;
static byte nConv = 0;
static unsigned int loAccum = 0, hiAccum = 0;
//SET_TP0_HI;
loAccum += ADCL; // lower 8 bits: must read before ADCH per Atmel
hiAccum += ADCH; // upper 2 bits
if (++nConv >= N_ADC_AVE)
{
//SET_TP1_HI;
adcReading = INV_N_ADC * (256UL * hiAccum + loAccum);
hiAccum = 0; loAccum = 0;
nConv = 0;
ADCSRA &= ~bit(ADIE); // stop auto conversions
//SET_TP1_LO;
}
//SET_TP0_LO;
} // end of ADC_vect

View file

@ -0,0 +1,340 @@
/* Click in this box, then
CTRL-A to select all
CTRL-C to copy
CTRL-V to paste into Arduino IDE
File: Lab3_trajectory_generator
Written: Feb 15, 2020 Clark Hochgraf
Revised:
Desc:
vClosed loop speed control of dc motor with Trapezoidal reference
Speed of the motor is measured using a quadrature encoder.
Assumes fixed 5v 2amp power supply on Motor Driver
*/
volatile byte quadratureCode, oldquadratureCode;
volatile float quadPos = 0.0;
float lastquadPos = 0;
float motorspeedRPS = 0;
bool isModuleEn = false, prevModuleEn = false, isPrinting = false;
bool isProfileEn = false, oldProfileEn = false, isShowStats = false;
const byte TSAMP_MSEC = 20;
long timeElapsedTicks = 0;
const float TSAMP = 0.001 * TSAMP_MSEC;
long TOTAL_RUN_TIME_MSEC = 4000; // in millisec
volatile float adcReading = 0;
float pwm_value_commanded;// command supplied to the motor PWM value.
const int ENC2 = A2; // d16, PC2 PCINT10 (green wire)
const int ENC3 = A3; // d17, PC3 PCINT11 (blue wire
const int PWM_M1A_PIN = 3; // d3, PD3 PCINT19 digital output OCR2B (green wire)
const int PWM_M1B_PIN = 11; // d11, PB4 digital output OCR2A (blue wire)
const float VOLTS_PER_PWM = 5.0 / 255.0; // motor drive voltage per pwm command
const float PWM_PER_VOLT = 1 / VOLTS_PER_PWM; // pwm value to achieve 1 volt output
const float RADPERSEC_PERVOLT = 356.0; // from datasheet calculations
float Wref = 0;
float Varm;
float mtrVel = 0.0, mtrPos = 0.0, errVel = 0.0, errPos = 0.0, errDist = 0.0;
float refAcc = 0.0, refVel = 0.0, refPos = 0.0, refDist = 200.0;
float refAccT = 0.0, refVelT = 0.0, refPosT = 0.0, refDistT = 200.0;
unsigned int tick = 0;
float dir = 1.0;
float disp_rad = 0;
float specAcc = 0.0, specVel, specDisp_rad, specVdist;
float trapAcc = 0.0, trapVel = 0.0, trapDisp_rad = 0.0;
float trapAccT = 0.0;
int dwellStartT, accT, platT, dwellEndT;
int T0, T1, T2, T3, T4, T5, T6, T7, T8;
int D0, D1, D2, D3, D4, D5, D6, D7, D8;
float dD1, dD2, dD3, dD4, dD5, dD6, dD7, dD8;
boolean isTrapezoid = true;
//---------------------------------------------------------------------
// Motor constants: DF robot motor with encoder model FIT0458
const float K_EMF = 0.00285; //(V/(160*120))*60.0/TWO_PI; // V/rad/sec from V/1000RPM
const float K_TRQ = 0.008 / 2.8; // N-m/Amp
const float R_ARM = 2.14; // ohms
const float GEAR_RATIO = 120; // motor turns per output shaft turns
const float D_DRAG = 6.54e-7;
const float SYS_A = 26.47;
const float SYS_B = 26.54;
const float MaxTrqmN = 1000 * (5.0 / R_ARM) * K_TRQ;
const float V_FRICTION = 0.2595;
float errInt=0;
float Ki=0;
float Kp=0.0125;
float trapeAccel = 2 * 256;
static float trapeVel = 0;
float Vdist = 0;
#define signof(x) ((x) < 0 ? -1 : ((x) > 0 ? 1 : 0))
#include "trapeRef.h" // for the PID classes (not a library)
// ##################################################################
void setup()
{
Serial.begin(115200);//Initialize the serial port ** Set Serial Monitor to same 115200
Serial.println(F("Lab3_trajectory_generator"));
Serial.println(F("runs for four seconds and then stops"));
displayMenu();
initMotorPins();
initEncoderInterrupts();
initPWMtimer2();
}
// ##################################################################
void loop()
{ manageMenu();
syncSample();
if (isModuleEn) {
isProfileEn=true;
// for feasible trajectory, uncomment the line below
float accRef=1300; float velRef=700; float dispRef=6.283*120; float Ncycles=1;
// for infeasible trajectory, uncomment the line below
//float accRef=10250; float velRef=700; float dispRef=6.283*120; float Ncycles=1;
trapRefVel(dispRef, velRef, accRef, Ncycles); //displacement (radians), veloc (rad/sec), acceler (rad/sec/sec), Ncycles
//stepRefVel(500); // input is velocity in radians per sec
Wref = refVelT; refVel=refVelT;
calculateError();
Varm = 0;
errInt=errInt+errVel*TSAMP;
Varm=Kp*(Wref-mtrVel)+errInt*Ki;
driveMotorVolts(Varm);
printResults(); // only print while motor running
}
else { //send zero voltage command to pwm if not enabled
Varm = 0;
driveMotorVolts(Varm);
}
if (timeElapsedTicks * TSAMP_MSEC > TOTAL_RUN_TIME_MSEC) //stop motor after 2 seconds
{
isModuleEn = false; isProfileEn=false;
}
prevModuleEn = isModuleEn;
} // End main loop
// ##################################################################
float closedLoopVelP(float errorIn, float Kp)
{
return Kp * errorIn;
}
//*********************************************************************
void stepRefVel(float vel_rad_per_sec) // step input velocity reference levels
{
if (timeElapsedTicks < 0) refVel = 0.0;
else if (timeElapsedTicks < 400) refVel = vel_rad_per_sec;
else if (timeElapsedTicks < 800) refVel = -vel_rad_per_sec;
else if (timeElapsedTicks < 1000) refVel = 0.0;
else isModuleEn = false;
}
//********************************************************************
void calculateError(void)
{
mtrVel = (quadPos - lastquadPos) / (TSAMP_MSEC * 0.001); // radians per time interval (rad/sec)
lastquadPos = quadPos;
errVel = refVel - mtrVel;
}
//********************************************************************
void driveMotorVolts(float Vmotor)
{
int pwm_command = (int)(Vmotor * PWM_PER_VOLT);
if (pwm_command < 0) { // negative case -- set direction CW
pwm_command = - int(pwm_command);
OCR2B = 0;
OCR2A = constrain(pwm_command, 0, 255); //Serial.println(OCR2A);
}
else
{ //positive case -- set direction CW
pwm_command = int(pwm_command);
OCR2A = 0;
OCR2B = constrain(pwm_command, 0, 255); //Serial.println(OCR2B);
}
}
//********************************************************************
void printResults(void)
{ if ((isModuleEn != prevModuleEn) && isModuleEn)
{
//print header
Serial.print("time (msec): "); Serial.print(",");
Serial.print("motorspeed: (rad/sec) "); Serial.print(",");
Serial.print("quadPos: (rad) "); Serial.print(",");
Serial.print("pwm_command: () "); Serial.print(",");
Serial.print("Varm (V) "); Serial.print(",");
Serial.print("Wref (rad/sec)");
Serial.println();
quadPos = 0;
lastquadPos = quadPos;
}
motorspeedRPS = mtrVel;
Serial.print(timeElapsedTicks * TSAMP_MSEC); Serial.print(",");
Serial.print(motorspeedRPS); Serial.print(",");
Serial.print(quadPos); Serial.print(",");
Serial.print(pwm_value_commanded); Serial.print(",");
Serial.print(Varm); Serial.print(",");
Serial.print(Wref);
Serial.println();
timeElapsedTicks++;
}
//********************************************************************
void displayMenu()
{
Serial.println("\nEnter 'e' to toggle module enable.");
}
//********************************************************************
void manageMenu()
{
char inChar = Serial.read();
if (inChar == 'e')
{
isModuleEn = !isModuleEn;
if (isModuleEn) {
Serial.println(F("Module ENABLED"));
timeElapsedTicks = 0;
}
else Serial.println(F("Module DISABLED"));
}
}
//********************************************************************
void initMotorPins()
{ // configure pins as input or output
pinMode(ENC2, INPUT); // Encoder A
pinMode(ENC3, INPUT); // Encoder B
pinMode(PWM_M1A_PIN, OUTPUT); // set motor PWM signal to output
pinMode(PWM_M1B_PIN, OUTPUT); // set motor direction pin to output
}
//********************************************************************
void initEncoderInterrupts(void)
{
// Position encoder ISR setup
// PCINT1_vect ISR triggered for enabled bit changes on PCMSK1
cli(); // disable global interrupts
PCMSK1 = 0b00001100; // ENC3,2,1,0 -> A3,A2,A1,A0 -> d17,16,15,14
PCICR = (1 << PCIE1); // enable pin change interrupts 8..14
sei(); // enable global interrupts
}
//********************************************************************
void initPWMtimer2(void)
{
//-----------------------------------------------------------------
// Use Timer 2 for direct motor drive PWM generation.
// Prescale = 1, FAST PWM, 8-bit (Mode 3) -> 62.5 kHz PWM
// Output pins OC2B (d3~) and OC2A (d11~) driven by counter hardware.
cli();
TCCR2B = 0;
TCCR2A = 0;
TCCR2B = (0 << WGM22); // start FAST PWM mode 3 setup
TCCR2A = (1 << WGM21) | (1 << WGM20); // finish FAST PWM setup
//TCCR2B |= (0 << CS22) | (0 << CS21) | (1 << CS20); // clock prescale = 1
TCCR2B |= (0 << CS22) | (1 << CS21) | (1 << CS20); // clock prescale = 32
TCCR2A |= (1 << COM2B1) | (0 << COM2B0); // OCR2B pin (d3~) noninverting PWM
TCCR2A |= (1 << COM2A1) | (0 << COM2A0); // OCR2A pin (d11~) noninverting PWM
OCR2B = 1; OCR2A = 1;
sei();
}
//********************************************************************
void decodeEncoder32(void) // 2 bit quad decoder
{
const float MTR_RAD_PER_TICK = TWO_PI / 32;
static byte oldquadratureCode = 0;
oldquadratureCode = quadratureCode;
quadratureCode = (PINC & 0b00001100);
// Quadrature sequence: 0,8,12,4 (update ?CW facing end)
switch (quadratureCode)
{
case 0:
if (oldquadratureCode == 4) quadPos += MTR_RAD_PER_TICK;
if (oldquadratureCode == 8) quadPos -= MTR_RAD_PER_TICK;
break;
case 8:
if (oldquadratureCode == 0) quadPos += MTR_RAD_PER_TICK;
if (oldquadratureCode == 12) quadPos -= MTR_RAD_PER_TICK;
break;
case 12:
if (oldquadratureCode == 8) quadPos += MTR_RAD_PER_TICK;
if (oldquadratureCode == 4) quadPos -= MTR_RAD_PER_TICK;
break;
case 4:
if (oldquadratureCode == 12) quadPos += MTR_RAD_PER_TICK;
if (oldquadratureCode == 0) quadPos -= MTR_RAD_PER_TICK;
break;
}
} // decodeEncoder32( )
//********************************************************************
void syncSample() // set the sample rate for ADC and therefore for the main loop
{ // sample interval time is set by TSAMP_MSEC
const unsigned long TIC_USEC = TSAMP_MSEC * 1000UL;
const byte ADCSRA_ISR = 0b11101111; // auto ISR, clkdiv = 128
static unsigned long tic, stake = 0;
static boolean first_run = true;
if (first_run) {
stake = micros(); // only runs first time to set stake
first_run = false;
}
while ((tic - stake) < TIC_USEC) tic = micros(); // wait here until
stake = tic;
ADCSRA = ADCSRA_ISR; // start oversample-average series
}
//********************************************************************
ISR(PCINT1_vect) // if pin change occurs, update quadrature decoder
{
decodeEncoder32();
}
//********************************************************************
ISR (ADC_vect)
{
const byte N_ADC_AVE = 80;
const float INV_N_ADC = 1.0 / N_ADC_AVE;
static byte nConv = 0;
static unsigned int loAccum = 0, hiAccum = 0;
//SET_TP0_HI;
loAccum += ADCL; // lower 8 bits: must read before ADCH per Atmel
hiAccum += ADCH; // upper 2 bits
if (++nConv >= N_ADC_AVE)
{
//SET_TP1_HI;
adcReading = INV_N_ADC * (256UL * hiAccum + loAccum);
hiAccum = 0; loAccum = 0;
nConv = 0;
ADCSRA &= ~bit(ADIE); // stop auto conversions
//SET_TP1_LO;
}
//SET_TP0_LO;
} // end of ADC_vect

View file

@ -0,0 +1,101 @@
//**************************************************************
void trapBuildSymAcc(float Disp_rad, float Vplat, float Acc)
{
float tAcc = Vplat / Acc;
float dAcc = Vplat * tAcc;
float dPlat = Disp_rad - dAcc;
float tPlat = dPlat / Vplat;
trapAccT = Acc; // acceleration rate
accT = int(round(tAcc / TSAMP)); // time duration of acceleration
platT = int(round(tPlat / TSAMP)); // time duration of constant speed
float dTrap = (accT + platT) * TSAMP * Vplat; // total displacement during trapezoid profile
Serial.println();
Serial.print("tAcc = "); Serial.println(tAcc);
Serial.print("dAcc = "); Serial.println(dAcc);
Serial.print("dPlat = "); Serial.println(dPlat);
Serial.print("tPlat = "); Serial.println(tPlat);
Serial.print("accT = "); Serial.println(accT);
Serial.print("platT = "); Serial.println(platT);
Serial.print("dTrap = "); Serial.println(dTrap);
}
//*********************************************************************
void trapRefVel(float specDisp_rad, float specVel, float specAcc, int Ncycles) // trap velocity profile
{
if (!oldProfileEn && isProfileEn)
{
//specDisp_rad = 300.0; specVel = 150.0; specAcc = 800.0;
trapBuildSymAcc(specDisp_rad, specVel, specAcc);
dwellStartT = 1; dwellEndT = 1; specVdist = 0.0;
//specDisp_rad = 300.0, specVel = 100.0, specAcc = 200.0;
//trapBuildSymAcc(specDisp_rad, specVel, specAcc);
//dwellStartT = 50, dwellEndT = 200; specVdist = 2.0;
//specDisp_rad = 206.9, specVel = 110.0, specAcc = 180.0;
//trapBuildSymAcc(specDisp_rad, specVel, specAcc);
//dwellGoT = 300, dwellUpT = 500, dwellEndT = 200; specVdist = abs(V_DIST);
// Times when speed changes
T0 = dwellStartT;
T1 = T0 + accT; T2 = T1 + platT; T3 = T2 + accT; T4 = T3 + dwellEndT;
T5 = T4 + accT; T6 = T5 + platT; T7 = T6 + accT; T8 = T7 + dwellEndT;
//T0 = dwellGoT;
//T1 = T0 + accT, T2 = T1 + platT, T3 = T2 + accT, T4 = T3 + dwellUpT;
//T5 = T4 + accT, T6 = T5 + platT, T7 = T6 + accT, T8 = T7 + dwellEndT;
// Times when disturbances are applied and values
D1 = T3 + 100; D2 = D1 + 200;
dD1 = specVdist; dD2 = -specVdist;
//simJumpOn_simJumpOff();
//simJumpOn_simFileOff();
//weightOn_simJumpOff();
//weightOn_simFileOff();
}
tick = timeElapsedTicks % T8; //modulo allows rerunning of profile. Remove for single run.
// ---- Command profile -------------------------------------
oldProfileEn = isProfileEn;
if (tick < T0) refAccT = 0.0;
else if (tick < T1) refAccT = dir * trapAccT;
else if (tick < T2) refAccT = 0.0;
else if (tick < T3) refAccT = -dir * trapAccT;
else if (tick < T4) refAccT = 0.0;
//else if (tick == T4) isProfileEn = false;
else if (tick < T5) refAccT = -dir * trapAccT;
else if (tick < T6) refAccT = 0.0;
else if (tick < T7) refAccT = dir * trapAccT;
else if (tick < T8) refAccT = 0.0;
else if (tick == T8) isProfileEn = false;
//---- Disturbance profile -----------------------------------
if (tick < D1) Vdist = 0.0;
else if (tick == D1) Vdist += dD1 * specVdist; // module, sim load
else if (tick == D2) Vdist += dD2 * specVdist;
else if (tick == D3) Vdist += dD3 * specVdist;
else if (tick == D4) Vdist += dD4 * specVdist;
else if (tick == D5) Vdist += dD5 * specVdist;
else if (tick == D6) Vdist += dD6 * specVdist;
else if (tick == D7) Vdist += dD7 * specVdist;
else if (tick == D8) Vdist += dD8 * specVdist;
//---- Profile integration -----------------------------------
if (isProfileEn) {
refVelT += refAccT * TSAMP;
refPosT += refVelT * TSAMP;
}
else {
refAccT = 0.0;
refVelT = 0.0;
}
isShowStats = (oldProfileEn && !isProfileEn);
if ((timeElapsedTicks/T8)>=Ncycles) {isProfileEn=false; isModuleEn=false;}; // stop after 4 profiles
}

Binary file not shown.

After

Width:  |  Height:  |  Size: 45 KiB

BIN
lab3/labReport.png Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 62 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 43 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 47 KiB

BIN
lab3/section3.png Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 68 KiB

BIN
lab3/section4.png Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 61 KiB

Binary file not shown.

BIN
lab4/Lab 4 ANALYSIS.ods Normal file

Binary file not shown.

BIN
lab4/Lab 4 ANALYSIS.xlsx Normal file

Binary file not shown.

BIN
lab4/finalPlot.png Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 60 KiB

349
lab4/lab4Code/lab4Code.ino Normal file
View file

@ -0,0 +1,349 @@
/* Click in this box, then
CTRL-A to select all
CTRL-C to copy
CTRL-V to paste into Arduino IDE
File: Lab4_Velocity_PI_control
Written: Mar 1, 2021 Clark Hochgraf
Revised:
Desc:
Closed loop PI speed control of dc motor with Trapezoidal reference
Speed of the motor is measured using a quadrature encoder.
Assumes fixed 5v 2amp power supply on Motor Driver
*/
volatile byte quadratureCode, oldquadratureCode;
volatile float mtrPos = 0.0;
float lastmtrPos = 0;
float motorspeedRPS = 0;
bool isModuleEn = false, prevModuleEn = false, isPrinting = false;
bool isProfileEn = false, oldProfileEn = false, isShowStats = false;
const byte TSAMP_MSEC = 20;
long timeElapsedTicks = 0;
const float TSAMP = 0.001 * TSAMP_MSEC;
long TOTAL_RUN_TIME_MSEC = 4000000; // in millisec
volatile float adcReading = 0;
float pwm_value_commanded;// command supplied to the motor PWM value.
const int ENC2 = A2; // d16, PC2 PCINT10 (green wire)
const int ENC3 = A3; // d17, PC3 PCINT11 (blue wire
const int PWM_M1A_PIN = 3; // d3, PD3 PCINT19 digital output OCR2B (green wire)
const int PWM_M1B_PIN = 11; // d11, PB4 digital output OCR2A (blue wire)
const float VOLTS_PER_PWM = 5.0 / 255.0; // motor drive voltage per pwm command
const float PWM_PER_VOLT = 1 / VOLTS_PER_PWM; // pwm value to achieve 1 volt output
const float RADPERSEC_PERVOLT = 356.0; // from datasheet calculations
float Varm = 0, Vff = 0;
float mtrVel = 0.0, errVel = 0.0, errPos = 0.0, errDist = 0.0;
float refAcc = 0.0, refVel = 0.0, refPos = 0.0, refDist = 200.0;
float refAccT = 0.0, refVelT = 0.0, refPosT = 0.0, refDistT = 200.0;
unsigned int tick = 0;
float dir = 1.0;
float disp_rad = 0;
float specAcc = 0.0, specVel, specDisp_rad, specVdist;
float trapAcc = 0.0, trapVel = 0.0, trapDisp_rad = 0.0;
float trapAccT = 0.0;
int dwellStartT, accT, platT, dwellEndT;
int T0, T1, T2, T3, T4, T5, T6, T7, T8;
int D0, D1, D2, D3, D4, D5, D6, D7, D8;
float dD1, dD2, dD3, dD4, dD5, dD6, dD7, dD8;
boolean isTrapezoid = true;
//---------------------------------------------------------------------
// Motor constants: DF robot motor with encoder model FIT0458
const float K_EMF = 0.00285; //(V/(160*120))*60.0/TWO_PI; // V/rad/sec from V/1000RPM
const float K_TRQ = 0.008 / 2.8; // N-m/Amp
const float R_ARM = 2.14; // ohms
const float GEAR_RATIO = 120; // motor turns per output shaft turns
const float D_DRAG = 2.45e-6;
const float SYS_A = 2491.5;
const float SYS_B = 8.3333;
const float MaxTrqmN = 1000 * (5.0 / R_ARM) * K_TRQ;
const float V_FRICTION = 0.0;
float trapeAccel = 2 * 256;
static float trapeVel = 0;
float Vdist = 0;
#define signof(x) ((x) < 0 ? -1 : ((x) > 0 ? 1 : 0))
#include "trapeRef.h" // for the PID classes (not a library)
// ##################################################################
void setup()
{
Serial.begin(115200);//Initialize the serial port ** Set Serial Monitor to same 115200
Serial.println(F("Lab4_Velocity_PI_control"));
Serial.println(F("runs for four seconds and then stops"));
displayMenu();
initMotorPins();
initEncoderInterrupts();
initPWMtimer2();
}
// ##################################################################
void loop()
{ manageMenu();
syncSample();
if (isModuleEn) {
boolean useTrapezoidalReference = true;
if (useTrapezoidalReference) {
isProfileEn = true;
float maxAccel = 1300; float maxVelocity = 700; float totalDisplacement = 900; float Ncycles = 1;
trapRefVel(totalDisplacement, maxVelocity, maxAccel, Ncycles);
//displacement (radians), veloc (rad/sec), acceleration (rad/sec/sec), Ncycles
refVel = refVelT; refPos = refPosT;
}
else { // use step reference for velocity
refVel = 300;
}
calculateMotorVelocity();
calculateError();
Vff = refAccT / SYS_A + refVel * K_EMF + V_FRICTION * signof(refVel) + mtrVel * D_DRAG * R_ARM / K_TRQ;
//Vff = 0;
Varm = Vff + closedLoopPI(errVel, 0.0125, 0.195);
driveMotorVolts(Varm);
printResults(); // only print while motor running
}
else { //send zero voltage command to pwm if not enabled
Varm = 0;
driveMotorVolts(Varm);
}
if (timeElapsedTicks * TSAMP_MSEC > TOTAL_RUN_TIME_MSEC) //stop motor after 2 seconds
{
isModuleEn = false; isProfileEn = false;
}
prevModuleEn = isModuleEn;
} // End main loop
// ##################################################################
//*********************************************************************
float closedLoopPI(float errorIn, float Kp, float Ki)
{
static float PI_integralError=0;
PI_integralError+= errorIn*TSAMP;
return Kp * errorIn+ Ki*PI_integralError;
}
//*********************************************************************
void stepRefVel(float vel_rad_per_sec) // step input velocity reference levels
{
if (timeElapsedTicks < 0) refVel = 0.0;
else if (timeElapsedTicks < 400) refVel = vel_rad_per_sec;
else if (timeElapsedTicks < 800) refVel = -vel_rad_per_sec;
else if (timeElapsedTicks < 1000) refVel = 0.0;
else isModuleEn = false;
}
//********************************************************************
void calculateMotorVelocity(void)
{
mtrVel = (mtrPos - lastmtrPos) / (TSAMP_MSEC * 0.001); // radians per time interval (rad/sec)
lastmtrPos = mtrPos;
}
//********************************************************************
void calculateError(void)
{
lastmtrPos = mtrPos;
errVel = refVel - mtrVel;
}
//********************************************************************
void driveMotorVolts(float Vmotor)
{
int pwm_command = (int)(Vmotor * PWM_PER_VOLT);
if (pwm_command < 0) { // negative case -- set direction CW
pwm_command = - int(pwm_command);
OCR2B = 0;
OCR2A = constrain(pwm_command, 0, 255); //Serial.println(OCR2A);
}
else
{ //positive case -- set direction CW
pwm_command = int(pwm_command);
OCR2A = 0;
OCR2B = constrain(pwm_command, 0, 255); //Serial.println(OCR2B);
}
}
//********************************************************************
void printResults(void)
{ if ((isModuleEn != prevModuleEn) && isModuleEn)
{
//print header
Serial.print("time (msec): "); Serial.print(",");
Serial.print("motorspeed: (rad/sec) "); Serial.print(",");
Serial.print("mtrPos: (rad) "); Serial.print(",");
Serial.print("pwm_command: () "); Serial.print(",");
Serial.print("Varm (V) "); Serial.print(",");
Serial.print("refVel (rad/sec)");
Serial.println();
mtrPos = 0;
lastmtrPos = mtrPos;
}
motorspeedRPS = mtrVel;
Serial.print(timeElapsedTicks * TSAMP_MSEC); Serial.print(",");
Serial.print(motorspeedRPS); Serial.print(",");
Serial.print(mtrPos); Serial.print(",");
Serial.print(pwm_value_commanded); Serial.print(",");
Serial.print(Varm); Serial.print(",");
Serial.print(refVel);
Serial.println();
timeElapsedTicks++;
}
//********************************************************************
void displayMenu()
{
Serial.println("\nEnter 'e' to toggle module enable.");
}
//********************************************************************
void manageMenu()
{
char inChar = Serial.read();
if (inChar == 'e')
{
isModuleEn = !isModuleEn;
if (isModuleEn) {
Serial.println(F("Module ENABLED"));
timeElapsedTicks = 0;
}
else Serial.println(F("Module DISABLED"));
}
}
//********************************************************************
void initMotorPins()
{ // configure pins as input or output
pinMode(ENC2, INPUT); // Encoder A
pinMode(ENC3, INPUT); // Encoder B
pinMode(PWM_M1A_PIN, OUTPUT); // set motor PWM signal to output
pinMode(PWM_M1B_PIN, OUTPUT); // set motor direction pin to output
}
//********************************************************************
void initEncoderInterrupts(void)
{
// Position encoder ISR setup
// PCINT1_vect ISR triggered for enabled bit changes on PCMSK1
cli(); // disable global interrupts
PCMSK1 = 0b00001100; // ENC3,2,1,0 -> A3,A2,A1,A0 -> d17,16,15,14
PCICR = (1 << PCIE1); // enable pin change interrupts 8..14
sei(); // enable global interrupts
}
//********************************************************************
void initPWMtimer2(void)
{
//-----------------------------------------------------------------
// Use Timer 2 for direct motor drive PWM generation.
// Prescale = 1, FAST PWM, 8-bit (Mode 3) -> 62.5 kHz PWM
// Output pins OC2B (d3~) and OC2A (d11~) driven by counter hardware.
cli();
TCCR2B = 0;
TCCR2A = 0;
TCCR2B = (0 << WGM22); // start FAST PWM mode 3 setup
TCCR2A = (1 << WGM21) | (1 << WGM20); // finish FAST PWM setup
TCCR2B |= (0 << CS22) | (1 << CS21) | (1 << CS20); // clock prescale = 32
TCCR2A |= (1 << COM2B1) | (0 << COM2B0); // OCR2B pin (d3~) noninverting PWM
TCCR2A |= (1 << COM2A1) | (0 << COM2A0); // OCR2A pin (d11~) noninverting PWM
OCR2B = 1; OCR2A = 1;
sei();
}
//********************************************************************
void decodeEncoder32(void) // 2 bit quad decoder
{
const float MTR_RAD_PER_TICK = TWO_PI / 32;
static byte oldquadratureCode = 0;
oldquadratureCode = quadratureCode;
quadratureCode = (PINC & 0b00001100);
// Quadrature sequence: 0,8,12,4 (update ?CW facing end)
switch (quadratureCode)
{
case 0:
if (oldquadratureCode == 4) mtrPos += MTR_RAD_PER_TICK;
if (oldquadratureCode == 8) mtrPos -= MTR_RAD_PER_TICK;
break;
case 8:
if (oldquadratureCode == 0) mtrPos += MTR_RAD_PER_TICK;
if (oldquadratureCode == 12) mtrPos -= MTR_RAD_PER_TICK;
break;
case 12:
if (oldquadratureCode == 8) mtrPos += MTR_RAD_PER_TICK;
if (oldquadratureCode == 4) mtrPos -= MTR_RAD_PER_TICK;
break;
case 4:
if (oldquadratureCode == 12) mtrPos += MTR_RAD_PER_TICK;
if (oldquadratureCode == 0) mtrPos -= MTR_RAD_PER_TICK;
break;
}
} // decodeEncoder32( )
//********************************************************************
void syncSample() // set the sample rate for ADC and therefore for the main loop
{ // sample interval time is set by TSAMP_MSEC
const unsigned long TIC_USEC = TSAMP_MSEC * 1000UL;
const byte ADCSRA_ISR = 0b11101111; // auto ISR, clkdiv = 128
static unsigned long tic, stake = 0;
static boolean first_run = true;
if (first_run) {
stake = micros(); // only runs first time to set stake
first_run = false;
}
while ((tic - stake) < TIC_USEC) tic = micros(); // wait here until
stake = tic;
ADCSRA = ADCSRA_ISR; // start oversample-average series
}
//********************************************************************
ISR(PCINT1_vect) // if pin change occurs, update quadrature decoder
{
decodeEncoder32();
}
//********************************************************************
ISR (ADC_vect)
{
const byte N_ADC_AVE = 80;
const float INV_N_ADC = 1.0 / N_ADC_AVE;
static byte nConv = 0;
static unsigned int loAccum = 0, hiAccum = 0;
//SET_TP0_HI;
loAccum += ADCL; // lower 8 bits: must read before ADCH per Atmel
hiAccum += ADCH; // upper 2 bits
if (++nConv >= N_ADC_AVE)
{
//SET_TP1_HI;
adcReading = INV_N_ADC * (256UL * hiAccum + loAccum);
hiAccum = 0; loAccum = 0;
nConv = 0;
ADCSRA &= ~bit(ADIE); // stop auto conversions
//SET_TP1_LO;
}
//SET_TP0_LO;
} // end of ADC_vect

101
lab4/lab4Code/trapeRef.h Normal file
View file

@ -0,0 +1,101 @@
//**************************************************************
void trapBuildSymAcc(float Disp_rad, float Vplat, float Acc)
{
float tAcc = Vplat / Acc;
float dAcc = Vplat * tAcc;
float dPlat = Disp_rad - dAcc;
float tPlat = dPlat / Vplat;
trapAccT = Acc; // acceleration rate
accT = int(round(tAcc / TSAMP)); // time duration of acceleration
platT = int(round(tPlat / TSAMP)); // time duration of constant speed
float dTrap = (accT + platT) * TSAMP * Vplat; // total displacement during trapezoid profile
Serial.println();
Serial.print("tAcc = "); Serial.println(tAcc);
Serial.print("dAcc = "); Serial.println(dAcc);
Serial.print("dPlat = "); Serial.println(dPlat);
Serial.print("tPlat = "); Serial.println(tPlat);
Serial.print("accT = "); Serial.println(accT);
Serial.print("platT = "); Serial.println(platT);
Serial.print("dTrap = "); Serial.println(dTrap);
}
//*********************************************************************
void trapRefVel(float specDisp_rad, float specVel, float specAcc, int Ncycles) // trap velocity profile
{
if (!oldProfileEn && isProfileEn)
{
//specDisp_rad = 300.0; specVel = 150.0; specAcc = 800.0;
trapBuildSymAcc(specDisp_rad, specVel, specAcc);
dwellStartT = 1; dwellEndT = 1; specVdist = 0.0;
//specDisp_rad = 300.0, specVel = 100.0, specAcc = 200.0;
//trapBuildSymAcc(specDisp_rad, specVel, specAcc);
//dwellStartT = 50, dwellEndT = 200; specVdist = 2.0;
//specDisp_rad = 206.9, specVel = 110.0, specAcc = 180.0;
//trapBuildSymAcc(specDisp_rad, specVel, specAcc);
//dwellGoT = 300, dwellUpT = 500, dwellEndT = 200; specVdist = abs(V_DIST);
// Times when speed changes
T0 = dwellStartT;
T1 = T0 + accT; T2 = T1 + platT; T3 = T2 + accT; T4 = T3 + dwellEndT;
T5 = T4 + accT; T6 = T5 + platT; T7 = T6 + accT; T8 = T7 + dwellEndT;
//T0 = dwellGoT;
//T1 = T0 + accT, T2 = T1 + platT, T3 = T2 + accT, T4 = T3 + dwellUpT;
//T5 = T4 + accT, T6 = T5 + platT, T7 = T6 + accT, T8 = T7 + dwellEndT;
// Times when disturbances are applied and values
D1 = T3 + 100; D2 = D1 + 200;
dD1 = specVdist; dD2 = -specVdist;
//simJumpOn_simJumpOff();
//simJumpOn_simFileOff();
//weightOn_simJumpOff();
//weightOn_simFileOff();
}
tick = timeElapsedTicks % T8; //modulo allows rerunning of profile. Remove for single run.
// ---- Command profile -------------------------------------
oldProfileEn = isProfileEn;
if (tick < T0) refAccT = 0.0;
else if (tick < T1) refAccT = dir * trapAccT;
else if (tick < T2) refAccT = 0.0;
else if (tick < T3) refAccT = -dir * trapAccT;
else if (tick < T4) refAccT = 0.0;
//else if (tick == T4) isProfileEn = false;
else if (tick < T5) refAccT = -dir * trapAccT;
else if (tick < T6) refAccT = 0.0;
else if (tick < T7) refAccT = dir * trapAccT;
else if (tick < T8) refAccT = 0.0;
else if (tick == T8) isProfileEn = false;
//---- Disturbance profile -----------------------------------
if (tick < D1) Vdist = 0.0;
else if (tick == D1) Vdist += dD1 * specVdist; // module, sim load
else if (tick == D2) Vdist += dD2 * specVdist;
else if (tick == D3) Vdist += dD3 * specVdist;
else if (tick == D4) Vdist += dD4 * specVdist;
else if (tick == D5) Vdist += dD5 * specVdist;
else if (tick == D6) Vdist += dD6 * specVdist;
else if (tick == D7) Vdist += dD7 * specVdist;
else if (tick == D8) Vdist += dD8 * specVdist;
//---- Profile integration -----------------------------------
if (isProfileEn) {
refVelT += refAccT * TSAMP;
refPosT += refVelT * TSAMP;
}
else {
refAccT = 0.0;
refVelT = 0.0;
}
isShowStats = (oldProfileEn && !isProfileEn);
if ((timeElapsedTicks/T8)>=Ncycles) {isProfileEn=false; isModuleEn=false;}; // stop after 4 profiles
}

BIN
lab4/plot1.png Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 61 KiB

BIN
lab4/plot2.png Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 56 KiB

BIN
lab4/plot3.png Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 56 KiB

BIN
lab4/plot4.png Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 106 KiB

Binary file not shown.

BIN
lab5/Lab 5 ANALYSIS.ods Normal file

Binary file not shown.

View file

@ -0,0 +1,362 @@
/* Click in this box, then
CTRL-A to select all
CTRL-C to copy
CTRL-V to paste into Arduino IDE
File: Lab5_Position_PI+PZ_control
Written: Mar 1, 2021 Clark Hochgraf
Revised:
Desc:
Closed loop PI speed control of dc motor with Trapezoidal reference
Speed of the motor is measured using a quadrature encoder.
Assumes fixed 5v 2amp power supply on Motor Driver
*/
volatile byte quadratureCode, oldquadratureCode;
volatile float mtrPos = 0.0;
float lastmtrPos = 0;
bool isModuleEn = false, prevModuleEn = false, isPrinting = false;
bool isProfileEn = false, oldProfileEn = false, isShowStats = false;
const byte TSAMP_MSEC = 20;
long timeElapsedTicks = 0;
const float TSAMP = 0.001 * TSAMP_MSEC;
long TOTAL_RUN_TIME_MSEC = 4000; // in millisec
volatile float adcReading = 0;
float pwm_value_commanded;// command supplied to the motor PWM value.
const int ENC2 = A2; // d16, PC2 PCINT10 (green wire)
const int ENC3 = A3; // d17, PC3 PCINT11 (blue wire
const int PWM_M1A_PIN = 3; // d3, PD3 PCINT19 digital output OCR2B (green wire)
const int PWM_M1B_PIN = 11; // d11, PB4 digital output OCR2A (blue wire)
const float VOLTS_PER_PWM = 5.0 / 255.0; // motor drive voltage per pwm command
const float PWM_PER_VOLT = 1 / VOLTS_PER_PWM; // pwm value to achieve 1 volt output
const float RADPERSEC_PERVOLT = 356.0; // from datasheet calculations
float Varm = 0, Vff = 0;
float mtrVel = 0.0, errVel = 0.0, errPos = 0.0, errDist = 0.0;
float refAcc = 0.0, refVel = 0.0, refPos = 0.0, refDist = 200.0;
float refAccT = 0.0, refVelT = 0.0, refPosT = 0.0, refDistT = 200.0;
unsigned int tick = 0;
float dir = 1.0;
float disp_rad = 0;
float specAcc = 0.0, specVel, specDisp_rad, specVdist;
float trapAcc = 0.0, trapVel = 0.0, trapDisp_rad = 0.0;
float trapAccT = 0.0;
int dwellStartT, accT, platT, dwellEndT;
int T0, T1, T2, T3, T4, T5, T6, T7, T8;
int D0, D1, D2, D3, D4, D5, D6, D7, D8;
float dD1, dD2, dD3, dD4, dD5, dD6, dD7, dD8;
boolean isTrapezoid = true;
//---------------------------------------------------------------------
// Motor constants: DF robot motor with encoder model FIT0458
const float K_EMF = 0.00285; //(V/(160*120))*60.0/TWO_PI; // V/rad/sec from V/1000RPM
const float K_TRQ = 0.008 / 2.8; // N-m/Amp
const float R_ARM = 2.14; // ohms
const float GEAR_RATIO = 120; // motor turns per output shaft turns
const float D_DRAG = 6.54e-7;
const float SYS_A = 2491.5;
const float SYS_B = 8.333;
const float MaxTrqmN = 1000 * (5.0 / R_ARM) * K_TRQ;
const float V_FRICTION = 0.2595;
float Vdist = 0;
#define signof(x) ((x) < 0 ? -1 : ((x) > 0 ? 1 : 0))
#include "trapeRef.h" // for the PID classes (not a library)
// ##################################################################
void setup()
{
Serial.begin(115200);//Initialize the serial port ** Set Serial Monitor to same 115200
Serial.println(F("Lab5_Position_PI+PZ_control"));
displayMenu();
initMotorPins();
initEncoderInterrupts();
initPWMtimer2();
}
// ##################################################################
void loop()
{ manageMenu();
syncSample();
if (isModuleEn) {
isProfileEn = true;
boolean useTrapezoidalReference = true;
if (useTrapezoidalReference) {
float maxAccel = 700; float maxVelocity = 300; float totalDisplacement = 200; float Ncycles = 1;
trapRefVel(totalDisplacement, maxVelocity, maxAccel, Ncycles);
//displacement (radians), veloc (rad/sec), acceleration (rad/sec/sec), Ncycles
refVel = refVelT; refPos = refPosT;
}
else { // use step reference for position control system
refPos = 100;
}
calculateMotorVelocity();
calculateError();
Vff = refAccT / SYS_A + refVel * K_EMF + V_FRICTION * signof(refVel) + mtrVel * D_DRAG * R_ARM / K_TRQ;
//Vff = 0;
//Varm = Vff + closedLoopPI(errPos, 0.2, 0.1); //
Varm = Vff + PZ_compensate(closedLoopPI(errPos, 0.2, 0.1), 5.625, 20); //
driveMotorVolts(Varm);
printResults(); // only print while motor running
}
else { //send zero voltage command to pwm if not enabled
Varm = 0;
driveMotorVolts(Varm);
}
if (timeElapsedTicks * TSAMP_MSEC > TOTAL_RUN_TIME_MSEC) //stop motor after 2 seconds
{
isModuleEn = false; isProfileEn = false;
}
prevModuleEn = isModuleEn;
} // End main loop
// ##################################################################
float PZ_compensate(float x, float c, float d)
{
// pole-zero compensator
// Cancel pole at -c, replace with a pole at -d.
// Implement (s+c)/(s+d) as 1 + (c-d)/(s+d).
// and post scale by d/c to get unity gain at DC.
static float yd = 0.0;
yd += ((c - d) * x - d * yd) * TSAMP;
float ypd = x + yd;
ypd = ypd * d / c; // correct scaling to unity gain at DC.
return ypd;
}
//*********************************************************************
float closedLoopP(float errorIn, float Kp)
{
return Kp * errorIn;
}
//*********************************************************************
float closedLoopPI(float errorIn, float Kp, float Ki)
{
// Implement (Kp s+Ki)/s as Kp + Ki/s.
static float PI_integralError = 0;
PI_integralError += errorIn * TSAMP;
return (Kp * errorIn + Ki * PI_integralError);
}
//*********************************************************************
void stepRefVel(float vel_rad_per_sec) // step input velocity reference levels
{
if (timeElapsedTicks < 0) refVel = 0.0;
else if (timeElapsedTicks < 400) refVel = vel_rad_per_sec;
else if (timeElapsedTicks < 800) refVel = -vel_rad_per_sec;
else if (timeElapsedTicks < 1000) refVel = 0.0;
else isModuleEn = false;
}
//********************************************************************
void calculateMotorVelocity(void)
{
mtrVel = (mtrPos - lastmtrPos) / (TSAMP_MSEC * 0.001); // radians per time interval (rad/sec)
lastmtrPos = mtrPos;
}
//********************************************************************
void calculateError(void)
{
errVel = refVel - mtrVel;
errPos = refPos - mtrPos;
}
//********************************************************************
void driveMotorVolts(float Vmotor)
{
int pwm_command = (int)(Vmotor * PWM_PER_VOLT);
if (pwm_command < 0) { // negative case -- set direction CW
pwm_command = - int(pwm_command);
OCR2B = 0;
OCR2A = constrain(pwm_command, 0, 255); //Serial.println(OCR2A);
}
else
{ //positive case -- set direction CW
pwm_command = int(pwm_command);
OCR2A = 0;
OCR2B = constrain(pwm_command, 0, 255); //Serial.println(OCR2B);
}
}
//********************************************************************
void printResults(void)
{ if ((isModuleEn != prevModuleEn) && isModuleEn)
{
//print header
Serial.print("time (msec): "); Serial.print(",");
Serial.print("motorspeed: (rad/sec) "); Serial.print(",");
Serial.print("mtrPos: (rad) "); Serial.print(",");
Serial.print("pwm_command: () "); Serial.print(",");
Serial.print("Varm (V) "); Serial.print(",");
Serial.print("refVel (rad/sec)"); Serial.print(",");
Serial.print("refPos (rad)");
Serial.println();
mtrPos = 0;
lastmtrPos = mtrPos;
}
Serial.print(timeElapsedTicks * TSAMP_MSEC); Serial.print(",");
Serial.print(mtrVel); Serial.print(",");
Serial.print(mtrPos); Serial.print(",");
Serial.print(pwm_value_commanded); Serial.print(",");
Serial.print(Varm); Serial.print(",");
Serial.print(refVel); Serial.print(",");
Serial.print(refPos);
Serial.println();
timeElapsedTicks++;
}
//********************************************************************
void displayMenu()
{
Serial.println("\nEnter 'e' to toggle module enable.");
}
//********************************************************************
void manageMenu()
{
char inChar = Serial.read();
if (inChar == 'e')
{
isModuleEn = !isModuleEn;
if (isModuleEn) {
Serial.println(F("Module ENABLED"));
timeElapsedTicks = 0;
}
else Serial.println(F("Module DISABLED"));
}
}
//********************************************************************
void initMotorPins()
{ // configure pins as input or output
pinMode(ENC2, INPUT); // Encoder A
pinMode(ENC3, INPUT); // Encoder B
pinMode(PWM_M1A_PIN, OUTPUT); // set motor PWM signal to output
pinMode(PWM_M1B_PIN, OUTPUT); // set motor direction pin to output
}
//********************************************************************
void initEncoderInterrupts(void)
{
// Position encoder ISR setup
// PCINT1_vect ISR triggered for enabled bit changes on PCMSK1
cli(); // disable global interrupts
PCMSK1 = 0b00001100; // ENC3,2,1,0 -> A3,A2,A1,A0 -> d17,16,15,14
PCICR = (1 << PCIE1); // enable pin change interrupts 8..14
sei(); // enable global interrupts
}
//********************************************************************
void initPWMtimer2(void)
{
//-----------------------------------------------------------------
// Use Timer 2 for direct motor drive PWM generation.
// Prescale = 1, FAST PWM, 8-bit (Mode 3) -> 62.5 kHz PWM
// Output pins OC2B (d3~) and OC2A (d11~) driven by counter hardware.
cli();
TCCR2B = 0;
TCCR2A = 0;
TCCR2B = (0 << WGM22); // start FAST PWM mode 3 setup
TCCR2A = (1 << WGM21) | (1 << WGM20); // finish FAST PWM setup
TCCR2B |= (0 << CS22) | (1 << CS21) | (1 << CS20); // clock prescale = 32
TCCR2A |= (1 << COM2B1) | (0 << COM2B0); // OCR2B pin (d3~) noninverting PWM
TCCR2A |= (1 << COM2A1) | (0 << COM2A0); // OCR2A pin (d11~) noninverting PWM
OCR2B = 1; OCR2A = 1;
sei();
}
//********************************************************************
void decodeEncoder32(void) // 2 bit quad decoder
{
const float MTR_RAD_PER_TICK = TWO_PI / 32;
static byte oldquadratureCode = 0;
oldquadratureCode = quadratureCode;
quadratureCode = (PINC & 0b00001100);
// Quadrature sequence: 0,8,12,4 (update ?CW facing end)
switch (quadratureCode)
{
case 0:
if (oldquadratureCode == 4) mtrPos += MTR_RAD_PER_TICK;
if (oldquadratureCode == 8) mtrPos -= MTR_RAD_PER_TICK;
break;
case 8:
if (oldquadratureCode == 0) mtrPos += MTR_RAD_PER_TICK;
if (oldquadratureCode == 12) mtrPos -= MTR_RAD_PER_TICK;
break;
case 12:
if (oldquadratureCode == 8) mtrPos += MTR_RAD_PER_TICK;
if (oldquadratureCode == 4) mtrPos -= MTR_RAD_PER_TICK;
break;
case 4:
if (oldquadratureCode == 12) mtrPos += MTR_RAD_PER_TICK;
if (oldquadratureCode == 0) mtrPos -= MTR_RAD_PER_TICK;
break;
}
} // decodeEncoder32( )
//********************************************************************
void syncSample() // set the sample rate for ADC and therefore for the main loop
{ // sample interval time is set by TSAMP_MSEC
const unsigned long TIC_USEC = TSAMP_MSEC * 1000UL;
const byte ADCSRA_ISR = 0b11101111; // auto ISR, clkdiv = 128
static unsigned long tic, stake = 0;
static boolean first_run = true;
if (first_run) {
stake = micros(); // only runs first time to set stake
first_run = false;
}
while ((tic - stake) < TIC_USEC) tic = micros(); // wait here until
stake = tic;
ADCSRA = ADCSRA_ISR; // start oversample-average series
}
//********************************************************************
ISR(PCINT1_vect) // if pin change occurs, update quadrature decoder
{
decodeEncoder32();
}
//********************************************************************
ISR (ADC_vect)
{
const byte N_ADC_AVE = 80;
const float INV_N_ADC = 1.0 / N_ADC_AVE;
static byte nConv = 0;
static unsigned int loAccum = 0, hiAccum = 0;
//SET_TP0_HI;
loAccum += ADCL; // lower 8 bits: must read before ADCH per Atmel
hiAccum += ADCH; // upper 2 bits
if (++nConv >= N_ADC_AVE)
{
//SET_TP1_HI;
adcReading = INV_N_ADC * (256UL * hiAccum + loAccum);
hiAccum = 0; loAccum = 0;
nConv = 0;
ADCSRA &= ~bit(ADIE); // stop auto conversions
//SET_TP1_LO;
}
//SET_TP0_LO;
} // end of ADC_vect

View file

@ -0,0 +1,101 @@
//**************************************************************
void trapBuildSymAcc(float Disp_rad, float Vplat, float Acc)
{
float tAcc = Vplat / Acc;
float dAcc = Vplat * tAcc;
float dPlat = Disp_rad - dAcc;
float tPlat = dPlat / Vplat;
trapAccT = Acc; // acceleration rate
accT = int(round(tAcc / TSAMP)); // time duration of acceleration
platT = int(round(tPlat / TSAMP)); // time duration of constant speed
float dTrap = (accT + platT) * TSAMP * Vplat; // total displacement during trapezoid profile
Serial.println();
Serial.print("tAcc = "); Serial.println(tAcc);
Serial.print("dAcc = "); Serial.println(dAcc);
Serial.print("dPlat = "); Serial.println(dPlat);
Serial.print("tPlat = "); Serial.println(tPlat);
Serial.print("accT = "); Serial.println(accT);
Serial.print("platT = "); Serial.println(platT);
Serial.print("dTrap = "); Serial.println(dTrap);
}
//*********************************************************************
void trapRefVel(float specDisp_rad, float specVel, float specAcc, int Ncycles) // trap velocity profile
{
if (!oldProfileEn && isProfileEn)
{
//specDisp_rad = 300.0; specVel = 150.0; specAcc = 800.0;
trapBuildSymAcc(specDisp_rad, specVel, specAcc);
dwellStartT = 1; dwellEndT = 1; specVdist = 0.0;
//specDisp_rad = 300.0, specVel = 100.0, specAcc = 200.0;
//trapBuildSymAcc(specDisp_rad, specVel, specAcc);
//dwellStartT = 50, dwellEndT = 200; specVdist = 2.0;
//specDisp_rad = 206.9, specVel = 110.0, specAcc = 180.0;
//trapBuildSymAcc(specDisp_rad, specVel, specAcc);
//dwellGoT = 300, dwellUpT = 500, dwellEndT = 200; specVdist = abs(V_DIST);
// Times when speed changes
T0 = dwellStartT;
T1 = T0 + accT; T2 = T1 + platT; T3 = T2 + accT; T4 = T3 + dwellEndT;
T5 = T4 + accT; T6 = T5 + platT; T7 = T6 + accT; T8 = T7 + dwellEndT;
//T0 = dwellGoT;
//T1 = T0 + accT, T2 = T1 + platT, T3 = T2 + accT, T4 = T3 + dwellUpT;
//T5 = T4 + accT, T6 = T5 + platT, T7 = T6 + accT, T8 = T7 + dwellEndT;
// Times when disturbances are applied and values
D1 = T3 + 100; D2 = D1 + 200;
dD1 = specVdist; dD2 = -specVdist;
//simJumpOn_simJumpOff();
//simJumpOn_simFileOff();
//weightOn_simJumpOff();
//weightOn_simFileOff();
}
tick = timeElapsedTicks % T8; //modulo allows rerunning of profile. Remove for single run.
// ---- Command profile -------------------------------------
oldProfileEn = isProfileEn;
if (tick < T0) refAccT = 0.0;
else if (tick < T1) refAccT = dir * trapAccT;
else if (tick < T2) refAccT = 0.0;
else if (tick < T3) refAccT = -dir * trapAccT;
else if (tick < T4) refAccT = 0.0;
//else if (tick == T4) isProfileEn = false;
else if (tick < T5) refAccT = -dir * trapAccT;
else if (tick < T6) refAccT = 0.0;
else if (tick < T7) refAccT = dir * trapAccT;
else if (tick < T8) refAccT = 0.0;
else if (tick == T8) isProfileEn = false;
//---- Disturbance profile -----------------------------------
if (tick < D1) Vdist = 0.0;
else if (tick == D1) Vdist += dD1 * specVdist; // module, sim load
else if (tick == D2) Vdist += dD2 * specVdist;
else if (tick == D3) Vdist += dD3 * specVdist;
else if (tick == D4) Vdist += dD4 * specVdist;
else if (tick == D5) Vdist += dD5 * specVdist;
else if (tick == D6) Vdist += dD6 * specVdist;
else if (tick == D7) Vdist += dD7 * specVdist;
else if (tick == D8) Vdist += dD8 * specVdist;
//---- Profile integration -----------------------------------
if (isProfileEn) {
refVelT += refAccT * TSAMP;
refPosT += refVelT * TSAMP;
}
else {
refAccT = 0.0;
refVelT = 0.0;
}
isShowStats = (oldProfileEn && !isProfileEn);
if ((timeElapsedTicks/T8)>=Ncycles) {isProfileEn=false; isModuleEn=false;}; // stop after 4 profiles
}

View file

@ -0,0 +1,342 @@
/* Click in this box, then
CTRL-A to select all
CTRL-C to copy
CTRL-V to paste into Arduino IDE
File: Lab3_trajectory_generator
Written: Feb 15, 2020 Clark Hochgraf
Revised:
Desc:
vClosed loop speed control of dc motor with Trapezoidal reference
Speed of the motor is measured using a quadrature encoder.
Assumes fixed 5v 2amp power supply on Motor Driver
*/
volatile byte quadratureCode, oldquadratureCode;
volatile float quadPos = 0.0;
float lastquadPos = 0;
float motorspeedRPS = 0;
bool isModuleEn = false, prevModuleEn = false, isPrinting = false;
bool isProfileEn = false, oldProfileEn = false, isShowStats = false;
const byte TSAMP_MSEC = 20;
long timeElapsedTicks = 0;
const float TSAMP = 0.001 * TSAMP_MSEC;
long TOTAL_RUN_TIME_MSEC = 4000000; // in millisec
volatile float adcReading = 0;
float pwm_value_commanded;// command supplied to the motor PWM value.
const int ENC2 = A2; // d16, PC2 PCINT10 (green wire)
const int ENC3 = A3; // d17, PC3 PCINT11 (blue wire
const int PWM_M1A_PIN = 3; // d3, PD3 PCINT19 digital output OCR2B (green wire)
const int PWM_M1B_PIN = 11; // d11, PB4 digital output OCR2A (blue wire)
const float VOLTS_PER_PWM = 5.0 / 255.0; // motor drive voltage per pwm command
const float PWM_PER_VOLT = 1 / VOLTS_PER_PWM; // pwm value to achieve 1 volt output
const float RADPERSEC_PERVOLT = 356.0; // from datasheet calculations
float Wref = 0;
float Varm;
float mtrVel = 0.0, mtrPos = 0.0, errVel = 0.0, errPos = 0.0, errDist = 0.0;
float refAcc = 0.0, refVel = 0.0, refPos = 0.0, refDist = 200.0;
float refAccT = 0.0, refVelT = 0.0, refPosT = 0.0, refDistT = 200.0;
unsigned int tick = 0;
float dir = 1.0;
float disp_rad = 0;
float specAcc = 0.0, specVel, specDisp_rad, specVdist;
float trapAcc = 0.0, trapVel = 0.0, trapDisp_rad = 0.0;
float trapAccT = 0.0;
int dwellStartT, accT, platT, dwellEndT;
int T0, T1, T2, T3, T4, T5, T6, T7, T8;
int D0, D1, D2, D3, D4, D5, D6, D7, D8;
float dD1, dD2, dD3, dD4, dD5, dD6, dD7, dD8;
boolean isTrapezoid = true;
//---------------------------------------------------------------------
// Motor constants: DF robot motor with encoder model FIT0458
const float K_EMF = 0.00285; //(V/(160*120))*60.0/TWO_PI; // V/rad/sec from V/1000RPM
const float K_TRQ = 0.008 / 2.8; // N-m/Amp
const float R_ARM = 2.14; // ohms
const float GEAR_RATIO = 120; // motor turns per output shaft turns
const float D_DRAG = 1 * 2.09e-6;
const float SYS_A = 2000;
const float SYS_B = 6;
const float MaxTrqmN = 1000 * (5.0 / R_ARM) * K_TRQ;
const float V_FRICTION = 0.2;
float trapeAccel = 2 * 256;
static float trapeVel = 0;
float Vdist = 0;
#define signof(x) ((x) < 0 ? -1 : ((x) > 0 ? 1 : 0))
#include "trapeRef.h" // for the PID classes (not a library)
// ##################################################################
void setup()
{
Serial.begin(115200);//Initialize the serial port ** Set Serial Monitor to same 115200
Serial.println(F("Lab3_trajectory_generator"));
Serial.println(F("runs for four seconds and then stops"));
displayMenu();
initMotorPins();
initEncoderInterrupts();
initPWMtimer2();
}
// ##################################################################
void loop()
{ manageMenu();
syncSample();
if (isModuleEn) {
isProfileEn = true;
// for feasible trajectory, uncomment the line below
float accRef = 0.7 * 1904.768; float velRef = 200; float dispRef = 6.283 * 8; float Ncycles = 3;
// for infeasible trajectory, uncomment the line below
//float accRef=20*1904.768; float velRef=1000; float dispRef=6.283*60; float Ncycles=1;
trapRefVel(dispRef, velRef, accRef, Ncycles); //displacement (radians), veloc (rad/sec), acceler (rad/sec/sec), Ncycles
//stepRefVel(500); // input is velocity in radians per sec
Wref = refVelT; refVel = refVelT;
calculateError();
//Varm = closedLoopVelP(errVel, 0.0125); // error signal, Kp gain // closed loop control
//Varm = refVel * K_EMF; // uncomment for open loop speed control
//Varm = refVel * K_EMF + V_FRICTION; // uncomment for open loop speed control
//Varm = refVel * K_EMF + V_FRICTION + mtrVel * D_DRAG * R_ARM / K_TRQ; // uncomment for open loop speed control
//Varm = refAccT/SYS_A + refVel * K_EMF + V_FRICTION + mtrVel * D_DRAG * R_ARM / K_TRQ; // uncomment for open loop speed control
Varm = refAccT/SYS_A + refVel * K_EMF + V_FRICTION*signof(Wref) + mtrVel * D_DRAG * R_ARM / K_TRQ; // uncomment for open loop speed control
//Varm = 0;
Varm = Varm + closedLoopVelP(errVel, 0.0125);
driveMotorVolts(Varm);
printResults(); // only print while motor running
}
else { //send zero voltage command to pwm if not enabled
Varm = 0;
driveMotorVolts(Varm);
}
if (timeElapsedTicks * TSAMP_MSEC > TOTAL_RUN_TIME_MSEC) //stop motor after 2 seconds
{
isModuleEn = false; isProfileEn = false;
}
prevModuleEn = isModuleEn;
} // End main loop
// ##################################################################
float closedLoopVelP(float errorIn, float Kp)
{
return Kp * errorIn;
}
//*********************************************************************
void stepRefVel(float vel_rad_per_sec) // step input velocity reference levels
{
if (timeElapsedTicks < 0) refVel = 0.0;
else if (timeElapsedTicks < 400) refVel = vel_rad_per_sec;
else if (timeElapsedTicks < 800) refVel = -vel_rad_per_sec;
else if (timeElapsedTicks < 1000) refVel = 0.0;
else isModuleEn = false;
}
//********************************************************************
void calculateError(void)
{
mtrVel = (quadPos - lastquadPos) / (TSAMP_MSEC * 0.001); // radians per time interval (rad/sec)
lastquadPos = quadPos;
errVel = refVel - mtrVel;
}
//********************************************************************
void driveMotorVolts(float Vmotor)
{
int pwm_command = (int)(Vmotor * PWM_PER_VOLT);
if (pwm_command < 0) { // negative case -- set direction CW
pwm_command = - int(pwm_command);
OCR2B = 0;
OCR2A = constrain(pwm_command, 0, 255); //Serial.println(OCR2A);
}
else
{ //positive case -- set direction CW
pwm_command = int(pwm_command);
OCR2A = 0;
OCR2B = constrain(pwm_command, 0, 255); //Serial.println(OCR2B);
}
}
//********************************************************************
void printResults(void)
{ if ((isModuleEn != prevModuleEn) && isModuleEn)
{
//print header
Serial.print("time (msec): "); Serial.print(",");
Serial.print("motorspeed: (rad/sec) "); Serial.print(",");
Serial.print("quadPos: (rad) "); Serial.print(",");
Serial.print("pwm_command: () "); Serial.print(",");
Serial.print("Varm (V) "); Serial.print(",");
Serial.print("Wref (rad/sec)");
Serial.println();
quadPos = 0;
lastquadPos = quadPos;
}
motorspeedRPS = mtrVel;
Serial.print(timeElapsedTicks * TSAMP_MSEC); Serial.print(",");
Serial.print(motorspeedRPS); Serial.print(",");
Serial.print(quadPos); Serial.print(",");
Serial.print(pwm_value_commanded); Serial.print(",");
Serial.print(Varm); Serial.print(",");
Serial.print(Wref);
Serial.println();
timeElapsedTicks++;
}
//********************************************************************
void displayMenu()
{
Serial.println("\nEnter 'e' to toggle module enable.");
}
//********************************************************************
void manageMenu()
{
char inChar = Serial.read();
if (inChar == 'e')
{
isModuleEn = !isModuleEn;
if (isModuleEn) {
Serial.println(F("Module ENABLED"));
timeElapsedTicks = 0;
}
else Serial.println(F("Module DISABLED"));
}
}
//********************************************************************
void initMotorPins()
{ // configure pins as input or output
pinMode(ENC2, INPUT); // Encoder A
pinMode(ENC3, INPUT); // Encoder B
pinMode(PWM_M1A_PIN, OUTPUT); // set motor PWM signal to output
pinMode(PWM_M1B_PIN, OUTPUT); // set motor direction pin to output
}
//********************************************************************
void initEncoderInterrupts(void)
{
// Position encoder ISR setup
// PCINT1_vect ISR triggered for enabled bit changes on PCMSK1
cli(); // disable global interrupts
PCMSK1 = 0b00001100; // ENC3,2,1,0 -> A3,A2,A1,A0 -> d17,16,15,14
PCICR = (1 << PCIE1); // enable pin change interrupts 8..14
sei(); // enable global interrupts
}
//********************************************************************
void initPWMtimer2(void)
{
//-----------------------------------------------------------------
// Use Timer 2 for direct motor drive PWM generation.
// Prescale = 1, FAST PWM, 8-bit (Mode 3) -> 62.5 kHz PWM
// Output pins OC2B (d3~) and OC2A (d11~) driven by counter hardware.
cli();
TCCR2B = 0;
TCCR2A = 0;
TCCR2B = (0 << WGM22); // start FAST PWM mode 3 setup
TCCR2A = (1 << WGM21) | (1 << WGM20); // finish FAST PWM setup
TCCR2B |= (0 << CS22) | (0 << CS21) | (1 << CS20); // clock prescale = 1
TCCR2A |= (1 << COM2B1) | (0 << COM2B0); // OCR2B pin (d3~) noninverting PWM
TCCR2A |= (1 << COM2A1) | (0 << COM2A0); // OCR2A pin (d11~) noninverting PWM
OCR2B = 1; OCR2A = 1;
sei();
}
//********************************************************************
void decodeEncoder32(void) // 2 bit quad decoder
{
const float MTR_RAD_PER_TICK = TWO_PI / 32;
static byte oldquadratureCode = 0;
oldquadratureCode = quadratureCode;
quadratureCode = (PINC & 0b00001100);
// Quadrature sequence: 0,8,12,4 (update ?CW facing end)
switch (quadratureCode)
{
case 0:
if (oldquadratureCode == 4) quadPos += MTR_RAD_PER_TICK;
if (oldquadratureCode == 8) quadPos -= MTR_RAD_PER_TICK;
break;
case 8:
if (oldquadratureCode == 0) quadPos += MTR_RAD_PER_TICK;
if (oldquadratureCode == 12) quadPos -= MTR_RAD_PER_TICK;
break;
case 12:
if (oldquadratureCode == 8) quadPos += MTR_RAD_PER_TICK;
if (oldquadratureCode == 4) quadPos -= MTR_RAD_PER_TICK;
break;
case 4:
if (oldquadratureCode == 12) quadPos += MTR_RAD_PER_TICK;
if (oldquadratureCode == 0) quadPos -= MTR_RAD_PER_TICK;
break;
}
} // decodeEncoder32( )
//********************************************************************
void syncSample() // set the sample rate for ADC and therefore for the main loop
{ // sample interval time is set by TSAMP_MSEC
const unsigned long TIC_USEC = TSAMP_MSEC * 1000UL;
const byte ADCSRA_ISR = 0b11101111; // auto ISR, clkdiv = 128
static unsigned long tic, stake = 0;
static boolean first_run = true;
if (first_run) {
stake = micros(); // only runs first time to set stake
first_run = false;
}
while ((tic - stake) < TIC_USEC) tic = micros(); // wait here until
stake = tic;
ADCSRA = ADCSRA_ISR; // start oversample-average series
}
//********************************************************************
ISR(PCINT1_vect) // if pin change occurs, update quadrature decoder
{
decodeEncoder32();
}
//********************************************************************
ISR (ADC_vect)
{
const byte N_ADC_AVE = 80;
const float INV_N_ADC = 1.0 / N_ADC_AVE;
static byte nConv = 0;
static unsigned int loAccum = 0, hiAccum = 0;
//SET_TP0_HI;
loAccum += ADCL; // lower 8 bits: must read before ADCH per Atmel
hiAccum += ADCH; // upper 2 bits
if (++nConv >= N_ADC_AVE)
{
//SET_TP1_HI;
adcReading = INV_N_ADC * (256UL * hiAccum + loAccum);
hiAccum = 0; loAccum = 0;
nConv = 0;
ADCSRA &= ~bit(ADIE); // stop auto conversions
//SET_TP1_LO;
}
//SET_TP0_LO;
} // end of ADC_vect

BIN
lab5/lab5Continued.ods Normal file

Binary file not shown.

BIN
lab5/section2Kp02.png Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 13 KiB

BIN
lab5/section2Kp08.png Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 29 KiB

BIN
lab5/section3C6.png Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 12 KiB

BIN
lab5/section4Overview.png Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 19 KiB

Binary file not shown.

BIN
lab6/Lab 6 analysis.xlsx Normal file

Binary file not shown.

577
lab6/Lab6Code/Lab6Code.ino Normal file
View file

@ -0,0 +1,577 @@
// Click in this box, then
// CTRL-A to select all
// CTRL-C to copy
// CTRL-V to paste into Arduino IDE
// File: Lab6_Pos_PI_PZ_DEV
// Written: Sept 21, 2020 Clark Hochgraf
// Revised:
// Desc:
// Closed loop P+I control of motor speed.
// Assumes fixed 5v 2amp power supply on Motor Driver
volatile byte quadratureCode, oldquadratureCode;
volatile float quadPos = 0.0;
volatile bool isEncoderChange = false;
float lastquadPos = 0;
bool isModuleEn = false, prevModuleEn = false, isPrinting = false;
bool isProfileEn = false, oldProfileEn = false, isShowStats = false;
const byte TSAMP_MSEC = 20;
int TIC_MSEC = TSAMP_MSEC;
long timeElapsedTicks = 0;
const float TSAMP = 0.001 * TSAMP_MSEC;
volatile float adcReading = 0;
const int ENC2 = A2; // d16, PC2 PCINT10 (green wire)
const int ENC3 = A3; // d17, PC3 PCINT11 (blue wire
const int PWM_M1A_PIN = 3; // d3, PD3 PCINT19 digital output OCR2B (green wire)
const int PWM_M1B_PIN = 11; // d11, PB4 digital output OCR2A (blue wire)
const float VOLTS_PER_PWM = 5. / 255.0; // motor drive voltage per pwm command
const float PWM_PER_VOLT = 1 / VOLTS_PER_PWM; // pwm value to achieve 1 volt output
float Vctl, Varm;
float mtrVel = 0.0, mtrPos = 0.0, errVel = 0.0, errPos = 0.0;
float refAcc = 0.0, refVel = 0.0, refPos = 0.0;
unsigned int tick = 0;
float dir = 1.0;
float disp_rad = 0;
float specAcc = 0.0, specVel, specDisp_rad, specVdist;
float trapAcc = 0.0, trapVel = 0.0, trapDisp_rad = 0.0;
int dwellStartT, accT, platT, dwellEndT;
int T0, T1, T2, T3, T4, T5, T6, T7, T8;
int D0, D1, D2, D3, D4, D5, D6, D7, D8;
float dD1, dD2, dD3, dD4, dD5, dD6, dD7, dD8;
boolean isTrapezoid = true;
//---------------------------------------------------------------------
// Motor constants: DF robot motor with encoder model FIT0458
const float K_EMF = 0.00285; //(V/(160*120))*60.0/TWO_PI; // V/rad/sec from V/1000RPM
const float K_TRQ = 0.008 / 2.8; // N-m/Amp
const float R_ARM = 2.14; // ohms
const float D_DRAG = 0*1.117e-6;
const float SYS_A = 1795;//1795; //2040//1717
const float SYS_B = 6.21;
boolean isFrictionCompensated = true; boolean isVff = true;
const float V_FRICTION = 0.20;
float Vffwd = 0;
float Vdist = 0;
static float lastmicroseconds=0;
void setup()
{
Serial.begin(115200);//Initialize the serial port ** Set Serial Monitor to same 115200
Serial.println(F("Lab6_Pos_PI_PZ_DEV"));
displayMenu();
initMotorPins();
initEncoderInterrupts();
initPWMtimer2();
}
// ##################################################################
void loop()
{ manageMenu();
syncSample();
lastmicroseconds=micros();
isProfileEn = isModuleEn;
if (isModuleEn) {
isTrapezoid=false;
if (isTrapezoid) { // Choose speed reference
trapRefVel(700.0, 600.0, 1500.0); //displacement (radians), veloc (rad/sec), acceler (rad/sec/sec)
// good values for trapRefVel are 700, 600, 1500
} else {
stepRefPos(50);
}
// Choose which control method to use by uncommenting it below
calculateError(); // location of function call for efficient software execution
//delayMicroseconds(20000); // To model delay of digital controller, add delay here
//closedLoopVelPI(isFrictionCompensated, isVff, 0.004, 0.01); // friction enabled? Vff enabled? Kp gain
closedLoopPosPI(isFrictionCompensated, isVff, 0.16, 0.1); // friction enabled? Vff enabled? Kp gain
//closedLoopPosPI_PZ(isFrictionCompensated, isVff, 0.16,0.1,5,20); // friction enabled? Vff enabled? Kp,Ki,CompC,CompD
//calculateError(); // if the calculateError() is called here system stability is severely degraded.
}
else { // stop motor by sending zero voltage command to pwm
OCR2B = 0; OCR2A = 0;
timeElapsedTicks=0;
quadPos=0;
lastquadPos = quadPos;
}
if (isModuleEn && (timeElapsedTicks * TSAMP_MSEC) <= 4000) //stop print after 4 seconds
{
//isModuleEn = false;
printResults();
}
if (isPrinting) printResults();
//lastmicroseconds=micros();
//Serial.println(micros()-lastmicroseconds);
if (isModuleEn) timeElapsedTicks++;
prevModuleEn = isModuleEn;
} // End main loop
// ##################################################################
//**************************************************************
float PD_compensate(float x, float c, float d)
{
// Proportional plus Derivative compensator
// Cancel pole at -c, replace with a pole at -d.
// Implement (s+c)/(s+d) as 1 + (c-d)/(s+d).
// and post scale by d/c to get unity gain at DC.
// PD section
static float yd = 0.0;
yd += ((c - d) * x - d * yd) * TSAMP;
float ypd = x + yd;
ypd = ypd * d / c; // correct scaling to unity gain at DC.
return ypd;
}
//********************************************************************
float VfrictionVelocity(float Vcmd)
{ // calculates voltage required to overcome friction.
// direction of voltage depends on commanded direction of velocity
float frictionV = 0.0;
//Coulomb friction
if (Vcmd > 0.001) frictionV = V_FRICTION;
if (Vcmd < -0.001) frictionV = -V_FRICTION;
//static friction
if ((mtrVel < 1) && (mtrVel > -1) && (Vcmd > 0.001)) frictionV += 0.4;
if ((mtrVel < 1) && (mtrVel > -1) && (Vcmd < -0.001)) frictionV -= 0.4;
return frictionV;
}
//********************************************************************
void calculateError(void)
{
mtrVel = (quadPos - lastquadPos) / (TSAMP_MSEC * 0.001); // radians per time interval (rad/sec)
lastquadPos = quadPos;
mtrPos = quadPos;
errVel = refVel - mtrVel;
errPos = refPos - mtrPos;
}
//********************************************************************
void printResults(void)
{ if (isModuleEn != prevModuleEn)
{
//print header
Serial.print("time (msec): ");
Serial.print("\tmotorspeed: (rad/sec)");
Serial.print("\tquadPos: (rad)");
Serial.print("\t errVel: (rad/sec)");
Serial.print("\t Vctrl (V)");
Serial.print("\t Wref (rad/sec)");
Serial.print("\t Posref (rad)");
Serial.println();
//lastquadPos = quadPos;
}
Serial.print(timeElapsedTicks * TSAMP_MSEC); Serial.print("\t");
Serial.print(mtrVel); Serial.print("\t");
Serial.print(quadPos); Serial.print("\t");
Serial.print(errVel); Serial.print("\t");
Serial.print(Vctl); Serial.print("\t");
Serial.print(refVel); Serial.print("\t");
Serial.print(refPos);
Serial.println();
}
//********************************************************************
void initEncoderInterrupts(void)
{
// Position encoder ISR setup
// PCINT1_vect ISR triggered for enabled bit changes on PCMSK1
cli(); // disable global interrupts
PCMSK1 = 0b00001100; // ENC3,2,1,0 -> A3,A2,A1,A0 -> d17,16,15,14
PCICR = (1 << PCIE1); // enable pin change interrupts 8..14
sei(); // enable global interrupts
}
//********************************************************************
void initPWMtimer2(void)
{
//-----------------------------------------------------------------
// Use Timer 2 for direct motor drive PWM generation.
// Prescale = 1, FAST PWM, 8-bit (Mode 3) -> 62.5 kHz PWM
// Output pins OC2B (d3~) and OC2A (d11~) driven by counter hardware.
cli();
TCCR2B = 0;
TCCR2A = 0;
TCCR2B = (0 << WGM22); // start FAST PWM mode 3 setup
TCCR2A = (1 << WGM21) | (1 << WGM20); // finish FAST PWM setup
TCCR2B |= (0 << CS22) | (0 << CS21) | (1 << CS20); // clock prescale = 1
TCCR2A |= (1 << COM2B1) | (0 << COM2B0); // OCR2B pin (d3~) noninverting PWM
TCCR2A |= (1 << COM2A1) | (0 << COM2A0); // OCR2A pin (d11~) noninverting PWM
OCR2B = 1; OCR2A = 1;
sei();
}
//********************************************************************
ISR(PCINT1_vect) // vector to quadrature decoder
{
//digitalWrite(ALED,!digitalRead(ALED));
isEncoderChange = true;
decodeEncoder32();
}
//********************************************************************
void decodeEncoder32(void) // 2 bit quad decoder
{
const float MTR_RAD_PER_TICK = TWO_PI / 32;
static byte oldquadratureCode = 0;
oldquadratureCode = quadratureCode;
quadratureCode = (PINC & 0b00001100); // inner tracks
// Quadrature sequence: 0,8,12,4 (update ?CW facing end)
switch (quadratureCode)
{
case 0:
if (oldquadratureCode == 4) quadPos += MTR_RAD_PER_TICK;
if (oldquadratureCode == 8) quadPos -= MTR_RAD_PER_TICK;
break;
case 8:
if (oldquadratureCode == 0) quadPos += MTR_RAD_PER_TICK;
if (oldquadratureCode == 12) quadPos -= MTR_RAD_PER_TICK;
break;
case 12:
if (oldquadratureCode == 8) quadPos += MTR_RAD_PER_TICK;
if (oldquadratureCode == 4) quadPos -= MTR_RAD_PER_TICK;
break;
case 4:
if (oldquadratureCode == 12) quadPos += MTR_RAD_PER_TICK;
if (oldquadratureCode == 0) quadPos -= MTR_RAD_PER_TICK;
break;
}
} // decodeEncoder32( )
//********************************************************************
void syncSample() // set the sample rate for ADC and therefore for the main loop
{ // sample interval time is set by TIC_MSEC
const unsigned long TIC_USEC = TIC_MSEC * 1000UL;
const byte ADCSRA_ISR = 0b11101111; // auto ISR, clkdiv = 128
static unsigned long tic, stake = 0;
static boolean first_run = true;
if (first_run) {
stake = micros(); // only runs first time to set stake
first_run = false;
}
while ((tic - stake) < TIC_USEC) tic = micros(); // wait here until
stake = tic;
ADCSRA = ADCSRA_ISR; // start oversample-average series
}
//********************************************************************
ISR (ADC_vect)
{
const byte N_ADC_AVE = 80;
const float INV_N_ADC = 1.0 / N_ADC_AVE;
static byte nConv = 0;
static unsigned int loAccum = 0, hiAccum = 0;
//SET_TP0_HI;
loAccum += ADCL; // lower 8 bits: must read before ADCH per Atmel
hiAccum += ADCH; // upper 2 bits
if (++nConv >= N_ADC_AVE)
{
//SET_TP1_HI;
adcReading = INV_N_ADC * (256UL * hiAccum + loAccum);
hiAccum = 0; loAccum = 0;
nConv = 0;
ADCSRA &= ~bit(ADIE); // stop auto conversions
//SET_TP1_LO;
}
//SET_TP0_LO;
} // end of ADC_vect
//********************************************************************
void displayMenu()
{
Serial.println("\nEnter 'e' to toggle module enable.");
//Serial.println("Enter 'g' to go.");
}
//********************************************************************
void manageMenu()
{
char inChar = Serial.read();
if (inChar == 'e')
{
isModuleEn = !isModuleEn;
//digitalWrite(PWMVAL_PIN, isModuleEn); // PWM disable low
if (isModuleEn) {
Serial.println(F("Module ENABLED"));
timeElapsedTicks = 0;
oldProfileEn=false; isProfileEn=true;
}
else {
Serial.println(F("Module DISABLED"));
quadPos=0;
lastquadPos=quadPos;
}
}
else if (inChar == 'g')
{
timeElapsedTicks = 0;
dir = 1.0;
isProfileEn = true;
}
else if (inChar == 'p')
{
isPrinting = !isPrinting;
}
else if (inChar == 'f')
{
isFrictionCompensated = !isFrictionCompensated;
if (isFrictionCompensated) Serial.println(F("Stiction Comp Enabled"));
}
else if (inChar == 't')
{
isTrapezoid = !isTrapezoid;
if (isTrapezoid) {
Serial.println(F("Trapezoidal Reference"));
}
else {
Serial.println(F("Step Reference"));
}
}
}
//********************************************************************
void initMotorPins()
{ // configure pins as input or output
pinMode(ENC2, INPUT); // Encoder A
pinMode(ENC3, INPUT); // Encoder B
pinMode(PWM_M1A_PIN, OUTPUT); // set motor PWM signal to output
pinMode(PWM_M1B_PIN, OUTPUT); // set motor direction pin to output
}
//*********************************************************************
void stepRefPos(float pos_rad) // step input velocity reference levels
{
static float refPos_last_time = 0;
oldProfileEn = isProfileEn;
if (timeElapsedTicks < 0) refVel = 0.0;
else if (timeElapsedTicks < 40000) refPos = pos_rad;
else if (timeElapsedTicks < 80) refPos = -pos_rad;
else if (timeElapsedTicks < 100) refPos = 0.0;
else isProfileEn = false;
//refPos += refVel_last_time * TSAMP;
//refVel_last_time = refVel;
isShowStats = (oldProfileEn && !isProfileEn);
}
//*********************************************************************
void trapRefVel(float specDisp_rad, float specVel, float specAcc) // trap velocity profile
{
if (!oldProfileEn && isProfileEn)
{
//specDisp_rad = 300.0; specVel = 150.0; specAcc = 800.0;
trapBuildSymAcc(specDisp_rad, specVel, specAcc);
dwellStartT = 10; dwellEndT = 10; specVdist = 0.0;
//specDisp_rad = 300.0, specVel = 100.0, specAcc = 200.0;
//trapBuildSymAcc(specDisp_rad, specVel, specAcc);
//dwellStartT = 50, dwellEndT = 200; specVdist = 2.0;
//specDisp_rad = 206.9, specVel = 110.0, specAcc = 180.0;
//trapBuildSymAcc(specDisp_rad, specVel, specAcc);
//dwellGoT = 300, dwellUpT = 500, dwellEndT = 200; specVdist = abs(V_DIST);
// Times when speed changes
T0 = dwellStartT;
T1 = T0 + accT; T2 = T1 + platT; T3 = T2 + accT; T4 = T3 + dwellEndT;
T5 = T4 + accT; T6 = T5 + platT; T7 = T6 + accT; T8 = T7 + dwellEndT;
//T0 = dwellGoT;
//T1 = T0 + accT, T2 = T1 + platT, T3 = T2 + accT, T4 = T3 + dwellUpT;
//T5 = T4 + accT, T6 = T5 + platT, T7 = T6 + accT, T8 = T7 + dwellEndT;
// Times when disturbances are applied and values
D1 = T3 + 100; D2 = D1 + 200;
dD1 = specVdist; dD2 = -specVdist;
//simJumpOn_simJumpOff();
//simJumpOn_simFileOff();
//weightOn_simJumpOff();
//weightOn_simFileOff();
}
tick = timeElapsedTicks;
// ---- Command profile -------------------------------------
oldProfileEn = isProfileEn;
if (tick < T0) refAcc = 0.0;
else if (tick < T1) refAcc = dir * trapAcc;
else if (tick < T2) refAcc = 0.0;
else if (tick < T3) refAcc = -dir * trapAcc;
else if (tick < T4) refAcc = 0.0;
//else if (tick == T4) isProfileEn = false;
else if (tick < T5) refAcc = -dir * trapAcc;
else if (tick < T6) refAcc = 0.0;
else if (tick < T7) refAcc = dir * trapAcc;
else if (tick < T8) refAcc = 0.0;
else if (tick == T8) isProfileEn = false;
//---- Disturbance profile -----------------------------------
if (tick < D1) Vdist = 0.0;
else if (tick == D1) Vdist += dD1 * specVdist; // module, sim load
else if (tick == D2) Vdist += dD2 * specVdist;
else if (tick == D3) Vdist += dD3 * specVdist;
else if (tick == D4) Vdist += dD4 * specVdist;
else if (tick == D5) Vdist += dD5 * specVdist;
else if (tick == D6) Vdist += dD6 * specVdist;
else if (tick == D7) Vdist += dD7 * specVdist;
else if (tick == D8) Vdist += dD8 * specVdist;
//---- Profile integration -----------------------------------
if (isProfileEn) {
refVel += refAcc * TSAMP;
refPos += refVel * TSAMP;
}
else {
refAcc = 0.0;
refVel = 0.0;
}
isShowStats = (oldProfileEn && !isProfileEn);
}
//**************************************************************
void trapBuildSymAcc(float Disp_rad, float Vplat, float Acc)
{
float tAcc = Vplat / Acc;
float dAcc = Vplat * tAcc;
float dPlat = Disp_rad - dAcc;
float tPlat = dPlat / Vplat;
trapAcc = Acc; // acceleration rate
accT = int(round(tAcc / TSAMP)); // time duration of acceleration
platT = int(round(tPlat / TSAMP)); // time duration of constant speed
float dTrap = (accT + platT) * TSAMP * Vplat; // total displacement during trapezoid profile
// Serial.println();
// Serial.print("tAcc = "); Serial.println(tAcc);
// Serial.print("dAcc = "); Serial.println(dAcc);
// Serial.print("dPlat = "); Serial.println(dPlat);
// Serial.print("tPlat = "); Serial.println(tPlat);
// Serial.print("accT = "); Serial.println(accT);
// Serial.print("platT = "); Serial.println(platT);
// Serial.print("dTrap = "); Serial.println(dTrap);
}
//********************************************************************
void closedLoopVelPI(boolean isFrictionCompensated, boolean isVff, float KpGain, float KiGain)
{
float Kp = KpGain;
float Ki = KiGain;
Vffwd = ((SYS_B / SYS_A) * refVel + (1.0 / SYS_A) * refAcc);
Vctl = PI_compensate(errVel, Kp, Ki); // PI control
if (isFrictionCompensated) {
Vctl += VfrictionVelocity(refVel);
}
if (isVff) {
Vctl += Vffwd;
}
Varm = Vctl;
if (isModuleEn) driveMotor(Varm, mtrVel, mtrPos);
}
//********************************************************************
void closedLoopPosPI(boolean isFrictionCompensated, boolean isVff, float KpGain, float KiGain)
{
float Kp = KpGain;
float Ki = KiGain;
Vffwd = ((SYS_B / SYS_A) * refVel + (1.0 / SYS_A) * refAcc);
Vctl = PI_compensate(errPos, Kp, Ki); // PI control
if (isFrictionCompensated) {
Vctl += VfrictionVelocity(refVel);
}
if (isVff) {
Vctl += Vffwd;
}
Varm = Vctl;
if (isModuleEn) driveMotor(Varm, mtrVel, mtrPos);
}
//********************************************************************
void closedLoopPosPI_PZ(boolean isFrictionCompensated, boolean isVff, float KpGain, float KiGain, float CompC, float CompD)
{
float Kp = KpGain;
float Ki = KiGain;
Vffwd = ((SYS_B / SYS_A) * refVel + (1.0 / SYS_A) * refAcc);
Vctl = PI_compensate(errPos, Kp, Ki); // PI control
Vctl = PD_compensate(Vctl, CompC, CompD); // PD control, signal, CompC, CompD)
if (isFrictionCompensated) {
Vctl += VfrictionVelocity(refVel);
}
if (isVff) {
Vctl += Vffwd;
}
Varm = Vctl;
if (isModuleEn) driveMotor(Varm, mtrVel, mtrPos);
//Serial.println(micros()-lastmicroseconds);
}
//**************************************************************
float PI_compensate(float x, float Kp, float Ki)
{
// Implement (Kp s+Ki)/s as Kp + Ki/s.
static float Integralx = 0.0;
Integralx += x * TSAMP;
float ypi = Kp * x + Ki * Integralx;
// Apply integral compensator windup clipping.
return ypi;
}
//********************************************************************
void driveMotor(float Varm, float &vel, float &disp_rad)
{
// 8 bit PWM, ~5 volt rail
// note: reversed sign of Varm to get positive speed for positive volts
float pwm_command = -Varm * PWM_PER_VOLT;
if (pwm_command < 0) { // negative case -- set direction CW
pwm_command = - int(pwm_command);
OCR2A = 0;
OCR2B = constrain(pwm_command, 0, 255);
//Serial.println(OCR2B);
}
else
{ //positive case -- set direction CW
pwm_command = int(pwm_command);
OCR2B = 0;
OCR2A = constrain(pwm_command, 0, 255);
//Serial.println(OCR2A);
}
}

12
lab6/section1.m Normal file
View file

@ -0,0 +1,12 @@
s=tf('s');
a=1800.0;
b=6.0;
Gpy=a/(s+b);
Gpp=a/(s*(s+b));
figure(1)
step(Gpy);
title("Motor Speed Step Response")
figure(2)
step(Gpp);
title("Motor Position Step Response")

BIN
lab6/section1Position.png Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 35 KiB

BIN
lab6/section1Speed.png Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 40 KiB

20
lab6/section2.m Normal file
View file

@ -0,0 +1,20 @@
s=tf('s');
a=1800.0;
b=6.0;
Gpv=a/(s+b);
Gpp=a/(s*(s+b));
Kp=0.16;
Ki=0.1;
H=1;
Gc=(s*Kp+Ki)/s;
TFv=feedback(Gc*Gpv,H);
figure(3);
step(TFv);
title("Closed Loop Motor Velocity Step Response")
TFp=feedback(Gpp*(Gc),H);
figure(4);
step(TFp);
title("Closed Loop Motor Velocity Step Response")

BIN
lab6/section2Position.png Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 54 KiB

BIN
lab6/section2Speed.png Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 45 KiB

31
lab6/section3.m Normal file
View file

@ -0,0 +1,31 @@
s=tf('s');
a=1800.0;
b=6.0;
Gpv=a/(s+b);
Gpp=a/(s*(s+b));
Kp=0.05;
Ki=0.0001;
H=1;
Gc=(s*Kp+Ki)/s;
TFv=feedback(Gc*Gpv,H);
TFp=feedback(Gpp*(Gc),H);
% Part 3
figure(5);
t=0:0.02:4; % time vector: start, step, stop
vel_ref = arrayfun(@trapezoidalRef,t); % make trapezoidal reference
[pos_ref,t]=lsim(1/s,vel_ref,t); % make position reference
[y,t]=lsim(TFp,pos_ref,t); % linear simulation
plot(t,y)
hold on
plot(t,pos_ref)
title('trapezoidal reference response')
plot(t,vel_ref)
pos_err=pos_ref-y;
plot(t,150*Kp*pos_err)% scale by 50
hold off

BIN
lab6/section3.png Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 95 KiB

53
lab6/section4.m Normal file
View file

@ -0,0 +1,53 @@
s=tf('s');
a=1800.0;
b=6.0;
Gpv=a/(s+b);
Gpp=a/(s*(s+b));
Kp=0.5;
Ki=0.001;
H=1;
Gc=(s*Kp+Ki)/s;
TFv=feedback(Gc*Gpv,H);
TFp=feedback(Gpp*(Gc),H);
% Part 3
t=0:0.002:4; % time vector: start, step, stop
vel_ref = arrayfun(@trapezoidalRef,t); % make trapezoidal reference
[pos_ref,t]=lsim(1/s,vel_ref,t); % make position reference
[y,t]=lsim(TFp,pos_ref,t); % linear simulation
pos_err=pos_ref-y;
% Part 4 Pole zero compensator
C=5.625;
D=20;
Gpz= (D/C)*(s+C)/(s+D);
TFppz=feedback(Gc*Gpz*Gpp,H); % Find transfer function of closed loop feedback with pole-zero comp
figure(6);
step(TFppz);
% digital controller delay model
Td=0.000268; % controller sample delay as measured in Arduino
%Td=0.020268; % worst case delay with poor design of software
%Gd=(1-(Td/2)*s)/(1+(Td/2)*s); % Digital delay - pade delay approximation
%Gd=1/(1+(Td/2)*s); % Digital delay-single pole approximation
Gd=exp(-Td*s); % time delay model
% ref: https://www.mathworks.com/help/control/ug/time-delay-approximation-in-continuous-time-open-loop-model.html
TF=feedback(Gc*Gd*Gpp,H); % can use this for feedback only or connect method below
figure(7);
[y,t]=lsim(TFppz,pos_ref,t); % linear simulation
plot(t,y)
hold on
plot(t,pos_ref)
title('trapezoidal reference response')
plot(t,vel_ref)
pos_err=pos_ref-y;
plot(t,150*Kp*pos_err)% scale by 150
hold off

Binary file not shown.

After

Width:  |  Height:  |  Size: 89 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 44 KiB

30
lab6/trapezoidalRef.m Normal file
View file

@ -0,0 +1,30 @@
function input = trapezoidalRef(t)
accel_rate=1500;
plateau=600;
start_delay=0.1;
displacement=700;
dead_time=1;
middle_delay=0.1;
time_plat=(displacement-(plateau/accel_rate)*plateau)/plateau;
if t<start_delay
input=0;
elseif (t<(start_delay+plateau/accel_rate))
input=(t-start_delay)*accel_rate;
elseif (t<(start_delay+plateau/accel_rate)+time_plat)
input=plateau;
elseif (t<(start_delay+plateau/accel_rate)+time_plat+plateau/accel_rate);
input=plateau-accel_rate*(t-start_delay-time_plat-plateau/accel_rate);
elseif (t<(start_delay+plateau/accel_rate)+time_plat+plateau/accel_rate+middle_delay)
input=0;
elseif (t<(start_delay+plateau/accel_rate)+time_plat+plateau/accel_rate+middle_delay+plateau/accel_rate)
temp=(start_delay+plateau/accel_rate+time_plat+plateau/accel_rate+middle_delay);
input =-(t-temp)*accel_rate;
elseif (t<(start_delay+plateau/accel_rate)+time_plat+plateau/accel_rate+middle_delay+plateau/accel_rate+time_plat)
input =-plateau;
elseif (t<(start_delay+plateau/accel_rate)+time_plat+plateau/accel_rate+middle_delay+plateau/accel_rate+time_plat+plateau/accel_rate)
input =-plateau+accel_rate*(t-start_delay-time_plat-plateau/accel_rate-middle_delay-plateau/accel_rate-time_plat-plateau/accel_rate);
else
input=0;
end
end

30
simulationOfSystem.m Normal file
View file

@ -0,0 +1,30 @@
clear all;clc;
s=tf('s');
%Motor Position Control System
KpPos=0.2;
a=2491.5;
b=8.333;
Cpos=5.625;
Dpos=20;
Gcpos=KpPos*(Dpos/Cpos)*((s+Cpos)/(s+Dpos));
Gppos=a/(s*(s+b));
Hpos=1;
TFpos=feedback(Gcpos*Gppos,Hpos);
% Ball Position Control System
alpha=5.0/18.0;
KpBallDist=1;
g=9.8;
CBallDist = 1;
DBallDist = 6;
GcDist=(DBallDist/CBallDist)*((s+CBallDist)/(s+DBallDist));
GPlant= (alpha * g)/s^2;
GBallDist = KpBallDist* TFpos * GPlant;%GcDist *
HBallDist = GcDist;
TFBall=feedback(GBallDist, HBallDist);
%Bode Analysis
figure(1);step(TFBall);grid on;title("Step Response of Closed Loop System");hold on;
figure(2);bode(TFBall);grid on;title("Closed Loop Transfer Function");hold on;
figure(3);bode(GBallDist*HBallDist);grid on;title("Open Loop GH Gain");hold on;