mirror of
https://bitbucket.org/librepilot/librepilot.git
synced 2025-03-21 13:28:58 +01:00
Merge remote-tracking branch 'remotes/origin/next' into qwt_6.0.1_upgrade
Conflicts: ground/openpilotgcs/src/libs/qwt/src/qwt_global.h ground/openpilotgcs/src/libs/qwt/src/src.pro
This commit is contained in:
commit
81f01a0b96
2
Makefile
2
Makefile
@ -235,7 +235,7 @@ STM32FLASH_DIR := $(TOOLS_DIR)/stm32flash
|
||||
|
||||
.PHONY: stm32flash_install
|
||||
stm32flash_install: STM32FLASH_URL := http://stm32flash.googlecode.com/svn/trunk
|
||||
stm32flash_install: STM32FLASH_REV := 52
|
||||
stm32flash_install: STM32FLASH_REV := 61
|
||||
stm32flash_install: stm32flash_clean
|
||||
# download the source
|
||||
$(V0) @echo " DOWNLOAD $(STM32FLASH_URL) @ r$(STM32FLASH_REV)"
|
||||
|
135
artwork/Dials/deluxe/lineardial-horizontal.svg
Normal file → Executable file
135
artwork/Dials/deluxe/lineardial-horizontal.svg
Normal file → Executable file
@ -14,8 +14,8 @@
|
||||
height="70.597504"
|
||||
id="svg10068"
|
||||
version="1.1"
|
||||
inkscape:version="0.48.1 "
|
||||
sodipodi:docname="lineardial-horizontal.svg"
|
||||
inkscape:version="0.48.2 r9819"
|
||||
sodipodi:docname="lineardial-horizontal-old2.svg"
|
||||
inkscape:export-filename="H:\Documents\Hobbies\W433\My Gauges\vbat-001.png"
|
||||
inkscape:export-xdpi="103.61"
|
||||
inkscape:export-ydpi="103.61"
|
||||
@ -25,15 +25,19 @@
|
||||
<linearGradient
|
||||
id="linearGradient4439">
|
||||
<stop
|
||||
style="stop-color:#1a1a1a;stop-opacity:1"
|
||||
style="stop-color:#666666;stop-opacity:0;"
|
||||
offset="0"
|
||||
id="stop4441" />
|
||||
<stop
|
||||
id="stop4443"
|
||||
offset="0.19742694"
|
||||
style="stop-color:#808080;stop-opacity:1" />
|
||||
offset="0.31684026"
|
||||
style="stop-color:#a3a3a3;stop-opacity:1;" />
|
||||
<stop
|
||||
style="stop-color:#000000;stop-opacity:1"
|
||||
style="stop-color:#757575;stop-opacity:0.90517241;"
|
||||
offset="0.62995511"
|
||||
id="stop3987" />
|
||||
<stop
|
||||
style="stop-color:#666666;stop-opacity:0;"
|
||||
offset="1"
|
||||
id="stop4445" />
|
||||
</linearGradient>
|
||||
@ -57,15 +61,11 @@
|
||||
<stop
|
||||
id="stop4389"
|
||||
offset="0"
|
||||
style="stop-color:#4d4d4d;stop-opacity:1" />
|
||||
style="stop-color:#8a8a8a;stop-opacity:1;" />
|
||||
<stop
|
||||
style="stop-color:#000000;stop-opacity:1"
|
||||
offset="0.60976541"
|
||||
id="stop4391" />
|
||||
<stop
|
||||
id="stop4393"
|
||||
style="stop-color:#181818;stop-opacity:1;"
|
||||
offset="1"
|
||||
style="stop-color:#4d4d4d;stop-opacity:1" />
|
||||
id="stop4391" />
|
||||
</linearGradient>
|
||||
<linearGradient
|
||||
id="linearGradient4361">
|
||||
@ -237,15 +237,15 @@
|
||||
<stop
|
||||
id="stop3905"
|
||||
offset="0"
|
||||
style="stop-color:#000000;stop-opacity:1" />
|
||||
style="stop-color:#676767;stop-opacity:1;" />
|
||||
<stop
|
||||
style="stop-color:#ffffff;stop-opacity:1"
|
||||
offset="0.3220683"
|
||||
offset="0.43894145"
|
||||
id="stop3907" />
|
||||
<stop
|
||||
id="stop3909"
|
||||
offset="1"
|
||||
style="stop-color:#000000;stop-opacity:1" />
|
||||
style="stop-color:#7d7d7d;stop-opacity:1;" />
|
||||
</linearGradient>
|
||||
<linearGradient
|
||||
id="linearGradient5375">
|
||||
@ -425,46 +425,34 @@
|
||||
</linearGradient>
|
||||
<linearGradient
|
||||
id="linearGradient5116">
|
||||
<stop
|
||||
style="stop-color:#000000;stop-opacity:1"
|
||||
offset="0"
|
||||
id="stop5118" />
|
||||
<stop
|
||||
id="stop5124"
|
||||
offset="0.35911319"
|
||||
style="stop-color:#dcaf28;stop-opacity:1" />
|
||||
offset="0"
|
||||
style="stop-color:#ffc001;stop-opacity:1;" />
|
||||
<stop
|
||||
style="stop-color:#000000;stop-opacity:1"
|
||||
style="stop-color:#844700;stop-opacity:1;"
|
||||
offset="1"
|
||||
id="stop5120" />
|
||||
</linearGradient>
|
||||
<linearGradient
|
||||
id="linearGradient5106">
|
||||
<stop
|
||||
style="stop-color:#000000;stop-opacity:1"
|
||||
offset="0"
|
||||
id="stop5108" />
|
||||
<stop
|
||||
id="stop5114"
|
||||
offset="0.36023793"
|
||||
offset="0"
|
||||
style="stop-color:#00a000;stop-opacity:1" />
|
||||
<stop
|
||||
style="stop-color:#000000;stop-opacity:1"
|
||||
style="stop-color:#003d00;stop-opacity:1;"
|
||||
offset="1"
|
||||
id="stop5110" />
|
||||
</linearGradient>
|
||||
<linearGradient
|
||||
id="linearGradient5096">
|
||||
<stop
|
||||
style="stop-color:#100000;stop-opacity:1"
|
||||
offset="0"
|
||||
id="stop5098" />
|
||||
<stop
|
||||
id="stop5104"
|
||||
offset="0.36453304"
|
||||
style="stop-color:#aa0000;stop-opacity:1" />
|
||||
offset="0"
|
||||
style="stop-color:#e60000;stop-opacity:1;" />
|
||||
<stop
|
||||
style="stop-color:#0c0000;stop-opacity:1"
|
||||
style="stop-color:#710000;stop-opacity:1;"
|
||||
offset="1"
|
||||
id="stop5100" />
|
||||
</linearGradient>
|
||||
@ -687,7 +675,7 @@
|
||||
x2="87.074203"
|
||||
y2="168.83261"
|
||||
gradientUnits="userSpaceOnUse"
|
||||
gradientTransform="matrix(0,0.99999995,-0.99999975,0,-11.23354,-270.8763)" />
|
||||
gradientTransform="matrix(0,1.0110991,-1.0062411,0,-10.360287,-272.19756)" />
|
||||
<linearGradient
|
||||
inkscape:collect="always"
|
||||
xlink:href="#linearGradient5106"
|
||||
@ -697,7 +685,7 @@
|
||||
x2="86.644958"
|
||||
y2="173.46591"
|
||||
gradientUnits="userSpaceOnUse"
|
||||
gradientTransform="matrix(0,0.99999997,-1,0,-11.23354,-270.8763)" />
|
||||
gradientTransform="matrix(0,1.0224134,-1.0048488,0,-10.554719,-273.54528)" />
|
||||
<linearGradient
|
||||
inkscape:collect="always"
|
||||
xlink:href="#linearGradient5116"
|
||||
@ -707,7 +695,7 @@
|
||||
x2="86.547356"
|
||||
y2="168.82289"
|
||||
gradientUnits="userSpaceOnUse"
|
||||
gradientTransform="matrix(0,1,-1,0,-11.23354,-270.8763)" />
|
||||
gradientTransform="matrix(0,1,-1.0055415,0,-10.459485,-270.8763)" />
|
||||
<linearGradient
|
||||
inkscape:collect="always"
|
||||
xlink:href="#linearGradient5129"
|
||||
@ -932,7 +920,7 @@
|
||||
xlink:href="#linearGradient3903"
|
||||
id="linearGradient3899"
|
||||
gradientUnits="userSpaceOnUse"
|
||||
gradientTransform="matrix(0,-0.99999988,1.7142859,0,35.373449,-317.43383)"
|
||||
gradientTransform="matrix(0,-0.99937716,1.7523173,0,32.05963,-317.33185)"
|
||||
x1="-150.75359"
|
||||
y1="68.860146"
|
||||
x2="-150.75359"
|
||||
@ -1120,16 +1108,16 @@
|
||||
borderopacity="1.0"
|
||||
inkscape:pageopacity="0.0"
|
||||
inkscape:pageshadow="2"
|
||||
inkscape:zoom="3.1841238"
|
||||
inkscape:cx="140.38399"
|
||||
inkscape:zoom="5.5410688"
|
||||
inkscape:cx="55.238424"
|
||||
inkscape:cy="35.455778"
|
||||
inkscape:document-units="px"
|
||||
inkscape:current-layer="layer5"
|
||||
inkscape:current-layer="background"
|
||||
showgrid="false"
|
||||
inkscape:window-width="1366"
|
||||
inkscape:window-height="706"
|
||||
inkscape:window-x="-8"
|
||||
inkscape:window-y="-8"
|
||||
inkscape:window-width="1680"
|
||||
inkscape:window-height="957"
|
||||
inkscape:window-x="-5"
|
||||
inkscape:window-y="2"
|
||||
inkscape:window-maximized="1"
|
||||
inkscape:object-paths="true"
|
||||
showguides="true"
|
||||
@ -1163,8 +1151,7 @@
|
||||
inkscape:label="Dark background"
|
||||
id="g2932"
|
||||
inkscape:groupmode="layer"
|
||||
transform="translate(-368.2988,-507.08981)"
|
||||
sodipodi:insensitive="true">
|
||||
transform="translate(-368.2988,-507.08981)">
|
||||
<g
|
||||
id="background"
|
||||
inkscape:label="#g4447">
|
||||
@ -1225,17 +1212,16 @@
|
||||
id="layer5"
|
||||
inkscape:label="Green Zone"
|
||||
style="display:inline"
|
||||
transform="translate(-140.85549,-141.35611)"
|
||||
sodipodi:insensitive="true">
|
||||
transform="translate(-140.85549,-141.35611)">
|
||||
<rect
|
||||
inkscape:label="#rect5741"
|
||||
style="fill:url(#linearGradient5112);fill-opacity:1;stroke:none;display:inline"
|
||||
id="green"
|
||||
width="260.53882"
|
||||
height="32.20755"
|
||||
x="-411.77084"
|
||||
y="-184.00433"
|
||||
ry="2.3767958"
|
||||
width="261.80212"
|
||||
height="32.929432"
|
||||
x="-413.03415"
|
||||
y="-184.72621"
|
||||
ry="2.430068"
|
||||
inkscape:export-filename="H:\Documents\Hobbies\W433\g9905.png"
|
||||
inkscape:export-xdpi="88.809998"
|
||||
inkscape:export-ydpi="88.809998"
|
||||
@ -1246,17 +1232,16 @@
|
||||
id="layer4"
|
||||
inkscape:label="Yellow Zone"
|
||||
style="display:none"
|
||||
transform="translate(-140.85549,-141.35611)"
|
||||
sodipodi:insensitive="true">
|
||||
transform="translate(-140.85549,-141.35611)">
|
||||
<rect
|
||||
inkscape:export-ydpi="88.809998"
|
||||
inkscape:export-xdpi="88.809998"
|
||||
inkscape:export-filename="H:\Documents\Hobbies\W433\g9905.png"
|
||||
ry="2.4231479"
|
||||
y="-184.63248"
|
||||
x="-411.45679"
|
||||
x="-412.90054"
|
||||
height="32.835663"
|
||||
width="260.53882"
|
||||
width="261.98257"
|
||||
id="yellow"
|
||||
style="fill:url(#linearGradient5122);fill-opacity:1;stroke:none;display:inline"
|
||||
inkscape:label="#rect5741"
|
||||
@ -1267,17 +1252,16 @@
|
||||
id="layer3"
|
||||
inkscape:label="Red zone"
|
||||
style="display:none"
|
||||
transform="translate(-140.85549,-141.35611)"
|
||||
sodipodi:insensitive="true">
|
||||
transform="translate(-140.85549,-141.35611)">
|
||||
<rect
|
||||
inkscape:label="#rect5741"
|
||||
style="fill:url(#linearGradient5102);fill-opacity:1;stroke:none;display:inline"
|
||||
id="red"
|
||||
width="260.23901"
|
||||
height="32.519711"
|
||||
x="-411.38739"
|
||||
y="-184.35484"
|
||||
ry="2.399832"
|
||||
width="261.86325"
|
||||
height="32.880653"
|
||||
x="-413.01163"
|
||||
y="-184.71579"
|
||||
ry="2.4264681"
|
||||
inkscape:export-filename="H:\Documents\Hobbies\W433\g9905.png"
|
||||
inkscape:export-xdpi="88.809998"
|
||||
inkscape:export-ydpi="88.809998"
|
||||
@ -1288,17 +1272,18 @@
|
||||
id="layer6"
|
||||
inkscape:label="Indicator"
|
||||
style="display:inline"
|
||||
transform="translate(-140.85549,-141.35611)"
|
||||
sodipodi:insensitive="true">
|
||||
transform="translate(-140.85549,-141.35611)">
|
||||
<rect
|
||||
style="fill:url(#linearGradient3899);fill-opacity:1;stroke:#000000;stroke-width:0.2964696;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
style="fill:url(#linearGradient3899);fill-opacity:1;stroke:#000000;stroke-width:0.4;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="needle"
|
||||
width="32.035065"
|
||||
height="6.0045304"
|
||||
x="152.63882"
|
||||
y="-157.12926"
|
||||
width="33.114704"
|
||||
height="5.0989962"
|
||||
x="151.5576"
|
||||
y="-156.22531"
|
||||
inkscape:label="#rect5246"
|
||||
transform="matrix(0,1,-1,0,0,0)" />
|
||||
transform="matrix(0,1,-1,0,0,0)"
|
||||
ry="2.5494981"
|
||||
rx="1.9392394" />
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
|
Before Width: | Height: | Size: 39 KiB After Width: | Height: | Size: 39 KiB |
219
artwork/Dials/deluxe/lineardial-vertical.svg
Normal file → Executable file
219
artwork/Dials/deluxe/lineardial-vertical.svg
Normal file → Executable file
@ -14,20 +14,31 @@
|
||||
height="322.58304"
|
||||
id="svg10068"
|
||||
version="1.1"
|
||||
inkscape:version="0.48.1 "
|
||||
sodipodi:docname="lineardial-vertical.svg"
|
||||
inkscape:version="0.48.2 r9819"
|
||||
sodipodi:docname="lineardial-vertical-old2.svg"
|
||||
inkscape:export-filename="H:\Documents\Hobbies\W433\My Gauges\vbat-001.png"
|
||||
inkscape:export-xdpi="103.61"
|
||||
inkscape:export-ydpi="103.61"
|
||||
style="display:inline">
|
||||
<defs
|
||||
id="defs10070">
|
||||
<linearGradient
|
||||
id="linearGradient3894">
|
||||
<stop
|
||||
style="stop-color:#171717;stop-opacity:1;"
|
||||
offset="0"
|
||||
id="stop3896" />
|
||||
<stop
|
||||
style="stop-color:#b0b0b0;stop-opacity:1;"
|
||||
offset="1"
|
||||
id="stop3898" />
|
||||
</linearGradient>
|
||||
<linearGradient
|
||||
id="linearGradient3903">
|
||||
<stop
|
||||
id="stop3905"
|
||||
offset="0"
|
||||
style="stop-color:#000000;stop-opacity:1" />
|
||||
style="stop-color:#656565;stop-opacity:1;" />
|
||||
<stop
|
||||
style="stop-color:#ffffff;stop-opacity:1"
|
||||
offset="0.39386007"
|
||||
@ -35,7 +46,7 @@
|
||||
<stop
|
||||
id="stop3909"
|
||||
offset="1"
|
||||
style="stop-color:#000000;stop-opacity:1" />
|
||||
style="stop-color:#757575;stop-opacity:1;" />
|
||||
</linearGradient>
|
||||
<linearGradient
|
||||
id="linearGradient5375">
|
||||
@ -83,15 +94,19 @@
|
||||
<stop
|
||||
id="stop5348"
|
||||
offset="0"
|
||||
style="stop-color:#1a1a1a;stop-opacity:1" />
|
||||
style="stop-color:#9c9c9c;stop-opacity:0;" />
|
||||
<stop
|
||||
style="stop-color:#666666;stop-opacity:1"
|
||||
offset="0.35277387"
|
||||
id="stop5350" />
|
||||
id="stop3921"
|
||||
offset="0.359375"
|
||||
style="stop-color:#6c6c6c;stop-opacity:0.88793105;" />
|
||||
<stop
|
||||
style="stop-color:#5f5f5f;stop-opacity:0.62931037;"
|
||||
offset="0.62630206"
|
||||
id="stop3923" />
|
||||
<stop
|
||||
id="stop5352"
|
||||
offset="1"
|
||||
style="stop-color:#1a1a1a;stop-opacity:1" />
|
||||
style="stop-color:#9c9c9c;stop-opacity:0;" />
|
||||
</linearGradient>
|
||||
<linearGradient
|
||||
id="linearGradient5326">
|
||||
@ -215,46 +230,34 @@
|
||||
</linearGradient>
|
||||
<linearGradient
|
||||
id="linearGradient5116">
|
||||
<stop
|
||||
style="stop-color:#000000;stop-opacity:1"
|
||||
offset="0"
|
||||
id="stop5118" />
|
||||
<stop
|
||||
id="stop5124"
|
||||
offset="0.37640449"
|
||||
style="stop-color:#dcaf28;stop-opacity:1" />
|
||||
offset="0"
|
||||
style="stop-color:#ffc001;stop-opacity:1;" />
|
||||
<stop
|
||||
style="stop-color:#000000;stop-opacity:1"
|
||||
style="stop-color:#844700;stop-opacity:1;"
|
||||
offset="1"
|
||||
id="stop5120" />
|
||||
</linearGradient>
|
||||
<linearGradient
|
||||
id="linearGradient5106">
|
||||
<stop
|
||||
style="stop-color:#000000;stop-opacity:1"
|
||||
offset="0"
|
||||
id="stop5108" />
|
||||
<stop
|
||||
id="stop5114"
|
||||
offset="0.38184431"
|
||||
offset="0"
|
||||
style="stop-color:#00a000;stop-opacity:1" />
|
||||
<stop
|
||||
style="stop-color:#000000;stop-opacity:1"
|
||||
style="stop-color:#003d00;stop-opacity:1;"
|
||||
offset="1"
|
||||
id="stop5110" />
|
||||
</linearGradient>
|
||||
<linearGradient
|
||||
id="linearGradient5096">
|
||||
<stop
|
||||
style="stop-color:#100000;stop-opacity:1"
|
||||
offset="0"
|
||||
id="stop5098" />
|
||||
<stop
|
||||
id="stop5104"
|
||||
offset="0.39717463"
|
||||
style="stop-color:#aa0000;stop-opacity:1" />
|
||||
offset="0"
|
||||
style="stop-color:#e60000;stop-opacity:1;" />
|
||||
<stop
|
||||
style="stop-color:#0c0000;stop-opacity:1"
|
||||
style="stop-color:#710000;stop-opacity:1;"
|
||||
offset="1"
|
||||
id="stop5100" />
|
||||
</linearGradient>
|
||||
@ -475,7 +478,8 @@
|
||||
y1="132.84332"
|
||||
x2="-58.661255"
|
||||
y2="169.46072"
|
||||
gradientUnits="userSpaceOnUse" />
|
||||
gradientUnits="userSpaceOnUse"
|
||||
gradientTransform="matrix(1.0045664,0,0,0.98072534,3.8285685,3.8328979)" />
|
||||
<linearGradient
|
||||
inkscape:collect="always"
|
||||
xlink:href="#linearGradient5106"
|
||||
@ -484,7 +488,8 @@
|
||||
y1="133.15433"
|
||||
x2="-38.946774"
|
||||
y2="168.58655"
|
||||
gradientUnits="userSpaceOnUse" />
|
||||
gradientUnits="userSpaceOnUse"
|
||||
gradientTransform="matrix(1.0048708,0,0,1.0000284,3.816285,2.2385824)" />
|
||||
<linearGradient
|
||||
inkscape:collect="always"
|
||||
xlink:href="#linearGradient5116"
|
||||
@ -493,7 +498,8 @@
|
||||
y1="133.16322"
|
||||
x2="-17.108463"
|
||||
y2="168.82289"
|
||||
gradientUnits="userSpaceOnUse" />
|
||||
gradientUnits="userSpaceOnUse"
|
||||
gradientTransform="matrix(1.0057658,0,0,0.99502095,3.8176724,2.8357789)" />
|
||||
<linearGradient
|
||||
inkscape:collect="always"
|
||||
xlink:href="#linearGradient5129"
|
||||
@ -711,7 +717,8 @@
|
||||
x1="-246.82069"
|
||||
y1="353.9455"
|
||||
x2="-247.44464"
|
||||
y2="412.00528" />
|
||||
y2="412.00528"
|
||||
gradientTransform="matrix(1,0,0,0.98663274,0,3.8538758)" />
|
||||
<linearGradient
|
||||
inkscape:collect="always"
|
||||
xlink:href="#linearGradient5375"
|
||||
@ -727,11 +734,21 @@
|
||||
xlink:href="#linearGradient3903"
|
||||
id="linearGradient3899"
|
||||
gradientUnits="userSpaceOnUse"
|
||||
gradientTransform="matrix(0.99999998,0,0,1.7142857,306.20028,-235.50286)"
|
||||
gradientTransform="matrix(1.0304804,0,0,1.7130087,311.94981,-242.17845)"
|
||||
x1="-172.33069"
|
||||
y1="74.562233"
|
||||
x2="-135.50557"
|
||||
y2="74.562233" />
|
||||
x2="-136.75557"
|
||||
y2="74.015358" />
|
||||
<linearGradient
|
||||
inkscape:collect="always"
|
||||
xlink:href="#linearGradient3894"
|
||||
id="linearGradient3900"
|
||||
x1="-353.51318"
|
||||
y1="324.74451"
|
||||
x2="-355.30441"
|
||||
y2="355.70587"
|
||||
gradientUnits="userSpaceOnUse"
|
||||
gradientTransform="matrix(1.0187536,0,0,1.2873355,10.177224,-58.104213)" />
|
||||
</defs>
|
||||
<sodipodi:namedview
|
||||
id="base"
|
||||
@ -740,16 +757,16 @@
|
||||
borderopacity="1.0"
|
||||
inkscape:pageopacity="0.0"
|
||||
inkscape:pageshadow="2"
|
||||
inkscape:zoom="1.9843492"
|
||||
inkscape:cx="13.888309"
|
||||
inkscape:cy="302.67927"
|
||||
inkscape:zoom="7.87"
|
||||
inkscape:cx="0.68217946"
|
||||
inkscape:cy="151.28502"
|
||||
inkscape:document-units="px"
|
||||
inkscape:current-layer="layer6"
|
||||
inkscape:current-layer="layer4"
|
||||
showgrid="false"
|
||||
inkscape:window-width="1366"
|
||||
inkscape:window-height="706"
|
||||
inkscape:window-x="-8"
|
||||
inkscape:window-y="-8"
|
||||
inkscape:window-width="1680"
|
||||
inkscape:window-height="957"
|
||||
inkscape:window-x="0"
|
||||
inkscape:window-y="0"
|
||||
inkscape:window-maximized="1"
|
||||
inkscape:object-paths="true"
|
||||
showguides="true"
|
||||
@ -765,7 +782,7 @@
|
||||
<dc:format>image/svg+xml</dc:format>
|
||||
<dc:type
|
||||
rdf:resource="http://purl.org/dc/dcmitype/StillImage" />
|
||||
<dc:title />
|
||||
<dc:title></dc:title>
|
||||
<dc:creator>
|
||||
<cc:Agent>
|
||||
<dc:title>Edouard Lafargue</dc:title>
|
||||
@ -779,8 +796,7 @@
|
||||
inkscape:label="Dark background"
|
||||
id="g2932"
|
||||
inkscape:groupmode="layer"
|
||||
transform="translate(-357.06525,-236.21351)"
|
||||
sodipodi:insensitive="true">
|
||||
transform="translate(-357.06525,-236.21351)">
|
||||
<g
|
||||
id="background"
|
||||
inkscape:label="#g5354">
|
||||
@ -789,39 +805,39 @@
|
||||
style="fill:url(#linearGradient5344);fill-opacity:1;stroke:none"
|
||||
id="rect2936"
|
||||
width="318.58304"
|
||||
height="46.756046"
|
||||
height="46.131046"
|
||||
x="-556.79657"
|
||||
y="358.44128"
|
||||
ry="3.4504199"
|
||||
y="357.50378"
|
||||
ry="3.4042974"
|
||||
inkscape:export-filename="H:\Documents\Hobbies\W433\g9905.png"
|
||||
inkscape:export-xdpi="88.809998"
|
||||
inkscape:export-ydpi="88.809998" />
|
||||
<rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
style="fill:#332d2d;fill-opacity:1;stroke:none"
|
||||
id="bargraph"
|
||||
width="260.53882"
|
||||
height="34.835861"
|
||||
x="-519.56018"
|
||||
y="362.7359"
|
||||
ry="2.5707548"
|
||||
inkscape:export-filename="H:\Documents\Hobbies\W433\g9905.png"
|
||||
inkscape:export-xdpi="88.809998"
|
||||
inkscape:export-ydpi="88.809998"
|
||||
inkscape:label="#rect4388" />
|
||||
<rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
inkscape:label="#rect4388"
|
||||
inkscape:export-ydpi="88.809998"
|
||||
inkscape:export-xdpi="88.809998"
|
||||
inkscape:export-filename="H:\Documents\Hobbies\W433\g9905.png"
|
||||
ry="2.2944832"
|
||||
y="365.23175"
|
||||
x="-519.56018"
|
||||
height="31.09215"
|
||||
width="260.53882"
|
||||
ry="2.9537699"
|
||||
y="360.57819"
|
||||
x="-519.12665"
|
||||
height="40.026031"
|
||||
width="265.4249"
|
||||
id="bargraph-outer"
|
||||
style="fill:#332d2d;fill-opacity:1;stroke:none" />
|
||||
style="fill:url(#linearGradient3900);fill-opacity:1;stroke:none" />
|
||||
<rect
|
||||
transform="matrix(0,-1,1,0,0,0)"
|
||||
style="fill:#332d2d;fill-opacity:1;stroke:none"
|
||||
id="bargraph"
|
||||
width="262.19809"
|
||||
height="33.195633"
|
||||
x="-516.71185"
|
||||
y="363.7984"
|
||||
ry="16.597816"
|
||||
inkscape:export-filename="H:\Documents\Hobbies\W433\g9905.png"
|
||||
inkscape:export-xdpi="88.809998"
|
||||
inkscape:export-ydpi="88.809998"
|
||||
inkscape:label="#rect4388" />
|
||||
</g>
|
||||
</g>
|
||||
<g
|
||||
@ -829,17 +845,16 @@
|
||||
id="layer5"
|
||||
inkscape:label="Green Zone"
|
||||
style="display:inline"
|
||||
transform="translate(-129.62194,129.52019)"
|
||||
sodipodi:insensitive="true">
|
||||
transform="translate(-129.62194,129.52019)">
|
||||
<rect
|
||||
inkscape:label="#rect5741"
|
||||
style="fill:url(#linearGradient5112);fill-opacity:1;stroke:none;display:inline"
|
||||
id="green"
|
||||
width="260.53882"
|
||||
height="34.0919"
|
||||
x="-153.97397"
|
||||
y="134.02345"
|
||||
ry="2.5158536"
|
||||
width="261.80789"
|
||||
height="34.092869"
|
||||
x="-150.90765"
|
||||
y="136.26584"
|
||||
ry="2.5159254"
|
||||
inkscape:export-filename="H:\Documents\Hobbies\W433\g9905.png"
|
||||
inkscape:export-xdpi="88.809998"
|
||||
inkscape:export-ydpi="88.809998"
|
||||
@ -849,18 +864,17 @@
|
||||
inkscape:groupmode="layer"
|
||||
id="layer4"
|
||||
inkscape:label="Yellow Zone"
|
||||
style="display:none"
|
||||
transform="translate(-129.62194,129.52019)"
|
||||
sodipodi:insensitive="true">
|
||||
style="display:inline"
|
||||
transform="translate(-129.62194,129.52019)">
|
||||
<rect
|
||||
inkscape:export-ydpi="88.809998"
|
||||
inkscape:export-xdpi="88.809998"
|
||||
inkscape:export-filename="H:\Documents\Hobbies\W433\g9905.png"
|
||||
ry="2.5158532"
|
||||
y="134.02345"
|
||||
x="-153.97397"
|
||||
height="34.091896"
|
||||
width="260.53882"
|
||||
ry="2.5033269"
|
||||
y="136.19191"
|
||||
x="-151.04408"
|
||||
height="33.92215"
|
||||
width="262.04108"
|
||||
id="yellow"
|
||||
style="fill:url(#linearGradient5122);fill-opacity:1;stroke:none;display:inline"
|
||||
inkscape:label="#rect5741"
|
||||
@ -871,17 +885,16 @@
|
||||
id="layer3"
|
||||
inkscape:label="Red zone"
|
||||
style="display:none"
|
||||
transform="translate(-129.62194,129.52019)"
|
||||
sodipodi:insensitive="true">
|
||||
transform="translate(-129.62194,129.52019)">
|
||||
<rect
|
||||
inkscape:label="#rect5741"
|
||||
style="fill:url(#linearGradient5102);fill-opacity:1;stroke:none;display:inline"
|
||||
id="red"
|
||||
width="260.53882"
|
||||
height="34.589863"
|
||||
x="-154.0755"
|
||||
y="134.00487"
|
||||
ry="2.5526016"
|
||||
width="261.72849"
|
||||
height="33.923153"
|
||||
x="-150.95049"
|
||||
y="135.25487"
|
||||
ry="2.503401"
|
||||
inkscape:export-filename="H:\Documents\Hobbies\W433\g9905.png"
|
||||
inkscape:export-xdpi="88.809998"
|
||||
inkscape:export-ydpi="88.809998"
|
||||
@ -894,35 +907,35 @@
|
||||
style="display:inline"
|
||||
transform="translate(-129.62194,129.52019)">
|
||||
<rect
|
||||
style="fill:url(#linearGradient3899);fill-opacity:1;stroke:#000000;stroke-width:0.30000000999999998;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
style="fill:url(#linearGradient3899);fill-opacity:1;stroke:#000000;stroke-width:0.30442432;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="needle"
|
||||
width="33.162418"
|
||||
height="5.9393759"
|
||||
x="135.64999"
|
||||
y="-107.91632"
|
||||
inkscape:label="#rect5246" />
|
||||
width="34.173222"
|
||||
height="5.9349518"
|
||||
x="136.20108"
|
||||
y="-114.68695"
|
||||
inkscape:label="#rect5246"
|
||||
ry="2.4981377" />
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="layer1"
|
||||
inkscape:label="Text"
|
||||
style="display:inline"
|
||||
transform="translate(-129.62194,129.52019)"
|
||||
sodipodi:insensitive="true">
|
||||
transform="translate(-129.62194,129.52019)">
|
||||
<rect
|
||||
style="fill:#ffffff;fill-opacity:1;stroke:none"
|
||||
id="field"
|
||||
width="33.853165"
|
||||
width="46.305515"
|
||||
height="12.626906"
|
||||
x="128.30692"
|
||||
x="129.09726"
|
||||
y="157.31393"
|
||||
inkscape:label="#rect2878" />
|
||||
<rect
|
||||
inkscape:label="#rect2878"
|
||||
y="170.91206"
|
||||
x="128.88902"
|
||||
x="129.9335"
|
||||
height="12.626906"
|
||||
width="32.851257"
|
||||
width="45.176544"
|
||||
id="value"
|
||||
style="fill:#ffffff;fill-opacity:1;stroke:none" />
|
||||
</g>
|
||||
|
Before Width: | Height: | Size: 28 KiB After Width: | Height: | Size: 28 KiB |
@ -71,6 +71,7 @@ OPUAVOBJINC = $(OPUAVOBJ)/inc
|
||||
OPSYSINC = $(OPDIR)/System/inc
|
||||
BOOT = ../Bootloaders/AHRS
|
||||
BOOTINC = $(BOOT)/inc
|
||||
HWDEFSINC = ../board_hw_defs/$(BOARD_NAME)
|
||||
|
||||
OPUAVSYNTHDIR = $(OUTDIR)/../uavobject-synthetics/flight
|
||||
|
||||
@ -170,6 +171,7 @@ EXTRAINCDIRS += $(CMSISDIR)
|
||||
EXTRAINCDIRS += $(AHRSINC)
|
||||
EXTRAINCDIRS += $(OPUAVSYNTHDIR)
|
||||
EXTRAINCDIRS += $(BOOTINC)
|
||||
EXTRAINCDIRS += $(HWDEFSINC)
|
||||
|
||||
# List any extra directories to look for library files here.
|
||||
# Also add directories where the linker should search for
|
||||
|
@ -447,9 +447,9 @@ void print_ahrs_raw()
|
||||
valid_data_buffer = PIOS_ADC_GetRawBuffer();
|
||||
|
||||
if (total_conversion_blocks != previous_conversion + 1)
|
||||
PIOS_LED_On(LED1); // not keeping up
|
||||
PIOS_LED_On(PIOS_LED_HEARTBEAT); // not keeping up
|
||||
else
|
||||
PIOS_LED_Off(LED1);
|
||||
PIOS_LED_Off(PIOS_LED_HEARTBEAT);
|
||||
previous_conversion = total_conversion_blocks;
|
||||
|
||||
|
||||
@ -463,9 +463,9 @@ void print_ahrs_raw()
|
||||
PIOS_ADC_NUM_PINS *
|
||||
sizeof(valid_data_buffer[0]));
|
||||
if (result == 0)
|
||||
PIOS_LED_Off(LED1);
|
||||
PIOS_LED_Off(PIOS_LED_HEARTBEAT);
|
||||
else {
|
||||
PIOS_LED_On(LED1);
|
||||
PIOS_LED_On(PIOS_LED_HEARTBEAT);
|
||||
}
|
||||
}
|
||||
#endif
|
||||
@ -490,7 +490,7 @@ void print_ahrs_raw()
|
||||
// wait for new raw samples
|
||||
while (previous_conversion == total_conversion_blocks);
|
||||
if ((previous_conversion + 1) != total_conversion_blocks)
|
||||
PIOS_LED_On(LED1); // we are not keeping up
|
||||
PIOS_LED_On(PIOS_LED_HEARTBEAT); // we are not keeping up
|
||||
previous_conversion = total_conversion_blocks;
|
||||
|
||||
// fetch the buffer address for the new samples
|
||||
@ -534,9 +534,9 @@ void print_ahrs_raw()
|
||||
result += PIOS_COM_SendBufferNonBlocking(PIOS_COM_AUX, (uint8_t *)gyro_z, over_sampling * sizeof(gyro_z[0]));
|
||||
|
||||
if (result != 0)
|
||||
PIOS_LED_On(LED1); // all data not sent
|
||||
PIOS_LED_On(PIOS_LED_HEARTBEAT); // all data not sent
|
||||
else
|
||||
PIOS_LED_Off(LED1);
|
||||
PIOS_LED_Off(PIOS_LED_HEARTBEAT);
|
||||
}
|
||||
#endif
|
||||
|
||||
@ -616,7 +616,7 @@ for all data to be up to date before doing anything*/
|
||||
|
||||
// Alive signal
|
||||
if (((total_conversion_blocks % 100) & 0xFFFE) == 0)
|
||||
PIOS_LED_Toggle(LED1);
|
||||
PIOS_LED_Toggle(PIOS_LED_HEARTBEAT);
|
||||
|
||||
// Delay for valid data
|
||||
|
||||
|
@ -41,5 +41,6 @@
|
||||
#define PIOS_INCLUDE_GPIO
|
||||
#define PIOS_INCLUDE_EXTI
|
||||
#define PIOS_INCLUDE_BL_HELPER
|
||||
#define PIOS_INCLUDE_IAP
|
||||
|
||||
#endif /* PIOS_CONFIG_H */
|
||||
|
@ -23,336 +23,20 @@
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
|
||||
/* Pull in the board-specific static HW definitions.
|
||||
* Including .c files is a bit ugly but this allows all of
|
||||
* the HW definitions to be const and static to limit their
|
||||
* scope.
|
||||
*
|
||||
* NOTE: THIS IS THE ONLY PLACE THAT SHOULD EVER INCLUDE THIS FILE
|
||||
*/
|
||||
#include "board_hw_defs.c"
|
||||
|
||||
#include <pios.h>
|
||||
|
||||
#if defined(PIOS_INCLUDE_SPI)
|
||||
|
||||
#include <pios_spi_priv.h>
|
||||
|
||||
/* OP Interface
|
||||
*
|
||||
* NOTE: Leave this declared as const data so that it ends up in the
|
||||
* .rodata section (ie. Flash) rather than in the .bss section (RAM).
|
||||
*/
|
||||
void PIOS_SPI_op_irq_handler(void);
|
||||
void DMA1_Channel5_IRQHandler() __attribute__ ((alias("PIOS_SPI_op_irq_handler")));
|
||||
void DMA1_Channel4_IRQHandler() __attribute__ ((alias("PIOS_SPI_op_irq_handler")));
|
||||
static const struct pios_spi_cfg pios_spi_op_cfg = {
|
||||
.regs = SPI2,
|
||||
.init = {
|
||||
.SPI_Mode = SPI_Mode_Slave,
|
||||
.SPI_Direction = SPI_Direction_2Lines_FullDuplex,
|
||||
.SPI_DataSize = SPI_DataSize_8b,
|
||||
.SPI_NSS = SPI_NSS_Hard,
|
||||
.SPI_FirstBit = SPI_FirstBit_MSB,
|
||||
.SPI_CRCPolynomial = 7,
|
||||
.SPI_CPOL = SPI_CPOL_High,
|
||||
.SPI_CPHA = SPI_CPHA_2Edge,
|
||||
},
|
||||
.use_crc = TRUE,
|
||||
.dma = {
|
||||
.ahb_clk = RCC_AHBPeriph_DMA1,
|
||||
|
||||
.irq = {
|
||||
.flags =
|
||||
(DMA1_FLAG_TC4 | DMA1_FLAG_TE4 | DMA1_FLAG_HT4 |
|
||||
DMA1_FLAG_GL4),
|
||||
.init = {
|
||||
.NVIC_IRQChannel = DMA1_Channel4_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
|
||||
.rx = {
|
||||
.channel = DMA1_Channel4,
|
||||
.init = {
|
||||
.DMA_PeripheralBaseAddr =
|
||||
(uint32_t) & (SPI2->DR),
|
||||
.DMA_DIR = DMA_DIR_PeripheralSRC,
|
||||
.DMA_PeripheralInc =
|
||||
DMA_PeripheralInc_Disable,
|
||||
.DMA_MemoryInc = DMA_MemoryInc_Enable,
|
||||
.DMA_PeripheralDataSize =
|
||||
DMA_PeripheralDataSize_Byte,
|
||||
.DMA_MemoryDataSize =
|
||||
DMA_MemoryDataSize_Byte,
|
||||
.DMA_Mode = DMA_Mode_Normal,
|
||||
.DMA_Priority = DMA_Priority_Medium,
|
||||
.DMA_M2M = DMA_M2M_Disable,
|
||||
},
|
||||
},
|
||||
.tx = {
|
||||
.channel = DMA1_Channel5,
|
||||
.init = {
|
||||
.DMA_PeripheralBaseAddr =
|
||||
(uint32_t) & (SPI2->DR),
|
||||
.DMA_DIR = DMA_DIR_PeripheralDST,
|
||||
.DMA_PeripheralInc =
|
||||
DMA_PeripheralInc_Disable,
|
||||
.DMA_MemoryInc = DMA_MemoryInc_Enable,
|
||||
.DMA_PeripheralDataSize =
|
||||
DMA_PeripheralDataSize_Byte,
|
||||
.DMA_MemoryDataSize =
|
||||
DMA_MemoryDataSize_Byte,
|
||||
.DMA_Mode = DMA_Mode_Normal,
|
||||
.DMA_Priority = DMA_Priority_Medium,
|
||||
.DMA_M2M = DMA_M2M_Disable,
|
||||
},
|
||||
},
|
||||
},
|
||||
.ssel = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_12,
|
||||
.GPIO_Speed = GPIO_Speed_10MHz,
|
||||
.GPIO_Mode = GPIO_Mode_IN_FLOATING,
|
||||
},
|
||||
},
|
||||
.sclk = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_13,
|
||||
.GPIO_Speed = GPIO_Speed_10MHz,
|
||||
.GPIO_Mode = GPIO_Mode_IN_FLOATING,
|
||||
},
|
||||
},
|
||||
.miso = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_14,
|
||||
.GPIO_Speed = GPIO_Speed_10MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF_PP,
|
||||
},
|
||||
},
|
||||
.mosi = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_15,
|
||||
.GPIO_Speed = GPIO_Speed_10MHz,
|
||||
.GPIO_Mode = GPIO_Mode_IN_FLOATING,
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
uint32_t pios_spi_op_id;
|
||||
void PIOS_SPI_op_irq_handler(void)
|
||||
{
|
||||
/* Call into the generic code to handle the IRQ for this specific device */
|
||||
PIOS_SPI_IRQ_Handler(pios_spi_op_id);
|
||||
}
|
||||
|
||||
#endif /* PIOS_INCLUDE_SPI */
|
||||
|
||||
/*
|
||||
* ADC system
|
||||
*/
|
||||
#include "pios_adc_priv.h"
|
||||
extern void PIOS_ADC_handler(void);
|
||||
void DMA1_Channel1_IRQHandler() __attribute__ ((alias("PIOS_ADC_handler")));
|
||||
// Remap the ADC DMA handler to this one
|
||||
static const struct pios_adc_cfg pios_adc_cfg = {
|
||||
.dma = {
|
||||
.ahb_clk = RCC_AHBPeriph_DMA1,
|
||||
.irq = {
|
||||
.flags = (DMA1_FLAG_TC1 | DMA1_FLAG_TE1 | DMA1_FLAG_HT1 | DMA1_FLAG_GL1),
|
||||
.init = {
|
||||
.NVIC_IRQChannel = DMA1_Channel1_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
.rx = {
|
||||
.channel = DMA1_Channel1,
|
||||
.init = {
|
||||
.DMA_PeripheralBaseAddr = (uint32_t) & ADC1->DR,
|
||||
.DMA_DIR = DMA_DIR_PeripheralSRC,
|
||||
.DMA_PeripheralInc = DMA_PeripheralInc_Disable,
|
||||
.DMA_MemoryInc = DMA_MemoryInc_Enable,
|
||||
.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Word,
|
||||
.DMA_MemoryDataSize = DMA_MemoryDataSize_Word,
|
||||
.DMA_Mode = DMA_Mode_Circular,
|
||||
.DMA_Priority = DMA_Priority_High,
|
||||
.DMA_M2M = DMA_M2M_Disable,
|
||||
},
|
||||
}
|
||||
},
|
||||
.half_flag = DMA1_IT_HT1,
|
||||
.full_flag = DMA1_IT_TC1,
|
||||
};
|
||||
|
||||
struct pios_adc_dev pios_adc_devs[] = {
|
||||
{
|
||||
.cfg = &pios_adc_cfg,
|
||||
.callback_function = NULL,
|
||||
},
|
||||
};
|
||||
|
||||
uint8_t pios_adc_num_devices = NELEMENTS(pios_adc_devs);
|
||||
|
||||
void PIOS_ADC_handler() {
|
||||
PIOS_ADC_DMA_Handler();
|
||||
}
|
||||
|
||||
|
||||
#if defined(PIOS_INCLUDE_USART)
|
||||
#include <pios_usart_priv.h>
|
||||
|
||||
/*
|
||||
* AUX USART
|
||||
*/
|
||||
static const struct pios_usart_cfg pios_usart_aux_cfg = {
|
||||
.regs = USART3,
|
||||
.init = {
|
||||
.USART_BaudRate = 230400,
|
||||
.USART_WordLength = USART_WordLength_8b,
|
||||
.USART_Parity = USART_Parity_No,
|
||||
.USART_StopBits = USART_StopBits_1,
|
||||
.USART_HardwareFlowControl =
|
||||
USART_HardwareFlowControl_None,
|
||||
.USART_Mode = USART_Mode_Rx | USART_Mode_Tx,
|
||||
},
|
||||
.irq = {
|
||||
.init = {
|
||||
.NVIC_IRQChannel = USART3_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
.rx = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_11,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_IPU,
|
||||
},
|
||||
},
|
||||
.tx = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_10,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF_PP,
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
#endif /* PIOS_INCLUDE_USART */
|
||||
|
||||
#if defined(PIOS_INCLUDE_COM)
|
||||
|
||||
#include <pios_com_priv.h>
|
||||
|
||||
#define PIOS_COM_AUX_TX_BUF_LEN 192
|
||||
static uint8_t pios_com_aux_tx_buffer[PIOS_COM_AUX_TX_BUF_LEN];
|
||||
|
||||
#endif /* PIOS_INCLUDE_COM */
|
||||
|
||||
#if defined(PIOS_INCLUDE_I2C)
|
||||
|
||||
#include <pios_i2c_priv.h>
|
||||
|
||||
/*
|
||||
* I2C Adapters
|
||||
*/
|
||||
|
||||
void PIOS_I2C_main_adapter_ev_irq_handler(void);
|
||||
void PIOS_I2C_main_adapter_er_irq_handler(void);
|
||||
void I2C1_EV_IRQHandler()
|
||||
__attribute__ ((alias("PIOS_I2C_main_adapter_ev_irq_handler")));
|
||||
void I2C1_ER_IRQHandler()
|
||||
__attribute__ ((alias("PIOS_I2C_main_adapter_er_irq_handler")));
|
||||
|
||||
static const struct pios_i2c_adapter_cfg pios_i2c_main_adapter_cfg = {
|
||||
.regs = I2C1,
|
||||
.init = {
|
||||
.I2C_Mode = I2C_Mode_I2C,
|
||||
.I2C_OwnAddress1 = 0,
|
||||
.I2C_Ack = I2C_Ack_Enable,
|
||||
.I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit,
|
||||
.I2C_DutyCycle = I2C_DutyCycle_2,
|
||||
.I2C_ClockSpeed = 200000, /* bits/s */
|
||||
},
|
||||
.transfer_timeout_ms = 50,
|
||||
.scl = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_6,
|
||||
.GPIO_Speed = GPIO_Speed_10MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF_OD,
|
||||
},
|
||||
},
|
||||
.sda = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_7,
|
||||
.GPIO_Speed = GPIO_Speed_10MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF_OD,
|
||||
},
|
||||
},
|
||||
.event = {
|
||||
.flags = 0, /* FIXME: check this */
|
||||
.init = {
|
||||
.NVIC_IRQChannel = I2C1_EV_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGHEST,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
.error = {
|
||||
.flags = 0, /* FIXME: check this */
|
||||
.init = {
|
||||
.NVIC_IRQChannel = I2C1_ER_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGHEST,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
uint32_t pios_i2c_main_adapter_id;
|
||||
void PIOS_I2C_main_adapter_ev_irq_handler(void)
|
||||
{
|
||||
/* Call into the generic code to handle the IRQ for this specific device */
|
||||
PIOS_I2C_EV_IRQ_Handler(pios_i2c_main_adapter_id);
|
||||
}
|
||||
|
||||
void PIOS_I2C_main_adapter_er_irq_handler(void)
|
||||
{
|
||||
/* Call into the generic code to handle the IRQ for this specific device */
|
||||
PIOS_I2C_ER_IRQ_Handler(pios_i2c_main_adapter_id);
|
||||
}
|
||||
|
||||
#endif /* PIOS_INCLUDE_I2C */
|
||||
|
||||
#if defined(PIOS_ENABLE_DEBUG_PINS)
|
||||
|
||||
static const struct stm32_gpio pios_debug_pins[] = {
|
||||
{
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_11,
|
||||
.GPIO_Speed = GPIO_Speed_50MHz,
|
||||
.GPIO_Mode = GPIO_Mode_IN_FLOATING,
|
||||
},
|
||||
},
|
||||
{
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_10,
|
||||
.GPIO_Speed = GPIO_Speed_50MHz,
|
||||
.GPIO_Mode = GPIO_Mode_Out_PP,
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
#endif /* PIOS_ENABLE_DEBUG_PINS */
|
||||
|
||||
extern const struct pios_com_driver pios_usart_com_driver;
|
||||
|
||||
uint32_t pios_com_aux_id;
|
||||
uint8_t adc_fifo_buf[sizeof(float) * 6 * 4] __attribute__ ((aligned(4))); // align to 32-bit to try and provide speed improvement
|
||||
|
||||
@ -365,7 +49,13 @@ void PIOS_Board_Init(void) {
|
||||
/* Brings up System using CMSIS functions, enables the LEDs. */
|
||||
PIOS_SYS_Init();
|
||||
|
||||
PIOS_LED_On(LED1);
|
||||
#if defined(PIOS_INCLUDE_LED)
|
||||
PIOS_LED_Init(&pios_led_cfg);
|
||||
#endif /* PIOS_INCLUDE_LED */
|
||||
|
||||
#if defined(PIOS_LED_HEARTBEAT)
|
||||
PIOS_LED_On(PIOS_LED_HEARTBEAT);
|
||||
#endif /* PIOS_LED_HEARTBEAT */
|
||||
|
||||
/* Delay system */
|
||||
PIOS_DELAY_Init();
|
||||
|
@ -65,7 +65,7 @@ STMUSBDIR = $(STMLIBDIR)/STM32_USB-FS-Device_Driver
|
||||
STMSPDSRCDIR = $(STMSPDDIR)/src
|
||||
STMSPDINCDIR = $(STMSPDDIR)/inc
|
||||
CMSISDIR = $(STMLIBDIR)/CMSIS/Core/CM3
|
||||
|
||||
HWDEFSINC = ../../board_hw_defs/$(BOARD_NAME)
|
||||
|
||||
# List C source files here. (C dependencies are automatically generated.)
|
||||
# use file-extension c for "c-only"-files
|
||||
@ -155,6 +155,7 @@ EXTRAINCDIRS += $(PIOSBOARDS)
|
||||
EXTRAINCDIRS += $(STMSPDINCDIR)
|
||||
EXTRAINCDIRS += $(CMSISDIR)
|
||||
EXTRAINCDIRS += $(AHRS_BLINC)
|
||||
EXTRAINCDIRS += $(HWDEFSINC)
|
||||
|
||||
# List any extra directories to look for library files here.
|
||||
# Also add directories where the linker should search for
|
||||
|
@ -16,7 +16,7 @@ bool WriteData(uint32_t offset, uint8_t *buffer, uint32_t size) {
|
||||
PIOS_COM_SendFormattedString(PIOS_COM_AUX, "Wrote %d bytes to %d\r\n",
|
||||
size, offset);
|
||||
memcpy(buf, buffer, size);
|
||||
PIOS_LED_Toggle(LED1);
|
||||
PIOS_LED_Toggle(PIOS_LED_HEARTBEAT);
|
||||
return (true);
|
||||
}
|
||||
|
||||
@ -28,7 +28,7 @@ bool ReadData(uint32_t offset, uint8_t *buffer, uint32_t size) {
|
||||
PIOS_COM_SendFormattedString(PIOS_COM_AUX, "Read %d bytes from %d\r\n",
|
||||
size, offset);
|
||||
memcpy(buffer, buf, size);
|
||||
PIOS_LED_Toggle(LED1);
|
||||
PIOS_LED_Toggle(PIOS_LED_HEARTBEAT);
|
||||
return (true);
|
||||
}
|
||||
|
||||
|
@ -36,5 +36,6 @@
|
||||
#define PIOS_INCLUDE_BL_HELPER
|
||||
#define PIOS_INCLUDE_BL_HELPER_WRITE_SUPPORT
|
||||
#define PIOS_INCLUDE_GPIO
|
||||
#define PIOS_INCLUDE_IAP
|
||||
|
||||
#endif /* PIOS_CONFIG_H */
|
||||
|
@ -79,12 +79,7 @@ int main() {
|
||||
break;
|
||||
}
|
||||
}
|
||||
//while(TRUE)
|
||||
// {
|
||||
// PIOS_LED_Toggle(LED1);
|
||||
// PIOS_DELAY_WaitmS(1000);
|
||||
// }
|
||||
//GO_dfu = TRUE;
|
||||
|
||||
PIOS_IAP_Init();
|
||||
GO_dfu = GO_dfu | PIOS_IAP_CheckRequest();// OR with app boot request
|
||||
if (GO_dfu == FALSE) {
|
||||
@ -97,7 +92,7 @@ int main() {
|
||||
PIOS_Board_Init();
|
||||
boot_status = idle;
|
||||
Fw_crc = PIOS_BL_HELPER_CRC_Memory_Calc();
|
||||
PIOS_LED_On(LED1);
|
||||
PIOS_LED_On(PIOS_LED_HEARTBEAT);
|
||||
while (1) {
|
||||
process_spi_request();
|
||||
}
|
||||
@ -150,7 +145,7 @@ void process_spi_request(void) {
|
||||
Fw_crc = PIOS_BL_HELPER_CRC_Memory_Calc();
|
||||
lfsm_user_set_tx_v0(&user_tx_v0);
|
||||
boot_status = idle;
|
||||
PIOS_LED_Off(LED1);
|
||||
PIOS_LED_Off(PIOS_LED_HEARTBEAT);
|
||||
user_tx_v0.payload.user.v.rsp.fwup_status.status = boot_status;
|
||||
break;
|
||||
case OPAHRS_MSG_V0_REQ_RESET:
|
||||
@ -158,7 +153,6 @@ void process_spi_request(void) {
|
||||
PIOS_SYS_Reset();
|
||||
break;
|
||||
case OPAHRS_MSG_V0_REQ_VERSIONS:
|
||||
//PIOS_LED_On(LED1);
|
||||
opahrs_msg_v0_init_user_tx(&user_tx_v0, OPAHRS_MSG_V0_RSP_VERSIONS);
|
||||
user_tx_v0.payload.user.v.rsp.versions.bl_version = BOOTLOADER_VERSION;
|
||||
user_tx_v0.payload.user.v.rsp.versions.hw_version = (BOARD_TYPE << 8)
|
||||
@ -191,7 +185,7 @@ void process_spi_request(void) {
|
||||
lfsm_user_set_tx_v0(&user_tx_v0);
|
||||
break;
|
||||
case OPAHRS_MSG_V0_REQ_FWUP_DATA:
|
||||
PIOS_LED_On(LED1);
|
||||
PIOS_LED_On(PIOS_LED_HEARTBEAT);
|
||||
opahrs_msg_v0_init_user_tx(&user_tx_v0, OPAHRS_MSG_V0_RSP_FWUP_STATUS);
|
||||
if (!(user_rx_v0.payload.user.v.req.fwup_data.adress
|
||||
< bdinfo->fw_base)) {
|
||||
@ -209,7 +203,7 @@ void process_spi_request(void) {
|
||||
} else {
|
||||
boot_status = outside_dev_capabilities;
|
||||
}
|
||||
PIOS_LED_Off(LED1);
|
||||
PIOS_LED_Off(PIOS_LED_HEARTBEAT);
|
||||
user_tx_v0.payload.user.v.rsp.fwup_status.status = boot_status;
|
||||
lfsm_user_set_tx_v0(&user_tx_v0);
|
||||
break;
|
||||
@ -227,10 +221,10 @@ void process_spi_request(void) {
|
||||
opahrs_msg_v0_init_user_tx(&user_tx_v0, OPAHRS_MSG_V0_RSP_FWUP_STATUS);
|
||||
user_tx_v0.payload.user.v.rsp.fwup_status.status = boot_status;
|
||||
lfsm_user_set_tx_v0(&user_tx_v0);
|
||||
PIOS_LED_On(LED1);
|
||||
PIOS_LED_On(PIOS_LED_HEARTBEAT);
|
||||
if (PIOS_BL_HELPER_FLASH_Start() == TRUE) {
|
||||
boot_status = started;
|
||||
PIOS_LED_Off(LED1);
|
||||
PIOS_LED_Off(PIOS_LED_HEARTBEAT);
|
||||
} else {
|
||||
boot_status = start_failed;
|
||||
break;
|
||||
@ -254,15 +248,13 @@ void process_spi_request(void) {
|
||||
void jump_to_app() {
|
||||
const struct pios_board_info * bdinfo = &pios_board_info_blob;
|
||||
|
||||
PIOS_LED_On(LED1);
|
||||
PIOS_LED_On(PIOS_LED_HEARTBEAT);
|
||||
if (((*(__IO uint32_t*) bdinfo->fw_base) & 0x2FFE0000) == 0x20000000) { /* Jump to user application */
|
||||
FLASH_Lock();
|
||||
RCC_APB2PeriphResetCmd(0xffffffff, ENABLE);
|
||||
RCC_APB1PeriphResetCmd(0xffffffff, ENABLE);
|
||||
RCC_APB2PeriphResetCmd(0xffffffff, DISABLE);
|
||||
RCC_APB1PeriphResetCmd(0xffffffff, DISABLE);
|
||||
//_SetCNTR(0); // clear interrupt mask
|
||||
//_SetISTR(0); // clear all requests
|
||||
|
||||
JumpAddress = *(__IO uint32_t*) (bdinfo->fw_base + 4);
|
||||
Jump_To_Application = (pFunction) JumpAddress;
|
||||
|
@ -23,112 +23,16 @@
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
|
||||
#include <pios.h>
|
||||
|
||||
#if defined(PIOS_INCLUDE_SPI)
|
||||
|
||||
#include <pios_spi_priv.h>
|
||||
|
||||
/* OP Interface
|
||||
*
|
||||
* NOTE: Leave this declared as const data so that it ends up in the
|
||||
* .rodata section (ie. Flash) rather than in the .bss section (RAM).
|
||||
/* Pull in the board-specific static HW definitions.
|
||||
* Including .c files is a bit ugly but this allows all of
|
||||
* the HW definitions to be const and static to limit their
|
||||
* scope.
|
||||
*
|
||||
* NOTE: THIS IS THE ONLY PLACE THAT SHOULD EVER INCLUDE THIS FILE
|
||||
*/
|
||||
void PIOS_SPI_op_irq_handler(void);
|
||||
void DMA1_Channel5_IRQHandler() __attribute__ ((alias ("PIOS_SPI_op_irq_handler")));
|
||||
void DMA1_Channel4_IRQHandler() __attribute__ ((alias ("PIOS_SPI_op_irq_handler")));
|
||||
static const struct pios_spi_cfg
|
||||
pios_spi_op_cfg = {
|
||||
.regs = SPI2,
|
||||
.init = {
|
||||
.SPI_Mode = SPI_Mode_Slave,
|
||||
.SPI_Direction = SPI_Direction_2Lines_FullDuplex,
|
||||
.SPI_DataSize = SPI_DataSize_8b,
|
||||
.SPI_NSS = SPI_NSS_Hard,
|
||||
.SPI_FirstBit = SPI_FirstBit_MSB,
|
||||
.SPI_CRCPolynomial = 7,
|
||||
.SPI_CPOL = SPI_CPOL_High,
|
||||
.SPI_CPHA = SPI_CPHA_2Edge,
|
||||
},
|
||||
.use_crc = TRUE,
|
||||
.dma = {
|
||||
.ahb_clk = RCC_AHBPeriph_DMA1,
|
||||
#include "board_hw_defs.c"
|
||||
|
||||
.irq = {
|
||||
.flags = (DMA1_FLAG_TC4 | DMA1_FLAG_TE4 | DMA1_FLAG_HT4 | DMA1_FLAG_GL4),
|
||||
.init = {
|
||||
.NVIC_IRQChannel = DMA1_Channel4_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
|
||||
.rx = {
|
||||
.channel = DMA1_Channel4,
|
||||
.init = {
|
||||
.DMA_PeripheralBaseAddr = (uint32_t)&(SPI2->DR),
|
||||
.DMA_DIR = DMA_DIR_PeripheralSRC,
|
||||
.DMA_PeripheralInc = DMA_PeripheralInc_Disable,
|
||||
.DMA_MemoryInc = DMA_MemoryInc_Enable,
|
||||
.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte,
|
||||
.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte,
|
||||
.DMA_Mode = DMA_Mode_Normal,
|
||||
.DMA_Priority = DMA_Priority_Medium,
|
||||
.DMA_M2M = DMA_M2M_Disable,
|
||||
},
|
||||
},
|
||||
.tx = {
|
||||
.channel = DMA1_Channel5,
|
||||
.init = {
|
||||
.DMA_PeripheralBaseAddr = (uint32_t)&(SPI2->DR),
|
||||
.DMA_DIR = DMA_DIR_PeripheralDST,
|
||||
.DMA_PeripheralInc = DMA_PeripheralInc_Disable,
|
||||
.DMA_MemoryInc = DMA_MemoryInc_Enable,
|
||||
.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte,
|
||||
.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte,
|
||||
.DMA_Mode = DMA_Mode_Normal,
|
||||
.DMA_Priority = DMA_Priority_Medium,
|
||||
.DMA_M2M = DMA_M2M_Disable,
|
||||
},
|
||||
},
|
||||
}, .ssel = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_12,
|
||||
.GPIO_Speed = GPIO_Speed_50MHz,
|
||||
.GPIO_Mode = GPIO_Mode_IN_FLOATING,
|
||||
},
|
||||
}, .sclk = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_13,
|
||||
.GPIO_Speed = GPIO_Speed_50MHz,
|
||||
.GPIO_Mode = GPIO_Mode_IN_FLOATING,
|
||||
},
|
||||
}, .miso = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_14,
|
||||
.GPIO_Speed = GPIO_Speed_50MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF_PP,
|
||||
},
|
||||
}, .mosi = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_15,
|
||||
.GPIO_Speed = GPIO_Speed_50MHz,
|
||||
.GPIO_Mode = GPIO_Mode_IN_FLOATING,
|
||||
},
|
||||
}, };
|
||||
|
||||
uint32_t pios_spi_op_id;
|
||||
void PIOS_SPI_op_irq_handler(void) {
|
||||
/* Call into the generic code to handle the IRQ for this specific device */
|
||||
PIOS_SPI_IRQ_Handler(pios_spi_op_id);
|
||||
}
|
||||
|
||||
#endif /* PIOS_INCLUDE_SPI */
|
||||
#include <pios.h>
|
||||
|
||||
#include "bl_fsm.h" /* lfsm_* */
|
||||
|
||||
@ -138,6 +42,10 @@ void PIOS_Board_Init() {
|
||||
return;
|
||||
}
|
||||
|
||||
#if defined(PIOS_INCLUDE_LED)
|
||||
PIOS_LED_Init(&pios_led_cfg);
|
||||
#endif /* PIOS_INCLUDE_LED */
|
||||
|
||||
/* Set up the SPI interface to the OP board */
|
||||
if (PIOS_SPI_Init(&pios_spi_op_id, &pios_spi_op_cfg)) {
|
||||
PIOS_DEBUG_Assert(0);
|
||||
|
@ -89,6 +89,7 @@ RTOSDIR = $(APPLIBDIR)/FreeRTOS
|
||||
RTOSSRCDIR = $(RTOSDIR)/Source
|
||||
RTOSINCDIR = $(RTOSSRCDIR)/include
|
||||
DOXYGENDIR = ../Doc/Doxygen
|
||||
HWDEFSINC = $(TOP)/flight/board_hw_defs/$(BOARD_NAME)
|
||||
|
||||
# List C source files here. (C dependencies are automatically generated.)
|
||||
# use file-extension c for "c-only"-files
|
||||
@ -165,6 +166,7 @@ EXTRAINCDIRS += $(MSDDIR)
|
||||
EXTRAINCDIRS += $(RTOSINCDIR)
|
||||
EXTRAINCDIRS += $(APPLIBDIR)
|
||||
EXTRAINCDIRS += $(RTOSSRCDIR)/portable/GCC/ARM_CM3
|
||||
EXTRAINCDIRS += $(HWDEFSINC)
|
||||
|
||||
|
||||
|
||||
|
@ -50,14 +50,14 @@ int main() {
|
||||
|
||||
PIOS_SYS_Init();
|
||||
PIOS_Board_Init();
|
||||
PIOS_LED_On(LED1);
|
||||
PIOS_LED_On(PIOS_LED_HEARTBEAT);
|
||||
PIOS_DELAY_WaitmS(3000);
|
||||
PIOS_LED_Off(LED1);
|
||||
PIOS_LED_Off(PIOS_LED_HEARTBEAT);
|
||||
|
||||
/// Self overwrite check
|
||||
uint32_t base_address = SCB->VTOR;
|
||||
if ((0x08000000 + embedded_image_size) > base_address)
|
||||
error(LED1);
|
||||
error(PIOS_LED_HEARTBEAT);
|
||||
///
|
||||
FLASH_Unlock();
|
||||
|
||||
@ -82,7 +82,7 @@ int main() {
|
||||
}
|
||||
|
||||
if (fail == true)
|
||||
error(LED1);
|
||||
error(PIOS_LED_HEARTBEAT);
|
||||
|
||||
|
||||
///
|
||||
@ -90,7 +90,7 @@ int main() {
|
||||
/// Bootloader programing
|
||||
for (uint32_t offset = 0; offset < embedded_image_size/sizeof(uint32_t); ++offset) {
|
||||
bool result = false;
|
||||
PIOS_LED_Toggle(LED1);
|
||||
PIOS_LED_Toggle(PIOS_LED_HEARTBEAT);
|
||||
for (uint8_t retry = 0; retry < MAX_WRI_RETRYS; ++retry) {
|
||||
if (result == false) {
|
||||
result = (FLASH_ProgramWord(0x08000000 + (offset * 4), embedded_image_start[offset])
|
||||
@ -98,13 +98,13 @@ int main() {
|
||||
}
|
||||
}
|
||||
if (result == false)
|
||||
error(LED1);
|
||||
error(PIOS_LED_HEARTBEAT);
|
||||
}
|
||||
///
|
||||
for (uint8_t x = 0; x < 3; ++x) {
|
||||
PIOS_LED_On(LED1);
|
||||
PIOS_LED_On(PIOS_LED_HEARTBEAT);
|
||||
PIOS_DELAY_WaitmS(1000);
|
||||
PIOS_LED_Off(LED1);
|
||||
PIOS_LED_Off(PIOS_LED_HEARTBEAT);
|
||||
PIOS_DELAY_WaitmS(1000);
|
||||
}
|
||||
|
||||
|
@ -23,6 +23,15 @@
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
|
||||
/* Pull in the board-specific static HW definitions.
|
||||
* Including .c files is a bit ugly but this allows all of
|
||||
* the HW definitions to be const and static to limit their
|
||||
* scope.
|
||||
*
|
||||
* NOTE: THIS IS THE ONLY PLACE THAT SHOULD EVER INCLUDE THIS FILE
|
||||
*/
|
||||
#include "board_hw_defs.c"
|
||||
|
||||
#include <pios.h>
|
||||
|
||||
void PIOS_Board_Init(void) {
|
||||
@ -38,4 +47,8 @@ void PIOS_Board_Init(void) {
|
||||
/* Initialize the PiOS library */
|
||||
PIOS_GPIO_Init();
|
||||
|
||||
#if defined(PIOS_INCLUDE_LED)
|
||||
PIOS_LED_Init(&pios_led_cfg);
|
||||
#endif /* PIOS_INCLUDE_LED */
|
||||
|
||||
}
|
||||
|
@ -86,6 +86,7 @@ RTOSDIR = $(APPLIBDIR)/FreeRTOS
|
||||
RTOSSRCDIR = $(RTOSDIR)/Source
|
||||
RTOSINCDIR = $(RTOSSRCDIR)/include
|
||||
DOXYGENDIR = ../Doc/Doxygen
|
||||
HWDEFSINC = ../../board_hw_defs/$(BOARD_NAME)
|
||||
|
||||
# List C source files here. (C dependencies are automatically generated.)
|
||||
# use file-extension c for "c-only"-files
|
||||
@ -104,7 +105,6 @@ SRC += $(PIOSSTM32F10X)/pios_irq.c
|
||||
SRC += $(PIOSSTM32F10X)/pios_debug.c
|
||||
SRC += $(PIOSSTM32F10X)/pios_gpio.c
|
||||
|
||||
|
||||
# PIOS USB related files (seperated to make code maintenance more easy)
|
||||
SRC += $(PIOSSTM32F10X)/pios_usb.c
|
||||
SRC += $(PIOSSTM32F10X)/pios_usbhook.c
|
||||
@ -116,7 +116,7 @@ SRC += $(PIOSCOMMON)/pios_usb_desc_hid_only.c
|
||||
|
||||
## PIOS Hardware (Common)
|
||||
SRC += $(PIOSCOMMON)/pios_board_info.c
|
||||
SRC += $(PIOSCOMMON)/pios_com.c
|
||||
SRC += $(PIOSCOMMON)/pios_com_msg.c
|
||||
SRC += $(PIOSCOMMON)/pios_bl_helper.c
|
||||
SRC += $(PIOSCOMMON)/pios_iap.c
|
||||
SRC += $(PIOSCOMMON)/printf-stdarg.c
|
||||
@ -199,8 +199,7 @@ EXTRAINCDIRS += $(MSDDIR)
|
||||
EXTRAINCDIRS += $(RTOSINCDIR)
|
||||
EXTRAINCDIRS += $(APPLIBDIR)
|
||||
EXTRAINCDIRS += $(RTOSSRCDIR)/portable/GCC/ARM_CM3
|
||||
|
||||
|
||||
EXTRAINCDIRS += $(HWDEFSINC)
|
||||
|
||||
# List any extra directories to look for library files here.
|
||||
# Also add directories where the linker should search for
|
||||
|
@ -39,8 +39,9 @@
|
||||
#define PIOS_INCLUDE_SYS
|
||||
#define PIOS_INCLUDE_USB
|
||||
#define PIOS_INCLUDE_USB_HID
|
||||
#define PIOS_INCLUDE_COM
|
||||
#define PIOS_INCLUDE_COM_MSG
|
||||
#define PIOS_INCLUDE_GPIO
|
||||
#define PIOS_INCLUDE_IAP
|
||||
#define PIOS_NO_GPS
|
||||
|
||||
#endif /* PIOS_CONFIG_H */
|
||||
|
@ -37,33 +37,6 @@
|
||||
|
||||
#include "pios_usb_defs.h" /* struct usb_* */
|
||||
|
||||
struct usb_board_config {
|
||||
struct usb_configuration_desc config;
|
||||
struct usb_interface_desc hid_if;
|
||||
struct usb_hid_desc hid;
|
||||
struct usb_endpoint_desc hid_in;
|
||||
struct usb_endpoint_desc hid_out;
|
||||
} __attribute__((packed));
|
||||
|
||||
extern const struct usb_device_desc PIOS_USB_BOARD_DeviceDescriptor;
|
||||
extern const struct usb_board_config PIOS_USB_BOARD_Configuration;
|
||||
extern const struct usb_string_langid PIOS_USB_BOARD_StringLangID;
|
||||
|
||||
/* NOTE NOTE NOTE
|
||||
*
|
||||
* Care must be taken to ensure that the _actual_ contents of
|
||||
* these arrays (in each board's pios_usb_board_data.c) is no
|
||||
* smaller than the stated sizes here or these descriptors
|
||||
* will end up with trailing zeros on the wire.
|
||||
*
|
||||
* The compiler will catch any time that these definitions are
|
||||
* too small.
|
||||
*/
|
||||
extern const uint8_t PIOS_USB_BOARD_HidReportDescriptor[36];
|
||||
extern const uint8_t PIOS_USB_BOARD_StringVendorID[28];
|
||||
extern const uint8_t PIOS_USB_BOARD_StringProductID[28];
|
||||
extern uint8_t PIOS_USB_BOARD_StringSerial[52];
|
||||
|
||||
#define PIOS_USB_BOARD_PRODUCT_ID USB_PRODUCT_ID_COPTERCONTROL
|
||||
#define PIOS_USB_BOARD_DEVICE_VER USB_OP_DEVICE_VER(USB_OP_BOARD_ID_COPTERCONTROL, USB_OP_BOARD_MODE_BL)
|
||||
|
||||
|
@ -32,6 +32,7 @@
|
||||
#include "usb_lib.h"
|
||||
#include "pios_iap.h"
|
||||
#include "fifo_buffer.h"
|
||||
#include "pios_com_msg.h"
|
||||
/* Prototype of PIOS_Board_Init() function */
|
||||
extern void PIOS_Board_Init(void);
|
||||
extern void FLASH_Download();
|
||||
@ -62,13 +63,12 @@ uint8_t JumpToApp = FALSE;
|
||||
uint8_t GO_dfu = FALSE;
|
||||
uint8_t USB_connected = FALSE;
|
||||
uint8_t User_DFU_request = FALSE;
|
||||
static uint8_t mReceive_Buffer[64];
|
||||
static uint8_t mReceive_Buffer[63];
|
||||
/* Private function prototypes -----------------------------------------------*/
|
||||
uint32_t LedPWM(uint32_t pwm_period, uint32_t pwm_sweep_steps, uint32_t count);
|
||||
uint8_t processRX();
|
||||
void jump_to_app();
|
||||
|
||||
#define BLUE LED1
|
||||
int main() {
|
||||
PIOS_SYS_Init();
|
||||
if (BSL_HOLD_STATE == 0)
|
||||
@ -111,7 +111,7 @@ int main() {
|
||||
case DFUidle:
|
||||
period1 = 5000;
|
||||
sweep_steps1 = 100;
|
||||
PIOS_LED_Off(BLUE);
|
||||
PIOS_LED_Off(PIOS_LED_HEARTBEAT);
|
||||
period2 = 0;
|
||||
break;
|
||||
case uploading:
|
||||
@ -123,12 +123,12 @@ int main() {
|
||||
case downloading:
|
||||
period1 = 2500;
|
||||
sweep_steps1 = 50;
|
||||
PIOS_LED_Off(BLUE);
|
||||
PIOS_LED_Off(PIOS_LED_HEARTBEAT);
|
||||
period2 = 0;
|
||||
break;
|
||||
case BLidle:
|
||||
period1 = 0;
|
||||
PIOS_LED_On(BLUE);
|
||||
PIOS_LED_On(PIOS_LED_HEARTBEAT);
|
||||
period2 = 0;
|
||||
break;
|
||||
default://error
|
||||
@ -140,19 +140,19 @@ int main() {
|
||||
|
||||
if (period1 != 0) {
|
||||
if (LedPWM(period1, sweep_steps1, stopwatch))
|
||||
PIOS_LED_On(BLUE);
|
||||
PIOS_LED_On(PIOS_LED_HEARTBEAT);
|
||||
else
|
||||
PIOS_LED_Off(BLUE);
|
||||
PIOS_LED_Off(PIOS_LED_HEARTBEAT);
|
||||
} else
|
||||
PIOS_LED_On(BLUE);
|
||||
PIOS_LED_On(PIOS_LED_HEARTBEAT);
|
||||
|
||||
if (period2 != 0) {
|
||||
if (LedPWM(period2, sweep_steps2, stopwatch))
|
||||
PIOS_LED_On(BLUE);
|
||||
PIOS_LED_On(PIOS_LED_HEARTBEAT);
|
||||
else
|
||||
PIOS_LED_Off(BLUE);
|
||||
PIOS_LED_Off(PIOS_LED_HEARTBEAT);
|
||||
} else
|
||||
PIOS_LED_Off(BLUE);
|
||||
PIOS_LED_Off(PIOS_LED_HEARTBEAT);
|
||||
|
||||
if (stopwatch > 50 * 1000 * 1000)
|
||||
stopwatch = 0;
|
||||
@ -198,7 +198,7 @@ uint32_t LedPWM(uint32_t pwm_period, uint32_t pwm_sweep_steps, uint32_t count) {
|
||||
}
|
||||
|
||||
uint8_t processRX() {
|
||||
if (PIOS_COM_ReceiveBuffer(PIOS_COM_TELEM_USB, mReceive_Buffer, 63, 0) == 63) {
|
||||
if (PIOS_COM_MSG_Receive(PIOS_COM_TELEM_USB, mReceive_Buffer, sizeof(mReceive_Buffer))) {
|
||||
processComand(mReceive_Buffer);
|
||||
}
|
||||
return TRUE;
|
||||
|
@ -30,6 +30,7 @@
|
||||
#include "pios.h"
|
||||
#include "op_dfu.h"
|
||||
#include "pios_bl_helper.h"
|
||||
#include "pios_com_msg.h"
|
||||
#include <pios_board_info.h>
|
||||
//programmable devices
|
||||
Device devicesTable[10];
|
||||
@ -446,9 +447,7 @@ uint32_t CalcFirmCRC() {
|
||||
|
||||
}
|
||||
void sendData(uint8_t * buf, uint16_t size) {
|
||||
PIOS_COM_SendBuffer(PIOS_COM_TELEM_USB, buf, size);
|
||||
if (DeviceState == downloading)
|
||||
PIOS_DELAY_WaitmS(20);//this is an hack, we should check wtf is wrong with hid
|
||||
PIOS_COM_MSG_Send(PIOS_COM_TELEM_USB, buf, size);
|
||||
}
|
||||
|
||||
bool flash_read(uint8_t * buffer, uint32_t adr, DFUProgType type) {
|
||||
|
@ -23,50 +23,17 @@
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
|
||||
/* Pull in the board-specific static HW definitions.
|
||||
* Including .c files is a bit ugly but this allows all of
|
||||
* the HW definitions to be const and static to limit their
|
||||
* scope.
|
||||
*
|
||||
* NOTE: THIS IS THE ONLY PLACE THAT SHOULD EVER INCLUDE THIS FILE
|
||||
*/
|
||||
#include "board_hw_defs.c"
|
||||
|
||||
#include <pios.h>
|
||||
|
||||
// ***********************************************************************************
|
||||
|
||||
#if defined(PIOS_INCLUDE_COM)
|
||||
|
||||
#include <pios_com_priv.h>
|
||||
|
||||
#define PIOS_COM_TELEM_USB_RX_BUF_LEN 192
|
||||
#define PIOS_COM_TELEM_USB_TX_BUF_LEN 192
|
||||
|
||||
static uint8_t pios_com_telem_usb_rx_buffer[PIOS_COM_TELEM_USB_RX_BUF_LEN];
|
||||
static uint8_t pios_com_telem_usb_tx_buffer[PIOS_COM_TELEM_USB_TX_BUF_LEN];
|
||||
|
||||
#endif /* PIOS_INCLUDE_COM */
|
||||
|
||||
// ***********************************************************************************
|
||||
|
||||
#if defined(PIOS_INCLUDE_USB)
|
||||
#include "pios_usb_priv.h"
|
||||
|
||||
static const struct pios_usb_cfg pios_usb_main_cfg = {
|
||||
.irq = {
|
||||
.init = {
|
||||
.NVIC_IRQChannel = USB_LP_CAN1_RX0_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_LOW,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
};
|
||||
#endif /* PIOS_INCLUDE_USB */
|
||||
|
||||
#if defined(PIOS_INCLUDE_USB_HID)
|
||||
#include <pios_usb_hid_priv.h>
|
||||
|
||||
const struct pios_usb_hid_cfg pios_usb_hid_cfg = {
|
||||
.data_if = 0,
|
||||
.data_rx_ep = 1,
|
||||
.data_tx_ep = 1,
|
||||
};
|
||||
|
||||
#endif /* PIOS_INCLUDE_USB_HID */
|
||||
|
||||
uint32_t pios_com_telem_usb_id;
|
||||
|
||||
/**
|
||||
@ -92,22 +59,30 @@ void PIOS_Board_Init(void) {
|
||||
/* Initialize the PiOS library */
|
||||
PIOS_GPIO_Init();
|
||||
|
||||
#if defined(PIOS_INCLUDE_LED)
|
||||
PIOS_LED_Init(&pios_led_cfg);
|
||||
#endif /* PIOS_INCLUDE_LED */
|
||||
|
||||
#if defined(PIOS_INCLUDE_USB)
|
||||
/* Initialize board specific USB data */
|
||||
PIOS_USB_BOARD_DATA_Init();
|
||||
|
||||
/* Activate the HID-only USB configuration */
|
||||
PIOS_USB_DESC_HID_ONLY_Init();
|
||||
|
||||
uint32_t pios_usb_id;
|
||||
if (PIOS_USB_Init(&pios_usb_id, &pios_usb_main_cfg)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
#if defined(PIOS_INCLUDE_USB_HID) && defined(PIOS_INCLUDE_COM)
|
||||
#if defined(PIOS_INCLUDE_USB_HID) && defined(PIOS_INCLUDE_COM_MSG)
|
||||
uint32_t pios_usb_hid_id;
|
||||
if (PIOS_USB_HID_Init(&pios_usb_hid_id, &pios_usb_hid_cfg, pios_usb_id)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
if (PIOS_COM_Init(&pios_com_telem_usb_id, &pios_usb_hid_com_driver, pios_usb_hid_id,
|
||||
pios_com_telem_usb_rx_buffer, sizeof(pios_com_telem_usb_rx_buffer),
|
||||
pios_com_telem_usb_tx_buffer, sizeof(pios_com_telem_usb_tx_buffer))) {
|
||||
if (PIOS_COM_MSG_Init(&pios_com_telem_usb_id, &pios_usb_hid_com_driver, pios_usb_hid_id)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_USB_HID && PIOS_INCLUDE_COM */
|
||||
#endif /* PIOS_INCLUDE_USB_HID && PIOS_INCLUDE_COM_MSG */
|
||||
|
||||
#endif /* PIOS_INCLUDE_USB */
|
||||
|
||||
|
@ -29,9 +29,11 @@
|
||||
*/
|
||||
|
||||
#include "pios_usb_board_data.h" /* struct usb_*, USB_* */
|
||||
#include "pios_sys.h" /* PIOS_SYS_SerialNumberGet */
|
||||
#include "pios_usbhook.h" /* PIOS_USBHOOK_* */
|
||||
|
||||
const uint8_t PIOS_USB_BOARD_StringProductID[] = {
|
||||
sizeof(PIOS_USB_BOARD_StringProductID),
|
||||
static const uint8_t usb_product_id[28] = {
|
||||
sizeof(usb_product_id),
|
||||
USB_DESC_TYPE_STRING,
|
||||
'C', 0,
|
||||
'o', 0,
|
||||
@ -48,3 +50,74 @@ const uint8_t PIOS_USB_BOARD_StringProductID[] = {
|
||||
'l', 0,
|
||||
};
|
||||
|
||||
static uint8_t usb_serial_number[52] = {
|
||||
sizeof(usb_serial_number),
|
||||
USB_DESC_TYPE_STRING,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0
|
||||
};
|
||||
|
||||
static const struct usb_string_langid usb_lang_id = {
|
||||
.bLength = sizeof(usb_lang_id),
|
||||
.bDescriptorType = USB_DESC_TYPE_STRING,
|
||||
.bLangID = htousbs(USB_LANGID_ENGLISH_UK),
|
||||
};
|
||||
|
||||
static const uint8_t usb_vendor_id[28] = {
|
||||
sizeof(usb_vendor_id),
|
||||
USB_DESC_TYPE_STRING,
|
||||
'o', 0,
|
||||
'p', 0,
|
||||
'e', 0,
|
||||
'n', 0,
|
||||
'p', 0,
|
||||
'i', 0,
|
||||
'l', 0,
|
||||
'o', 0,
|
||||
't', 0,
|
||||
'.', 0,
|
||||
'o', 0,
|
||||
'r', 0,
|
||||
'g', 0
|
||||
};
|
||||
|
||||
int32_t PIOS_USB_BOARD_DATA_Init(void)
|
||||
{
|
||||
/* Load device serial number into serial number string */
|
||||
uint8_t sn[25];
|
||||
PIOS_SYS_SerialNumberGet((char *)sn);
|
||||
for (uint8_t i = 0; sn[i] != '\0' && (2 * i) < usb_serial_number[0]; i++) {
|
||||
usb_serial_number[2 + 2 * i] = sn[i];
|
||||
}
|
||||
|
||||
PIOS_USBHOOK_RegisterString(USB_STRING_DESC_PRODUCT, (uint8_t *)&usb_product_id, sizeof(usb_product_id));
|
||||
PIOS_USBHOOK_RegisterString(USB_STRING_DESC_SERIAL, (uint8_t *)&usb_serial_number, sizeof(usb_serial_number));
|
||||
|
||||
PIOS_USBHOOK_RegisterString(USB_STRING_DESC_LANG, (uint8_t *)&usb_lang_id, sizeof(usb_lang_id));
|
||||
PIOS_USBHOOK_RegisterString(USB_STRING_DESC_VENDOR, (uint8_t *)&usb_vendor_id, sizeof(usb_vendor_id));
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
@ -86,6 +86,7 @@ RTOSDIR = $(APPLIBDIR)/FreeRTOS
|
||||
RTOSSRCDIR = $(RTOSDIR)/Source
|
||||
RTOSINCDIR = $(RTOSSRCDIR)/include
|
||||
DOXYGENDIR = ../Doc/Doxygen
|
||||
HWDEFSINC = ../../board_hw_defs/$(BOARD_NAME)
|
||||
|
||||
# List C source files here. (C dependencies are automatically generated.)
|
||||
# use file-extension c for "c-only"-files
|
||||
@ -119,6 +120,7 @@ SRC += $(PIOSCOMMON)/pios_usb_desc_hid_only.c
|
||||
|
||||
## PIOS Hardware (Common)
|
||||
SRC += $(PIOSCOMMON)/pios_board_info.c
|
||||
SRC += $(PIOSCOMMON)/pios_com_msg.c
|
||||
SRC += $(PIOSCOMMON)/pios_com.c
|
||||
SRC += $(PIOSCOMMON)/pios_opahrs_v0.c
|
||||
SRC += $(PIOSCOMMON)/pios_bl_helper.c
|
||||
@ -205,6 +207,7 @@ EXTRAINCDIRS += $(MSDDIR)
|
||||
EXTRAINCDIRS += $(RTOSINCDIR)
|
||||
EXTRAINCDIRS += $(APPLIBDIR)
|
||||
EXTRAINCDIRS += $(RTOSSRCDIR)/portable/GCC/ARM_CM3
|
||||
EXTRAINCDIRS += $(HWDEFSINC)
|
||||
|
||||
|
||||
|
||||
@ -292,7 +295,7 @@ CSTANDARD = -std=gnu99
|
||||
# Flags for C and C++ (arm-elf-gcc/arm-elf-g++)
|
||||
|
||||
ifeq ($(DEBUG),YES)
|
||||
CFLAGS = -DDEBUG
|
||||
CFLAGS += -DDEBUG
|
||||
endif
|
||||
|
||||
CFLAGS += -g$(DEBUGF)
|
||||
|
@ -42,7 +42,9 @@
|
||||
#define PIOS_INCLUDE_USB_HID
|
||||
#define PIOS_INCLUDE_OPAHRS
|
||||
#define PIOS_INCLUDE_COM
|
||||
#define PIOS_INCLUDE_COM_MSG
|
||||
#define PIOS_INCLUDE_GPIO
|
||||
#define PIOS_INCLUDE_IAP
|
||||
//#define DEBUG_SSP
|
||||
|
||||
/* Defaults for Logging */
|
||||
|
@ -37,33 +37,6 @@
|
||||
|
||||
#include "pios_usb_defs.h" /* struct usb_* */
|
||||
|
||||
struct usb_board_config {
|
||||
struct usb_configuration_desc config;
|
||||
struct usb_interface_desc hid_if;
|
||||
struct usb_hid_desc hid;
|
||||
struct usb_endpoint_desc hid_in;
|
||||
struct usb_endpoint_desc hid_out;
|
||||
} __attribute__((packed));
|
||||
|
||||
extern const struct usb_device_desc PIOS_USB_BOARD_DeviceDescriptor;
|
||||
extern const struct usb_board_config PIOS_USB_BOARD_Configuration;
|
||||
extern const struct usb_string_langid PIOS_USB_BOARD_StringLangID;
|
||||
|
||||
/* NOTE NOTE NOTE
|
||||
*
|
||||
* Care must be taken to ensure that the _actual_ contents of
|
||||
* these arrays (in each board's pios_usb_board_data.c) is no
|
||||
* smaller than the stated sizes here or these descriptors
|
||||
* will end up with trailing zeros on the wire.
|
||||
*
|
||||
* The compiler will catch any time that these definitions are
|
||||
* too small.
|
||||
*/
|
||||
extern const uint8_t PIOS_USB_BOARD_HidReportDescriptor[36];
|
||||
extern const uint8_t PIOS_USB_BOARD_StringVendorID[28];
|
||||
extern const uint8_t PIOS_USB_BOARD_StringProductID[20];
|
||||
extern uint8_t PIOS_USB_BOARD_StringSerial[52];
|
||||
|
||||
#define PIOS_USB_BOARD_PRODUCT_ID USB_PRODUCT_ID_OPENPILOT_MAIN
|
||||
#define PIOS_USB_BOARD_DEVICE_VER USB_OP_DEVICE_VER(USB_OP_BOARD_ID_OPENPILOT_MAIN, USB_OP_BOARD_MODE_BL)
|
||||
|
||||
|
@ -35,6 +35,7 @@
|
||||
#include "pios_iap.h"
|
||||
#include "ssp.h"
|
||||
#include "fifo_buffer.h"
|
||||
#include "pios_com_msg.h"
|
||||
/* Prototype of PIOS_Board_Init() function */
|
||||
extern void PIOS_Board_Init(void);
|
||||
extern void FLASH_Download();
|
||||
@ -90,21 +91,15 @@ uint8_t JumpToApp = FALSE;
|
||||
uint8_t GO_dfu = FALSE;
|
||||
uint8_t USB_connected = FALSE;
|
||||
uint8_t User_DFU_request = FALSE;
|
||||
static uint8_t mReceive_Buffer[64];
|
||||
static uint8_t mReceive_Buffer[63];
|
||||
/* Private function prototypes -----------------------------------------------*/
|
||||
uint32_t LedPWM(uint32_t pwm_period, uint32_t pwm_sweep_steps, uint32_t count);
|
||||
uint8_t processRX();
|
||||
void jump_to_app();
|
||||
uint32_t sspTimeSource();
|
||||
|
||||
#define BLUE LED1
|
||||
#define RED LED2
|
||||
#define LED_PWM_TIMER TIM6
|
||||
int main() {
|
||||
/* NOTE: Do NOT modify the following start-up sequence */
|
||||
/* Any new initialization functions should be added in OpenPilotInit() */
|
||||
|
||||
/* Brings up System using CMSIS functions, enables the LEDs. */
|
||||
PIOS_SYS_Init();
|
||||
if (BSL_HOLD_STATE == 0)
|
||||
USB_connected = TRUE;
|
||||
@ -162,7 +157,7 @@ int main() {
|
||||
case DFUidle:
|
||||
period1 = 50;
|
||||
sweep_steps1 = 100;
|
||||
PIOS_LED_Off(RED);
|
||||
PIOS_LED_Off(PIOS_LED_ALARM);
|
||||
period2 = 0;
|
||||
break;
|
||||
case uploading:
|
||||
@ -174,12 +169,12 @@ int main() {
|
||||
case downloading:
|
||||
period1 = 25;
|
||||
sweep_steps1 = 50;
|
||||
PIOS_LED_Off(RED);
|
||||
PIOS_LED_Off(PIOS_LED_ALARM);
|
||||
period2 = 0;
|
||||
break;
|
||||
case BLidle:
|
||||
period1 = 0;
|
||||
PIOS_LED_On(BLUE);
|
||||
PIOS_LED_On(PIOS_LED_HEARTBEAT);
|
||||
period2 = 0;
|
||||
break;
|
||||
default://error
|
||||
@ -191,19 +186,19 @@ int main() {
|
||||
|
||||
if (period1 != 0) {
|
||||
if (LedPWM(period1, sweep_steps1, STOPWATCH_ValueGet(LED_PWM_TIMER)))
|
||||
PIOS_LED_On(BLUE);
|
||||
PIOS_LED_On(PIOS_LED_HEARTBEAT);
|
||||
else
|
||||
PIOS_LED_Off(BLUE);
|
||||
PIOS_LED_Off(PIOS_LED_HEARTBEAT);
|
||||
} else
|
||||
PIOS_LED_On(BLUE);
|
||||
PIOS_LED_On(PIOS_LED_HEARTBEAT);
|
||||
|
||||
if (period2 != 0) {
|
||||
if (LedPWM(period2, sweep_steps2, STOPWATCH_ValueGet(LED_PWM_TIMER)))
|
||||
PIOS_LED_On(RED);
|
||||
PIOS_LED_On(PIOS_LED_ALARM);
|
||||
else
|
||||
PIOS_LED_Off(RED);
|
||||
PIOS_LED_Off(PIOS_LED_ALARM);
|
||||
} else
|
||||
PIOS_LED_Off(RED);
|
||||
PIOS_LED_Off(PIOS_LED_ALARM);
|
||||
|
||||
if (STOPWATCH_ValueGet(LED_PWM_TIMER) > 100 * 50 * 100)
|
||||
STOPWATCH_Reset(LED_PWM_TIMER);
|
||||
@ -227,7 +222,6 @@ void jump_to_app() {
|
||||
RCC_APB1PeriphResetCmd(0xffffffff, DISABLE);
|
||||
_SetCNTR(0); // clear interrupt mask
|
||||
_SetISTR(0); // clear all requests
|
||||
|
||||
JumpAddress = *(__IO uint32_t*) (bdinfo->fw_base + 4);
|
||||
Jump_To_Application = (pFunction) JumpAddress;
|
||||
/* Initialize user application's Stack Pointer */
|
||||
@ -249,7 +243,7 @@ uint32_t LedPWM(uint32_t pwm_period, uint32_t pwm_sweep_steps, uint32_t count) {
|
||||
|
||||
uint8_t processRX() {
|
||||
if (ProgPort == Usb) {
|
||||
if (PIOS_COM_ReceiveBuffer(PIOS_COM_TELEM_USB, mReceive_Buffer, 63, 0) == 63) {
|
||||
if (PIOS_COM_MSG_Receive(PIOS_COM_TELEM_USB, mReceive_Buffer, sizeof(mReceive_Buffer))) {
|
||||
processComand(mReceive_Buffer);
|
||||
}
|
||||
} else if (ProgPort == Serial) {
|
||||
|
@ -30,13 +30,10 @@
|
||||
#include "pios.h"
|
||||
#include "op_dfu.h"
|
||||
#include "pios_bl_helper.h"
|
||||
#include "pios_com_msg.h"
|
||||
#include <pios_board_info.h>
|
||||
#include "pios_opahrs.h"
|
||||
#include "ssp.h"
|
||||
/* Private typedef -----------------------------------------------------------*/
|
||||
/* Private define ------------------------------------------------------------*/
|
||||
/* Private macro -------------------------------------------------------------*/
|
||||
/* Private variables ---------------------------------------------------------*/
|
||||
//programmable devices
|
||||
Device devicesTable[10];
|
||||
uint8_t numberOfDevices = 0;
|
||||
@ -222,7 +219,7 @@ void processComand(uint8_t *xReceive_Buffer) {
|
||||
}
|
||||
}
|
||||
if (result != 1) {
|
||||
DeviceState = Last_operation_failed;//ok
|
||||
DeviceState = Last_operation_failed;
|
||||
Aditionals = (uint32_t) Command;
|
||||
} else {
|
||||
|
||||
@ -299,7 +296,6 @@ void processComand(uint8_t *xReceive_Buffer) {
|
||||
|
||||
++Next_Packet;
|
||||
} else {
|
||||
|
||||
DeviceState = wrong_packet_received;
|
||||
Aditionals = Count;
|
||||
}
|
||||
@ -353,10 +349,18 @@ void processComand(uint8_t *xReceive_Buffer) {
|
||||
DeviceState = failed_jump;
|
||||
break;
|
||||
} else {
|
||||
if (Data == 0x5AFE) {
|
||||
/* Force board into safe mode */
|
||||
PIOS_IAP_WriteBootCount(0xFFFF);
|
||||
}
|
||||
FLASH_Lock();
|
||||
JumpToApp = 1;
|
||||
}
|
||||
} else {
|
||||
if (Data == 0x5AFE) {
|
||||
/* Force board into safe mode */
|
||||
PIOS_IAP_WriteBootCount(0xFFFF);
|
||||
}
|
||||
FLASH_Lock();
|
||||
JumpToApp = 1;
|
||||
}
|
||||
@ -384,7 +388,6 @@ void processComand(uint8_t *xReceive_Buffer) {
|
||||
DeviceState = too_few_packets;
|
||||
}
|
||||
}
|
||||
|
||||
break;
|
||||
case Download_Req:
|
||||
#ifdef DEBUG_SSP
|
||||
@ -508,6 +511,7 @@ uint32_t baseOfAdressType(DFUTransfer type) {
|
||||
return currentDevice.startOfUserCode + currentDevice.sizeOfCode;
|
||||
break;
|
||||
default:
|
||||
|
||||
return 0;
|
||||
}
|
||||
}
|
||||
@ -550,11 +554,7 @@ uint32_t CalcFirmCRC() {
|
||||
}
|
||||
void sendData(uint8_t * buf, uint16_t size) {
|
||||
if (ProgPort == Usb) {
|
||||
|
||||
PIOS_COM_SendBuffer(PIOS_COM_TELEM_USB, buf, size);
|
||||
if (DeviceState == downloading)
|
||||
PIOS_DELAY_WaitmS(10);
|
||||
|
||||
PIOS_COM_MSG_Send(PIOS_COM_TELEM_USB, buf, size);
|
||||
} else if (ProgPort == Serial) {
|
||||
ssp_SendData(&ssp_port, buf, size);
|
||||
}
|
||||
|
@ -25,170 +25,16 @@
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
|
||||
/* Pull in the board-specific static HW definitions.
|
||||
* Including .c files is a bit ugly but this allows all of
|
||||
* the HW definitions to be const and static to limit their
|
||||
* scope.
|
||||
*
|
||||
* NOTE: THIS IS THE ONLY PLACE THAT SHOULD EVER INCLUDE THIS FILE
|
||||
*/
|
||||
#include "board_hw_defs.c"
|
||||
|
||||
#include <pios.h>
|
||||
//#include <openpilot.h>
|
||||
//#include <uavobjectsinit.h>
|
||||
|
||||
#if defined(PIOS_INCLUDE_SPI)
|
||||
|
||||
#include <pios_spi_priv.h>
|
||||
|
||||
/* AHRS Interface
|
||||
*
|
||||
* NOTE: Leave this declared as const data so that it ends up in the
|
||||
* .rodata section (ie. Flash) rather than in the .bss section (RAM).
|
||||
*/
|
||||
void PIOS_SPI_ahrs_irq_handler(void);
|
||||
void DMA1_Channel4_IRQHandler() __attribute__ ((alias ("PIOS_SPI_ahrs_irq_handler")));
|
||||
void DMA1_Channel5_IRQHandler() __attribute__ ((alias ("PIOS_SPI_ahrs_irq_handler")));
|
||||
const struct pios_spi_cfg
|
||||
pios_spi_ahrs_cfg = {
|
||||
.regs = SPI2,
|
||||
.init = {
|
||||
.SPI_Mode = SPI_Mode_Master,
|
||||
.SPI_Direction = SPI_Direction_2Lines_FullDuplex,
|
||||
.SPI_DataSize = SPI_DataSize_8b,
|
||||
.SPI_NSS = SPI_NSS_Soft,
|
||||
.SPI_FirstBit = SPI_FirstBit_MSB,
|
||||
.SPI_CRCPolynomial = 7,
|
||||
.SPI_CPOL = SPI_CPOL_High,
|
||||
.SPI_CPHA = SPI_CPHA_2Edge,
|
||||
.SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_8,
|
||||
},
|
||||
.use_crc = TRUE,
|
||||
.dma = {
|
||||
.ahb_clk = RCC_AHBPeriph_DMA1,
|
||||
|
||||
.irq = {
|
||||
.flags = (DMA1_FLAG_TC4 | DMA1_FLAG_TE4 | DMA1_FLAG_HT4 | DMA1_FLAG_GL4),
|
||||
.init = {
|
||||
.NVIC_IRQChannel = DMA1_Channel4_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
|
||||
.rx = {
|
||||
.channel = DMA1_Channel4,
|
||||
.init = {
|
||||
.DMA_PeripheralBaseAddr = (uint32_t)&(SPI2->DR),
|
||||
.DMA_DIR = DMA_DIR_PeripheralSRC,
|
||||
.DMA_PeripheralInc = DMA_PeripheralInc_Disable,
|
||||
.DMA_MemoryInc = DMA_MemoryInc_Enable,
|
||||
.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte,
|
||||
.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte,
|
||||
.DMA_Mode = DMA_Mode_Normal,
|
||||
.DMA_Priority = DMA_Priority_Medium,
|
||||
.DMA_M2M = DMA_M2M_Disable,
|
||||
},
|
||||
},
|
||||
.tx = {
|
||||
.channel = DMA1_Channel5,
|
||||
.init = {
|
||||
.DMA_PeripheralBaseAddr = (uint32_t)&(SPI2->DR),
|
||||
.DMA_DIR = DMA_DIR_PeripheralDST,
|
||||
.DMA_PeripheralInc = DMA_PeripheralInc_Disable,
|
||||
.DMA_MemoryInc = DMA_MemoryInc_Enable,
|
||||
.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte,
|
||||
.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte,
|
||||
.DMA_Mode = DMA_Mode_Normal,
|
||||
.DMA_Priority = DMA_Priority_Medium,
|
||||
.DMA_M2M = DMA_M2M_Disable,
|
||||
},
|
||||
},
|
||||
}, .ssel = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_12,
|
||||
.GPIO_Speed = GPIO_Speed_50MHz,
|
||||
.GPIO_Mode = GPIO_Mode_Out_PP,
|
||||
},
|
||||
}, .sclk = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_13,
|
||||
.GPIO_Speed = GPIO_Speed_50MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF_PP,
|
||||
},
|
||||
}, .miso = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_14,
|
||||
.GPIO_Speed = GPIO_Speed_50MHz,
|
||||
.GPIO_Mode = GPIO_Mode_IN_FLOATING,
|
||||
},
|
||||
}, .mosi = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_15,
|
||||
.GPIO_Speed = GPIO_Speed_50MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF_PP,
|
||||
},
|
||||
}, };
|
||||
|
||||
uint32_t pios_spi_ahrs_id;
|
||||
void PIOS_SPI_ahrs_irq_handler(void) {
|
||||
/* Call into the generic code to handle the IRQ for this specific device */
|
||||
PIOS_SPI_IRQ_Handler(pios_spi_ahrs_id);
|
||||
}
|
||||
|
||||
#endif /* PIOS_INCLUDE_SPI */
|
||||
|
||||
#if defined(PIOS_INCLUDE_USART)
|
||||
|
||||
#include "pios_usart_priv.h"
|
||||
|
||||
/*
|
||||
* Telemetry USART
|
||||
*/
|
||||
const struct pios_usart_cfg pios_usart_telem_cfg = {
|
||||
.regs = USART2,
|
||||
.init = {
|
||||
#if defined (PIOS_COM_TELEM_BAUDRATE)
|
||||
.USART_BaudRate = PIOS_COM_TELEM_BAUDRATE,
|
||||
#else
|
||||
.USART_BaudRate = 57600,
|
||||
#endif
|
||||
.USART_WordLength = USART_WordLength_8b,
|
||||
.USART_Parity = USART_Parity_No,
|
||||
.USART_StopBits = USART_StopBits_1,
|
||||
.USART_HardwareFlowControl = USART_HardwareFlowControl_None,
|
||||
.USART_Mode = USART_Mode_Rx | USART_Mode_Tx,
|
||||
}, .irq = {
|
||||
.init = {
|
||||
.NVIC_IRQChannel = USART2_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
}, .rx = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_3,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_IPU,
|
||||
},
|
||||
}, .tx = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_2,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF_PP,
|
||||
},
|
||||
}, };
|
||||
|
||||
#endif /* PIOS_INCLUDE_USART */
|
||||
|
||||
#if defined(PIOS_INCLUDE_COM)
|
||||
|
||||
#include "pios_com_priv.h"
|
||||
|
||||
#define PIOS_COM_TELEM_USB_RX_BUF_LEN 192
|
||||
#define PIOS_COM_TELEM_USB_TX_BUF_LEN 192
|
||||
|
||||
static uint8_t pios_com_telem_usb_rx_buffer[PIOS_COM_TELEM_USB_RX_BUF_LEN];
|
||||
static uint8_t pios_com_telem_usb_tx_buffer[PIOS_COM_TELEM_USB_TX_BUF_LEN];
|
||||
|
||||
#define PIOS_COM_TELEM_RF_RX_BUF_LEN 192
|
||||
#define PIOS_COM_TELEM_RF_TX_BUF_LEN 192
|
||||
@ -196,34 +42,6 @@ static uint8_t pios_com_telem_usb_tx_buffer[PIOS_COM_TELEM_USB_TX_BUF_LEN];
|
||||
static uint8_t pios_com_telem_rf_rx_buffer[PIOS_COM_TELEM_RF_RX_BUF_LEN];
|
||||
static uint8_t pios_com_telem_rf_tx_buffer[PIOS_COM_TELEM_RF_TX_BUF_LEN];
|
||||
|
||||
#endif /* PIOS_INCLUDE_COM */
|
||||
|
||||
#if defined(PIOS_INCLUDE_USB)
|
||||
#include "pios_usb_priv.h"
|
||||
|
||||
static const struct pios_usb_cfg pios_usb_main_cfg = {
|
||||
.irq = {
|
||||
.init = {
|
||||
.NVIC_IRQChannel = USB_LP_CAN1_RX0_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_LOW,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
};
|
||||
#endif /* PIOS_INCLUDE_USB_HID */
|
||||
|
||||
#if defined(PIOS_INCLUDE_USB_HID)
|
||||
#include <pios_usb_hid_priv.h>
|
||||
|
||||
const struct pios_usb_hid_cfg pios_usb_hid_cfg = {
|
||||
.data_if = 0,
|
||||
.data_rx_ep = 1,
|
||||
.data_tx_ep = 1,
|
||||
};
|
||||
|
||||
#endif /* PIOS_INCLUDE_USB_HID */
|
||||
|
||||
uint32_t pios_com_telem_rf_id;
|
||||
uint32_t pios_com_telem_usb_id;
|
||||
|
||||
@ -265,22 +83,30 @@ void PIOS_Board_Init(void) {
|
||||
|
||||
PIOS_GPIO_Init();
|
||||
|
||||
#if defined(PIOS_INCLUDE_LED)
|
||||
PIOS_LED_Init(&pios_led_cfg);
|
||||
#endif /* PIOS_INCLUDE_LED */
|
||||
|
||||
#if defined(PIOS_INCLUDE_USB)
|
||||
/* Initialize board specific USB data */
|
||||
PIOS_USB_BOARD_DATA_Init();
|
||||
|
||||
/* Activate the HID-only USB configuration */
|
||||
PIOS_USB_DESC_HID_ONLY_Init();
|
||||
|
||||
uint32_t pios_usb_id;
|
||||
if (PIOS_USB_Init(&pios_usb_id, &pios_usb_main_cfg)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
#if defined(PIOS_INCLUDE_USB_HID) && defined(PIOS_INCLUDE_COM)
|
||||
#if defined(PIOS_INCLUDE_USB_HID) && defined(PIOS_INCLUDE_COM_MSG)
|
||||
uint32_t pios_usb_hid_id;
|
||||
if (PIOS_USB_HID_Init(&pios_usb_hid_id, &pios_usb_hid_cfg, pios_usb_id)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
if (PIOS_COM_Init(&pios_com_telem_usb_id, &pios_usb_hid_com_driver, pios_usb_hid_id,
|
||||
pios_com_telem_usb_rx_buffer, sizeof(pios_com_telem_usb_rx_buffer),
|
||||
pios_com_telem_usb_tx_buffer, sizeof(pios_com_telem_usb_tx_buffer))) {
|
||||
if (PIOS_COM_MSG_Init(&pios_com_telem_usb_id, &pios_usb_hid_com_driver, pios_usb_hid_id)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_USB_HID && PIOS_INCLUDE_COM */
|
||||
#endif /* PIOS_INCLUDE_USB_HID && PIOS_INCLUDE_COM_MSG */
|
||||
|
||||
#endif /* PIOS_INCLUDE_USB */
|
||||
|
||||
|
@ -29,9 +29,11 @@
|
||||
*/
|
||||
|
||||
#include "pios_usb_board_data.h" /* struct usb_*, USB_* */
|
||||
#include "pios_sys.h" /* PIOS_SYS_SerialNumberGet */
|
||||
#include "pios_usbhook.h" /* PIOS_USBHOOK_* */
|
||||
|
||||
const uint8_t PIOS_USB_BOARD_StringProductID[] = {
|
||||
sizeof(PIOS_USB_BOARD_StringProductID),
|
||||
static const uint8_t usb_product_id[20] = {
|
||||
sizeof(usb_product_id),
|
||||
USB_DESC_TYPE_STRING,
|
||||
'O', 0,
|
||||
'p', 0,
|
||||
@ -43,3 +45,75 @@ const uint8_t PIOS_USB_BOARD_StringProductID[] = {
|
||||
'o', 0,
|
||||
't', 0,
|
||||
};
|
||||
|
||||
static uint8_t usb_serial_number[52] = {
|
||||
sizeof(usb_serial_number),
|
||||
USB_DESC_TYPE_STRING,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0
|
||||
};
|
||||
|
||||
static const struct usb_string_langid usb_lang_id = {
|
||||
.bLength = sizeof(usb_lang_id),
|
||||
.bDescriptorType = USB_DESC_TYPE_STRING,
|
||||
.bLangID = htousbs(USB_LANGID_ENGLISH_UK),
|
||||
};
|
||||
|
||||
static const uint8_t usb_vendor_id[28] = {
|
||||
sizeof(usb_vendor_id),
|
||||
USB_DESC_TYPE_STRING,
|
||||
'o', 0,
|
||||
'p', 0,
|
||||
'e', 0,
|
||||
'n', 0,
|
||||
'p', 0,
|
||||
'i', 0,
|
||||
'l', 0,
|
||||
'o', 0,
|
||||
't', 0,
|
||||
'.', 0,
|
||||
'o', 0,
|
||||
'r', 0,
|
||||
'g', 0
|
||||
};
|
||||
|
||||
int32_t PIOS_USB_BOARD_DATA_Init(void)
|
||||
{
|
||||
/* Load device serial number into serial number string */
|
||||
uint8_t sn[25];
|
||||
PIOS_SYS_SerialNumberGet((char *)sn);
|
||||
for (uint8_t i = 0; sn[i] != '\0' && (2 * i) < usb_serial_number[0]; i++) {
|
||||
usb_serial_number[2 + 2 * i] = sn[i];
|
||||
}
|
||||
|
||||
PIOS_USBHOOK_RegisterString(USB_STRING_DESC_PRODUCT, (uint8_t *)&usb_product_id, sizeof(usb_product_id));
|
||||
PIOS_USBHOOK_RegisterString(USB_STRING_DESC_SERIAL, (uint8_t *)&usb_serial_number, sizeof(usb_serial_number));
|
||||
|
||||
PIOS_USBHOOK_RegisterString(USB_STRING_DESC_LANG, (uint8_t *)&usb_lang_id, sizeof(usb_lang_id));
|
||||
PIOS_USBHOOK_RegisterString(USB_STRING_DESC_VENDOR, (uint8_t *)&usb_vendor_id, sizeof(usb_vendor_id));
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
@ -115,7 +115,7 @@ SRC += $(PIOSCOMMON)/pios_usb_desc_hid_only.c
|
||||
|
||||
## PIOS Hardware (Common)
|
||||
SRC += $(PIOSCOMMON)/pios_board_info.c
|
||||
SRC += $(PIOSCOMMON)/pios_com.c
|
||||
SRC += $(PIOSCOMMON)/pios_com_msg.c
|
||||
SRC += $(PIOSCOMMON)/pios_bl_helper.c
|
||||
SRC += $(PIOSCOMMON)/pios_iap.c
|
||||
SRC += $(PIOSCOMMON)/printf-stdarg.c
|
||||
@ -287,7 +287,7 @@ CSTANDARD = -std=gnu99
|
||||
# Flags for C and C++ (arm-elf-gcc/arm-elf-g++)
|
||||
|
||||
ifeq ($(DEBUG),YES)
|
||||
CFLAGS = -DDEBUG
|
||||
CFLAGS += -DDEBUG
|
||||
endif
|
||||
|
||||
CFLAGS += -g$(DEBUGF)
|
||||
|
@ -38,9 +38,9 @@
|
||||
#define PIOS_INCLUDE_SYS
|
||||
#define PIOS_INCLUDE_USB
|
||||
#define PIOS_INCLUDE_USB_HID
|
||||
#define PIOS_INCLUDE_COM
|
||||
#define PIOS_INCLUDE_COM_MSG
|
||||
#define PIOS_INCLUDE_GPIO
|
||||
//#define DEBUG_SSP
|
||||
#define PIOS_INCLUDE_IAP
|
||||
|
||||
/* Defaults for Logging */
|
||||
#define LOG_FILENAME "PIOS.LOG"
|
||||
|
@ -37,33 +37,6 @@
|
||||
|
||||
#include "pios_usb_defs.h" /* struct usb_* */
|
||||
|
||||
struct usb_board_config {
|
||||
struct usb_configuration_desc config;
|
||||
struct usb_interface_desc hid_if;
|
||||
struct usb_hid_desc hid;
|
||||
struct usb_endpoint_desc hid_in;
|
||||
struct usb_endpoint_desc hid_out;
|
||||
} __attribute__((packed));
|
||||
|
||||
extern const struct usb_device_desc PIOS_USB_BOARD_DeviceDescriptor;
|
||||
extern const struct usb_board_config PIOS_USB_BOARD_Configuration;
|
||||
extern const struct usb_string_langid PIOS_USB_BOARD_StringLangID;
|
||||
|
||||
/* NOTE NOTE NOTE
|
||||
*
|
||||
* Care must be taken to ensure that the _actual_ contents of
|
||||
* these arrays (in each board's pios_usb_board_data.c) is no
|
||||
* smaller than the stated sizes here or these descriptors
|
||||
* will end up with trailing zeros on the wire.
|
||||
*
|
||||
* The compiler will catch any time that these definitions are
|
||||
* too small.
|
||||
*/
|
||||
extern const uint8_t PIOS_USB_BOARD_HidReportDescriptor[36];
|
||||
extern const uint8_t PIOS_USB_BOARD_StringVendorID[28];
|
||||
extern const uint8_t PIOS_USB_BOARD_StringProductID[20];
|
||||
extern uint8_t PIOS_USB_BOARD_StringSerial[52];
|
||||
|
||||
#define PIOS_USB_BOARD_PRODUCT_ID USB_PRODUCT_ID_PIPXTREME
|
||||
#define PIOS_USB_BOARD_DEVICE_VER USB_OP_DEVICE_VER(USB_OP_BOARD_ID_PIPXTREME, USB_OP_BOARD_MODE_BL)
|
||||
|
||||
|
@ -32,6 +32,7 @@
|
||||
#include "usb_lib.h"
|
||||
#include "pios_iap.h"
|
||||
#include "fifo_buffer.h"
|
||||
#include "pios_com_msg.h"
|
||||
/* Prototype of PIOS_Board_Init() function */
|
||||
extern void PIOS_Board_Init(void);
|
||||
extern void FLASH_Download();
|
||||
@ -62,19 +63,13 @@ uint8_t JumpToApp = FALSE;
|
||||
uint8_t GO_dfu = FALSE;
|
||||
uint8_t USB_connected = FALSE;
|
||||
uint8_t User_DFU_request = FALSE;
|
||||
static uint8_t mReceive_Buffer[64];
|
||||
static uint8_t mReceive_Buffer[63];
|
||||
/* Private function prototypes -----------------------------------------------*/
|
||||
uint32_t LedPWM(uint32_t pwm_period, uint32_t pwm_sweep_steps, uint32_t count);
|
||||
uint8_t processRX();
|
||||
void jump_to_app();
|
||||
|
||||
#define BLUE LED1
|
||||
#define RED LED4
|
||||
int main() {
|
||||
/* NOTE: Do NOT modify the following start-up sequence */
|
||||
/* Any new initialization functions should be added in OpenPilotInit() */
|
||||
|
||||
/* Brings up System using CMSIS functions, enables the LEDs. */
|
||||
PIOS_SYS_Init();
|
||||
if (BSL_HOLD_STATE == 0)
|
||||
USB_connected = TRUE;
|
||||
@ -116,7 +111,7 @@ int main() {
|
||||
case DFUidle:
|
||||
period1 = 5000;
|
||||
sweep_steps1 = 100;
|
||||
PIOS_LED_Off(RED);
|
||||
PIOS_LED_Off(PIOS_LED_ALARM);
|
||||
period2 = 0;
|
||||
break;
|
||||
case uploading:
|
||||
@ -128,12 +123,12 @@ int main() {
|
||||
case downloading:
|
||||
period1 = 2500;
|
||||
sweep_steps1 = 50;
|
||||
PIOS_LED_Off(RED);
|
||||
PIOS_LED_Off(PIOS_LED_ALARM);
|
||||
period2 = 0;
|
||||
break;
|
||||
case BLidle:
|
||||
period1 = 0;
|
||||
PIOS_LED_On(BLUE);
|
||||
PIOS_LED_On(PIOS_LED_HEARTBEAT);
|
||||
period2 = 0;
|
||||
break;
|
||||
default://error
|
||||
@ -145,19 +140,19 @@ int main() {
|
||||
|
||||
if (period1 != 0) {
|
||||
if (LedPWM(period1, sweep_steps1, stopwatch))
|
||||
PIOS_LED_On(BLUE);
|
||||
PIOS_LED_On(PIOS_LED_HEARTBEAT);
|
||||
else
|
||||
PIOS_LED_Off(BLUE);
|
||||
PIOS_LED_Off(PIOS_LED_HEARTBEAT);
|
||||
} else
|
||||
PIOS_LED_On(BLUE);
|
||||
PIOS_LED_On(PIOS_LED_HEARTBEAT);
|
||||
|
||||
if (period2 != 0) {
|
||||
if (LedPWM(period2, sweep_steps2, stopwatch))
|
||||
PIOS_LED_On(RED);
|
||||
PIOS_LED_On(PIOS_LED_ALARM);
|
||||
else
|
||||
PIOS_LED_Off(RED);
|
||||
PIOS_LED_Off(PIOS_LED_ALARM);
|
||||
} else
|
||||
PIOS_LED_Off(RED);
|
||||
PIOS_LED_Off(PIOS_LED_ALARM);
|
||||
|
||||
if (stopwatch > 50 * 1000 * 1000)
|
||||
stopwatch = 0;
|
||||
@ -181,7 +176,6 @@ void jump_to_app() {
|
||||
RCC_APB1PeriphResetCmd(0xffffffff, DISABLE);
|
||||
_SetCNTR(0); // clear interrupt mask
|
||||
_SetISTR(0); // clear all requests
|
||||
|
||||
JumpAddress = *(__IO uint32_t*) (bdinfo->fw_base + 4);
|
||||
Jump_To_Application = (pFunction) JumpAddress;
|
||||
/* Initialize user application's Stack Pointer */
|
||||
@ -204,7 +198,7 @@ uint32_t LedPWM(uint32_t pwm_period, uint32_t pwm_sweep_steps, uint32_t count) {
|
||||
}
|
||||
|
||||
uint8_t processRX() {
|
||||
if (PIOS_COM_ReceiveBuffer(PIOS_COM_TELEM_USB, mReceive_Buffer, 63, 0) == 63) {
|
||||
if (PIOS_COM_MSG_Receive(PIOS_COM_TELEM_USB, mReceive_Buffer, sizeof(mReceive_Buffer))) {
|
||||
processComand(mReceive_Buffer);
|
||||
}
|
||||
return TRUE;
|
||||
|
@ -30,11 +30,8 @@
|
||||
#include "pios.h"
|
||||
#include "op_dfu.h"
|
||||
#include "pios_bl_helper.h"
|
||||
#include "pios_com_msg.h"
|
||||
#include <pios_board_info.h>
|
||||
/* Private typedef -----------------------------------------------------------*/
|
||||
/* Private define ------------------------------------------------------------*/
|
||||
/* Private macro -------------------------------------------------------------*/
|
||||
/* Private variables ---------------------------------------------------------*/
|
||||
//programmable devices
|
||||
Device devicesTable[10];
|
||||
uint8_t numberOfDevices = 0;
|
||||
@ -102,33 +99,9 @@ void DataDownload(DownloadAction action) {
|
||||
currentProgrammingDestination)) {
|
||||
DeviceState = Last_operation_failed;
|
||||
}
|
||||
/*
|
||||
switch (currentProgrammingDestination) {
|
||||
case Remote_flash_via_spi:
|
||||
if (downType == Descript) {
|
||||
SendBuffer[6 + (x * 4)]
|
||||
= spi_dev_desc[(uint8_t) partoffset];
|
||||
SendBuffer[7 + (x * 4)] = spi_dev_desc[(uint8_t) partoffset
|
||||
+ 1];
|
||||
SendBuffer[8 + (x * 4)] = spi_dev_desc[(uint8_t) partoffset
|
||||
+ 2];
|
||||
SendBuffer[9 + (x * 4)] = spi_dev_desc[(uint8_t) partoffset
|
||||
+ 3];
|
||||
}
|
||||
break;
|
||||
case Self_flash:
|
||||
SendBuffer[6 + (x * 4)] = *PIOS_BL_HELPER_FLASH_If_Read(offset);
|
||||
SendBuffer[7 + (x * 4)] = *PIOS_BL_HELPER_FLASH_If_Read(offset + 1);
|
||||
SendBuffer[8 + (x * 4)] = *PIOS_BL_HELPER_FLASH_If_Read(offset + 2);
|
||||
SendBuffer[9 + (x * 4)] = *PIOS_BL_HELPER_FLASH_If_Read(offset + 3);
|
||||
break;
|
||||
}
|
||||
*/
|
||||
}
|
||||
//PIOS USB_SIL_Write(EP1_IN, (uint8_t*) SendBuffer, 64);
|
||||
downPacketCurrent = downPacketCurrent + 1;
|
||||
if (downPacketCurrent > downPacketTotal - 1) {
|
||||
// STM_EVAL_LEDOn(LED2);
|
||||
DeviceState = Last_operation_Success;
|
||||
Aditionals = (uint32_t) Download;
|
||||
}
|
||||
@ -168,7 +141,7 @@ void processComand(uint8_t *xReceive_Buffer) {
|
||||
case EnterDFU:
|
||||
if (((DeviceState == BLidle) && (Data0 < numberOfDevices))
|
||||
|| (DeviceState == DFUidle)) {
|
||||
if (Data0 > 0)//PORQUE???
|
||||
if (Data0 > 0)
|
||||
OPDfuIni(TRUE);
|
||||
DeviceState = DFUidle;
|
||||
currentProgrammingDestination = devicesTable[Data0].programmingType;
|
||||
@ -225,7 +198,7 @@ void processComand(uint8_t *xReceive_Buffer) {
|
||||
}
|
||||
}
|
||||
if (result != 1) {
|
||||
DeviceState = Last_operation_failed;//ok
|
||||
DeviceState = Last_operation_failed;
|
||||
Aditionals = (uint32_t) Command;
|
||||
} else {
|
||||
|
||||
@ -276,11 +249,9 @@ void processComand(uint8_t *xReceive_Buffer) {
|
||||
|
||||
++Next_Packet;
|
||||
} else {
|
||||
|
||||
DeviceState = wrong_packet_received;
|
||||
Aditionals = Count;
|
||||
}
|
||||
// FLASH_ProgramWord(MemLocations[TransferType]+4,++Next_Packet);//+Count,Data);
|
||||
} else {
|
||||
DeviceState = Last_operation_failed;
|
||||
Aditionals = (uint32_t) Command;
|
||||
@ -322,9 +293,12 @@ void processComand(uint8_t *xReceive_Buffer) {
|
||||
Buffer[15] = devicesTable[Data0 - 1].devID;
|
||||
}
|
||||
sendData(Buffer + 1, 63);
|
||||
//PIOS_COM_SendBuffer(PIOS_COM_TELEM_USB, Buffer + 1, 63);//FIX+1
|
||||
break;
|
||||
case JumpFW:
|
||||
if (Data == 0x5AFE) {
|
||||
/* Force board into safe mode */
|
||||
PIOS_IAP_WriteBootCount(0xFFFF);
|
||||
}
|
||||
FLASH_Lock();
|
||||
JumpToApp = 1;
|
||||
break;
|
||||
@ -351,7 +325,6 @@ void processComand(uint8_t *xReceive_Buffer) {
|
||||
DeviceState = too_few_packets;
|
||||
}
|
||||
}
|
||||
|
||||
break;
|
||||
case Download_Req:
|
||||
#ifdef DEBUG_SSP
|
||||
@ -474,9 +447,7 @@ uint32_t CalcFirmCRC() {
|
||||
|
||||
}
|
||||
void sendData(uint8_t * buf, uint16_t size) {
|
||||
PIOS_COM_SendBuffer(PIOS_COM_TELEM_USB, buf, size);
|
||||
if (DeviceState == downloading)
|
||||
PIOS_DELAY_WaitmS(10);
|
||||
PIOS_COM_MSG_Send(PIOS_COM_TELEM_USB, buf, size);
|
||||
}
|
||||
|
||||
bool flash_read(uint8_t * buffer, uint32_t adr, DFUProgType type) {
|
||||
|
@ -25,21 +25,64 @@
|
||||
|
||||
#include <pios.h>
|
||||
|
||||
// ***********************************************************************************
|
||||
#if defined(PIOS_INCLUDE_LED)
|
||||
|
||||
#if defined(PIOS_INCLUDE_COM)
|
||||
#include <pios_led_priv.h>
|
||||
static const struct pios_led pios_leds[] = {
|
||||
[PIOS_LED_USB] = {
|
||||
.pin = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_3,
|
||||
.GPIO_Mode = GPIO_Mode_Out_PP,
|
||||
.GPIO_Speed = GPIO_Speed_50MHz,
|
||||
},
|
||||
},
|
||||
},
|
||||
[PIOS_LED_LINK] = {
|
||||
.pin = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_5,
|
||||
.GPIO_Mode = GPIO_Mode_Out_PP,
|
||||
.GPIO_Speed = GPIO_Speed_50MHz,
|
||||
},
|
||||
},
|
||||
},
|
||||
[PIOS_LED_RX] = {
|
||||
.pin = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_6,
|
||||
.GPIO_Mode = GPIO_Mode_Out_PP,
|
||||
.GPIO_Speed = GPIO_Speed_50MHz,
|
||||
},
|
||||
},
|
||||
},
|
||||
[PIOS_LED_TX] = {
|
||||
.pin = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_7,
|
||||
.GPIO_Mode = GPIO_Mode_Out_PP,
|
||||
.GPIO_Speed = GPIO_Speed_50MHz,
|
||||
},
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
#include <pios_com_priv.h>
|
||||
static const struct pios_led_cfg pios_led_cfg = {
|
||||
.leds = pios_leds,
|
||||
.num_leds = NELEMENTS(pios_leds),
|
||||
};
|
||||
|
||||
#define PIOS_COM_TELEM_USB_RX_BUF_LEN 192
|
||||
#define PIOS_COM_TELEM_USB_TX_BUF_LEN 192
|
||||
#endif /* PIOS_INCLUDE_LED */
|
||||
|
||||
static uint8_t pios_com_telem_usb_rx_buffer[PIOS_COM_TELEM_USB_RX_BUF_LEN];
|
||||
static uint8_t pios_com_telem_usb_tx_buffer[PIOS_COM_TELEM_USB_TX_BUF_LEN];
|
||||
#if defined(PIOS_INCLUDE_COM_MSG)
|
||||
|
||||
#endif /* PIOS_INCLUDE_COM */
|
||||
#include <pios_com_msg_priv.h>
|
||||
|
||||
// ***********************************************************************************
|
||||
#endif /* PIOS_INCLUDE_COM_MSG */
|
||||
|
||||
#if defined(PIOS_INCLUDE_USB)
|
||||
#include "pios_usb_priv.h"
|
||||
@ -55,6 +98,9 @@ static const struct pios_usb_cfg pios_usb_main_cfg = {
|
||||
},
|
||||
};
|
||||
|
||||
#include "pios_usb_board_data_priv.h"
|
||||
#include "pios_usb_desc_hid_only_priv.h"
|
||||
|
||||
#endif /* PIOS_INCLUDE_USB */
|
||||
|
||||
#if defined(PIOS_INCLUDE_USB_HID)
|
||||
@ -94,21 +140,26 @@ void PIOS_Board_Init(void) {
|
||||
PIOS_GPIO_Init();
|
||||
|
||||
#if defined(PIOS_INCLUDE_USB)
|
||||
/* Initialize board specific USB data */
|
||||
PIOS_USB_BOARD_DATA_Init();
|
||||
|
||||
/* Activate the HID-only USB configuration */
|
||||
PIOS_USB_DESC_HID_ONLY_Init();
|
||||
|
||||
uint32_t pios_usb_id;
|
||||
if (PIOS_USB_Init(&pios_usb_id, &pios_usb_main_cfg)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
#if defined(PIOS_INCLUDE_USB_HID) && defined(PIOS_INCLUDE_COM)
|
||||
uint32_t pios_usb_com_id;
|
||||
if (PIOS_USB_HID_Init(&pios_usb_com_id, &pios_usb_hid_cfg, pios_usb_id)) {
|
||||
#if defined(PIOS_INCLUDE_USB_HID) && defined(PIOS_INCLUDE_COM_MSG)
|
||||
uint32_t pios_usb_hid_id;
|
||||
if (PIOS_USB_HID_Init(&pios_usb_hid_id, &pios_usb_hid_cfg, pios_usb_id)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
if (PIOS_COM_Init(&pios_com_telem_usb_id, &pios_usb_hid_com_driver, pios_usb_com_id,
|
||||
pios_com_telem_usb_rx_buffer, sizeof(pios_com_telem_usb_rx_buffer),
|
||||
pios_com_telem_usb_tx_buffer, sizeof(pios_com_telem_usb_tx_buffer))) {
|
||||
if (PIOS_COM_MSG_Init(&pios_com_telem_usb_id, &pios_usb_hid_com_driver, pios_usb_hid_id)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_USB_HID && PIOS_INCLUDE_COM */
|
||||
#endif /* PIOS_INCLUDE_USB_HID && PIOS_INCLUDE_COM_MSG */
|
||||
|
||||
#endif /* PIOS_INCLUDE_USB */
|
||||
|
||||
RCC_AHBPeriphClockCmd(RCC_AHBPeriph_CRC, ENABLE);//TODO Tirar
|
||||
|
@ -29,9 +29,11 @@
|
||||
*/
|
||||
|
||||
#include "pios_usb_board_data.h" /* struct usb_*, USB_* */
|
||||
#include "pios_sys.h" /* PIOS_SYS_SerialNumberGet */
|
||||
#include "pios_usbhook.h" /* PIOS_USBHOOK_* */
|
||||
|
||||
const uint8_t PIOS_USB_BOARD_StringProductID[] = {
|
||||
sizeof(PIOS_USB_BOARD_StringProductID),
|
||||
static const uint8_t usb_product_id[20] = {
|
||||
sizeof(usb_product_id),
|
||||
USB_DESC_TYPE_STRING,
|
||||
'P', 0,
|
||||
'i', 0,
|
||||
@ -44,3 +46,74 @@ const uint8_t PIOS_USB_BOARD_StringProductID[] = {
|
||||
'e', 0,
|
||||
};
|
||||
|
||||
static uint8_t usb_serial_number[52] = {
|
||||
sizeof(usb_serial_number),
|
||||
USB_DESC_TYPE_STRING,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0
|
||||
};
|
||||
|
||||
static const struct usb_string_langid usb_lang_id = {
|
||||
.bLength = sizeof(usb_lang_id),
|
||||
.bDescriptorType = USB_DESC_TYPE_STRING,
|
||||
.bLangID = htousbs(USB_LANGID_ENGLISH_UK),
|
||||
};
|
||||
|
||||
static const uint8_t usb_vendor_id[28] = {
|
||||
sizeof(usb_vendor_id),
|
||||
USB_DESC_TYPE_STRING,
|
||||
'o', 0,
|
||||
'p', 0,
|
||||
'e', 0,
|
||||
'n', 0,
|
||||
'p', 0,
|
||||
'i', 0,
|
||||
'l', 0,
|
||||
'o', 0,
|
||||
't', 0,
|
||||
'.', 0,
|
||||
'o', 0,
|
||||
'r', 0,
|
||||
'g', 0
|
||||
};
|
||||
|
||||
int32_t PIOS_USB_BOARD_DATA_Init(void)
|
||||
{
|
||||
/* Load device serial number into serial number string */
|
||||
uint8_t sn[25];
|
||||
PIOS_SYS_SerialNumberGet((char *)sn);
|
||||
for (uint8_t i = 0; sn[i] != '\0' && (2 * i) < usb_serial_number[0]; i++) {
|
||||
usb_serial_number[2 + 2 * i] = sn[i];
|
||||
}
|
||||
|
||||
PIOS_USBHOOK_RegisterString(USB_STRING_DESC_PRODUCT, (uint8_t *)&usb_product_id, sizeof(usb_product_id));
|
||||
PIOS_USBHOOK_RegisterString(USB_STRING_DESC_SERIAL, (uint8_t *)&usb_serial_number, sizeof(usb_serial_number));
|
||||
|
||||
PIOS_USBHOOK_RegisterString(USB_STRING_DESC_LANG, (uint8_t *)&usb_lang_id, sizeof(usb_lang_id));
|
||||
PIOS_USBHOOK_RegisterString(USB_STRING_DESC_VENDOR, (uint8_t *)&usb_vendor_id, sizeof(usb_vendor_id));
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
@ -50,7 +50,7 @@ ENABLE_AUX_UART ?= NO
|
||||
|
||||
USE_GPS ?= YES
|
||||
|
||||
USE_I2C ?= NO
|
||||
USE_I2C ?= YES
|
||||
|
||||
# Set to YES when using Code Sourcery toolchain
|
||||
CODE_SOURCERY ?= YES
|
||||
@ -65,7 +65,7 @@ endif
|
||||
FLASH_TOOL = OPENOCD
|
||||
|
||||
# List of modules to include
|
||||
OPTMODULES = CameraStab ComUsbBridge
|
||||
OPTMODULES = CameraStab ComUsbBridge Altitude
|
||||
ifeq ($(USE_GPS), YES)
|
||||
OPTMODULES += GPS
|
||||
endif
|
||||
@ -121,6 +121,7 @@ PYMITEINC += $(PYMITEPLAT)
|
||||
PYMITEINC += $(OUTDIR)
|
||||
FLIGHTPLANLIB = $(OPMODULEDIR)/FlightPlan/lib
|
||||
FLIGHTPLANS = $(OPMODULEDIR)/FlightPlan/flightplans
|
||||
HWDEFSINC = ../board_hw_defs/$(BOARD_NAME)
|
||||
|
||||
OPUAVSYNTHDIR = $(OUTDIR)/../uavobject-synthetics/flight
|
||||
|
||||
@ -136,7 +137,6 @@ SRC += ${OPMODULEDIR}/System/systemmod.c
|
||||
SRC += $(OPSYSTEM)/coptercontrol.c
|
||||
SRC += $(OPSYSTEM)/pios_board.c
|
||||
SRC += $(OPSYSTEM)/alarms.c
|
||||
SRC += $(OPSYSTEM)/taskmonitor.c
|
||||
SRC += $(OPUAVTALK)/uavtalk.c
|
||||
SRC += $(OPUAVOBJ)/uavobjectmanager.c
|
||||
SRC += $(OPUAVOBJ)/eventdispatcher.c
|
||||
@ -182,6 +182,7 @@ SRC += $(OPUAVSYNTHDIR)/receiveractivity.c
|
||||
SRC += $(OPUAVSYNTHDIR)/taskinfo.c
|
||||
SRC += $(OPUAVSYNTHDIR)/mixerstatus.c
|
||||
SRC += $(OPUAVSYNTHDIR)/ratedesired.c
|
||||
SRC += $(OPUAVSYNTHDIR)/baroaltitude.c
|
||||
|
||||
endif
|
||||
|
||||
@ -216,6 +217,7 @@ SRC += $(PIOSSTM32F10X)/pios_usb_hid_istr.c
|
||||
SRC += $(PIOSSTM32F10X)/pios_usb_hid_pwr.c
|
||||
SRC += $(OPSYSTEM)/pios_usb_board_data.c
|
||||
SRC += $(PIOSCOMMON)/pios_usb_desc_hid_cdc.c
|
||||
SRC += $(PIOSCOMMON)/pios_usb_desc_hid_only.c
|
||||
|
||||
## PIOS Hardware (Common)
|
||||
SRC += $(PIOSCOMMON)/pios_crc.c
|
||||
@ -224,6 +226,7 @@ SRC += $(PIOSCOMMON)/pios_flash_w25x.c
|
||||
SRC += $(PIOSCOMMON)/pios_adxl345.c
|
||||
SRC += $(PIOSCOMMON)/pios_com.c
|
||||
SRC += $(PIOSCOMMON)/pios_i2c_esc.c
|
||||
SRC += $(PIOSCOMMON)/pios_bmp085.c
|
||||
SRC += $(PIOSCOMMON)/pios_iap.c
|
||||
SRC += $(PIOSCOMMON)/pios_bl_helper.c
|
||||
SRC += $(PIOSCOMMON)/pios_rcvr.c
|
||||
@ -232,6 +235,7 @@ SRC += $(PIOSCOMMON)/printf-stdarg.c
|
||||
## Libraries for flight calculations
|
||||
SRC += $(FLIGHTLIB)/fifo_buffer.c
|
||||
SRC += $(FLIGHTLIB)/CoordinateConversions.c
|
||||
SRC += $(FLIGHTLIB)/taskmonitor.c
|
||||
|
||||
## CMSIS for STM32
|
||||
SRC += $(CMSISDIR)/core_cm3.c
|
||||
@ -345,6 +349,7 @@ EXTRAINCDIRS += $(APPLIBDIR)
|
||||
EXTRAINCDIRS += $(RTOSSRCDIR)/portable/GCC/ARM_CM3
|
||||
EXTRAINCDIRS += $(AHRSBOOTLOADERINC)
|
||||
EXTRAINCDIRS += $(PYMITEINC)
|
||||
EXTRAINCDIRS += $(HWDEFSINC)
|
||||
|
||||
EXTRAINCDIRS += ${foreach MOD, ${OPTMODULES} ${MODULES}, ${OPMODULEDIR}/${MOD}/inc} ${OPMODULEDIR}/System/inc
|
||||
|
||||
@ -409,6 +414,9 @@ ifeq ($(USE_I2C), YES)
|
||||
CDEFS += -DUSE_I2C
|
||||
endif
|
||||
|
||||
# Declare all non-optional modules as built-in to force inclusion
|
||||
CDEFS += ${foreach MOD, ${MODULES}, -DMODULE_$(MOD)_BUILTIN }
|
||||
|
||||
# Place project-specific -D and/or -U options for
|
||||
# Assembler with preprocessor here.
|
||||
#ADEFS = -DUSE_IRQ_ASM_WRAPPER
|
||||
@ -435,15 +443,15 @@ CSTANDARD = -std=gnu99
|
||||
# Flags for C and C++ (arm-elf-gcc/arm-elf-g++)
|
||||
|
||||
ifeq ($(DEBUG),YES)
|
||||
CFLAGS = -DDEBUG
|
||||
CFLAGS += -DDEBUG
|
||||
endif
|
||||
|
||||
ifeq ($(DIAGNOSTICS),YES)
|
||||
CFLAGS = -DDIAGNOSTICS
|
||||
CFLAGS += -DDIAGNOSTICS
|
||||
endif
|
||||
|
||||
ifeq ($(DIAG_TASKS),YES)
|
||||
CFLAGS = -DDIAG_TASKS
|
||||
CFLAGS += -DDIAG_TASKS
|
||||
endif
|
||||
|
||||
CFLAGS += -g$(DEBUGF)
|
||||
|
@ -72,7 +72,9 @@ int main()
|
||||
|
||||
#ifdef ERASE_FLASH
|
||||
PIOS_Flash_W25X_EraseChip();
|
||||
PIOS_LED_Off(LED1);
|
||||
#if defined(PIOS_LED_HEARTBEAT)
|
||||
PIOS_LED_Off(PIOS_LED_HEARTBEAT);
|
||||
#endif /* PIOS_LED_HEARTBEAT */
|
||||
while (1) ;
|
||||
#endif
|
||||
|
||||
@ -88,13 +90,14 @@ int main()
|
||||
/* If all is well we will never reach here as the scheduler will now be running. */
|
||||
|
||||
/* Do some indication to user that something bad just happened */
|
||||
PIOS_LED_Off(LED1);
|
||||
while (1) {
|
||||
PIOS_LED_Toggle(LED1);
|
||||
#if defined(PIOS_LED_HEARTBEAT)
|
||||
PIOS_LED_Toggle(PIOS_LED_HEARTBEAT);
|
||||
#endif /* PIOS_LED_HEARTBEAT */
|
||||
PIOS_DELAY_WaitmS(100);
|
||||
}
|
||||
|
||||
return 0;
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
|
@ -42,6 +42,8 @@
|
||||
#endif
|
||||
#define PIOS_INCLUDE_IRQ
|
||||
#define PIOS_INCLUDE_LED
|
||||
#define PIOS_INCLUDE_IAP
|
||||
#define PIOS_INCLUDE_TIM
|
||||
|
||||
#define PIOS_INCLUDE_RCVR
|
||||
|
||||
@ -76,13 +78,11 @@
|
||||
#define PIOS_INCLUDE_ADXL345
|
||||
#define PIOS_INCLUDE_FLASH
|
||||
|
||||
#define PIOS_INCLUDE_BMP085
|
||||
|
||||
/* A really shitty setting saving implementation */
|
||||
#define PIOS_INCLUDE_FLASH_SECTOR_SETTINGS
|
||||
|
||||
/* Defaults for Logging */
|
||||
#define LOG_FILENAME "PIOS.LOG"
|
||||
#define STARTUP_LOG_ENABLED 1
|
||||
|
||||
/* Alarm Thresholds */
|
||||
#define HEAP_LIMIT_WARNING 220
|
||||
#define HEAP_LIMIT_CRITICAL 40
|
||||
|
@ -37,44 +37,7 @@
|
||||
|
||||
#define PIOS_USB_BOARD_EP_NUM 4
|
||||
|
||||
#include "pios_usb_defs.h" /* struct usb_* */
|
||||
|
||||
struct usb_board_config {
|
||||
struct usb_configuration_desc config;
|
||||
struct usb_interface_association_desc iad;
|
||||
struct usb_interface_desc hid_if;
|
||||
struct usb_hid_desc hid;
|
||||
struct usb_endpoint_desc hid_in;
|
||||
struct usb_endpoint_desc hid_out;
|
||||
struct usb_interface_desc cdc_control_if;
|
||||
struct usb_cdc_header_func_desc cdc_header;
|
||||
struct usb_cdc_callmgmt_func_desc cdc_callmgmt;
|
||||
struct usb_cdc_acm_func_desc cdc_acm;
|
||||
struct usb_cdc_union_func_desc cdc_union;
|
||||
struct usb_endpoint_desc cdc_mgmt_in;
|
||||
struct usb_interface_desc cdc_data_if;
|
||||
struct usb_endpoint_desc cdc_in;
|
||||
struct usb_endpoint_desc cdc_out;
|
||||
} __attribute__((packed));
|
||||
|
||||
extern const struct usb_device_desc PIOS_USB_BOARD_DeviceDescriptor;
|
||||
extern const struct usb_board_config PIOS_USB_BOARD_Configuration;
|
||||
extern const struct usb_string_langid PIOS_USB_BOARD_StringLangID;
|
||||
|
||||
/* NOTE NOTE NOTE
|
||||
*
|
||||
* Care must be taken to ensure that the _actual_ contents of
|
||||
* these arrays (in each board's pios_usb_board_data.c) is no
|
||||
* smaller than the stated sizes here or these descriptors
|
||||
* will end up with trailing zeros on the wire.
|
||||
*
|
||||
* The compiler will catch any time that these definitions are
|
||||
* too small.
|
||||
*/
|
||||
extern const uint8_t PIOS_USB_BOARD_HidReportDescriptor[36];
|
||||
extern const uint8_t PIOS_USB_BOARD_StringVendorID[28];
|
||||
extern const uint8_t PIOS_USB_BOARD_StringProductID[28];
|
||||
extern uint8_t PIOS_USB_BOARD_StringSerial[52];
|
||||
#include "pios_usb_defs.h" /* USB_* macros */
|
||||
|
||||
#define PIOS_USB_BOARD_PRODUCT_ID USB_PRODUCT_ID_COPTERCONTROL
|
||||
#define PIOS_USB_BOARD_DEVICE_VER USB_OP_DEVICE_VER(USB_OP_BOARD_ID_COPTERCONTROL, USB_OP_BOARD_MODE_FW)
|
||||
|
@ -27,6 +27,15 @@
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
|
||||
/* Pull in the board-specific static HW definitions.
|
||||
* Including .c files is a bit ugly but this allows all of
|
||||
* the HW definitions to be const and static to limit their
|
||||
* scope.
|
||||
*
|
||||
* NOTE: THIS IS THE ONLY PLACE THAT SHOULD EVER INCLUDE THIS FILE
|
||||
*/
|
||||
#include "board_hw_defs.c"
|
||||
|
||||
#include <pios.h>
|
||||
#include <openpilot.h>
|
||||
#include <uavobjectsinit.h>
|
||||
@ -34,751 +43,11 @@
|
||||
#include <manualcontrolsettings.h>
|
||||
#include <gcsreceiver.h>
|
||||
|
||||
#if defined(PIOS_INCLUDE_SPI)
|
||||
|
||||
#include <pios_spi_priv.h>
|
||||
|
||||
/* Flash/Accel Interface
|
||||
*
|
||||
* NOTE: Leave this declared as const data so that it ends up in the
|
||||
* .rodata section (ie. Flash) rather than in the .bss section (RAM).
|
||||
/* One slot per selectable receiver group.
|
||||
* eg. PWM, PPM, GCS, DSMMAINPORT, DSMFLEXIPORT, SBUS
|
||||
* NOTE: No slot in this map for NONE.
|
||||
*/
|
||||
void PIOS_SPI_flash_accel_irq_handler(void);
|
||||
void DMA1_Channel4_IRQHandler() __attribute__ ((alias ("PIOS_SPI_flash_accel_irq_handler")));
|
||||
void DMA1_Channel5_IRQHandler() __attribute__ ((alias ("PIOS_SPI_flash_accel_irq_handler")));
|
||||
static const struct pios_spi_cfg pios_spi_flash_accel_cfg = {
|
||||
.regs = SPI2,
|
||||
.init = {
|
||||
.SPI_Mode = SPI_Mode_Master,
|
||||
.SPI_Direction = SPI_Direction_2Lines_FullDuplex,
|
||||
.SPI_DataSize = SPI_DataSize_8b,
|
||||
.SPI_NSS = SPI_NSS_Soft,
|
||||
.SPI_FirstBit = SPI_FirstBit_MSB,
|
||||
.SPI_CRCPolynomial = 7,
|
||||
.SPI_CPOL = SPI_CPOL_High,
|
||||
.SPI_CPHA = SPI_CPHA_2Edge,
|
||||
.SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_2,
|
||||
},
|
||||
.use_crc = FALSE,
|
||||
.dma = {
|
||||
.ahb_clk = RCC_AHBPeriph_DMA1,
|
||||
|
||||
.irq = {
|
||||
.flags = (DMA1_FLAG_TC4 | DMA1_FLAG_TE4 | DMA1_FLAG_HT4 | DMA1_FLAG_GL4),
|
||||
.init = {
|
||||
.NVIC_IRQChannel = DMA1_Channel4_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
|
||||
.rx = {
|
||||
.channel = DMA1_Channel4,
|
||||
.init = {
|
||||
.DMA_PeripheralBaseAddr = (uint32_t)&(SPI2->DR),
|
||||
.DMA_DIR = DMA_DIR_PeripheralSRC,
|
||||
.DMA_PeripheralInc = DMA_PeripheralInc_Disable,
|
||||
.DMA_MemoryInc = DMA_MemoryInc_Enable,
|
||||
.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte,
|
||||
.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte,
|
||||
.DMA_Mode = DMA_Mode_Normal,
|
||||
.DMA_Priority = DMA_Priority_High,
|
||||
.DMA_M2M = DMA_M2M_Disable,
|
||||
},
|
||||
},
|
||||
.tx = {
|
||||
.channel = DMA1_Channel5,
|
||||
.init = {
|
||||
.DMA_PeripheralBaseAddr = (uint32_t)&(SPI2->DR),
|
||||
.DMA_DIR = DMA_DIR_PeripheralDST,
|
||||
.DMA_PeripheralInc = DMA_PeripheralInc_Disable,
|
||||
.DMA_MemoryInc = DMA_MemoryInc_Enable,
|
||||
.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte,
|
||||
.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte,
|
||||
.DMA_Mode = DMA_Mode_Normal,
|
||||
.DMA_Priority = DMA_Priority_High,
|
||||
.DMA_M2M = DMA_M2M_Disable,
|
||||
},
|
||||
},
|
||||
},
|
||||
.ssel = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_12,
|
||||
.GPIO_Speed = GPIO_Speed_10MHz,
|
||||
.GPIO_Mode = GPIO_Mode_Out_PP,
|
||||
},
|
||||
},
|
||||
.sclk = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_13,
|
||||
.GPIO_Speed = GPIO_Speed_10MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF_PP,
|
||||
},
|
||||
},
|
||||
.miso = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_14,
|
||||
.GPIO_Speed = GPIO_Speed_10MHz,
|
||||
.GPIO_Mode = GPIO_Mode_IN_FLOATING,
|
||||
},
|
||||
},
|
||||
.mosi = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_15,
|
||||
.GPIO_Speed = GPIO_Speed_10MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF_PP,
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
static uint32_t pios_spi_flash_accel_id;
|
||||
void PIOS_SPI_flash_accel_irq_handler(void)
|
||||
{
|
||||
/* Call into the generic code to handle the IRQ for this specific device */
|
||||
PIOS_SPI_IRQ_Handler(pios_spi_flash_accel_id);
|
||||
}
|
||||
|
||||
#endif /* PIOS_INCLUDE_SPI */
|
||||
|
||||
/*
|
||||
* ADC system
|
||||
*/
|
||||
#include "pios_adc_priv.h"
|
||||
extern void PIOS_ADC_handler(void);
|
||||
void DMA1_Channel1_IRQHandler() __attribute__ ((alias("PIOS_ADC_handler")));
|
||||
// Remap the ADC DMA handler to this one
|
||||
static const struct pios_adc_cfg pios_adc_cfg = {
|
||||
.dma = {
|
||||
.ahb_clk = RCC_AHBPeriph_DMA1,
|
||||
.irq = {
|
||||
.flags = (DMA1_FLAG_TC1 | DMA1_FLAG_TE1 | DMA1_FLAG_HT1 | DMA1_FLAG_GL1),
|
||||
.init = {
|
||||
.NVIC_IRQChannel = DMA1_Channel1_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
.rx = {
|
||||
.channel = DMA1_Channel1,
|
||||
.init = {
|
||||
.DMA_PeripheralBaseAddr = (uint32_t) & ADC1->DR,
|
||||
.DMA_DIR = DMA_DIR_PeripheralSRC,
|
||||
.DMA_PeripheralInc = DMA_PeripheralInc_Disable,
|
||||
.DMA_MemoryInc = DMA_MemoryInc_Enable,
|
||||
.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Word,
|
||||
.DMA_MemoryDataSize = DMA_MemoryDataSize_Word,
|
||||
.DMA_Mode = DMA_Mode_Circular,
|
||||
.DMA_Priority = DMA_Priority_High,
|
||||
.DMA_M2M = DMA_M2M_Disable,
|
||||
},
|
||||
}
|
||||
},
|
||||
.half_flag = DMA1_IT_HT1,
|
||||
.full_flag = DMA1_IT_TC1,
|
||||
};
|
||||
|
||||
struct pios_adc_dev pios_adc_devs[] = {
|
||||
{
|
||||
.cfg = &pios_adc_cfg,
|
||||
.callback_function = NULL,
|
||||
},
|
||||
};
|
||||
|
||||
uint8_t pios_adc_num_devices = NELEMENTS(pios_adc_devs);
|
||||
|
||||
void PIOS_ADC_handler() {
|
||||
PIOS_ADC_DMA_Handler();
|
||||
}
|
||||
|
||||
#include "pios_tim_priv.h"
|
||||
|
||||
static const TIM_TimeBaseInitTypeDef tim_1_2_3_4_time_base = {
|
||||
.TIM_Prescaler = (PIOS_MASTER_CLOCK / 1000000) - 1,
|
||||
.TIM_ClockDivision = TIM_CKD_DIV1,
|
||||
.TIM_CounterMode = TIM_CounterMode_Up,
|
||||
.TIM_Period = ((1000000 / PIOS_SERVO_UPDATE_HZ) - 1),
|
||||
.TIM_RepetitionCounter = 0x0000,
|
||||
};
|
||||
|
||||
static const struct pios_tim_clock_cfg tim_1_cfg = {
|
||||
.timer = TIM1,
|
||||
.time_base_init = &tim_1_2_3_4_time_base,
|
||||
.irq = {
|
||||
.init = {
|
||||
.NVIC_IRQChannel = TIM1_CC_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
static const struct pios_tim_clock_cfg tim_2_cfg = {
|
||||
.timer = TIM2,
|
||||
.time_base_init = &tim_1_2_3_4_time_base,
|
||||
.irq = {
|
||||
.init = {
|
||||
.NVIC_IRQChannel = TIM2_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
static const struct pios_tim_clock_cfg tim_3_cfg = {
|
||||
.timer = TIM3,
|
||||
.time_base_init = &tim_1_2_3_4_time_base,
|
||||
.irq = {
|
||||
.init = {
|
||||
.NVIC_IRQChannel = TIM3_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
static const struct pios_tim_clock_cfg tim_4_cfg = {
|
||||
.timer = TIM4,
|
||||
.time_base_init = &tim_1_2_3_4_time_base,
|
||||
.irq = {
|
||||
.init = {
|
||||
.NVIC_IRQChannel = TIM4_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
static const struct pios_tim_channel pios_tim_rcvrport_all_channels[] = {
|
||||
{
|
||||
.timer = TIM4,
|
||||
.timer_chan = TIM_Channel_1,
|
||||
.pin = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_6,
|
||||
.GPIO_Mode = GPIO_Mode_IPD,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
},
|
||||
},
|
||||
},
|
||||
{
|
||||
.timer = TIM3,
|
||||
.timer_chan = TIM_Channel_2,
|
||||
.pin = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_5,
|
||||
.GPIO_Mode = GPIO_Mode_IPD,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
},
|
||||
},
|
||||
.remap = GPIO_PartialRemap_TIM3,
|
||||
},
|
||||
{
|
||||
.timer = TIM3,
|
||||
.timer_chan = TIM_Channel_3,
|
||||
.pin = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_0,
|
||||
.GPIO_Mode = GPIO_Mode_IPD,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
},
|
||||
},
|
||||
},
|
||||
{
|
||||
.timer = TIM3,
|
||||
.timer_chan = TIM_Channel_4,
|
||||
.pin = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_1,
|
||||
.GPIO_Mode = GPIO_Mode_IPD,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
},
|
||||
},
|
||||
},
|
||||
{
|
||||
.timer = TIM2,
|
||||
.timer_chan = TIM_Channel_1,
|
||||
.pin = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_0,
|
||||
.GPIO_Mode = GPIO_Mode_IPD,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
},
|
||||
},
|
||||
},
|
||||
{
|
||||
.timer = TIM2,
|
||||
.timer_chan = TIM_Channel_2,
|
||||
.pin = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_1,
|
||||
.GPIO_Mode = GPIO_Mode_IPD,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
},
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
static const struct pios_tim_channel pios_tim_servoport_all_pins[] = {
|
||||
{
|
||||
.timer = TIM4,
|
||||
.timer_chan = TIM_Channel_4,
|
||||
.pin = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_9,
|
||||
.GPIO_Mode = GPIO_Mode_AF_PP,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
},
|
||||
},
|
||||
},
|
||||
{
|
||||
.timer = TIM4,
|
||||
.timer_chan = TIM_Channel_3,
|
||||
.pin = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_8,
|
||||
.GPIO_Mode = GPIO_Mode_AF_PP,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
},
|
||||
},
|
||||
},
|
||||
{
|
||||
.timer = TIM4,
|
||||
.timer_chan = TIM_Channel_2,
|
||||
.pin = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_7,
|
||||
.GPIO_Mode = GPIO_Mode_AF_PP,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
},
|
||||
},
|
||||
},
|
||||
{
|
||||
.timer = TIM1,
|
||||
.timer_chan = TIM_Channel_1,
|
||||
.pin = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_8,
|
||||
.GPIO_Mode = GPIO_Mode_AF_PP,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
},
|
||||
},
|
||||
},
|
||||
{
|
||||
.timer = TIM3,
|
||||
.timer_chan = TIM_Channel_1,
|
||||
.pin = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_4,
|
||||
.GPIO_Mode = GPIO_Mode_AF_PP,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
},
|
||||
},
|
||||
.remap = GPIO_PartialRemap_TIM3,
|
||||
},
|
||||
{
|
||||
.timer = TIM2,
|
||||
.timer_chan = TIM_Channel_3,
|
||||
.pin = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_2,
|
||||
.GPIO_Mode = GPIO_Mode_AF_PP,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
},
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
|
||||
static const struct pios_tim_channel pios_tim_servoport_rcvrport_pins[] = {
|
||||
{
|
||||
.timer = TIM4,
|
||||
.timer_chan = TIM_Channel_4,
|
||||
.pin = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_9,
|
||||
.GPIO_Mode = GPIO_Mode_AF_PP,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
},
|
||||
},
|
||||
},
|
||||
{
|
||||
.timer = TIM4,
|
||||
.timer_chan = TIM_Channel_3,
|
||||
.pin = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_8,
|
||||
.GPIO_Mode = GPIO_Mode_AF_PP,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
},
|
||||
},
|
||||
},
|
||||
{
|
||||
.timer = TIM4,
|
||||
.timer_chan = TIM_Channel_2,
|
||||
.pin = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_7,
|
||||
.GPIO_Mode = GPIO_Mode_AF_PP,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
},
|
||||
},
|
||||
},
|
||||
{
|
||||
.timer = TIM1,
|
||||
.timer_chan = TIM_Channel_1,
|
||||
.pin = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_8,
|
||||
.GPIO_Mode = GPIO_Mode_AF_PP,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
},
|
||||
},
|
||||
},
|
||||
{
|
||||
.timer = TIM3,
|
||||
.timer_chan = TIM_Channel_1,
|
||||
.pin = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_4,
|
||||
.GPIO_Mode = GPIO_Mode_AF_PP,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
},
|
||||
},
|
||||
.remap = GPIO_PartialRemap_TIM3,
|
||||
},
|
||||
{
|
||||
.timer = TIM2,
|
||||
.timer_chan = TIM_Channel_3,
|
||||
.pin = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_2,
|
||||
.GPIO_Mode = GPIO_Mode_AF_PP,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
},
|
||||
},
|
||||
},
|
||||
|
||||
// Receiver port pins
|
||||
// S3-S6 inputs are used as outputs in this case
|
||||
{
|
||||
.timer = TIM3,
|
||||
.timer_chan = TIM_Channel_3,
|
||||
.pin = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_0,
|
||||
.GPIO_Mode = GPIO_Mode_AF_PP,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
},
|
||||
},
|
||||
},
|
||||
{
|
||||
.timer = TIM3,
|
||||
.timer_chan = TIM_Channel_4,
|
||||
.pin = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_1,
|
||||
.GPIO_Mode = GPIO_Mode_AF_PP,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
},
|
||||
},
|
||||
},
|
||||
{
|
||||
.timer = TIM2,
|
||||
.timer_chan = TIM_Channel_1,
|
||||
.pin = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_0,
|
||||
.GPIO_Mode = GPIO_Mode_AF_PP,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
},
|
||||
},
|
||||
},
|
||||
{
|
||||
.timer = TIM2,
|
||||
.timer_chan = TIM_Channel_2,
|
||||
.pin = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_1,
|
||||
.GPIO_Mode = GPIO_Mode_AF_PP,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
},
|
||||
},
|
||||
},
|
||||
};
|
||||
#if defined(PIOS_INCLUDE_USART)
|
||||
|
||||
#include "pios_usart_priv.h"
|
||||
|
||||
static const struct pios_usart_cfg pios_usart_generic_main_cfg = {
|
||||
.regs = USART1,
|
||||
.init = {
|
||||
.USART_BaudRate = 57600,
|
||||
.USART_WordLength = USART_WordLength_8b,
|
||||
.USART_Parity = USART_Parity_No,
|
||||
.USART_StopBits = USART_StopBits_1,
|
||||
.USART_HardwareFlowControl = USART_HardwareFlowControl_None,
|
||||
.USART_Mode = USART_Mode_Rx | USART_Mode_Tx,
|
||||
},
|
||||
.irq = {
|
||||
.init = {
|
||||
.NVIC_IRQChannel = USART1_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
.rx = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_10,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_IPU,
|
||||
},
|
||||
},
|
||||
.tx = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_9,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF_PP,
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
static const struct pios_usart_cfg pios_usart_generic_flexi_cfg = {
|
||||
.regs = USART3,
|
||||
.init = {
|
||||
.USART_BaudRate = 57600,
|
||||
.USART_WordLength = USART_WordLength_8b,
|
||||
.USART_Parity = USART_Parity_No,
|
||||
.USART_StopBits = USART_StopBits_1,
|
||||
.USART_HardwareFlowControl = USART_HardwareFlowControl_None,
|
||||
.USART_Mode = USART_Mode_Rx | USART_Mode_Tx,
|
||||
},
|
||||
.irq = {
|
||||
.init = {
|
||||
.NVIC_IRQChannel = USART3_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
.rx = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_11,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_IPU,
|
||||
},
|
||||
},
|
||||
.tx = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_10,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF_PP,
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
#if defined(PIOS_INCLUDE_DSM)
|
||||
/*
|
||||
* Spektrum/JR DSM USART
|
||||
*/
|
||||
#include <pios_dsm_priv.h>
|
||||
|
||||
static const struct pios_usart_cfg pios_usart_dsm_main_cfg = {
|
||||
.regs = USART1,
|
||||
.init = {
|
||||
.USART_BaudRate = 115200,
|
||||
.USART_WordLength = USART_WordLength_8b,
|
||||
.USART_Parity = USART_Parity_No,
|
||||
.USART_StopBits = USART_StopBits_1,
|
||||
.USART_HardwareFlowControl = USART_HardwareFlowControl_None,
|
||||
.USART_Mode = USART_Mode_Rx,
|
||||
},
|
||||
.irq = {
|
||||
.init = {
|
||||
.NVIC_IRQChannel = USART1_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
.rx = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_10,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_IPU,
|
||||
},
|
||||
},
|
||||
.tx = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_9,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_IN_FLOATING,
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
static const struct pios_dsm_cfg pios_dsm_main_cfg = {
|
||||
.bind = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_10,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_Out_PP,
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
static const struct pios_usart_cfg pios_usart_dsm_flexi_cfg = {
|
||||
.regs = USART3,
|
||||
.init = {
|
||||
.USART_BaudRate = 115200,
|
||||
.USART_WordLength = USART_WordLength_8b,
|
||||
.USART_Parity = USART_Parity_No,
|
||||
.USART_StopBits = USART_StopBits_1,
|
||||
.USART_HardwareFlowControl = USART_HardwareFlowControl_None,
|
||||
.USART_Mode = USART_Mode_Rx,
|
||||
},
|
||||
.irq = {
|
||||
.init = {
|
||||
.NVIC_IRQChannel = USART3_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
.rx = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_11,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_IPU,
|
||||
},
|
||||
},
|
||||
.tx = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_10,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_IN_FLOATING,
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
static const struct pios_dsm_cfg pios_dsm_flexi_cfg = {
|
||||
.bind = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_11,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_Out_PP,
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
#endif /* PIOS_INCLUDE_DSM */
|
||||
|
||||
#if defined(PIOS_INCLUDE_SBUS)
|
||||
/*
|
||||
* S.Bus USART
|
||||
*/
|
||||
#include <pios_sbus_priv.h>
|
||||
|
||||
static const struct pios_usart_cfg pios_usart_sbus_main_cfg = {
|
||||
.regs = USART1,
|
||||
.init = {
|
||||
.USART_BaudRate = 100000,
|
||||
.USART_WordLength = USART_WordLength_8b,
|
||||
.USART_Parity = USART_Parity_Even,
|
||||
.USART_StopBits = USART_StopBits_2,
|
||||
.USART_HardwareFlowControl = USART_HardwareFlowControl_None,
|
||||
.USART_Mode = USART_Mode_Rx,
|
||||
},
|
||||
.irq = {
|
||||
.init = {
|
||||
.NVIC_IRQChannel = USART1_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
.rx = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_10,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_IPU,
|
||||
},
|
||||
},
|
||||
.tx = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_9,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_IN_FLOATING,
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
static const struct pios_sbus_cfg pios_sbus_cfg = {
|
||||
/* Inverter configuration */
|
||||
.inv = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_2,
|
||||
.GPIO_Mode = GPIO_Mode_Out_PP,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
},
|
||||
},
|
||||
.gpio_clk_func = RCC_APB2PeriphClockCmd,
|
||||
.gpio_clk_periph = RCC_APB2Periph_GPIOB,
|
||||
.gpio_inv_enable = Bit_SET,
|
||||
};
|
||||
|
||||
#endif /* PIOS_INCLUDE_SBUS */
|
||||
|
||||
#endif /* PIOS_INCLUDE_USART */
|
||||
|
||||
#if defined(PIOS_INCLUDE_COM)
|
||||
|
||||
#include "pios_com_priv.h"
|
||||
uint32_t pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_NONE];
|
||||
|
||||
#define PIOS_COM_TELEM_RF_RX_BUF_LEN 32
|
||||
#define PIOS_COM_TELEM_RF_TX_BUF_LEN 12
|
||||
@ -791,238 +60,6 @@ static const struct pios_sbus_cfg pios_sbus_cfg = {
|
||||
#define PIOS_COM_BRIDGE_RX_BUF_LEN 65
|
||||
#define PIOS_COM_BRIDGE_TX_BUF_LEN 12
|
||||
|
||||
#endif /* PIOS_INCLUDE_COM */
|
||||
|
||||
#if defined(PIOS_INCLUDE_RTC)
|
||||
/*
|
||||
* Realtime Clock (RTC)
|
||||
*/
|
||||
#include <pios_rtc_priv.h>
|
||||
|
||||
void PIOS_RTC_IRQ_Handler (void);
|
||||
void RTC_IRQHandler() __attribute__ ((alias ("PIOS_RTC_IRQ_Handler")));
|
||||
static const struct pios_rtc_cfg pios_rtc_main_cfg = {
|
||||
.clksrc = RCC_RTCCLKSource_HSE_Div128,
|
||||
.prescaler = 100,
|
||||
.irq = {
|
||||
.init = {
|
||||
.NVIC_IRQChannel = RTC_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
void PIOS_RTC_IRQ_Handler (void)
|
||||
{
|
||||
PIOS_RTC_irq_handler ();
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
/*
|
||||
* Servo outputs
|
||||
*/
|
||||
#include <pios_servo_priv.h>
|
||||
|
||||
const struct pios_servo_cfg pios_servo_cfg = {
|
||||
.tim_oc_init = {
|
||||
.TIM_OCMode = TIM_OCMode_PWM1,
|
||||
.TIM_OutputState = TIM_OutputState_Enable,
|
||||
.TIM_OutputNState = TIM_OutputNState_Disable,
|
||||
.TIM_Pulse = PIOS_SERVOS_INITIAL_POSITION,
|
||||
.TIM_OCPolarity = TIM_OCPolarity_High,
|
||||
.TIM_OCNPolarity = TIM_OCPolarity_High,
|
||||
.TIM_OCIdleState = TIM_OCIdleState_Reset,
|
||||
.TIM_OCNIdleState = TIM_OCNIdleState_Reset,
|
||||
},
|
||||
.channels = pios_tim_servoport_all_pins,
|
||||
.num_channels = NELEMENTS(pios_tim_servoport_all_pins),
|
||||
};
|
||||
|
||||
const struct pios_servo_cfg pios_servo_rcvr_cfg = {
|
||||
.tim_oc_init = {
|
||||
.TIM_OCMode = TIM_OCMode_PWM1,
|
||||
.TIM_OutputState = TIM_OutputState_Enable,
|
||||
.TIM_OutputNState = TIM_OutputNState_Disable,
|
||||
.TIM_Pulse = PIOS_SERVOS_INITIAL_POSITION,
|
||||
.TIM_OCPolarity = TIM_OCPolarity_High,
|
||||
.TIM_OCNPolarity = TIM_OCPolarity_High,
|
||||
.TIM_OCIdleState = TIM_OCIdleState_Reset,
|
||||
.TIM_OCNIdleState = TIM_OCNIdleState_Reset,
|
||||
},
|
||||
.channels = pios_tim_servoport_rcvrport_pins,
|
||||
.num_channels = NELEMENTS(pios_tim_servoport_rcvrport_pins),
|
||||
};
|
||||
|
||||
|
||||
/*
|
||||
* PPM Inputs
|
||||
*/
|
||||
#if defined(PIOS_INCLUDE_PPM)
|
||||
#include <pios_ppm_priv.h>
|
||||
|
||||
const struct pios_ppm_cfg pios_ppm_cfg = {
|
||||
.tim_ic_init = {
|
||||
.TIM_ICPolarity = TIM_ICPolarity_Rising,
|
||||
.TIM_ICSelection = TIM_ICSelection_DirectTI,
|
||||
.TIM_ICPrescaler = TIM_ICPSC_DIV1,
|
||||
.TIM_ICFilter = 0x0,
|
||||
},
|
||||
/* Use only the first channel for ppm */
|
||||
.channels = &pios_tim_rcvrport_all_channels[0],
|
||||
.num_channels = 1,
|
||||
};
|
||||
|
||||
#endif /* PIOS_INCLUDE_PPM */
|
||||
|
||||
/*
|
||||
* PWM Inputs
|
||||
*/
|
||||
#if defined(PIOS_INCLUDE_PWM)
|
||||
#include <pios_pwm_priv.h>
|
||||
|
||||
const struct pios_pwm_cfg pios_pwm_cfg = {
|
||||
.tim_ic_init = {
|
||||
.TIM_ICPolarity = TIM_ICPolarity_Rising,
|
||||
.TIM_ICSelection = TIM_ICSelection_DirectTI,
|
||||
.TIM_ICPrescaler = TIM_ICPSC_DIV1,
|
||||
.TIM_ICFilter = 0x0,
|
||||
},
|
||||
.channels = pios_tim_rcvrport_all_channels,
|
||||
.num_channels = NELEMENTS(pios_tim_rcvrport_all_channels),
|
||||
};
|
||||
#endif
|
||||
|
||||
#if defined(PIOS_INCLUDE_I2C)
|
||||
|
||||
#include <pios_i2c_priv.h>
|
||||
|
||||
/*
|
||||
* I2C Adapters
|
||||
*/
|
||||
|
||||
void PIOS_I2C_main_adapter_ev_irq_handler(void);
|
||||
void PIOS_I2C_main_adapter_er_irq_handler(void);
|
||||
void I2C2_EV_IRQHandler() __attribute__ ((alias ("PIOS_I2C_main_adapter_ev_irq_handler")));
|
||||
void I2C2_ER_IRQHandler() __attribute__ ((alias ("PIOS_I2C_main_adapter_er_irq_handler")));
|
||||
|
||||
static const struct pios_i2c_adapter_cfg pios_i2c_main_adapter_cfg = {
|
||||
.regs = I2C2,
|
||||
.init = {
|
||||
.I2C_Mode = I2C_Mode_I2C,
|
||||
.I2C_OwnAddress1 = 0,
|
||||
.I2C_Ack = I2C_Ack_Enable,
|
||||
.I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit,
|
||||
.I2C_DutyCycle = I2C_DutyCycle_2,
|
||||
.I2C_ClockSpeed = 400000, /* bits/s */
|
||||
},
|
||||
.transfer_timeout_ms = 50,
|
||||
.scl = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_10,
|
||||
.GPIO_Speed = GPIO_Speed_10MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF_OD,
|
||||
},
|
||||
},
|
||||
.sda = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_11,
|
||||
.GPIO_Speed = GPIO_Speed_10MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF_OD,
|
||||
},
|
||||
},
|
||||
.event = {
|
||||
.flags = 0, /* FIXME: check this */
|
||||
.init = {
|
||||
.NVIC_IRQChannel = I2C2_EV_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGHEST,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
.error = {
|
||||
.flags = 0, /* FIXME: check this */
|
||||
.init = {
|
||||
.NVIC_IRQChannel = I2C2_ER_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGHEST,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
uint32_t pios_i2c_main_adapter_id;
|
||||
void PIOS_I2C_main_adapter_ev_irq_handler(void)
|
||||
{
|
||||
/* Call into the generic code to handle the IRQ for this specific device */
|
||||
PIOS_I2C_EV_IRQ_Handler(pios_i2c_main_adapter_id);
|
||||
}
|
||||
|
||||
void PIOS_I2C_main_adapter_er_irq_handler(void)
|
||||
{
|
||||
/* Call into the generic code to handle the IRQ for this specific device */
|
||||
PIOS_I2C_ER_IRQ_Handler(pios_i2c_main_adapter_id);
|
||||
}
|
||||
|
||||
#endif /* PIOS_INCLUDE_I2C */
|
||||
|
||||
#if defined(PIOS_INCLUDE_GCSRCVR)
|
||||
#include "pios_gcsrcvr_priv.h"
|
||||
#endif /* PIOS_INCLUDE_GCSRCVR */
|
||||
|
||||
#if defined(PIOS_INCLUDE_RCVR)
|
||||
#include "pios_rcvr_priv.h"
|
||||
|
||||
/* One slot per selectable receiver group.
|
||||
* eg. PWM, PPM, GCS, DSMMAINPORT, DSMFLEXIPORT, SBUS
|
||||
* NOTE: No slot in this map for NONE.
|
||||
*/
|
||||
uint32_t pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_NONE];
|
||||
|
||||
#endif /* PIOS_INCLUDE_RCVR */
|
||||
|
||||
#if defined(PIOS_INCLUDE_USB)
|
||||
#include "pios_usb_priv.h"
|
||||
|
||||
static const struct pios_usb_cfg pios_usb_main_cfg = {
|
||||
.irq = {
|
||||
.init = {
|
||||
.NVIC_IRQChannel = USB_LP_CAN1_RX0_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_LOW,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
};
|
||||
#endif /* PIOS_INCLUDE_USB */
|
||||
|
||||
#if defined(PIOS_INCLUDE_USB_HID)
|
||||
#include <pios_usb_hid_priv.h>
|
||||
|
||||
const struct pios_usb_hid_cfg pios_usb_hid_cfg = {
|
||||
.data_if = 0,
|
||||
.data_rx_ep = 1,
|
||||
.data_tx_ep = 1,
|
||||
};
|
||||
#endif /* PIOS_INCLUDE_USB_HID */
|
||||
|
||||
#if defined(PIOS_INCLUDE_USB_CDC)
|
||||
#include <pios_usb_cdc_priv.h>
|
||||
|
||||
const struct pios_usb_cdc_cfg pios_usb_cdc_cfg = {
|
||||
.ctrl_if = 1,
|
||||
.ctrl_tx_ep = 2,
|
||||
|
||||
.data_if = 2,
|
||||
.data_rx_ep = 3,
|
||||
.data_tx_ep = 3,
|
||||
};
|
||||
#endif /* PIOS_INCLUDE_USB_CDC */
|
||||
|
||||
uint32_t pios_com_telem_rf_id;
|
||||
uint32_t pios_com_telem_usb_id;
|
||||
uint32_t pios_com_vcp_id;
|
||||
@ -1053,6 +90,15 @@ void PIOS_Board_Init(void) {
|
||||
EventDispatcherInitialize();
|
||||
UAVObjInitialize();
|
||||
|
||||
#if defined(PIOS_INCLUDE_RTC)
|
||||
/* Initialize the real-time clock and its associated tick */
|
||||
PIOS_RTC_Init(&pios_rtc_main_cfg);
|
||||
#endif
|
||||
|
||||
#if defined(PIOS_INCLUDE_LED)
|
||||
PIOS_LED_Init(&pios_led_cfg);
|
||||
#endif /* PIOS_INCLUDE_LED */
|
||||
|
||||
HwSettingsInitialize();
|
||||
|
||||
#ifndef ERASE_FLASH
|
||||
@ -1075,11 +121,6 @@ void PIOS_Board_Init(void) {
|
||||
AlarmsSet(SYSTEMALARMS_ALARM_BOOTFAULT, SYSTEMALARMS_ALARM_CRITICAL);
|
||||
}
|
||||
|
||||
#if defined(PIOS_INCLUDE_RTC)
|
||||
/* Initialize the real-time clock and its associated tick */
|
||||
PIOS_RTC_Init(&pios_rtc_main_cfg);
|
||||
#endif
|
||||
|
||||
/* Initialize the task monitor library */
|
||||
TaskMonitorInitialize();
|
||||
|
||||
@ -1090,14 +131,50 @@ void PIOS_Board_Init(void) {
|
||||
PIOS_TIM_InitClock(&tim_4_cfg);
|
||||
|
||||
#if defined(PIOS_INCLUDE_USB)
|
||||
/* Initialize board specific USB data */
|
||||
PIOS_USB_BOARD_DATA_Init();
|
||||
|
||||
/* Flags to determine if various USB interfaces are advertised */
|
||||
bool usb_hid_present = false;
|
||||
bool usb_cdc_present = false;
|
||||
|
||||
uint8_t hwsettings_usb_devicetype;
|
||||
HwSettingsUSB_DeviceTypeGet(&hwsettings_usb_devicetype);
|
||||
|
||||
switch (hwsettings_usb_devicetype) {
|
||||
case HWSETTINGS_USB_DEVICETYPE_HIDONLY:
|
||||
if (PIOS_USB_DESC_HID_ONLY_Init()) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
usb_hid_present = true;
|
||||
break;
|
||||
case HWSETTINGS_USB_DEVICETYPE_HIDVCP:
|
||||
if (PIOS_USB_DESC_HID_CDC_Init()) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
usb_hid_present = true;
|
||||
usb_cdc_present = true;
|
||||
break;
|
||||
case HWSETTINGS_USB_DEVICETYPE_VCPONLY:
|
||||
break;
|
||||
default:
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
|
||||
uint32_t pios_usb_id;
|
||||
PIOS_USB_Init(&pios_usb_id, &pios_usb_main_cfg);
|
||||
|
||||
#if defined(PIOS_INCLUDE_USB_CDC)
|
||||
/* Configure the USB VCP port */
|
||||
|
||||
uint8_t hwsettings_usb_vcpport;
|
||||
/* Configure the USB VCP port */
|
||||
HwSettingsUSB_VCPPortGet(&hwsettings_usb_vcpport);
|
||||
|
||||
if (!usb_cdc_present) {
|
||||
/* Force VCP port function to disabled if we haven't advertised VCP in our USB descriptor */
|
||||
hwsettings_usb_vcpport = HWSETTINGS_USB_VCPPORT_DISABLED;
|
||||
}
|
||||
|
||||
switch (hwsettings_usb_vcpport) {
|
||||
case HWSETTINGS_USB_VCPPORT_DISABLED:
|
||||
break;
|
||||
@ -1136,7 +213,6 @@ void PIOS_Board_Init(void) {
|
||||
tx_buffer, PIOS_COM_BRIDGE_TX_BUF_LEN)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_COM */
|
||||
break;
|
||||
@ -1148,6 +224,11 @@ void PIOS_Board_Init(void) {
|
||||
uint8_t hwsettings_usb_hidport;
|
||||
HwSettingsUSB_HIDPortGet(&hwsettings_usb_hidport);
|
||||
|
||||
if (!usb_hid_present) {
|
||||
/* Force HID port function to disabled if we haven't advertised HID in our USB descriptor */
|
||||
hwsettings_usb_hidport = HWSETTINGS_USB_HIDPORT_DISABLED;
|
||||
}
|
||||
|
||||
switch (hwsettings_usb_hidport) {
|
||||
case HWSETTINGS_USB_HIDPORT_DISABLED:
|
||||
break;
|
||||
@ -1419,7 +500,7 @@ void PIOS_Board_Init(void) {
|
||||
case HWSETTINGS_CC_FLEXIPORT_I2C:
|
||||
#if defined(PIOS_INCLUDE_I2C)
|
||||
{
|
||||
if (PIOS_I2C_Init(&pios_i2c_main_adapter_id, &pios_i2c_main_adapter_cfg)) {
|
||||
if (PIOS_I2C_Init(&pios_i2c_flexi_adapter_id, &pios_i2c_flexi_adapter_cfg)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
}
|
||||
|
@ -29,9 +29,11 @@
|
||||
*/
|
||||
|
||||
#include "pios_usb_board_data.h" /* struct usb_*, USB_* */
|
||||
#include "pios_sys.h" /* PIOS_SYS_SerialNumberGet */
|
||||
#include "pios_usbhook.h" /* PIOS_USBHOOK_* */
|
||||
|
||||
const uint8_t PIOS_USB_BOARD_StringProductID[] = {
|
||||
sizeof(PIOS_USB_BOARD_StringProductID),
|
||||
static const uint8_t usb_product_id[28] = {
|
||||
sizeof(usb_product_id),
|
||||
USB_DESC_TYPE_STRING,
|
||||
'C', 0,
|
||||
'o', 0,
|
||||
@ -48,3 +50,74 @@ const uint8_t PIOS_USB_BOARD_StringProductID[] = {
|
||||
'l', 0,
|
||||
};
|
||||
|
||||
static uint8_t usb_serial_number[52] = {
|
||||
sizeof(usb_serial_number),
|
||||
USB_DESC_TYPE_STRING,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0
|
||||
};
|
||||
|
||||
static const struct usb_string_langid usb_lang_id = {
|
||||
.bLength = sizeof(usb_lang_id),
|
||||
.bDescriptorType = USB_DESC_TYPE_STRING,
|
||||
.bLangID = htousbs(USB_LANGID_ENGLISH_UK),
|
||||
};
|
||||
|
||||
static const uint8_t usb_vendor_id[28] = {
|
||||
sizeof(usb_vendor_id),
|
||||
USB_DESC_TYPE_STRING,
|
||||
'o', 0,
|
||||
'p', 0,
|
||||
'e', 0,
|
||||
'n', 0,
|
||||
'p', 0,
|
||||
'i', 0,
|
||||
'l', 0,
|
||||
'o', 0,
|
||||
't', 0,
|
||||
'.', 0,
|
||||
'o', 0,
|
||||
'r', 0,
|
||||
'g', 0
|
||||
};
|
||||
|
||||
int32_t PIOS_USB_BOARD_DATA_Init(void)
|
||||
{
|
||||
/* Load device serial number into serial number string */
|
||||
uint8_t sn[25];
|
||||
PIOS_SYS_SerialNumberGet((char *)sn);
|
||||
for (uint8_t i = 0; sn[i] != '\0' && (2 * i) < usb_serial_number[0]; i++) {
|
||||
usb_serial_number[2 + 2 * i] = sn[i];
|
||||
}
|
||||
|
||||
PIOS_USBHOOK_RegisterString(USB_STRING_DESC_PRODUCT, (uint8_t *)&usb_product_id, sizeof(usb_product_id));
|
||||
PIOS_USBHOOK_RegisterString(USB_STRING_DESC_SERIAL, (uint8_t *)&usb_serial_number, sizeof(usb_serial_number));
|
||||
|
||||
PIOS_USBHOOK_RegisterString(USB_STRING_DESC_LANG, (uint8_t *)&usb_lang_id, sizeof(usb_lang_id));
|
||||
PIOS_USBHOOK_RegisterString(USB_STRING_DESC_VENDOR, (uint8_t *)&usb_vendor_id, sizeof(usb_vendor_id));
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
@ -1,131 +0,0 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup OpenPilotSystem OpenPilot System
|
||||
* @{
|
||||
* @addtogroup OpenPilotLibraries OpenPilot System Libraries
|
||||
* @{
|
||||
* @file taskmonitor.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @brief Task monitoring library
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
*
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* This program is free software; you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation; either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful, but
|
||||
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
|
||||
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
|
||||
* for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License along
|
||||
* with this program; if not, write to the Free Software Foundation, Inc.,
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
#include "openpilot.h"
|
||||
//#include "taskmonitor.h"
|
||||
|
||||
// Private constants
|
||||
|
||||
// Private types
|
||||
|
||||
// Private variables
|
||||
static xSemaphoreHandle lock;
|
||||
static xTaskHandle handles[TASKINFO_RUNNING_NUMELEM];
|
||||
static uint32_t lastMonitorTime;
|
||||
|
||||
// Private functions
|
||||
|
||||
/**
|
||||
* Initialize library
|
||||
*/
|
||||
int32_t TaskMonitorInitialize(void)
|
||||
{
|
||||
lock = xSemaphoreCreateRecursiveMutex();
|
||||
memset(handles, 0, sizeof(xTaskHandle)*TASKINFO_RUNNING_NUMELEM);
|
||||
lastMonitorTime = 0;
|
||||
#if defined(DIAG_TASKS)
|
||||
lastMonitorTime = portGET_RUN_TIME_COUNTER_VALUE();
|
||||
#endif
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* Register a task handle with the library
|
||||
*/
|
||||
int32_t TaskMonitorAdd(TaskInfoRunningElem task, xTaskHandle handle)
|
||||
{
|
||||
if (task < TASKINFO_RUNNING_NUMELEM)
|
||||
{
|
||||
xSemaphoreTakeRecursive(lock, portMAX_DELAY);
|
||||
handles[task] = handle;
|
||||
xSemaphoreGiveRecursive(lock);
|
||||
return 0;
|
||||
}
|
||||
else
|
||||
{
|
||||
return -1;
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Update the status of all tasks
|
||||
*/
|
||||
void TaskMonitorUpdateAll(void)
|
||||
{
|
||||
#if defined(DIAG_TASKS)
|
||||
TaskInfoData data;
|
||||
int n;
|
||||
|
||||
// Lock
|
||||
xSemaphoreTakeRecursive(lock, portMAX_DELAY);
|
||||
|
||||
#if ( configGENERATE_RUN_TIME_STATS == 1 )
|
||||
uint32_t currentTime;
|
||||
uint32_t deltaTime;
|
||||
|
||||
/*
|
||||
* Calculate the amount of elapsed run time between the last time we
|
||||
* measured and now. Scale so that we can convert task run times
|
||||
* directly to percentages.
|
||||
*/
|
||||
currentTime = portGET_RUN_TIME_COUNTER_VALUE();
|
||||
deltaTime = ((currentTime - lastMonitorTime) / 100) ? : 1; /* avoid divide-by-zero if the interval is too small */
|
||||
lastMonitorTime = currentTime;
|
||||
#endif
|
||||
|
||||
// Update all task information
|
||||
for (n = 0; n < TASKINFO_RUNNING_NUMELEM; ++n)
|
||||
{
|
||||
if (handles[n] != 0)
|
||||
{
|
||||
data.Running[n] = TASKINFO_RUNNING_TRUE;
|
||||
#if defined(ARCH_POSIX) || defined(ARCH_WIN32)
|
||||
data.StackRemaining[n] = 10000;
|
||||
#else
|
||||
data.StackRemaining[n] = uxTaskGetStackHighWaterMark(handles[n]) * 4;
|
||||
#if ( configGENERATE_RUN_TIME_STATS == 1 )
|
||||
/* Generate run time stats */
|
||||
data.RunningTime[n] = uxTaskGetRunTime(handles[n]) / deltaTime;
|
||||
#endif
|
||||
#endif
|
||||
|
||||
}
|
||||
else
|
||||
{
|
||||
data.Running[n] = TASKINFO_RUNNING_FALSE;
|
||||
data.StackRemaining[n] = 0;
|
||||
data.RunningTime[n] = 0;
|
||||
}
|
||||
}
|
||||
|
||||
// Update object
|
||||
TaskInfoSet(&data);
|
||||
|
||||
// Done
|
||||
xSemaphoreGiveRecursive(lock);
|
||||
#endif
|
||||
}
|
@ -71,6 +71,7 @@ OPUAVOBJINC = $(OPUAVOBJ)/inc
|
||||
OPSYSINC = $(OPDIR)/System/inc
|
||||
BOOT = ../Bootloaders/INS
|
||||
BOOTINC = $(BOOT)/inc
|
||||
HWDEFSINC = ../board_hw_defs/$(BOARD_NAME)
|
||||
|
||||
OPUAVSYNTHDIR = $(OUTDIR)/../uavobject-synthetics/flight
|
||||
|
||||
@ -172,6 +173,7 @@ EXTRAINCDIRS += $(CMSISDIR)
|
||||
EXTRAINCDIRS += $(INSINC)
|
||||
EXTRAINCDIRS += $(OPUAVSYNTHDIR)
|
||||
EXTRAINCDIRS += $(BOOTINC)
|
||||
EXTRAINCDIRS += $(HWDEFSINC)
|
||||
|
||||
# List any extra directories to look for library files here.
|
||||
# Also add directories where the linker should search for
|
||||
|
@ -51,6 +51,7 @@
|
||||
#define PIOS_INCLUDE_IMU3000
|
||||
#define PIOS_INCLUDE_GPIO
|
||||
#define PIOS_INCLUDE_EXTI
|
||||
#define PIOS_INCLUDE_IAP
|
||||
|
||||
#define PIOS_INCLUDE_BMA180
|
||||
|
||||
|
@ -94,18 +94,18 @@ void blink(int led, int times)
|
||||
void test_accel()
|
||||
{
|
||||
if(PIOS_BMA180_Test())
|
||||
blink(LED1, 1);
|
||||
blink(PIOS_LED_HEARTBEAT, 1);
|
||||
else
|
||||
blink(LED2, 1);
|
||||
blink(PIOS_LED_ALARM, 1);
|
||||
}
|
||||
|
||||
#if defined (PIOS_INCLUDE_HMC5883)
|
||||
void test_mag()
|
||||
{
|
||||
if(PIOS_HMC5883_Test())
|
||||
blink(LED1, 2);
|
||||
blink(PIOS_LED_HEARTBEAT, 2);
|
||||
else
|
||||
blink(LED2, 2);
|
||||
blink(PIOS_LED_ALARM, 2);
|
||||
}
|
||||
#endif
|
||||
|
||||
@ -113,9 +113,9 @@ void test_mag()
|
||||
void test_pressure()
|
||||
{
|
||||
if(PIOS_BMP085_Test())
|
||||
blink(LED1, 3);
|
||||
blink(PIOS_LED_HEARTBEAT, 3);
|
||||
else
|
||||
blink(LED2, 3);
|
||||
blink(PIOS_LED_ALARM, 3);
|
||||
}
|
||||
#endif
|
||||
|
||||
@ -123,9 +123,9 @@ void test_pressure()
|
||||
void test_imu()
|
||||
{
|
||||
if(PIOS_IMU3000_Test())
|
||||
blink(LED1, 4);
|
||||
blink(PIOS_LED_HEARTBEAT, 4);
|
||||
else
|
||||
blink(LED2, 4);
|
||||
blink(PIOS_LED_ALARM, 4);
|
||||
}
|
||||
#endif
|
||||
|
||||
|
@ -29,326 +29,16 @@
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
|
||||
#include <pios.h>
|
||||
|
||||
#if defined(PIOS_INCLUDE_SPI)
|
||||
|
||||
#include <pios_spi_priv.h>
|
||||
|
||||
/* SPI2 Interface
|
||||
* - Used for mainboard communications and magnetometer
|
||||
/* Pull in the board-specific static HW definitions.
|
||||
* Including .c files is a bit ugly but this allows all of
|
||||
* the HW definitions to be const and static to limit their
|
||||
* scope.
|
||||
*
|
||||
* NOTE: Leave this declared as const data so that it ends up in the
|
||||
* .rodata section (ie. Flash) rather than in the .bss section (RAM).
|
||||
* NOTE: THIS IS THE ONLY PLACE THAT SHOULD EVER INCLUDE THIS FILE
|
||||
*/
|
||||
void PIOS_SPI_op_mag_irq_handler(void);
|
||||
void DMA1_Channel5_IRQHandler() __attribute__ ((alias("PIOS_SPI_op_mag_irq_handler")));
|
||||
void DMA1_Channel4_IRQHandler() __attribute__ ((alias("PIOS_SPI_op_mag_irq_handler")));
|
||||
static const struct pios_spi_cfg pios_spi_op_mag_cfg = {
|
||||
.regs = SPI2,
|
||||
.init = {
|
||||
.SPI_Mode = SPI_Mode_Slave,
|
||||
.SPI_Direction = SPI_Direction_2Lines_FullDuplex,
|
||||
.SPI_DataSize = SPI_DataSize_8b,
|
||||
.SPI_NSS = SPI_NSS_Hard,
|
||||
.SPI_FirstBit = SPI_FirstBit_MSB,
|
||||
.SPI_CRCPolynomial = 7,
|
||||
.SPI_CPOL = SPI_CPOL_High,
|
||||
.SPI_CPHA = SPI_CPHA_2Edge,
|
||||
},
|
||||
.use_crc = TRUE,
|
||||
.dma = {
|
||||
.ahb_clk = RCC_AHBPeriph_DMA1,
|
||||
#include "board_hw_defs.c"
|
||||
|
||||
.irq = {
|
||||
.flags =
|
||||
(DMA1_FLAG_TC4 | DMA1_FLAG_TE4 | DMA1_FLAG_HT4 |
|
||||
DMA1_FLAG_GL4),
|
||||
.init = {
|
||||
.NVIC_IRQChannel = DMA1_Channel4_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
|
||||
.rx = {
|
||||
.channel = DMA1_Channel4,
|
||||
.init = {
|
||||
.DMA_PeripheralBaseAddr =
|
||||
(uint32_t) & (SPI2->DR),
|
||||
.DMA_DIR = DMA_DIR_PeripheralSRC,
|
||||
.DMA_PeripheralInc =
|
||||
DMA_PeripheralInc_Disable,
|
||||
.DMA_MemoryInc = DMA_MemoryInc_Enable,
|
||||
.DMA_PeripheralDataSize =
|
||||
DMA_PeripheralDataSize_Byte,
|
||||
.DMA_MemoryDataSize =
|
||||
DMA_MemoryDataSize_Byte,
|
||||
.DMA_Mode = DMA_Mode_Normal,
|
||||
.DMA_Priority = DMA_Priority_Medium,
|
||||
.DMA_M2M = DMA_M2M_Disable,
|
||||
},
|
||||
},
|
||||
.tx = {
|
||||
.channel = DMA1_Channel5,
|
||||
.init = {
|
||||
.DMA_PeripheralBaseAddr =
|
||||
(uint32_t) & (SPI2->DR),
|
||||
.DMA_DIR = DMA_DIR_PeripheralDST,
|
||||
.DMA_PeripheralInc =
|
||||
DMA_PeripheralInc_Disable,
|
||||
.DMA_MemoryInc = DMA_MemoryInc_Enable,
|
||||
.DMA_PeripheralDataSize =
|
||||
DMA_PeripheralDataSize_Byte,
|
||||
.DMA_MemoryDataSize =
|
||||
DMA_MemoryDataSize_Byte,
|
||||
.DMA_Mode = DMA_Mode_Normal,
|
||||
.DMA_Priority = DMA_Priority_Medium,
|
||||
.DMA_M2M = DMA_M2M_Disable,
|
||||
},
|
||||
},
|
||||
},
|
||||
.ssel = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_12,
|
||||
.GPIO_Speed = GPIO_Speed_10MHz,
|
||||
.GPIO_Mode = GPIO_Mode_IN_FLOATING,
|
||||
},
|
||||
},
|
||||
.sclk = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_13,
|
||||
.GPIO_Speed = GPIO_Speed_10MHz,
|
||||
.GPIO_Mode = GPIO_Mode_IN_FLOATING,
|
||||
},
|
||||
},
|
||||
.miso = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_14,
|
||||
.GPIO_Speed = GPIO_Speed_10MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF_PP,
|
||||
},
|
||||
},
|
||||
.mosi = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_15,
|
||||
.GPIO_Speed = GPIO_Speed_10MHz,
|
||||
.GPIO_Mode = GPIO_Mode_IN_FLOATING,
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
uint32_t pios_spi_op_mag_id;
|
||||
void PIOS_SPI_op_mag_irq_handler(void)
|
||||
{
|
||||
/* Call into the generic code to handle the IRQ for this specific device */
|
||||
PIOS_SPI_IRQ_Handler(pios_spi_op_mag_id);
|
||||
}
|
||||
|
||||
/* SPI1 Interface
|
||||
* - Used for BMA180 accelerometer
|
||||
*/
|
||||
void PIOS_SPI_accel_irq_handler(void);
|
||||
void DMA1_Channel2_IRQHandler() __attribute__ ((alias("PIOS_SPI_accel_irq_handler")));
|
||||
void DMA1_Channel3_IRQHandler() __attribute__ ((alias("PIOS_SPI_accel_irq_handler")));
|
||||
static const struct pios_spi_cfg pios_spi_accel_cfg = {
|
||||
.regs = SPI1,
|
||||
.init = {
|
||||
.SPI_Mode = SPI_Mode_Master,
|
||||
.SPI_Direction = SPI_Direction_2Lines_FullDuplex,
|
||||
.SPI_DataSize = SPI_DataSize_8b,
|
||||
.SPI_NSS = SPI_NSS_Soft,
|
||||
.SPI_FirstBit = SPI_FirstBit_MSB,
|
||||
.SPI_CRCPolynomial = 7,
|
||||
.SPI_CPOL = SPI_CPOL_High,
|
||||
.SPI_CPHA = SPI_CPHA_1Edge,
|
||||
.SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_2,
|
||||
},
|
||||
.use_crc = FALSE,
|
||||
.dma = {
|
||||
.ahb_clk = RCC_AHBPeriph_DMA1,
|
||||
|
||||
.irq = {
|
||||
.flags = (DMA1_FLAG_TC2 | DMA1_FLAG_TE2 | DMA1_FLAG_HT2 | DMA1_FLAG_GL2),
|
||||
.init = {
|
||||
.NVIC_IRQChannel = DMA1_Channel2_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
|
||||
.rx = {
|
||||
.channel = DMA1_Channel2,
|
||||
.init = {
|
||||
.DMA_PeripheralBaseAddr = (uint32_t)&(SPI1->DR),
|
||||
.DMA_DIR = DMA_DIR_PeripheralSRC,
|
||||
.DMA_PeripheralInc = DMA_PeripheralInc_Disable,
|
||||
.DMA_MemoryInc = DMA_MemoryInc_Enable,
|
||||
.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte,
|
||||
.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte,
|
||||
.DMA_Mode = DMA_Mode_Normal,
|
||||
.DMA_Priority = DMA_Priority_Medium,
|
||||
.DMA_M2M = DMA_M2M_Disable,
|
||||
},
|
||||
},
|
||||
.tx = {
|
||||
.channel = DMA1_Channel3,
|
||||
.init = {
|
||||
.DMA_PeripheralBaseAddr = (uint32_t)&(SPI1->DR),
|
||||
.DMA_DIR = DMA_DIR_PeripheralDST,
|
||||
.DMA_PeripheralInc = DMA_PeripheralInc_Disable,
|
||||
.DMA_MemoryInc = DMA_MemoryInc_Enable,
|
||||
.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte,
|
||||
.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte,
|
||||
.DMA_Mode = DMA_Mode_Normal,
|
||||
.DMA_Priority = DMA_Priority_High,
|
||||
.DMA_M2M = DMA_M2M_Disable,
|
||||
},
|
||||
},
|
||||
},
|
||||
.ssel = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_4,
|
||||
.GPIO_Speed = GPIO_Speed_10MHz,
|
||||
.GPIO_Mode = GPIO_Mode_Out_PP,
|
||||
},
|
||||
},
|
||||
.sclk = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_5,
|
||||
.GPIO_Speed = GPIO_Speed_10MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF_PP,
|
||||
},
|
||||
},
|
||||
.miso = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_6,
|
||||
.GPIO_Speed = GPIO_Speed_10MHz,
|
||||
.GPIO_Mode = GPIO_Mode_IN_FLOATING,
|
||||
},
|
||||
},
|
||||
.mosi = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_7,
|
||||
.GPIO_Speed = GPIO_Speed_10MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF_PP,
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
static uint32_t pios_spi_accel_id;
|
||||
void PIOS_SPI_accel_irq_handler(void)
|
||||
{
|
||||
/* Call into the generic code to handle the IRQ for this specific device */
|
||||
PIOS_SPI_IRQ_Handler(pios_spi_accel_id);
|
||||
}
|
||||
|
||||
#endif /* PIOS_INCLUDE_SPI */
|
||||
|
||||
|
||||
|
||||
#if defined(PIOS_INCLUDE_GPS)
|
||||
#include <pios_usart_priv.h>
|
||||
|
||||
/*
|
||||
* GPS USART
|
||||
*/
|
||||
static const struct pios_usart_cfg pios_usart_gps_cfg = {
|
||||
.regs = USART1,
|
||||
.init = {
|
||||
.USART_BaudRate = 57600,
|
||||
.USART_WordLength = USART_WordLength_8b,
|
||||
.USART_Parity = USART_Parity_No,
|
||||
.USART_StopBits = USART_StopBits_1,
|
||||
.USART_HardwareFlowControl =
|
||||
USART_HardwareFlowControl_None,
|
||||
.USART_Mode = USART_Mode_Rx | USART_Mode_Tx,
|
||||
},
|
||||
.irq = {
|
||||
.init = {
|
||||
.NVIC_IRQChannel = USART1_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
.rx = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_10,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_IPU,
|
||||
},
|
||||
},
|
||||
.tx = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_9,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF_PP,
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
#endif /* PIOS_INCLUDE_GPS */
|
||||
|
||||
#ifdef PIOS_COM_AUX
|
||||
/*
|
||||
* AUX USART
|
||||
*/
|
||||
static const struct pios_usart_cfg pios_usart_aux_cfg = {
|
||||
.regs = USART4,
|
||||
.init = {
|
||||
.USART_BaudRate = 57600,
|
||||
.USART_WordLength = USART_WordLength_8b,
|
||||
.USART_Parity = USART_Parity_No,
|
||||
.USART_StopBits = USART_StopBits_1,
|
||||
.USART_HardwareFlowControl =
|
||||
USART_HardwareFlowControl_None,
|
||||
.USART_Mode = USART_Mode_Rx | USART_Mode_Tx,
|
||||
},
|
||||
.irq = {
|
||||
.init = {
|
||||
.NVIC_IRQChannel = USART4_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
.rx = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_11,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_IPU,
|
||||
},
|
||||
},
|
||||
.tx = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_10,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF_PP,
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
#endif /* PIOS_COM_AUX */
|
||||
|
||||
|
||||
#if defined(PIOS_INCLUDE_COM)
|
||||
|
||||
#include <pios_com_priv.h>
|
||||
#include <pios.h>
|
||||
|
||||
#if 0
|
||||
#define PIOS_COM_AUX_TX_BUF_LEN 192
|
||||
@ -358,156 +48,6 @@ static uint8_t pios_com_aux_tx_buffer[PIOS_COM_AUX_TX_BUF_LEN];
|
||||
#define PIOS_COM_GPS_RX_BUF_LEN 96
|
||||
static uint8_t pios_com_gps_rx_buffer[PIOS_COM_GPS_RX_BUF_LEN];
|
||||
|
||||
|
||||
#endif /* PIOS_INCLUDE_COM */
|
||||
|
||||
#if defined(PIOS_INCLUDE_I2C)
|
||||
|
||||
#include <pios_i2c_priv.h>
|
||||
|
||||
/*
|
||||
* I2C Adapters
|
||||
*/
|
||||
|
||||
void PIOS_I2C_pres_mag_adapter_ev_irq_handler(void);
|
||||
void PIOS_I2C_pres_mag_adapter_er_irq_handler(void);
|
||||
void I2C1_EV_IRQHandler()
|
||||
__attribute__ ((alias("PIOS_I2C_pres_mag_adapter_ev_irq_handler")));
|
||||
void I2C1_ER_IRQHandler()
|
||||
__attribute__ ((alias("PIOS_I2C_pres_mag_adapter_er_irq_handler")));
|
||||
|
||||
static const struct pios_i2c_adapter_cfg pios_i2c_pres_mag_adapter_cfg = {
|
||||
.regs = I2C1,
|
||||
.init = {
|
||||
.I2C_Mode = I2C_Mode_I2C,
|
||||
.I2C_OwnAddress1 = 0,
|
||||
.I2C_Ack = I2C_Ack_Enable,
|
||||
.I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit,
|
||||
.I2C_DutyCycle = I2C_DutyCycle_2,
|
||||
.I2C_ClockSpeed = 200000, /* bits/s */
|
||||
},
|
||||
.transfer_timeout_ms = 50,
|
||||
.scl = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_6,
|
||||
.GPIO_Speed = GPIO_Speed_10MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF_OD,
|
||||
},
|
||||
},
|
||||
.sda = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_7,
|
||||
.GPIO_Speed = GPIO_Speed_10MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF_OD,
|
||||
},
|
||||
},
|
||||
.event = {
|
||||
.flags = 0, /* FIXME: check this */
|
||||
.init = {
|
||||
.NVIC_IRQChannel = I2C1_EV_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGHEST,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
.error = {
|
||||
.flags = 0, /* FIXME: check this */
|
||||
.init = {
|
||||
.NVIC_IRQChannel = I2C1_ER_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGHEST,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
uint32_t pios_i2c_pres_mag_adapter_id;
|
||||
void PIOS_I2C_pres_mag_adapter_ev_irq_handler(void)
|
||||
{
|
||||
/* Call into the generic code to handle the IRQ for this specific device */
|
||||
PIOS_I2C_EV_IRQ_Handler(pios_i2c_pres_mag_adapter_id);
|
||||
}
|
||||
|
||||
void PIOS_I2C_pres_mag_adapter_er_irq_handler(void)
|
||||
{
|
||||
/* Call into the generic code to handle the IRQ for this specific device */
|
||||
PIOS_I2C_ER_IRQ_Handler(pios_i2c_pres_mag_adapter_id);
|
||||
}
|
||||
|
||||
|
||||
void PIOS_I2C_gyro_adapter_ev_irq_handler(void);
|
||||
void PIOS_I2C_gyro_adapter_er_irq_handler(void);
|
||||
void I2C2_EV_IRQHandler() __attribute__ ((alias ("PIOS_I2C_gyro_adapter_ev_irq_handler")));
|
||||
void I2C2_ER_IRQHandler() __attribute__ ((alias ("PIOS_I2C_gyro_adapter_er_irq_handler")));
|
||||
|
||||
static const struct pios_i2c_adapter_cfg pios_i2c_gyro_adapter_cfg = {
|
||||
.regs = I2C2,
|
||||
.init = {
|
||||
.I2C_Mode = I2C_Mode_I2C,
|
||||
.I2C_OwnAddress1 = 0,
|
||||
.I2C_Ack = I2C_Ack_Enable,
|
||||
.I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit,
|
||||
.I2C_DutyCycle = I2C_DutyCycle_2,
|
||||
.I2C_ClockSpeed = 400000, /* bits/s */
|
||||
},
|
||||
.transfer_timeout_ms = 50,
|
||||
.scl = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_10,
|
||||
.GPIO_Speed = GPIO_Speed_10MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF_OD,
|
||||
},
|
||||
},
|
||||
.sda = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_11,
|
||||
.GPIO_Speed = GPIO_Speed_10MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF_OD,
|
||||
},
|
||||
},
|
||||
.event = {
|
||||
.flags = 0, /* FIXME: check this */
|
||||
.init = {
|
||||
.NVIC_IRQChannel = I2C2_EV_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGHEST,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
.error = {
|
||||
.flags = 0, /* FIXME: check this */
|
||||
.init = {
|
||||
.NVIC_IRQChannel = I2C2_ER_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGHEST,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
uint32_t pios_i2c_gyro_adapter_id;
|
||||
void PIOS_I2C_gyro_adapter_ev_irq_handler(void)
|
||||
{
|
||||
/* Call into the generic code to handle the IRQ for this specific device */
|
||||
PIOS_I2C_EV_IRQ_Handler(pios_i2c_gyro_adapter_id);
|
||||
}
|
||||
|
||||
void PIOS_I2C_gyro_adapter_er_irq_handler(void)
|
||||
{
|
||||
/* Call into the generic code to handle the IRQ for this specific device */
|
||||
PIOS_I2C_ER_IRQ_Handler(pios_i2c_gyro_adapter_id);
|
||||
}
|
||||
|
||||
#endif /* PIOS_INCLUDE_I2C */
|
||||
|
||||
|
||||
|
||||
extern const struct pios_com_driver pios_usart_com_driver;
|
||||
|
||||
uint32_t pios_com_aux_id;
|
||||
uint32_t pios_com_gps_id;
|
||||
|
||||
@ -520,6 +60,10 @@ void PIOS_Board_Init(void) {
|
||||
/* Brings up System using CMSIS functions, enables the LEDs. */
|
||||
PIOS_SYS_Init();
|
||||
|
||||
#if defined(PIOS_INCLUDE_LED)
|
||||
PIOS_LED_Init(&pios_led_cfg);
|
||||
#endif /* PIOS_INCLUDE_LED */
|
||||
|
||||
/* Delay system */
|
||||
PIOS_DELAY_Init();
|
||||
|
||||
|
@ -47,7 +47,7 @@ int32_t TaskMonitorInitialize(void)
|
||||
lock = xSemaphoreCreateRecursiveMutex();
|
||||
memset(handles, 0, sizeof(xTaskHandle)*TASKINFO_RUNNING_NUMELEM);
|
||||
lastMonitorTime = 0;
|
||||
#if defined(DIAGNOSTICS)
|
||||
#if defined(DIAG_TASKS)
|
||||
lastMonitorTime = portGET_RUN_TIME_COUNTER_VALUE();
|
||||
#endif
|
||||
return 0;
|
||||
@ -94,7 +94,7 @@ int32_t TaskMonitorRemove(TaskInfoRunningElem task)
|
||||
*/
|
||||
void TaskMonitorUpdateAll(void)
|
||||
{
|
||||
#if defined(DIAGNOSTICS)
|
||||
#if defined(DIAG_TASKS)
|
||||
TaskInfoData data;
|
||||
int n;
|
||||
|
||||
@ -128,7 +128,6 @@ void TaskMonitorUpdateAll(void)
|
||||
#if ( configGENERATE_RUN_TIME_STATS == 1 )
|
||||
/* Generate run time stats */
|
||||
data.RunningTime[n] = uxTaskGetRunTime(handles[n]) / deltaTime;
|
||||
|
||||
#endif
|
||||
#endif
|
||||
|
@ -37,6 +37,7 @@
|
||||
*/
|
||||
|
||||
#include "openpilot.h"
|
||||
#include "hwsettings.h"
|
||||
#include "altitude.h"
|
||||
#include "baroaltitude.h" // object that will be updated by the module
|
||||
#if defined(PIOS_INCLUDE_HCSR04)
|
||||
@ -46,8 +47,7 @@
|
||||
// Private constants
|
||||
#define STACK_SIZE_BYTES 500
|
||||
#define TASK_PRIORITY (tskIDLE_PRIORITY+1)
|
||||
//#define UPDATE_PERIOD 100
|
||||
#define UPDATE_PERIOD 25
|
||||
#define UPDATE_PERIOD 50
|
||||
|
||||
// Private types
|
||||
|
||||
@ -60,6 +60,8 @@ static int32_t alt_ds_temp = 0;
|
||||
static int32_t alt_ds_pres = 0;
|
||||
static int alt_ds_count = 0;
|
||||
|
||||
static bool altitudeEnabled;
|
||||
|
||||
// Private functions
|
||||
static void altitudeTask(void *parameters);
|
||||
|
||||
@ -69,17 +71,19 @@ static void altitudeTask(void *parameters);
|
||||
*/
|
||||
int32_t AltitudeStart()
|
||||
{
|
||||
|
||||
BaroAltitudeInitialize();
|
||||
#if defined(PIOS_INCLUDE_HCSR04)
|
||||
SonarAltitudeInitialze();
|
||||
#endif
|
||||
|
||||
// Start main task
|
||||
xTaskCreate(altitudeTask, (signed char *)"Altitude", STACK_SIZE_BYTES/4, NULL, TASK_PRIORITY, &taskHandle);
|
||||
TaskMonitorAdd(TASKINFO_RUNNING_ALTITUDE, taskHandle);
|
||||
|
||||
return 0;
|
||||
if (altitudeEnabled) {
|
||||
BaroAltitudeInitialize();
|
||||
#if defined(PIOS_INCLUDE_HCSR04)
|
||||
SonarAltitudeInitialze();
|
||||
#endif
|
||||
|
||||
// Start main task
|
||||
xTaskCreate(altitudeTask, (signed char *)"Altitude", STACK_SIZE_BYTES/4, NULL, TASK_PRIORITY, &taskHandle);
|
||||
TaskMonitorAdd(TASKINFO_RUNNING_ALTITUDE, taskHandle);
|
||||
return 0;
|
||||
}
|
||||
return -1;
|
||||
}
|
||||
|
||||
/**
|
||||
@ -88,11 +92,23 @@ int32_t AltitudeStart()
|
||||
*/
|
||||
int32_t AltitudeInitialize()
|
||||
{
|
||||
#ifdef MODULE_Altitude_BUILTIN
|
||||
altitudeEnabled = 1;
|
||||
#else
|
||||
HwSettingsInitialize();
|
||||
uint8_t optionalModules[HWSETTINGS_OPTIONALMODULES_NUMELEM];
|
||||
HwSettingsOptionalModulesGet(optionalModules);
|
||||
if (optionalModules[HWSETTINGS_OPTIONALMODULES_ALTITUDE] == HWSETTINGS_OPTIONALMODULES_ENABLED) {
|
||||
altitudeEnabled = 1;
|
||||
} else {
|
||||
altitudeEnabled = 0;
|
||||
}
|
||||
#endif
|
||||
|
||||
// init down-sampling data
|
||||
alt_ds_temp = 0;
|
||||
alt_ds_pres = 0;
|
||||
alt_ds_count = 0;
|
||||
alt_ds_temp = 0;
|
||||
alt_ds_pres = 0;
|
||||
alt_ds_count = 0;
|
||||
|
||||
return 0;
|
||||
}
|
||||
@ -144,34 +160,42 @@ static void altitudeTask(void *parameters)
|
||||
#endif
|
||||
// Update the temperature data
|
||||
PIOS_BMP085_StartADC(TemperatureConv);
|
||||
#ifdef PIOS_BMP085_HAS_GPIOS
|
||||
xSemaphoreTake(PIOS_BMP085_EOC, portMAX_DELAY);
|
||||
#else
|
||||
vTaskDelay(5 / portTICK_RATE_MS);
|
||||
#endif
|
||||
PIOS_BMP085_ReadADC();
|
||||
alt_ds_temp += PIOS_BMP085_GetTemperature();
|
||||
|
||||
// Update the pressure data
|
||||
PIOS_BMP085_StartADC(PressureConv);
|
||||
#ifdef PIOS_BMP085_HAS_GPIOS
|
||||
xSemaphoreTake(PIOS_BMP085_EOC, portMAX_DELAY);
|
||||
#else
|
||||
vTaskDelay(26 / portTICK_RATE_MS);
|
||||
#endif
|
||||
PIOS_BMP085_ReadADC();
|
||||
alt_ds_pres += PIOS_BMP085_GetPressure();
|
||||
|
||||
if (++alt_ds_count >= alt_ds_size)
|
||||
{
|
||||
alt_ds_count = 0;
|
||||
{
|
||||
alt_ds_count = 0;
|
||||
|
||||
// Convert from 1/10ths of degC to degC
|
||||
data.Temperature = alt_ds_temp / (10.0 * alt_ds_size);
|
||||
alt_ds_temp = 0;
|
||||
// Convert from 1/10ths of degC to degC
|
||||
data.Temperature = alt_ds_temp / (10.0 * alt_ds_size);
|
||||
alt_ds_temp = 0;
|
||||
|
||||
// Convert from Pa to kPa
|
||||
data.Pressure = alt_ds_pres / (1000.0f * alt_ds_size);
|
||||
alt_ds_pres = 0;
|
||||
// Convert from Pa to kPa
|
||||
data.Pressure = alt_ds_pres / (1000.0f * alt_ds_size);
|
||||
alt_ds_pres = 0;
|
||||
|
||||
// Compute the current altitude (all pressures in kPa)
|
||||
data.Altitude = 44330.0 * (1.0 - powf((data.Pressure / (BMP085_P0 / 1000.0)), (1.0 / 5.255)));
|
||||
// Compute the current altitude (all pressures in kPa)
|
||||
data.Altitude = 44330.0 * (1.0 - powf((data.Pressure / (BMP085_P0 / 1000.0)), (1.0 / 5.255)));
|
||||
|
||||
// Update the AltitudeActual UAVObject
|
||||
BaroAltitudeSet(&data);
|
||||
}
|
||||
// Update the AltitudeActual UAVObject
|
||||
BaroAltitudeSet(&data);
|
||||
}
|
||||
|
||||
// Delay until it is time to read the next sample
|
||||
vTaskDelayUntil(&lastSysTime, UPDATE_PERIOD / portTICK_RATE_MS);
|
||||
|
@ -78,6 +78,10 @@ static float bound(float val, float limit);
|
||||
int32_t CameraStabInitialize(void)
|
||||
{
|
||||
bool cameraStabEnabled;
|
||||
|
||||
#ifdef MODULE_CameraStab_BUILTIN
|
||||
cameraStabEnabled = true;
|
||||
#else
|
||||
uint8_t optionalModules[HWSETTINGS_OPTIONALMODULES_NUMELEM];
|
||||
|
||||
HwSettingsInitialize();
|
||||
@ -87,6 +91,7 @@ int32_t CameraStabInitialize(void)
|
||||
cameraStabEnabled = true;
|
||||
else
|
||||
cameraStabEnabled = false;
|
||||
#endif
|
||||
|
||||
if (cameraStabEnabled) {
|
||||
|
||||
|
@ -94,6 +94,9 @@ static int32_t comUsbBridgeInitialize(void)
|
||||
usart_port = PIOS_COM_BRIDGE;
|
||||
vcp_port = PIOS_COM_VCP;
|
||||
|
||||
#ifdef MODULE_ComUsbBridge_BUILTIN
|
||||
bridge_enabled = true;
|
||||
#else
|
||||
HwSettingsInitialize();
|
||||
uint8_t optionalModules[HWSETTINGS_OPTIONALMODULES_NUMELEM];
|
||||
|
||||
@ -104,6 +107,7 @@ static int32_t comUsbBridgeInitialize(void)
|
||||
bridge_enabled = true;
|
||||
else
|
||||
bridge_enabled = false;
|
||||
#endif
|
||||
|
||||
if (bridge_enabled) {
|
||||
com2usb_buf = pvPortMalloc(BRIDGE_BUF_LEN);
|
||||
|
@ -40,6 +40,9 @@ static uint8_t active_fault;
|
||||
|
||||
static int32_t fault_initialize(void)
|
||||
{
|
||||
#ifdef MODULE_Fault_BUILTIN
|
||||
module_enabled = true;
|
||||
#else
|
||||
HwSettingsInitialize();
|
||||
uint8_t optionalModules[HWSETTINGS_OPTIONALMODULES_NUMELEM];
|
||||
|
||||
@ -50,6 +53,7 @@ static int32_t fault_initialize(void)
|
||||
} else {
|
||||
module_enabled = false;
|
||||
}
|
||||
#endif
|
||||
|
||||
/* Do this outside the module_enabled test so that it
|
||||
* can be changed even when the module has been disabled.
|
||||
|
@ -230,11 +230,14 @@ static uint32_t get_time(void)
|
||||
* Executed by event dispatcher callback to reset INS before resetting OP
|
||||
*/
|
||||
static void resetTask(UAVObjEvent * ev)
|
||||
{
|
||||
PIOS_LED_Toggle(LED1);
|
||||
#if (PIOS_LED_NUM > 1)
|
||||
PIOS_LED_Toggle(LED2);
|
||||
#endif
|
||||
{
|
||||
#if defined (PIOS_LED_HEARTBEAT)
|
||||
PIOS_LED_Toggle(PIOS_LED_HEARTBEAT);
|
||||
#endif /* PIOS_LED_HEARTBEAT */
|
||||
|
||||
#if defined (PIOS_LED_ALARM)
|
||||
PIOS_LED_Toggle(PIOS_LED_ALARM);
|
||||
#endif /* PIOS_LED_ALARM */
|
||||
|
||||
if((portTickType) (xTaskGetTickCount() - lastResetSysTime) > RESET_DELAY / portTICK_RATE_MS) {
|
||||
lastResetSysTime = xTaskGetTickCount();
|
||||
|
@ -121,6 +121,9 @@ int32_t GPSInitialize(void)
|
||||
{
|
||||
gpsPort = PIOS_COM_GPS;
|
||||
|
||||
#ifdef MODULE_GPS_BUILTIN
|
||||
gpsEnabled = true;
|
||||
#else
|
||||
HwSettingsInitialize();
|
||||
uint8_t optionalModules[HWSETTINGS_OPTIONALMODULES_NUMELEM];
|
||||
|
||||
@ -130,6 +133,7 @@ int32_t GPSInitialize(void)
|
||||
gpsEnabled = true;
|
||||
else
|
||||
gpsEnabled = false;
|
||||
#endif
|
||||
|
||||
if (gpsPort && gpsEnabled) {
|
||||
GPSPositionInitialize();
|
||||
|
@ -48,8 +48,6 @@
|
||||
#include "taskinfo.h"
|
||||
#include "watchdogstatus.h"
|
||||
#include "taskmonitor.h"
|
||||
#include "pios_iap.h"
|
||||
|
||||
|
||||
// Private constants
|
||||
#define SYSTEM_UPDATE_PERIOD_MS 1000
|
||||
@ -148,8 +146,10 @@ static void systemTask(void *parameters)
|
||||
PIOS_SYS_Reset();
|
||||
}
|
||||
|
||||
#if defined(PIOS_INCLUDE_IAP)
|
||||
/* Record a successful boot */
|
||||
PIOS_IAP_WriteBootCount(0);
|
||||
#endif
|
||||
|
||||
// Initialize vars
|
||||
idleCounter = 0;
|
||||
@ -170,20 +170,25 @@ static void systemTask(void *parameters)
|
||||
updateI2Cstats();
|
||||
updateWDGstats();
|
||||
#endif
|
||||
|
||||
#if defined(DIAG_TASKS)
|
||||
// Update the task status object
|
||||
TaskMonitorUpdateAll();
|
||||
#endif
|
||||
|
||||
// Flash the heartbeat LED
|
||||
PIOS_LED_Toggle(LED1);
|
||||
#if defined(PIOS_LED_HEARTBEAT)
|
||||
PIOS_LED_Toggle(PIOS_LED_HEARTBEAT);
|
||||
#endif /* PIOS_LED_HEARTBEAT */
|
||||
|
||||
// Turn on the error LED if an alarm is set
|
||||
#if (PIOS_LED_NUM > 1)
|
||||
#if defined (PIOS_LED_ALARM)
|
||||
if (AlarmsHasWarnings()) {
|
||||
PIOS_LED_On(LED2);
|
||||
PIOS_LED_On(PIOS_LED_ALARM);
|
||||
} else {
|
||||
PIOS_LED_Off(LED2);
|
||||
PIOS_LED_Off(PIOS_LED_ALARM);
|
||||
}
|
||||
#endif
|
||||
#endif /* PIOS_LED_ALARM */
|
||||
|
||||
FlightStatusData flightStatus;
|
||||
FlightStatusGet(&flightStatus);
|
||||
|
@ -35,7 +35,6 @@
|
||||
#include "flighttelemetrystats.h"
|
||||
#include "gcstelemetrystats.h"
|
||||
#include "hwsettings.h"
|
||||
#include "pios_usb.h" /* PIOS_USB_* */
|
||||
|
||||
// Private constants
|
||||
#define MAX_QUEUE_SIZE TELEM_QUEUE_SIZE
|
||||
|
@ -39,6 +39,7 @@ DEBUG ?= YES
|
||||
|
||||
# Include objects that are just nice information to show
|
||||
DIAGNOSTICS ?= YES
|
||||
DIAG_TASKS ?= YES
|
||||
|
||||
# Set to YES to use the Servo output pins for debugging via scope or logic analyser
|
||||
ENABLE_DEBUG_PINS ?= NO
|
||||
@ -112,6 +113,7 @@ PYMITEINC += $(PYMITEPLAT)
|
||||
PYMITEINC += $(OUTDIR)
|
||||
FLIGHTPLANLIB = $(OPMODULEDIR)/FlightPlan/lib
|
||||
FLIGHTPLANS = $(OPMODULEDIR)/FlightPlan/flightplans
|
||||
HWDEFSINC = ../board_hw_defs/$(BOARD_NAME)
|
||||
|
||||
UAVOBJSYNTHDIR = $(OUTDIR)/../uavobject-synthetics/flight
|
||||
|
||||
@ -138,7 +140,6 @@ SRC += ${OPMODULEDIR}/System/systemmod.c
|
||||
SRC += $(OPSYSTEM)/openpilot.c
|
||||
SRC += $(OPSYSTEM)/pios_board.c
|
||||
SRC += $(OPSYSTEM)/alarms.c
|
||||
SRC += $(OPSYSTEM)/taskmonitor.c
|
||||
SRC += $(OPUAVTALK)/uavtalk.c
|
||||
SRC += $(OPUAVOBJ)/uavobjectmanager.c
|
||||
SRC += $(OPUAVOBJ)/eventdispatcher.c
|
||||
@ -183,9 +184,11 @@ SRC += $(PIOSSTM32F10X)/pios_wdg.c
|
||||
SRC += $(PIOSSTM32F10X)/pios_usb.c
|
||||
SRC += $(PIOSSTM32F10X)/pios_usbhook.c
|
||||
SRC += $(PIOSSTM32F10X)/pios_usb_hid.c
|
||||
SRC += $(PIOSSTM32F10X)/pios_usb_cdc.c
|
||||
SRC += $(PIOSSTM32F10X)/pios_usb_hid_istr.c
|
||||
SRC += $(PIOSSTM32F10X)/pios_usb_hid_pwr.c
|
||||
SRC += $(OPSYSTEM)/pios_usb_board_data.c
|
||||
SRC += $(PIOSCOMMON)/pios_usb_desc_hid_cdc.c
|
||||
SRC += $(PIOSCOMMON)/pios_usb_desc_hid_only.c
|
||||
|
||||
## PIOS Hardware (Common)
|
||||
@ -205,6 +208,7 @@ SRC += $(FLIGHTLIB)/ahrs_comm_objects.c
|
||||
SRC += $(FLIGHTLIB)/fifo_buffer.c
|
||||
SRC += $(FLIGHTLIB)/WorldMagModel.c
|
||||
SRC += $(FLIGHTLIB)/CoordinateConversions.c
|
||||
SRC += $(FLIGHTLIB)/taskmonitor.c
|
||||
|
||||
## CMSIS for STM32
|
||||
SRC += $(CMSISDIR)/core_cm3.c
|
||||
@ -314,6 +318,7 @@ EXTRAINCDIRS += $(APPLIBDIR)
|
||||
EXTRAINCDIRS += $(RTOSSRCDIR)/portable/GCC/ARM_CM3
|
||||
EXTRAINCDIRS += $(AHRSBOOTLOADERINC)
|
||||
EXTRAINCDIRS += $(PYMITEINC)
|
||||
EXTRAINCDIRS += $(HWDEFSINC)
|
||||
|
||||
EXTRAINCDIRS += ${foreach MOD, ${OPTMODULES} ${MODULES} ${PYMODULES}, $(OPMODULEDIR)/${MOD}/inc} ${OPMODULEDIR}/System/inc
|
||||
|
||||
@ -367,6 +372,9 @@ ifeq ($(ENABLE_AUX_UART), YES)
|
||||
CDEFS += -DPIOS_ENABLE_AUX_UART
|
||||
endif
|
||||
|
||||
# Declare all non-optional modules as built-in to force inclusion
|
||||
CDEFS += ${foreach MOD, ${MODULES}, -DMODULE_$(MOD)_BUILTIN }
|
||||
|
||||
# Place project-specific -D and/or -U options for
|
||||
# Assembler with preprocessor here.
|
||||
#ADEFS = -DUSE_IRQ_ASM_WRAPPER
|
||||
@ -393,11 +401,15 @@ CSTANDARD = -std=gnu99
|
||||
# Flags for C and C++ (arm-elf-gcc/arm-elf-g++)
|
||||
|
||||
ifeq ($(DEBUG),YES)
|
||||
CFLAGS = -DDEBUG
|
||||
CFLAGS += -DDEBUG
|
||||
endif
|
||||
|
||||
ifeq ($(DIAGNOSTICS),YES)
|
||||
CFLAGS = -DDIAGNOSTICS
|
||||
CFLAGS += -DDIAGNOSTICS
|
||||
endif
|
||||
|
||||
ifeq ($(DIAG_TASKS),YES)
|
||||
CFLAGS += -DDIAG_TASKS
|
||||
endif
|
||||
|
||||
CFLAGS += -g$(DEBUGF)
|
||||
|
@ -149,7 +149,6 @@ SRC += ${OPMODULEDIR}/System/systemmod.c
|
||||
SRC += $(OPSYSTEM)/openpilot.c
|
||||
SRC += $(OPSYSTEM)/pios_board_posix.c
|
||||
SRC += $(OPSYSTEM)/alarms.c
|
||||
SRC += $(OPSYSTEM)/taskmonitor.c
|
||||
SRC += $(OPUAVTALK)/uavtalk.c
|
||||
SRC += $(OPUAVOBJ)/uavobjectmanager.c
|
||||
SRC += $(OPUAVOBJ)/eventdispatcher.c
|
||||
@ -189,6 +188,7 @@ SRC += $(PIOSPOSIX)/pios_rcvr.c
|
||||
SRC += $(FLIGHTLIB)/fifo_buffer.c
|
||||
SRC += $(FLIGHTLIB)/WorldMagModel.c
|
||||
SRC += $(FLIGHTLIB)/CoordinateConversions.c
|
||||
SRC += $(FLIGHTLIB)/taskmonitor.c
|
||||
## RTOS and RTOS Portable
|
||||
SRC += $(RTOSSRCDIR)/list.c
|
||||
SRC += $(RTOSSRCDIR)/queue.c
|
||||
|
@ -41,6 +41,8 @@
|
||||
#define PIOS_INCLUDE_I2C
|
||||
#define PIOS_INCLUDE_IRQ
|
||||
#define PIOS_INCLUDE_LED
|
||||
#define PIOS_INCLUDE_IAP
|
||||
#define PIOS_INCLUDE_TIM
|
||||
|
||||
#define PIOS_INCLUDE_RCVR
|
||||
|
||||
@ -57,6 +59,7 @@
|
||||
#define PIOS_INCLUDE_USART
|
||||
#define PIOS_INCLUDE_USB
|
||||
#define PIOS_INCLUDE_USB_HID
|
||||
#define PIOS_INCLUDE_USB_CDC
|
||||
#define PIOS_INCLUDE_BMP085
|
||||
//#define PIOS_INCLUDE_HCSR04
|
||||
#define PIOS_INCLUDE_OPAHRS
|
||||
|
@ -39,43 +39,6 @@
|
||||
|
||||
#include "pios_usb_defs.h" /* struct usb_* */
|
||||
|
||||
struct usb_board_config {
|
||||
struct usb_configuration_desc config;
|
||||
struct usb_interface_association_desc iad;
|
||||
struct usb_interface_desc hid_if;
|
||||
struct usb_hid_desc hid;
|
||||
struct usb_endpoint_desc hid_in;
|
||||
struct usb_endpoint_desc hid_out;
|
||||
struct usb_interface_desc cdc_control_if;
|
||||
struct usb_cdc_header_func_desc cdc_header;
|
||||
struct usb_cdc_callmgmt_func_desc cdc_callmgmt;
|
||||
struct usb_cdc_acm_func_desc cdc_acm;
|
||||
struct usb_cdc_union_func_desc cdc_union;
|
||||
struct usb_endpoint_desc cdc_mgmt_in;
|
||||
struct usb_interface_desc cdc_data_if;
|
||||
struct usb_endpoint_desc cdc_in;
|
||||
struct usb_endpoint_desc cdc_out;
|
||||
} __attribute__((packed));
|
||||
|
||||
extern const struct usb_device_desc PIOS_USB_BOARD_DeviceDescriptor;
|
||||
extern const struct usb_board_config PIOS_USB_BOARD_Configuration;
|
||||
extern const struct usb_string_langid PIOS_USB_BOARD_StringLangID;
|
||||
|
||||
/* NOTE NOTE NOTE
|
||||
*
|
||||
* Care must be taken to ensure that the _actual_ contents of
|
||||
* these arrays (in each board's pios_usb_board_data.c) is no
|
||||
* smaller than the stated sizes here or these descriptors
|
||||
* will end up with trailing zeros on the wire.
|
||||
*
|
||||
* The compiler will catch any time that these definitions are
|
||||
* too small.
|
||||
*/
|
||||
extern const uint8_t PIOS_USB_BOARD_HidReportDescriptor[36];
|
||||
extern const uint8_t PIOS_USB_BOARD_StringVendorID[28];
|
||||
extern const uint8_t PIOS_USB_BOARD_StringProductID[20];
|
||||
extern uint8_t PIOS_USB_BOARD_StringSerial[52];
|
||||
|
||||
#define PIOS_USB_BOARD_PRODUCT_ID USB_PRODUCT_ID_OPENPILOT_MAIN
|
||||
#define PIOS_USB_BOARD_DEVICE_VER USB_OP_DEVICE_VER(USB_OP_BOARD_ID_OPENPILOT_MAIN, USB_OP_BOARD_MODE_FW)
|
||||
|
||||
|
@ -110,13 +110,12 @@ int main()
|
||||
/* If all is well we will never reach here as the scheduler will now be running. */
|
||||
|
||||
/* Do some indication to user that something bad just happened */
|
||||
PIOS_LED_Off(LED1); \
|
||||
for(;;) { \
|
||||
PIOS_LED_Toggle(LED1); \
|
||||
PIOS_DELAY_WaitmS(100); \
|
||||
};
|
||||
|
||||
return 0;
|
||||
while (1) {
|
||||
#if defined(PIOS_LED_HEARTBEAT)
|
||||
PIOS_LED_Toggle(PIOS_LED_HEARTBEAT);
|
||||
#endif /* PIOS_LED_HEARTBEAT */
|
||||
PIOS_DELAY_WaitmS(100);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
|
@ -27,6 +27,16 @@
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
|
||||
|
||||
/* Pull in the board-specific static HW definitions.
|
||||
* Including .c files is a bit ugly but this allows all of
|
||||
* the HW definitions to be const and static to limit their
|
||||
* scope.
|
||||
*
|
||||
* NOTE: THIS IS THE ONLY PLACE THAT SHOULD EVER INCLUDE THIS FILE
|
||||
*/
|
||||
#include "board_hw_defs.c"
|
||||
|
||||
#include <pios.h>
|
||||
#include <openpilot.h>
|
||||
#include <uavobjectsinit.h>
|
||||
@ -36,572 +46,11 @@
|
||||
//#define I2C_DEBUG_PIN 0
|
||||
//#define USART_GPS_DEBUG_PIN 1
|
||||
|
||||
#if defined(PIOS_INCLUDE_SPI)
|
||||
|
||||
#include <pios_spi_priv.h>
|
||||
|
||||
/* MicroSD Interface
|
||||
*
|
||||
* NOTE: Leave this declared as const data so that it ends up in the
|
||||
* .rodata section (ie. Flash) rather than in the .bss section (RAM).
|
||||
/* One slot per selectable receiver group.
|
||||
* eg. PWM, PPM, GCS, DSMMAINPORT, DSMFLEXIPORT, SBUS
|
||||
* NOTE: No slot in this map for NONE.
|
||||
*/
|
||||
void PIOS_SPI_sdcard_irq_handler(void);
|
||||
void DMA1_Channel2_IRQHandler() __attribute__ ((alias ("PIOS_SPI_sdcard_irq_handler")));
|
||||
void DMA1_Channel3_IRQHandler() __attribute__ ((alias ("PIOS_SPI_sdcard_irq_handler")));
|
||||
static const struct pios_spi_cfg pios_spi_sdcard_cfg = {
|
||||
.regs = SPI1,
|
||||
.init = {
|
||||
.SPI_Mode = SPI_Mode_Master,
|
||||
.SPI_Direction = SPI_Direction_2Lines_FullDuplex,
|
||||
.SPI_DataSize = SPI_DataSize_8b,
|
||||
.SPI_NSS = SPI_NSS_Soft,
|
||||
.SPI_FirstBit = SPI_FirstBit_MSB,
|
||||
.SPI_CRCPolynomial = 7,
|
||||
.SPI_CPOL = SPI_CPOL_High,
|
||||
.SPI_CPHA = SPI_CPHA_2Edge,
|
||||
.SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_256, /* Maximum divider (ie. slowest clock rate) */
|
||||
},
|
||||
.dma = {
|
||||
.ahb_clk = RCC_AHBPeriph_DMA1,
|
||||
|
||||
.irq = {
|
||||
.flags = (DMA1_FLAG_TC2 | DMA1_FLAG_TE2 | DMA1_FLAG_HT2 | DMA1_FLAG_GL2),
|
||||
.init = {
|
||||
.NVIC_IRQChannel = DMA1_Channel2_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
|
||||
.rx = {
|
||||
.channel = DMA1_Channel2,
|
||||
.init = {
|
||||
.DMA_PeripheralBaseAddr = (uint32_t)&(SPI1->DR),
|
||||
.DMA_DIR = DMA_DIR_PeripheralSRC,
|
||||
.DMA_PeripheralInc = DMA_PeripheralInc_Disable,
|
||||
.DMA_MemoryInc = DMA_MemoryInc_Enable,
|
||||
.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte,
|
||||
.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte,
|
||||
.DMA_Mode = DMA_Mode_Normal,
|
||||
.DMA_Priority = DMA_Priority_Medium,
|
||||
.DMA_M2M = DMA_M2M_Disable,
|
||||
},
|
||||
},
|
||||
.tx = {
|
||||
.channel = DMA1_Channel3,
|
||||
.init = {
|
||||
.DMA_PeripheralBaseAddr = (uint32_t)&(SPI1->DR),
|
||||
.DMA_DIR = DMA_DIR_PeripheralDST,
|
||||
.DMA_PeripheralInc = DMA_PeripheralInc_Disable,
|
||||
.DMA_MemoryInc = DMA_MemoryInc_Enable,
|
||||
.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte,
|
||||
.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte,
|
||||
.DMA_Mode = DMA_Mode_Normal,
|
||||
.DMA_Priority = DMA_Priority_Medium,
|
||||
.DMA_M2M = DMA_M2M_Disable,
|
||||
},
|
||||
},
|
||||
},
|
||||
.ssel = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_4,
|
||||
.GPIO_Speed = GPIO_Speed_50MHz,
|
||||
.GPIO_Mode = GPIO_Mode_Out_PP,
|
||||
},
|
||||
},
|
||||
.sclk = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_5,
|
||||
.GPIO_Speed = GPIO_Speed_50MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF_PP,
|
||||
},
|
||||
},
|
||||
.miso = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_6,
|
||||
.GPIO_Speed = GPIO_Speed_50MHz,
|
||||
.GPIO_Mode = GPIO_Mode_IPU,
|
||||
},
|
||||
},
|
||||
.mosi = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_7,
|
||||
.GPIO_Speed = GPIO_Speed_50MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF_PP,
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
/* AHRS Interface
|
||||
*
|
||||
* NOTE: Leave this declared as const data so that it ends up in the
|
||||
* .rodata section (ie. Flash) rather than in the .bss section (RAM).
|
||||
*/
|
||||
void PIOS_SPI_ahrs_irq_handler(void);
|
||||
void DMA1_Channel4_IRQHandler() __attribute__ ((alias ("PIOS_SPI_ahrs_irq_handler")));
|
||||
void DMA1_Channel5_IRQHandler() __attribute__ ((alias ("PIOS_SPI_ahrs_irq_handler")));
|
||||
static const struct pios_spi_cfg pios_spi_ahrs_cfg = {
|
||||
.regs = SPI2,
|
||||
.init = {
|
||||
.SPI_Mode = SPI_Mode_Master,
|
||||
.SPI_Direction = SPI_Direction_2Lines_FullDuplex,
|
||||
.SPI_DataSize = SPI_DataSize_8b,
|
||||
.SPI_NSS = SPI_NSS_Soft,
|
||||
.SPI_FirstBit = SPI_FirstBit_MSB,
|
||||
.SPI_CRCPolynomial = 7,
|
||||
.SPI_CPOL = SPI_CPOL_High,
|
||||
.SPI_CPHA = SPI_CPHA_2Edge,
|
||||
.SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_16,
|
||||
},
|
||||
.use_crc = TRUE,
|
||||
.dma = {
|
||||
.ahb_clk = RCC_AHBPeriph_DMA1,
|
||||
|
||||
.irq = {
|
||||
.flags = (DMA1_FLAG_TC4 | DMA1_FLAG_TE4 | DMA1_FLAG_HT4 | DMA1_FLAG_GL4),
|
||||
.init = {
|
||||
.NVIC_IRQChannel = DMA1_Channel4_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
|
||||
.rx = {
|
||||
.channel = DMA1_Channel4,
|
||||
.init = {
|
||||
.DMA_PeripheralBaseAddr = (uint32_t)&(SPI2->DR),
|
||||
.DMA_DIR = DMA_DIR_PeripheralSRC,
|
||||
.DMA_PeripheralInc = DMA_PeripheralInc_Disable,
|
||||
.DMA_MemoryInc = DMA_MemoryInc_Enable,
|
||||
.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte,
|
||||
.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte,
|
||||
.DMA_Mode = DMA_Mode_Normal,
|
||||
.DMA_Priority = DMA_Priority_High,
|
||||
.DMA_M2M = DMA_M2M_Disable,
|
||||
},
|
||||
},
|
||||
.tx = {
|
||||
.channel = DMA1_Channel5,
|
||||
.init = {
|
||||
.DMA_PeripheralBaseAddr = (uint32_t)&(SPI2->DR),
|
||||
.DMA_DIR = DMA_DIR_PeripheralDST,
|
||||
.DMA_PeripheralInc = DMA_PeripheralInc_Disable,
|
||||
.DMA_MemoryInc = DMA_MemoryInc_Enable,
|
||||
.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte,
|
||||
.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte,
|
||||
.DMA_Mode = DMA_Mode_Normal,
|
||||
.DMA_Priority = DMA_Priority_High,
|
||||
.DMA_M2M = DMA_M2M_Disable,
|
||||
},
|
||||
},
|
||||
},
|
||||
.ssel = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_12,
|
||||
.GPIO_Speed = GPIO_Speed_10MHz,
|
||||
.GPIO_Mode = GPIO_Mode_Out_PP,
|
||||
},
|
||||
},
|
||||
.sclk = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_13,
|
||||
.GPIO_Speed = GPIO_Speed_10MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF_PP,
|
||||
},
|
||||
},
|
||||
.miso = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_14,
|
||||
.GPIO_Speed = GPIO_Speed_10MHz,
|
||||
.GPIO_Mode = GPIO_Mode_IN_FLOATING,
|
||||
},
|
||||
},
|
||||
.mosi = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_15,
|
||||
.GPIO_Speed = GPIO_Speed_10MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF_PP,
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
static uint32_t pios_spi_sdcard_id;
|
||||
void PIOS_SPI_sdcard_irq_handler(void)
|
||||
{
|
||||
/* Call into the generic code to handle the IRQ for this specific device */
|
||||
PIOS_SPI_IRQ_Handler(pios_spi_sdcard_id);
|
||||
}
|
||||
|
||||
uint32_t pios_spi_ahrs_id;
|
||||
void PIOS_SPI_ahrs_irq_handler(void)
|
||||
{
|
||||
/* Call into the generic code to handle the IRQ for this specific device */
|
||||
PIOS_SPI_IRQ_Handler(pios_spi_ahrs_id);
|
||||
}
|
||||
|
||||
#endif /* PIOS_INCLUDE_SPI */
|
||||
|
||||
/*
|
||||
* ADC system
|
||||
*/
|
||||
#include "pios_adc_priv.h"
|
||||
extern void PIOS_ADC_handler(void);
|
||||
void DMA1_Channel1_IRQHandler() __attribute__ ((alias("PIOS_ADC_handler")));
|
||||
// Remap the ADC DMA handler to this one
|
||||
static const struct pios_adc_cfg pios_adc_cfg = {
|
||||
.dma = {
|
||||
.ahb_clk = RCC_AHBPeriph_DMA1,
|
||||
.irq = {
|
||||
.flags = (DMA1_FLAG_TC1 | DMA1_FLAG_TE1 | DMA1_FLAG_HT1 | DMA1_FLAG_GL1),
|
||||
.init = {
|
||||
.NVIC_IRQChannel = DMA1_Channel1_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_LOW,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
.rx = {
|
||||
.channel = DMA1_Channel1,
|
||||
.init = {
|
||||
.DMA_PeripheralBaseAddr = (uint32_t) & ADC1->DR,
|
||||
.DMA_DIR = DMA_DIR_PeripheralSRC,
|
||||
.DMA_PeripheralInc = DMA_PeripheralInc_Disable,
|
||||
.DMA_MemoryInc = DMA_MemoryInc_Enable,
|
||||
.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Word,
|
||||
.DMA_MemoryDataSize = DMA_MemoryDataSize_Word,
|
||||
.DMA_Mode = DMA_Mode_Circular,
|
||||
.DMA_Priority = DMA_Priority_Low,
|
||||
.DMA_M2M = DMA_M2M_Disable,
|
||||
},
|
||||
}
|
||||
},
|
||||
.half_flag = DMA1_IT_HT1,
|
||||
.full_flag = DMA1_IT_TC1,
|
||||
};
|
||||
|
||||
struct pios_adc_dev pios_adc_devs[] = {
|
||||
{
|
||||
.cfg = &pios_adc_cfg,
|
||||
.callback_function = NULL,
|
||||
},
|
||||
};
|
||||
|
||||
uint8_t pios_adc_num_devices = NELEMENTS(pios_adc_devs);
|
||||
|
||||
void PIOS_ADC_handler() {
|
||||
PIOS_ADC_DMA_Handler();
|
||||
}
|
||||
|
||||
#include "pios_tim_priv.h"
|
||||
|
||||
static const TIM_TimeBaseInitTypeDef tim_4_8_time_base = {
|
||||
.TIM_Prescaler = (PIOS_MASTER_CLOCK / 1000000) - 1,
|
||||
.TIM_ClockDivision = TIM_CKD_DIV1,
|
||||
.TIM_CounterMode = TIM_CounterMode_Up,
|
||||
.TIM_Period = ((1000000 / PIOS_SERVO_UPDATE_HZ) - 1),
|
||||
.TIM_RepetitionCounter = 0x0000,
|
||||
};
|
||||
|
||||
static const struct pios_tim_clock_cfg tim_4_cfg = {
|
||||
.timer = TIM4,
|
||||
.time_base_init = &tim_4_8_time_base,
|
||||
.irq = {
|
||||
.init = {
|
||||
.NVIC_IRQChannel = TIM4_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
static const struct pios_tim_clock_cfg tim_8_cfg = {
|
||||
.timer = TIM8,
|
||||
.time_base_init = &tim_4_8_time_base,
|
||||
.irq = {
|
||||
.init = {
|
||||
.NVIC_IRQChannel = TIM8_CC_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
static const TIM_TimeBaseInitTypeDef tim_1_3_5_time_base = {
|
||||
.TIM_Prescaler = (PIOS_MASTER_CLOCK / 1000000) - 1,
|
||||
.TIM_ClockDivision = TIM_CKD_DIV1,
|
||||
.TIM_CounterMode = TIM_CounterMode_Up,
|
||||
.TIM_Period = 0xFFFF,
|
||||
.TIM_RepetitionCounter = 0x0000,
|
||||
};
|
||||
|
||||
static const struct pios_tim_clock_cfg tim_1_cfg = {
|
||||
.timer = TIM1,
|
||||
.time_base_init = &tim_1_3_5_time_base,
|
||||
.irq = {
|
||||
.init = {
|
||||
.NVIC_IRQChannel = TIM1_CC_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
static const struct pios_tim_clock_cfg tim_3_cfg = {
|
||||
.timer = TIM3,
|
||||
.time_base_init = &tim_1_3_5_time_base,
|
||||
.irq = {
|
||||
.init = {
|
||||
.NVIC_IRQChannel = TIM3_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
static const struct pios_tim_clock_cfg tim_5_cfg = {
|
||||
.timer = TIM5,
|
||||
.time_base_init = &tim_1_3_5_time_base,
|
||||
.irq = {
|
||||
.init = {
|
||||
.NVIC_IRQChannel = TIM5_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
#if defined(PIOS_INCLUDE_USART)
|
||||
|
||||
#include "pios_usart_priv.h"
|
||||
|
||||
/*
|
||||
* Telemetry USART
|
||||
*/
|
||||
static const struct pios_usart_cfg pios_usart_telem_cfg = {
|
||||
.regs = USART2,
|
||||
.init = {
|
||||
.USART_BaudRate = 57600,
|
||||
.USART_WordLength = USART_WordLength_8b,
|
||||
.USART_Parity = USART_Parity_No,
|
||||
.USART_StopBits = USART_StopBits_1,
|
||||
.USART_HardwareFlowControl = USART_HardwareFlowControl_None,
|
||||
.USART_Mode = USART_Mode_Rx | USART_Mode_Tx,
|
||||
},
|
||||
.irq = {
|
||||
.init = {
|
||||
.NVIC_IRQChannel = USART2_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
.rx = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_3,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_IPU,
|
||||
},
|
||||
},
|
||||
.tx = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_2,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF_PP,
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
/*
|
||||
* GPS USART
|
||||
*/
|
||||
static const struct pios_usart_cfg pios_usart_gps_cfg = {
|
||||
.regs = USART3,
|
||||
.remap = GPIO_PartialRemap_USART3,
|
||||
.init = {
|
||||
.USART_BaudRate = 57600,
|
||||
.USART_WordLength = USART_WordLength_8b,
|
||||
.USART_Parity = USART_Parity_No,
|
||||
.USART_StopBits = USART_StopBits_1,
|
||||
.USART_HardwareFlowControl = USART_HardwareFlowControl_None,
|
||||
.USART_Mode = USART_Mode_Rx | USART_Mode_Tx,
|
||||
},
|
||||
.irq = {
|
||||
.init = {
|
||||
.NVIC_IRQChannel = USART3_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
.rx = {
|
||||
.gpio = GPIOC,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_11,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_IPU,
|
||||
},
|
||||
},
|
||||
.tx = {
|
||||
.gpio = GPIOC,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_10,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF_PP,
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
#ifdef PIOS_COM_AUX
|
||||
/*
|
||||
* AUX USART
|
||||
*/
|
||||
static const struct pios_usart_cfg pios_usart_aux_cfg = {
|
||||
.regs = USART1,
|
||||
.init = {
|
||||
.USART_BaudRate = 57600,
|
||||
.USART_WordLength = USART_WordLength_8b,
|
||||
.USART_Parity = USART_Parity_No,
|
||||
.USART_StopBits = USART_StopBits_1,
|
||||
.USART_HardwareFlowControl = USART_HardwareFlowControl_None,
|
||||
.USART_Mode = USART_Mode_Rx | USART_Mode_Tx,
|
||||
},
|
||||
.irq = {
|
||||
.init = {
|
||||
.NVIC_IRQChannel = USART1_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
.remap = GPIO_Remap_USART1,
|
||||
.rx = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_7,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_IPU,
|
||||
},
|
||||
},
|
||||
.tx = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_6,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF_PP,
|
||||
},
|
||||
},
|
||||
};
|
||||
#endif
|
||||
|
||||
#if defined(PIOS_INCLUDE_RTC)
|
||||
/*
|
||||
* Realtime Clock (RTC)
|
||||
*/
|
||||
#include <pios_rtc_priv.h>
|
||||
|
||||
void PIOS_RTC_IRQ_Handler (void);
|
||||
void RTC_IRQHandler() __attribute__ ((alias ("PIOS_RTC_IRQ_Handler")));
|
||||
static const struct pios_rtc_cfg pios_rtc_main_cfg = {
|
||||
.clksrc = RCC_RTCCLKSource_HSE_Div128,
|
||||
.prescaler = 100,
|
||||
.irq = {
|
||||
.init = {
|
||||
.NVIC_IRQChannel = RTC_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
void PIOS_RTC_IRQ_Handler (void)
|
||||
{
|
||||
PIOS_RTC_irq_handler ();
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
#if defined(PIOS_INCLUDE_DSM)
|
||||
/*
|
||||
* Spektrum/JR DSM USART
|
||||
*/
|
||||
#include <pios_dsm_priv.h>
|
||||
|
||||
static const struct pios_usart_cfg pios_usart_dsm_cfg = {
|
||||
.regs = USART1,
|
||||
.init = {
|
||||
.USART_BaudRate = 115200,
|
||||
.USART_WordLength = USART_WordLength_8b,
|
||||
.USART_Parity = USART_Parity_No,
|
||||
.USART_StopBits = USART_StopBits_1,
|
||||
.USART_HardwareFlowControl = USART_HardwareFlowControl_None,
|
||||
.USART_Mode = USART_Mode_Rx,
|
||||
},
|
||||
.irq = {
|
||||
.init = {
|
||||
.NVIC_IRQChannel = USART1_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
.rx = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_10,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_IPU,
|
||||
},
|
||||
},
|
||||
.tx = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_9,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_IN_FLOATING,
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
static const struct pios_dsm_cfg pios_dsm_cfg = {
|
||||
.bind = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_10,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_Out_PP,
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
#endif /* PIOS_COM_DSM */
|
||||
|
||||
#if defined(PIOS_INCLUDE_SBUS)
|
||||
#error PIOS_INCLUDE_SBUS not implemented
|
||||
#endif /* PIOS_INCLUDE_SBUS */
|
||||
|
||||
#endif /* PIOS_INCLUDE_USART */
|
||||
|
||||
#if defined(PIOS_INCLUDE_COM)
|
||||
|
||||
#include "pios_com_priv.h"
|
||||
uint32_t pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_NONE];
|
||||
|
||||
#define PIOS_COM_TELEM_RF_RX_BUF_LEN 192
|
||||
#define PIOS_COM_TELEM_RF_TX_BUF_LEN 192
|
||||
@ -611,464 +60,12 @@ static const struct pios_dsm_cfg pios_dsm_cfg = {
|
||||
#define PIOS_COM_TELEM_USB_RX_BUF_LEN 192
|
||||
#define PIOS_COM_TELEM_USB_TX_BUF_LEN 192
|
||||
|
||||
#endif /* PIOS_INCLUDE_COM */
|
||||
|
||||
/**
|
||||
* Pios servo configuration structures
|
||||
*/
|
||||
#include <pios_servo_priv.h>
|
||||
static const struct pios_tim_channel pios_tim_servoport_all_pins[] = {
|
||||
{
|
||||
.timer = TIM4,
|
||||
.timer_chan = TIM_Channel_1,
|
||||
.pin = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_6,
|
||||
.GPIO_Mode = GPIO_Mode_AF_PP,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
},
|
||||
},
|
||||
},
|
||||
{
|
||||
.timer = TIM4,
|
||||
.timer_chan = TIM_Channel_2,
|
||||
.pin = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_7,
|
||||
.GPIO_Mode = GPIO_Mode_AF_PP,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
},
|
||||
},
|
||||
},
|
||||
{
|
||||
.timer = TIM4,
|
||||
.timer_chan = TIM_Channel_3,
|
||||
.pin = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_8,
|
||||
.GPIO_Mode = GPIO_Mode_AF_PP,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
},
|
||||
},
|
||||
},
|
||||
{
|
||||
.timer = TIM4,
|
||||
.timer_chan = TIM_Channel_4,
|
||||
.pin = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_9,
|
||||
.GPIO_Mode = GPIO_Mode_AF_PP,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
},
|
||||
},
|
||||
},
|
||||
{
|
||||
.timer = TIM8,
|
||||
.timer_chan = TIM_Channel_1,
|
||||
.pin = {
|
||||
.gpio = GPIOC,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_6,
|
||||
.GPIO_Mode = GPIO_Mode_AF_PP,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
},
|
||||
},
|
||||
},
|
||||
{
|
||||
.timer = TIM8,
|
||||
.timer_chan = TIM_Channel_2,
|
||||
.pin = {
|
||||
.gpio = GPIOC,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_7,
|
||||
.GPIO_Mode = GPIO_Mode_AF_PP,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
},
|
||||
},
|
||||
},
|
||||
{
|
||||
.timer = TIM8,
|
||||
.timer_chan = TIM_Channel_3,
|
||||
.pin = {
|
||||
.gpio = GPIOC,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_8,
|
||||
.GPIO_Mode = GPIO_Mode_AF_PP,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
},
|
||||
},
|
||||
},
|
||||
{
|
||||
.timer = TIM8,
|
||||
.timer_chan = TIM_Channel_4,
|
||||
.pin = {
|
||||
.gpio = GPIOC,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_9,
|
||||
.GPIO_Mode = GPIO_Mode_AF_PP,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
},
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
const struct pios_servo_cfg pios_servo_cfg = {
|
||||
.tim_oc_init = {
|
||||
.TIM_OCMode = TIM_OCMode_PWM1,
|
||||
.TIM_OutputState = TIM_OutputState_Enable,
|
||||
.TIM_OutputNState = TIM_OutputNState_Disable,
|
||||
.TIM_Pulse = PIOS_SERVOS_INITIAL_POSITION,
|
||||
.TIM_OCPolarity = TIM_OCPolarity_High,
|
||||
.TIM_OCNPolarity = TIM_OCPolarity_High,
|
||||
.TIM_OCIdleState = TIM_OCIdleState_Reset,
|
||||
.TIM_OCNIdleState = TIM_OCNIdleState_Reset,
|
||||
},
|
||||
.channels = pios_tim_servoport_all_pins,
|
||||
.num_channels = NELEMENTS(pios_tim_servoport_all_pins),
|
||||
};
|
||||
|
||||
|
||||
/*
|
||||
* PWM Inputs
|
||||
*/
|
||||
#if defined(PIOS_INCLUDE_PWM) || defined(PIOS_INCLUDE_PPM)
|
||||
#include <pios_pwm_priv.h>
|
||||
static const struct pios_tim_channel pios_tim_rcvrport_all_channels[] = {
|
||||
{
|
||||
.timer = TIM1,
|
||||
.timer_chan = TIM_Channel_2,
|
||||
.pin = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_9,
|
||||
.GPIO_Mode = GPIO_Mode_IPD,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
},
|
||||
},
|
||||
},
|
||||
{
|
||||
.timer = TIM1,
|
||||
.timer_chan = TIM_Channel_3,
|
||||
.pin = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_10,
|
||||
.GPIO_Mode = GPIO_Mode_IPD,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
},
|
||||
},
|
||||
},
|
||||
{
|
||||
.timer = TIM5,
|
||||
.timer_chan = TIM_Channel_1,
|
||||
.pin = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_0,
|
||||
.GPIO_Mode = GPIO_Mode_IPD,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
},
|
||||
},
|
||||
},
|
||||
{
|
||||
.timer = TIM1,
|
||||
.timer_chan = TIM_Channel_1,
|
||||
.pin = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_8,
|
||||
.GPIO_Mode = GPIO_Mode_IPD,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
},
|
||||
},
|
||||
},
|
||||
{
|
||||
.timer = TIM3,
|
||||
.timer_chan = TIM_Channel_4,
|
||||
.pin = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_1,
|
||||
.GPIO_Mode = GPIO_Mode_IPD,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
},
|
||||
},
|
||||
},
|
||||
{
|
||||
.timer = TIM3,
|
||||
.timer_chan = TIM_Channel_3,
|
||||
.pin = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_0,
|
||||
.GPIO_Mode = GPIO_Mode_IPD,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
},
|
||||
},
|
||||
},
|
||||
{
|
||||
.timer = TIM3,
|
||||
.timer_chan = TIM_Channel_1,
|
||||
.pin = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_4,
|
||||
.GPIO_Mode = GPIO_Mode_IPD,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
},
|
||||
},
|
||||
.remap = GPIO_PartialRemap_TIM3,
|
||||
},
|
||||
{
|
||||
.timer = TIM3,
|
||||
.timer_chan = TIM_Channel_2,
|
||||
.pin = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_5,
|
||||
.GPIO_Mode = GPIO_Mode_IPD,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
},
|
||||
},
|
||||
.remap = GPIO_PartialRemap_TIM3,
|
||||
},
|
||||
};
|
||||
|
||||
const struct pios_pwm_cfg pios_pwm_cfg = {
|
||||
.tim_ic_init = {
|
||||
.TIM_ICPolarity = TIM_ICPolarity_Rising,
|
||||
.TIM_ICSelection = TIM_ICSelection_DirectTI,
|
||||
.TIM_ICPrescaler = TIM_ICPSC_DIV1,
|
||||
.TIM_ICFilter = 0x0,
|
||||
},
|
||||
.channels = pios_tim_rcvrport_all_channels,
|
||||
.num_channels = NELEMENTS(pios_tim_rcvrport_all_channels),
|
||||
};
|
||||
#endif
|
||||
|
||||
/*
|
||||
* PPM Input
|
||||
*/
|
||||
#if defined(PIOS_INCLUDE_PPM)
|
||||
#include <pios_ppm_priv.h>
|
||||
static const struct pios_ppm_cfg pios_ppm_cfg = {
|
||||
.tim_ic_init = {
|
||||
.TIM_ICPolarity = TIM_ICPolarity_Rising,
|
||||
.TIM_ICSelection = TIM_ICSelection_DirectTI,
|
||||
.TIM_ICPrescaler = TIM_ICPSC_DIV1,
|
||||
.TIM_ICFilter = 0x0,
|
||||
.TIM_Channel = TIM_Channel_2,
|
||||
},
|
||||
/* Use only the first channel for ppm */
|
||||
.channels = &pios_tim_rcvrport_all_channels[0],
|
||||
.num_channels = 1,
|
||||
};
|
||||
|
||||
#endif //PPM
|
||||
|
||||
#if defined(PIOS_INCLUDE_I2C)
|
||||
|
||||
#include <pios_i2c_priv.h>
|
||||
|
||||
/*
|
||||
* I2C Adapters
|
||||
*/
|
||||
|
||||
void PIOS_I2C_main_adapter_ev_irq_handler(void);
|
||||
void PIOS_I2C_main_adapter_er_irq_handler(void);
|
||||
void I2C2_EV_IRQHandler() __attribute__ ((alias ("PIOS_I2C_main_adapter_ev_irq_handler")));
|
||||
void I2C2_ER_IRQHandler() __attribute__ ((alias ("PIOS_I2C_main_adapter_er_irq_handler")));
|
||||
|
||||
static const struct pios_i2c_adapter_cfg pios_i2c_main_adapter_cfg = {
|
||||
.regs = I2C2,
|
||||
.init = {
|
||||
.I2C_Mode = I2C_Mode_I2C,
|
||||
.I2C_OwnAddress1 = 0,
|
||||
.I2C_Ack = I2C_Ack_Enable,
|
||||
.I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit,
|
||||
.I2C_DutyCycle = I2C_DutyCycle_2,
|
||||
.I2C_ClockSpeed = 400000, /* bits/s */
|
||||
},
|
||||
.transfer_timeout_ms = 50,
|
||||
.scl = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_10,
|
||||
.GPIO_Speed = GPIO_Speed_10MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF_OD,
|
||||
},
|
||||
},
|
||||
.sda = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_11,
|
||||
.GPIO_Speed = GPIO_Speed_10MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF_OD,
|
||||
},
|
||||
},
|
||||
.event = {
|
||||
.flags = 0, /* FIXME: check this */
|
||||
.init = {
|
||||
.NVIC_IRQChannel = I2C2_EV_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGHEST,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
.error = {
|
||||
.flags = 0, /* FIXME: check this */
|
||||
.init = {
|
||||
.NVIC_IRQChannel = I2C2_ER_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGHEST,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
uint32_t pios_i2c_main_adapter_id;
|
||||
void PIOS_I2C_main_adapter_ev_irq_handler(void)
|
||||
{
|
||||
#ifdef I2C_DEBUG_PIN
|
||||
PIOS_DEBUG_PinHigh(I2C_DEBUG_PIN);
|
||||
#endif
|
||||
/* Call into the generic code to handle the IRQ for this specific device */
|
||||
PIOS_I2C_EV_IRQ_Handler(pios_i2c_main_adapter_id);
|
||||
#ifdef I2C_DEBUG_PIN
|
||||
PIOS_DEBUG_PinLow(I2C_DEBUG_PIN);
|
||||
#endif
|
||||
}
|
||||
|
||||
void PIOS_I2C_main_adapter_er_irq_handler(void)
|
||||
{
|
||||
/* Call into the generic code to handle the IRQ for this specific device */
|
||||
PIOS_I2C_ER_IRQ_Handler(pios_i2c_main_adapter_id);
|
||||
}
|
||||
|
||||
#endif /* PIOS_INCLUDE_I2C */
|
||||
|
||||
#if defined(PIOS_ENABLE_DEBUG_PINS)
|
||||
|
||||
static const struct stm32_gpio pios_debug_pins[] = {
|
||||
#define PIOS_DEBUG_PIN_SERVO_1 0
|
||||
{
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_6,
|
||||
.GPIO_Speed = GPIO_Speed_50MHz,
|
||||
.GPIO_Mode = GPIO_Mode_Out_PP,
|
||||
},
|
||||
},
|
||||
#define PIOS_DEBUG_PIN_SERVO_2 1
|
||||
{
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_7,
|
||||
.GPIO_Speed = GPIO_Speed_50MHz,
|
||||
.GPIO_Mode = GPIO_Mode_Out_PP,
|
||||
},
|
||||
},
|
||||
#define PIOS_DEBUG_PIN_SERVO_3 2
|
||||
{
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_8,
|
||||
.GPIO_Speed = GPIO_Speed_50MHz,
|
||||
.GPIO_Mode = GPIO_Mode_Out_PP,
|
||||
},
|
||||
},
|
||||
#define PIOS_DEBUG_PIN_SERVO_4 3
|
||||
{
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_9,
|
||||
.GPIO_Speed = GPIO_Speed_50MHz,
|
||||
.GPIO_Mode = GPIO_Mode_Out_PP,
|
||||
},
|
||||
},
|
||||
#define PIOS_DEBUG_PIN_SERVO_5 4
|
||||
{
|
||||
.gpio = GPIOC,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_6,
|
||||
.GPIO_Speed = GPIO_Speed_50MHz,
|
||||
.GPIO_Mode = GPIO_Mode_Out_PP,
|
||||
},
|
||||
},
|
||||
#define PIOS_DEBUG_PIN_SERVO_6 5
|
||||
{
|
||||
.gpio = GPIOC,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_7,
|
||||
.GPIO_Speed = GPIO_Speed_50MHz,
|
||||
.GPIO_Mode = GPIO_Mode_Out_PP,
|
||||
},
|
||||
},
|
||||
#define PIOS_DEBUG_PIN_SERVO_7 6
|
||||
{
|
||||
.gpio = GPIOC,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_8,
|
||||
.GPIO_Speed = GPIO_Speed_50MHz,
|
||||
.GPIO_Mode = GPIO_Mode_Out_PP,
|
||||
},
|
||||
},
|
||||
#define PIOS_DEBUG_PIN_SERVO_8 7
|
||||
{
|
||||
.gpio = GPIOC,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_9,
|
||||
.GPIO_Speed = GPIO_Speed_50MHz,
|
||||
.GPIO_Mode = GPIO_Mode_Out_PP,
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
#endif /* PIOS_ENABLE_DEBUG_PINS */
|
||||
|
||||
#if defined(PIOS_INCLUDE_RCVR)
|
||||
#include "pios_rcvr_priv.h"
|
||||
|
||||
/* One slot per selectable receiver group.
|
||||
* eg. PWM, PPM, GCS, DSMMAINPORT, DSMFLEXIPORT, SBUS
|
||||
* NOTE: No slot in this map for NONE.
|
||||
*/
|
||||
uint32_t pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_NONE];
|
||||
|
||||
#endif /* PIOS_INCLUDE_RCVR */
|
||||
|
||||
#if defined(PIOS_INCLUDE_USB)
|
||||
#include "pios_usb_priv.h"
|
||||
|
||||
static const struct pios_usb_cfg pios_usb_main_cfg = {
|
||||
.irq = {
|
||||
.init = {
|
||||
.NVIC_IRQChannel = USB_LP_CAN1_RX0_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_LOW,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
};
|
||||
#endif /* PIOS_INCLUDE_USB */
|
||||
|
||||
#if defined(PIOS_INCLUDE_USB_HID)
|
||||
#include <pios_usb_hid_priv.h>
|
||||
|
||||
const struct pios_usb_hid_cfg pios_usb_hid_cfg = {
|
||||
.data_if = 0,
|
||||
.data_rx_ep = 1,
|
||||
.data_tx_ep = 1,
|
||||
};
|
||||
|
||||
#endif /* PIOS_INCLUDE_USB_HID */
|
||||
#define PIOS_COM_BRIDGE_RX_BUF_LEN 65
|
||||
#define PIOS_COM_BRIDGE_TX_BUF_LEN 12
|
||||
|
||||
uint32_t pios_com_telem_rf_id;
|
||||
uint32_t pios_com_telem_usb_id;
|
||||
uint32_t pios_com_vcp_id;
|
||||
uint32_t pios_com_gps_id;
|
||||
uint32_t pios_com_aux_id;
|
||||
uint32_t pios_com_dsm_id;
|
||||
@ -1107,16 +104,33 @@ void PIOS_Board_Init(void) {
|
||||
EventDispatcherInitialize();
|
||||
UAVObjInitialize();
|
||||
|
||||
HwSettingsInitialize();
|
||||
|
||||
#if defined(PIOS_INCLUDE_RTC)
|
||||
/* Initialize the real-time clock and its associated tick */
|
||||
PIOS_RTC_Init(&pios_rtc_main_cfg);
|
||||
#endif
|
||||
|
||||
#if defined(PIOS_INCLUDE_LED)
|
||||
PIOS_LED_Init(&pios_led_cfg);
|
||||
#endif /* PIOS_INCLUDE_LED */
|
||||
|
||||
HwSettingsInitialize();
|
||||
|
||||
PIOS_WDG_Init();
|
||||
|
||||
/* Initialize the alarms library */
|
||||
AlarmsInitialize();
|
||||
|
||||
PIOS_IAP_Init();
|
||||
uint16_t boot_count = PIOS_IAP_ReadBootCount();
|
||||
if (boot_count < 3) {
|
||||
PIOS_IAP_WriteBootCount(++boot_count);
|
||||
AlarmsClear(SYSTEMALARMS_ALARM_BOOTFAULT);
|
||||
} else {
|
||||
/* Too many failed boot attempts, force hwsettings to defaults */
|
||||
HwSettingsSetDefaults(HwSettingsHandle(), 0);
|
||||
AlarmsSet(SYSTEMALARMS_ALARM_BOOTFAULT, SYSTEMALARMS_ALARM_CRITICAL);
|
||||
}
|
||||
|
||||
/* Initialize the task monitor library */
|
||||
TaskMonitorInitialize();
|
||||
|
||||
@ -1124,7 +138,6 @@ void PIOS_Board_Init(void) {
|
||||
PIOS_TIM_InitClock(&tim_1_cfg);
|
||||
PIOS_TIM_InitClock(&tim_3_cfg);
|
||||
PIOS_TIM_InitClock(&tim_5_cfg);
|
||||
|
||||
PIOS_TIM_InitClock(&tim_4_cfg);
|
||||
PIOS_TIM_InitClock(&tim_8_cfg);
|
||||
|
||||
@ -1139,6 +152,133 @@ void PIOS_Board_Init(void) {
|
||||
/* Bind the AHRS comms layer to the AHRS SPI link */
|
||||
AhrsConnect(pios_spi_ahrs_id);
|
||||
|
||||
#if defined(PIOS_INCLUDE_USB)
|
||||
/* Initialize board specific USB data */
|
||||
PIOS_USB_BOARD_DATA_Init();
|
||||
|
||||
/* Flags to determine if various USB interfaces are advertised */
|
||||
bool usb_hid_present = false;
|
||||
bool usb_cdc_present = false;
|
||||
|
||||
uint8_t hwsettings_usb_devicetype;
|
||||
HwSettingsUSB_DeviceTypeGet(&hwsettings_usb_devicetype);
|
||||
|
||||
switch (hwsettings_usb_devicetype) {
|
||||
case HWSETTINGS_USB_DEVICETYPE_HIDONLY:
|
||||
if (PIOS_USB_DESC_HID_ONLY_Init()) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
usb_hid_present = true;
|
||||
break;
|
||||
case HWSETTINGS_USB_DEVICETYPE_HIDVCP:
|
||||
if (PIOS_USB_DESC_HID_CDC_Init()) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
usb_hid_present = true;
|
||||
usb_cdc_present = true;
|
||||
break;
|
||||
case HWSETTINGS_USB_DEVICETYPE_VCPONLY:
|
||||
break;
|
||||
default:
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
|
||||
uint32_t pios_usb_id;
|
||||
PIOS_USB_Init(&pios_usb_id, &pios_usb_main_cfg);
|
||||
|
||||
#if defined(PIOS_INCLUDE_USB_CDC)
|
||||
/* Configure the USB VCP port */
|
||||
uint8_t hwsettings_usb_vcpport;
|
||||
HwSettingsUSB_VCPPortGet(&hwsettings_usb_vcpport);
|
||||
|
||||
if (!usb_cdc_present) {
|
||||
/* Force VCP port function to disabled if we haven't advertised VCP in our USB descriptor */
|
||||
hwsettings_usb_vcpport = HWSETTINGS_USB_VCPPORT_DISABLED;
|
||||
}
|
||||
|
||||
switch (hwsettings_usb_vcpport) {
|
||||
case HWSETTINGS_USB_VCPPORT_DISABLED:
|
||||
break;
|
||||
case HWSETTINGS_USB_VCPPORT_USBTELEMETRY:
|
||||
#if defined(PIOS_INCLUDE_COM)
|
||||
{
|
||||
uint32_t pios_usb_cdc_id;
|
||||
if (PIOS_USB_CDC_Init(&pios_usb_cdc_id, &pios_usb_cdc_cfg, pios_usb_id)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
uint8_t * rx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_TELEM_USB_RX_BUF_LEN);
|
||||
uint8_t * tx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_TELEM_USB_TX_BUF_LEN);
|
||||
PIOS_Assert(rx_buffer);
|
||||
PIOS_Assert(tx_buffer);
|
||||
if (PIOS_COM_Init(&pios_com_telem_usb_id, &pios_usb_cdc_com_driver, pios_usb_cdc_id,
|
||||
rx_buffer, PIOS_COM_TELEM_USB_RX_BUF_LEN,
|
||||
tx_buffer, PIOS_COM_TELEM_USB_TX_BUF_LEN)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_COM */
|
||||
break;
|
||||
case HWSETTINGS_USB_VCPPORT_COMBRIDGE:
|
||||
#if defined(PIOS_INCLUDE_COM)
|
||||
{
|
||||
uint32_t pios_usb_cdc_id;
|
||||
if (PIOS_USB_CDC_Init(&pios_usb_cdc_id, &pios_usb_cdc_cfg, pios_usb_id)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
uint8_t * rx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_BRIDGE_RX_BUF_LEN);
|
||||
uint8_t * tx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_BRIDGE_TX_BUF_LEN);
|
||||
PIOS_Assert(rx_buffer);
|
||||
PIOS_Assert(tx_buffer);
|
||||
if (PIOS_COM_Init(&pios_com_vcp_id, &pios_usb_cdc_com_driver, pios_usb_cdc_id,
|
||||
rx_buffer, PIOS_COM_BRIDGE_RX_BUF_LEN,
|
||||
tx_buffer, PIOS_COM_BRIDGE_TX_BUF_LEN)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_COM */
|
||||
break;
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_USB_CDC */
|
||||
|
||||
#if defined(PIOS_INCLUDE_USB_HID)
|
||||
/* Configure the usb HID port */
|
||||
uint8_t hwsettings_usb_hidport;
|
||||
HwSettingsUSB_HIDPortGet(&hwsettings_usb_hidport);
|
||||
|
||||
if (!usb_hid_present) {
|
||||
/* Force HID port function to disabled if we haven't advertised HID in our USB descriptor */
|
||||
hwsettings_usb_hidport = HWSETTINGS_USB_HIDPORT_DISABLED;
|
||||
}
|
||||
|
||||
switch (hwsettings_usb_hidport) {
|
||||
case HWSETTINGS_USB_HIDPORT_DISABLED:
|
||||
break;
|
||||
case HWSETTINGS_USB_HIDPORT_USBTELEMETRY:
|
||||
#if defined(PIOS_INCLUDE_COM)
|
||||
{
|
||||
uint32_t pios_usb_hid_id;
|
||||
if (PIOS_USB_HID_Init(&pios_usb_hid_id, &pios_usb_hid_cfg, pios_usb_id)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
uint8_t * rx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_TELEM_USB_RX_BUF_LEN);
|
||||
uint8_t * tx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_TELEM_USB_TX_BUF_LEN);
|
||||
PIOS_Assert(rx_buffer);
|
||||
PIOS_Assert(tx_buffer);
|
||||
if (PIOS_COM_Init(&pios_com_telem_usb_id, &pios_usb_hid_com_driver, pios_usb_hid_id,
|
||||
rx_buffer, PIOS_COM_TELEM_USB_RX_BUF_LEN,
|
||||
tx_buffer, PIOS_COM_TELEM_USB_TX_BUF_LEN)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_COM */
|
||||
break;
|
||||
}
|
||||
|
||||
#endif /* PIOS_INCLUDE_USB_HID */
|
||||
|
||||
#endif /* PIOS_INCLUDE_USB */
|
||||
|
||||
/* Configure the main IO port */
|
||||
uint8_t hwsettings_op_mainport;
|
||||
HwSettingsOP_MainPortGet(&hwsettings_op_mainport);
|
||||
@ -1285,36 +425,14 @@ void PIOS_Board_Init(void) {
|
||||
break;
|
||||
}
|
||||
|
||||
#if defined(PIOS_INCLUDE_USB)
|
||||
uint32_t pios_usb_id;
|
||||
if (PIOS_USB_Init(&pios_usb_id, &pios_usb_main_cfg)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
#if defined(PIOS_INCLUDE_USB_HID) && defined(PIOS_INCLUDE_COM)
|
||||
uint32_t pios_usb_hid_id;
|
||||
if (PIOS_USB_HID_Init(&pios_usb_hid_id, &pios_usb_hid_cfg, pios_usb_id)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
uint8_t * rx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_TELEM_USB_RX_BUF_LEN);
|
||||
uint8_t * tx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_TELEM_USB_TX_BUF_LEN);
|
||||
PIOS_Assert(rx_buffer);
|
||||
PIOS_Assert(tx_buffer);
|
||||
if (PIOS_COM_Init(&pios_com_telem_usb_id, &pios_usb_hid_com_driver, pios_usb_hid_id,
|
||||
rx_buffer, PIOS_COM_TELEM_USB_RX_BUF_LEN,
|
||||
tx_buffer, PIOS_COM_TELEM_USB_TX_BUF_LEN)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_USB_HID && PIOS_INCLUDE_COM */
|
||||
|
||||
#endif /* PIOS_INCLUDE_USB */
|
||||
|
||||
#if defined(PIOS_INCLUDE_I2C)
|
||||
if (PIOS_I2C_Init(&pios_i2c_main_adapter_id, &pios_i2c_main_adapter_cfg)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_I2C */
|
||||
PIOS_IAP_Init();
|
||||
PIOS_WDG_Init();
|
||||
|
||||
/* Make sure we have at least one telemetry link configured or else fail initialization */
|
||||
PIOS_Assert(pios_com_telem_rf_id || pios_com_telem_usb_id);
|
||||
}
|
||||
|
||||
/**
|
||||
|
@ -29,9 +29,11 @@
|
||||
*/
|
||||
|
||||
#include "pios_usb_board_data.h" /* struct usb_*, USB_* */
|
||||
#include "pios_sys.h" /* PIOS_SYS_SerialNumberGet */
|
||||
#include "pios_usbhook.h" /* PIOS_USBHOOK_* */
|
||||
|
||||
const uint8_t PIOS_USB_BOARD_StringProductID[] = {
|
||||
sizeof(PIOS_USB_BOARD_StringProductID),
|
||||
static const uint8_t usb_product_id[20] = {
|
||||
sizeof(usb_product_id),
|
||||
USB_DESC_TYPE_STRING,
|
||||
'O', 0,
|
||||
'p', 0,
|
||||
@ -43,3 +45,76 @@ const uint8_t PIOS_USB_BOARD_StringProductID[] = {
|
||||
'o', 0,
|
||||
't', 0,
|
||||
};
|
||||
|
||||
static uint8_t usb_serial_number[52] = {
|
||||
sizeof(usb_serial_number),
|
||||
USB_DESC_TYPE_STRING,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0
|
||||
};
|
||||
|
||||
static const struct usb_string_langid usb_lang_id = {
|
||||
.bLength = sizeof(usb_lang_id),
|
||||
.bDescriptorType = USB_DESC_TYPE_STRING,
|
||||
.bLangID = htousbs(USB_LANGID_ENGLISH_UK),
|
||||
};
|
||||
|
||||
static const uint8_t usb_vendor_id[28] = {
|
||||
sizeof(usb_vendor_id),
|
||||
USB_DESC_TYPE_STRING,
|
||||
'o', 0,
|
||||
'p', 0,
|
||||
'e', 0,
|
||||
'n', 0,
|
||||
'p', 0,
|
||||
'i', 0,
|
||||
'l', 0,
|
||||
'o', 0,
|
||||
't', 0,
|
||||
'.', 0,
|
||||
'o', 0,
|
||||
'r', 0,
|
||||
'g', 0
|
||||
};
|
||||
|
||||
int32_t PIOS_USB_BOARD_DATA_Init(void)
|
||||
{
|
||||
/* Load device serial number into serial number string */
|
||||
uint8_t sn[25];
|
||||
PIOS_SYS_SerialNumberGet((char *)sn);
|
||||
for (uint8_t i = 0; sn[i] != '\0' && (2 * i) < usb_serial_number[0]; i++) {
|
||||
usb_serial_number[2 + 2 * i] = sn[i];
|
||||
}
|
||||
|
||||
PIOS_USBHOOK_RegisterString(USB_STRING_DESC_PRODUCT, (uint8_t *)&usb_product_id, sizeof(usb_product_id));
|
||||
PIOS_USBHOOK_RegisterString(USB_STRING_DESC_SERIAL, (uint8_t *)&usb_serial_number, sizeof(usb_serial_number));
|
||||
|
||||
PIOS_USBHOOK_RegisterString(USB_STRING_DESC_LANG, (uint8_t *)&usb_lang_id, sizeof(usb_lang_id));
|
||||
PIOS_USBHOOK_RegisterString(USB_STRING_DESC_VENDOR, (uint8_t *)&usb_vendor_id, sizeof(usb_vendor_id));
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
@ -72,7 +72,7 @@ void PIOS_DEBUG_PinValue4BitL(uint8_t value)
|
||||
/**
|
||||
* Report a serious error and halt
|
||||
*/
|
||||
void PIOS_DEBUG_Panic(const char *msg)
|
||||
void PIOS_DEBUG_Panic(const char *msg) __attribute__ ((noreturn))
|
||||
{
|
||||
#ifdef PIOS_COM_DEBUG
|
||||
register int *lr asm("lr"); // Link-register holds the PC of the caller
|
||||
|
@ -71,13 +71,7 @@ TIM8 | | | |
|
||||
//------------------------
|
||||
// PIOS_LED
|
||||
//------------------------
|
||||
#define PIOS_LED_LED1_GPIO_PORT GPIOA
|
||||
#define PIOS_LED_LED1_GPIO_PIN GPIO_Pin_3
|
||||
#define PIOS_LED_LED1_GPIO_CLK RCC_APB2Periph_GPIOA
|
||||
#define PIOS_LED_NUM 1
|
||||
#define PIOS_LED_PORTS { PIOS_LED_LED1_GPIO_PORT }
|
||||
#define PIOS_LED_PINS { PIOS_LED_LED1_GPIO_PIN }
|
||||
#define PIOS_LED_CLKS { PIOS_LED_LED1_GPIO_CLK }
|
||||
#define PIOS_LED_HEARTBEAT 0
|
||||
|
||||
//-------------------------
|
||||
// System Settings
|
||||
|
@ -83,13 +83,7 @@ TIM4 | RC In 1 | Servo 3 | Servo 2 | Servo 1
|
||||
//------------------------
|
||||
// PIOS_LED
|
||||
//------------------------
|
||||
#define PIOS_LED_LED1_GPIO_PORT GPIOA
|
||||
#define PIOS_LED_LED1_GPIO_PIN GPIO_Pin_6
|
||||
#define PIOS_LED_LED1_GPIO_CLK RCC_APB2Periph_GPIOA
|
||||
#define PIOS_LED_NUM 1
|
||||
#define PIOS_LED_PORTS { PIOS_LED_LED1_GPIO_PORT }
|
||||
#define PIOS_LED_PINS { PIOS_LED_LED1_GPIO_PIN }
|
||||
#define PIOS_LED_CLKS { PIOS_LED_LED1_GPIO_CLK }
|
||||
#define PIOS_LED_HEARTBEAT 0
|
||||
|
||||
//-------------------------
|
||||
// System Settings
|
||||
@ -110,8 +104,15 @@ TIM4 | RC In 1 | Servo 3 | Servo 2 | Servo 1
|
||||
// See also pios_board.c
|
||||
//------------------------
|
||||
#define PIOS_I2C_MAX_DEVS 1
|
||||
extern uint32_t pios_i2c_main_adapter_id;
|
||||
#define PIOS_I2C_MAIN_ADAPTER (pios_i2c_main_adapter_id)
|
||||
extern uint32_t pios_i2c_flexi_adapter_id;
|
||||
#define PIOS_I2C_MAIN_ADAPTER (pios_i2c_flexi_adapter_id)
|
||||
#define PIOS_I2C_ESC_ADAPTER (pios_i2c_flexi_adapter_id)
|
||||
#define PIOS_I2C_BMP085_ADAPTER (pios_i2c_flexi_adapter_id)
|
||||
|
||||
//------------------------
|
||||
// PIOS_BMP085
|
||||
//------------------------
|
||||
#define PIOS_BMP085_OVERSAMPLING 3
|
||||
|
||||
//-------------------------
|
||||
// SPI
|
||||
@ -277,6 +278,4 @@ extern uint32_t pios_com_telem_usb_id;
|
||||
#define PIOS_USB_DETECT_GPIO_PORT GPIOC
|
||||
#define PIOS_USB_MAX_DEVS 1
|
||||
#define PIOS_USB_DETECT_GPIO_PIN GPIO_Pin_15
|
||||
#define PIOS_USB_DETECT_EXTI_LINE EXTI_Line15
|
||||
#define PIOS_IRQ_USB_PRIORITY PIOS_IRQ_PRIO_MID
|
||||
#endif /* STM32103CB_AHRS_H_ */
|
||||
|
@ -80,42 +80,29 @@ TIM4 | STOPWATCH |
|
||||
// *****************************************************************
|
||||
// PIOS_LED
|
||||
|
||||
#define PIOS_LED_LED1_GPIO_PORT GPIOA // USB Activity LED
|
||||
#define PIOS_LED_LED1_GPIO_PIN GPIO_Pin_3
|
||||
#define PIOS_LED_LED1_GPIO_CLK RCC_APB2Periph_GPIOA
|
||||
#define PIOS_LED_USB 0
|
||||
#define PIOS_LED_LINK 1
|
||||
#define PIOS_LED_RX 2
|
||||
#define PIOS_LED_TX 3
|
||||
|
||||
#define PIOS_LED_LED2_GPIO_PORT GPIOB // LINK LED
|
||||
#define PIOS_LED_LED2_GPIO_PIN GPIO_Pin_5
|
||||
#define PIOS_LED_LED2_GPIO_CLK RCC_APB2Periph_GPIOB
|
||||
#define PIOS_LED_HEARTBEAT PIOS_LED_USB
|
||||
#define PIOS_LED_ALARM PIOS_LED_TX
|
||||
|
||||
#define PIOS_LED_LED3_GPIO_PORT GPIOB // RX LED
|
||||
#define PIOS_LED_LED3_GPIO_PIN GPIO_Pin_6
|
||||
#define PIOS_LED_LED3_GPIO_CLK RCC_APB2Periph_GPIOB
|
||||
#define USB_LED_ON PIOS_LED_On(PIOS_LED_USB)
|
||||
#define USB_LED_OFF PIOS_LED_Off(PIOS_LED_USB)
|
||||
#define USB_LED_TOGGLE PIOS_LED_Toggle(PIOS_LED_USB)
|
||||
|
||||
#define PIOS_LED_LED4_GPIO_PORT GPIOB // TX LED
|
||||
#define PIOS_LED_LED4_GPIO_PIN GPIO_Pin_7
|
||||
#define PIOS_LED_LED4_GPIO_CLK RCC_APB2Periph_GPIOB
|
||||
#define LINK_LED_ON PIOS_LED_On(PIOS_LED_LINK)
|
||||
#define LINK_LED_OFF PIOS_LED_Off(PIOS_LED_LINK)
|
||||
#define LINK_LED_TOGGLE PIOS_LED_Toggle(PIOS_LED_LINK)
|
||||
|
||||
#define PIOS_LED_NUM 4
|
||||
#define PIOS_LED_PORTS { PIOS_LED_LED1_GPIO_PORT, PIOS_LED_LED2_GPIO_PORT, PIOS_LED_LED3_GPIO_PORT, PIOS_LED_LED4_GPIO_PORT }
|
||||
#define PIOS_LED_PINS { PIOS_LED_LED1_GPIO_PIN, PIOS_LED_LED2_GPIO_PIN, PIOS_LED_LED3_GPIO_PIN, PIOS_LED_LED4_GPIO_PIN }
|
||||
#define PIOS_LED_CLKS { PIOS_LED_LED1_GPIO_CLK, PIOS_LED_LED2_GPIO_CLK, PIOS_LED_LED3_GPIO_CLK, PIOS_LED_LED4_GPIO_CLK }
|
||||
#define RX_LED_ON PIOS_LED_On(PIOS_LED_RX)
|
||||
#define RX_LED_OFF PIOS_LED_Off(PIOS_LED_RX)
|
||||
#define RX_LED_TOGGLE PIOS_LED_Toggle(PIOS_LED_RX)
|
||||
|
||||
#define USB_LED_ON PIOS_LED_On(LED1)
|
||||
#define USB_LED_OFF PIOS_LED_Off(LED1)
|
||||
#define USB_LED_TOGGLE PIOS_LED_Toggle(LED1)
|
||||
|
||||
#define LINK_LED_ON PIOS_LED_On(LED2)
|
||||
#define LINK_LED_OFF PIOS_LED_Off(LED2)
|
||||
#define LINK_LED_TOGGLE PIOS_LED_Toggle(LED2)
|
||||
|
||||
#define RX_LED_ON PIOS_LED_On(LED3)
|
||||
#define RX_LED_OFF PIOS_LED_Off(LED3)
|
||||
#define RX_LED_TOGGLE PIOS_LED_Toggle(LED3)
|
||||
|
||||
#define TX_LED_ON PIOS_LED_On(LED4)
|
||||
#define TX_LED_OFF PIOS_LED_Off(LED4)
|
||||
#define TX_LED_TOGGLE PIOS_LED_Toggle(LED4)
|
||||
#define TX_LED_ON PIOS_LED_On(PIOS_LED_TX)
|
||||
#define TX_LED_OFF PIOS_LED_Off(PIOS_LED_TX)
|
||||
#define TX_LED_TOGGLE PIOS_LED_Toggle(PIOS_LED_TX)
|
||||
|
||||
// *****************************************************************
|
||||
// Timer interrupt
|
||||
|
@ -76,16 +76,8 @@ TIM8 | | | |
|
||||
//------------------------
|
||||
// PIOS_LED
|
||||
//------------------------
|
||||
#define PIOS_LED_LED1_GPIO_PORT GPIOA
|
||||
#define PIOS_LED_LED1_GPIO_PIN GPIO_Pin_3
|
||||
#define PIOS_LED_LED1_GPIO_CLK RCC_APB2Periph_GPIOA
|
||||
#define PIOS_LED_LED2_GPIO_PORT GPIOA
|
||||
#define PIOS_LED_LED2_GPIO_PIN GPIO_Pin_2
|
||||
#define PIOS_LED_LED2_GPIO_CLK RCC_APB2Periph_GPIOA
|
||||
#define PIOS_LED_NUM 2
|
||||
#define PIOS_LED_PORTS { PIOS_LED_LED1_GPIO_PORT, PIOS_LED_LED2_GPIO_PORT }
|
||||
#define PIOS_LED_PINS { PIOS_LED_LED1_GPIO_PIN, PIOS_LED_LED2_GPIO_PIN }
|
||||
#define PIOS_LED_CLKS { PIOS_LED_LED1_GPIO_CLK, PIOS_LED_LED2_GPIO_CLK }
|
||||
#define PIOS_LED_HEARTBEAT 0
|
||||
#define PIOS_LED_ALARM 1
|
||||
|
||||
//------------------------
|
||||
// PIOS_SPI
|
||||
@ -100,12 +92,14 @@ TIM8 | | | |
|
||||
#define PIOS_I2C_MAX_DEVS 3
|
||||
extern uint32_t pios_i2c_pres_mag_adapter_id;
|
||||
#define PIOS_I2C_MAIN_ADAPTER (pios_i2c_pres_mag_adapter_id)
|
||||
#define PIOS_I2C_BMP085_ADAPTER (pios_i2c_pres_mag_adapter_id)
|
||||
extern uint32_t pios_i2c_gyro_adapter_id;
|
||||
#define PIOS_I2C_GYRO_ADAPTER (pios_i2c_gyro_adapter_id)
|
||||
|
||||
//------------------------
|
||||
// PIOS_BMP085
|
||||
//------------------------
|
||||
#define PIOS_BMP085_HAS_GPIOS
|
||||
#define PIOS_BMP085_EOC_GPIO_PORT GPIOC
|
||||
#define PIOS_BMP085_EOC_GPIO_PIN GPIO_Pin_2
|
||||
#define PIOS_BMP085_EOC_PORT_SOURCE GPIO_PortSourceGPIOC
|
||||
|
@ -91,16 +91,8 @@ TIM8 | Servo 5 | Servo 6 | Servo 7 | Servo 8
|
||||
//------------------------
|
||||
// PIOS_LED
|
||||
//------------------------
|
||||
#define PIOS_LED_LED1_GPIO_PORT GPIOC
|
||||
#define PIOS_LED_LED1_GPIO_PIN GPIO_Pin_12
|
||||
#define PIOS_LED_LED1_GPIO_CLK RCC_APB2Periph_GPIOC
|
||||
#define PIOS_LED_LED2_GPIO_PORT GPIOC
|
||||
#define PIOS_LED_LED2_GPIO_PIN GPIO_Pin_13
|
||||
#define PIOS_LED_LED2_GPIO_CLK RCC_APB2Periph_GPIOC
|
||||
#define PIOS_LED_NUM 2
|
||||
#define PIOS_LED_PORTS { PIOS_LED_LED1_GPIO_PORT, PIOS_LED_LED2_GPIO_PORT }
|
||||
#define PIOS_LED_PINS { PIOS_LED_LED1_GPIO_PIN, PIOS_LED_LED2_GPIO_PIN }
|
||||
#define PIOS_LED_CLKS { PIOS_LED_LED1_GPIO_CLK, PIOS_LED_LED2_GPIO_CLK }
|
||||
#define PIOS_LED_HEARTBEAT 0
|
||||
#define PIOS_LED_ALARM 1
|
||||
|
||||
//------------------------
|
||||
// PIOS_SPI
|
||||
@ -115,10 +107,13 @@ TIM8 | Servo 5 | Servo 6 | Servo 7 | Servo 8
|
||||
#define PIOS_I2C_MAX_DEVS 1
|
||||
extern uint32_t pios_i2c_main_adapter_id;
|
||||
#define PIOS_I2C_MAIN_ADAPTER (pios_i2c_main_adapter_id)
|
||||
#define PIOS_I2C_ESC_ADAPTER (pios_i2c_main_adapter_id)
|
||||
#define PIOS_I2C_BMP085_ADAPTER (pios_i2c_main_adapter_id)
|
||||
|
||||
//------------------------
|
||||
// PIOS_BMP085
|
||||
//------------------------
|
||||
#define PIOS_BMP085_HAS_GPIOS
|
||||
#define PIOS_BMP085_EOC_GPIO_PORT GPIOC
|
||||
#define PIOS_BMP085_EOC_GPIO_PIN GPIO_Pin_15
|
||||
#define PIOS_BMP085_EOC_PORT_SOURCE GPIO_PortSourceGPIOC
|
||||
@ -313,8 +308,6 @@ extern uint32_t pios_com_aux_id;
|
||||
#define PIOS_USB_MAX_DEVS 1
|
||||
#define PIOS_USB_HID_MAX_DEVS 1
|
||||
#define PIOS_USB_DETECT_GPIO_PIN GPIO_Pin_4
|
||||
#define PIOS_USB_DETECT_EXTI_LINE EXTI_Line4
|
||||
#define PIOS_IRQ_USB_PRIORITY PIOS_IRQ_PRIO_MID
|
||||
|
||||
/**
|
||||
* glue macros for file IO
|
||||
|
@ -36,13 +36,10 @@
|
||||
#error PIOS_EXTI Must be included in the project!
|
||||
#endif /* PIOS_INCLUDE_EXTI */
|
||||
|
||||
#include <pios_exti.h>
|
||||
|
||||
/* Glocal Variables */
|
||||
ConversionTypeTypeDef CurrentRead;
|
||||
#if defined(PIOS_INCLUDE_FREERTOS)
|
||||
xSemaphoreHandle PIOS_BMP085_EOC;
|
||||
#else
|
||||
int32_t PIOS_BMP085_EOC;
|
||||
#endif
|
||||
|
||||
/* Local Variables */
|
||||
static BMP085CalibDataTypeDef CalibData;
|
||||
@ -55,14 +52,68 @@ static volatile uint32_t RawPressure;
|
||||
static volatile uint32_t Pressure;
|
||||
static volatile uint16_t Temperature;
|
||||
|
||||
#ifdef PIOS_BMP085_HAS_GPIOS
|
||||
|
||||
#if defined(PIOS_INCLUDE_FREERTOS)
|
||||
xSemaphoreHandle PIOS_BMP085_EOC;
|
||||
#else
|
||||
int32_t PIOS_BMP085_EOC;
|
||||
#endif
|
||||
|
||||
void PIOS_BMP085_EndOfConversion (void)
|
||||
{
|
||||
#if defined(PIOS_INCLUDE_FREERTOS)
|
||||
portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE;
|
||||
#endif
|
||||
|
||||
/* Read the ADC Value */
|
||||
#if defined(PIOS_INCLUDE_FREERTOS)
|
||||
xSemaphoreGiveFromISR(PIOS_BMP085_EOC, &xHigherPriorityTaskWoken);
|
||||
#else
|
||||
PIOS_BMP085_EOC=1;
|
||||
#endif
|
||||
|
||||
#if defined(PIOS_INCLUDE_FREERTOS)
|
||||
/* Yield From ISR if needed */
|
||||
portEND_SWITCHING_ISR(xHigherPriorityTaskWoken);
|
||||
#endif
|
||||
}
|
||||
|
||||
static const struct pios_exti_cfg pios_exti_bmp085_cfg __exti_config = {
|
||||
.vector = PIOS_BMP085_EndOfConversion,
|
||||
.line = PIOS_BMP085_EOC_EXTI_LINE,
|
||||
.pin = {
|
||||
.gpio = PIOS_BMP085_EOC_GPIO_PORT,
|
||||
.init = {
|
||||
.GPIO_Pin = PIOS_BMP085_EOC_GPIO_PIN,
|
||||
.GPIO_Mode = GPIO_Mode_IN_FLOATING,
|
||||
},
|
||||
},
|
||||
.irq = {
|
||||
.init = {
|
||||
.NVIC_IRQChannel = PIOS_BMP085_EOC_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_BMP085_EOC_PRIO,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
.exti = {
|
||||
.init = {
|
||||
.EXTI_Line = PIOS_BMP085_EOC_EXTI_LINE,
|
||||
.EXTI_Mode = EXTI_Mode_Interrupt,
|
||||
.EXTI_Trigger = EXTI_Trigger_Rising,
|
||||
.EXTI_LineCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
#endif /* PIOS_BMP085_HAS_GPIOS */
|
||||
/**
|
||||
* Initialise the BMP085 sensor
|
||||
*/
|
||||
void PIOS_BMP085_Init(void)
|
||||
{
|
||||
GPIO_InitTypeDef GPIO_InitStructure;
|
||||
EXTI_InitTypeDef EXTI_InitStructure;
|
||||
NVIC_InitTypeDef NVIC_InitStructure;
|
||||
#ifdef PIOS_BMP085_HAS_GPIOS
|
||||
|
||||
#if defined(PIOS_INCLUDE_FREERTOS)
|
||||
/* Semaphore used by ISR to signal End-Of-Conversion */
|
||||
@ -76,31 +127,18 @@ void PIOS_BMP085_Init(void)
|
||||
/* Enable EOC GPIO clock */
|
||||
RCC_APB2PeriphClockCmd(PIOS_BMP085_EOC_CLK | RCC_APB2Periph_AFIO, ENABLE);
|
||||
|
||||
/* Configure EOC pin as input floating */
|
||||
GPIO_InitStructure.GPIO_Pin = PIOS_BMP085_EOC_GPIO_PIN;
|
||||
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN_FLOATING;
|
||||
GPIO_Init(PIOS_BMP085_EOC_GPIO_PORT, &GPIO_InitStructure);
|
||||
|
||||
/* Configure the End Of Conversion (EOC) interrupt */
|
||||
GPIO_EXTILineConfig(PIOS_BMP085_EOC_PORT_SOURCE, PIOS_BMP085_EOC_PIN_SOURCE);
|
||||
EXTI_InitStructure.EXTI_Line = PIOS_BMP085_EOC_EXTI_LINE;
|
||||
EXTI_InitStructure.EXTI_Mode = EXTI_Mode_Interrupt;
|
||||
EXTI_InitStructure.EXTI_Trigger = EXTI_Trigger_Rising;
|
||||
EXTI_InitStructure.EXTI_LineCmd = ENABLE;
|
||||
EXTI_Init(&EXTI_InitStructure);
|
||||
|
||||
/* Enable and set EOC EXTI Interrupt to the lowest priority */
|
||||
NVIC_InitStructure.NVIC_IRQChannel = PIOS_BMP085_EOC_IRQn;
|
||||
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = PIOS_BMP085_EOC_PRIO;
|
||||
NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0;
|
||||
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
|
||||
NVIC_Init(&NVIC_InitStructure);
|
||||
if (PIOS_EXTI_Init(&pios_exti_bmp085_cfg)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
|
||||
/* Configure XCLR pin as push/pull alternate funtion output */
|
||||
GPIO_InitTypeDef GPIO_InitStructure;
|
||||
GPIO_InitStructure.GPIO_Pin = PIOS_BMP085_XCLR_GPIO_PIN;
|
||||
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP;
|
||||
GPIO_Init(PIOS_BMP085_XCLR_GPIO_PORT, &GPIO_InitStructure);
|
||||
|
||||
#endif /* PIOS_BMP085_HAS_GPIOS */
|
||||
|
||||
/* Read all 22 bytes of calibration data in one transfer, this is a very optimized way of doing things */
|
||||
uint8_t Data[BMP085_CALIB_LEN];
|
||||
while (!PIOS_BMP085_Read(BMP085_CALIB_ADDR, Data, BMP085_CALIB_LEN))
|
||||
@ -235,7 +273,7 @@ bool PIOS_BMP085_Read(uint8_t address, uint8_t * buffer, uint8_t len)
|
||||
}
|
||||
};
|
||||
|
||||
return PIOS_I2C_Transfer(PIOS_I2C_MAIN_ADAPTER, txn_list, NELEMENTS(txn_list));
|
||||
return PIOS_I2C_Transfer(PIOS_I2C_BMP085_ADAPTER, txn_list, NELEMENTS(txn_list));
|
||||
}
|
||||
|
||||
/**
|
||||
@ -264,7 +302,7 @@ bool PIOS_BMP085_Write(uint8_t address, uint8_t buffer)
|
||||
,
|
||||
};
|
||||
|
||||
return PIOS_I2C_Transfer(PIOS_I2C_MAIN_ADAPTER, txn_list, NELEMENTS(txn_list));
|
||||
return PIOS_I2C_Transfer(PIOS_I2C_BMP085_ADAPTER, txn_list, NELEMENTS(txn_list));
|
||||
}
|
||||
|
||||
/**
|
||||
|
185
flight/PiOS/Common/pios_com_msg.c
Normal file
185
flight/PiOS/Common/pios_com_msg.c
Normal file
@ -0,0 +1,185 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup PIOS PIOS Core hardware abstraction layer
|
||||
* @{
|
||||
* @addtogroup PIOS_COM COM MSG layer functions
|
||||
* @brief Hardware communication layer
|
||||
* @{
|
||||
*
|
||||
* @file pios_com_msg.c
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @brief COM MSG layer functions
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
*
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* This program is free software; you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation; either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful, but
|
||||
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
|
||||
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
|
||||
* for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License along
|
||||
* with this program; if not, write to the Free Software Foundation, Inc.,
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
|
||||
/* Project Includes */
|
||||
#include "pios.h"
|
||||
|
||||
#if defined(PIOS_INCLUDE_COM_MSG)
|
||||
|
||||
#include "pios_com.h"
|
||||
|
||||
#define PIOS_COM_MSG_MAX_LEN 63
|
||||
|
||||
struct pios_com_msg_dev {
|
||||
uint32_t lower_id;
|
||||
const struct pios_com_driver * driver;
|
||||
|
||||
uint8_t rx_msg_buffer[PIOS_COM_MSG_MAX_LEN];
|
||||
volatile bool rx_msg_full;
|
||||
|
||||
uint8_t tx_msg_buffer[PIOS_COM_MSG_MAX_LEN];
|
||||
volatile bool tx_msg_full;
|
||||
};
|
||||
|
||||
static struct pios_com_msg_dev com_msg_dev;
|
||||
|
||||
static uint16_t PIOS_COM_MSG_TxOutCallback(uint32_t context, uint8_t * buf, uint16_t buf_len, uint16_t * headroom, bool * need_yield);
|
||||
static uint16_t PIOS_COM_MSG_RxInCallback(uint32_t context, uint8_t * buf, uint16_t buf_len, uint16_t * headroom, bool * need_yield);
|
||||
|
||||
int32_t PIOS_COM_MSG_Init(uint32_t * com_id, const struct pios_com_driver * driver, uint32_t lower_id)
|
||||
{
|
||||
PIOS_Assert(com_id);
|
||||
PIOS_Assert(driver);
|
||||
|
||||
PIOS_Assert(driver->bind_tx_cb);
|
||||
PIOS_Assert(driver->bind_rx_cb);
|
||||
|
||||
struct pios_com_msg_dev * com_dev = &com_msg_dev;
|
||||
|
||||
com_dev->driver = driver;
|
||||
com_dev->lower_id = lower_id;
|
||||
|
||||
com_dev->rx_msg_full = false;
|
||||
(com_dev->driver->bind_rx_cb)(lower_id, PIOS_COM_MSG_RxInCallback, (uint32_t)com_dev);
|
||||
(com_dev->driver->rx_start)(com_dev->lower_id, sizeof(com_dev->rx_msg_buffer));
|
||||
|
||||
com_dev->tx_msg_full = false;
|
||||
(com_dev->driver->bind_tx_cb)(lower_id, PIOS_COM_MSG_TxOutCallback, (uint32_t)com_dev);
|
||||
|
||||
*com_id = (uint32_t)com_dev;
|
||||
return(0);
|
||||
}
|
||||
|
||||
static uint16_t PIOS_COM_MSG_TxOutCallback(uint32_t context, uint8_t * buf, uint16_t buf_len, uint16_t * headroom, bool * need_yield)
|
||||
{
|
||||
struct pios_com_msg_dev * com_dev = (struct pios_com_msg_dev *)context;
|
||||
|
||||
PIOS_Assert(buf);
|
||||
PIOS_Assert(buf_len);
|
||||
|
||||
uint16_t bytes_from_fifo = 0;
|
||||
|
||||
if (com_dev->tx_msg_full && (buf_len >= sizeof(com_dev->tx_msg_buffer))) {
|
||||
/* Room for an entire message, send it */
|
||||
memcpy(buf, com_dev->tx_msg_buffer, sizeof(com_dev->tx_msg_buffer));
|
||||
bytes_from_fifo = sizeof(com_dev->tx_msg_buffer);
|
||||
com_dev->tx_msg_full = false;
|
||||
}
|
||||
|
||||
if (headroom) {
|
||||
if (com_dev->tx_msg_full) {
|
||||
*headroom = sizeof(com_dev->tx_msg_buffer);
|
||||
} else {
|
||||
*headroom = 0;
|
||||
}
|
||||
}
|
||||
|
||||
return (bytes_from_fifo);
|
||||
}
|
||||
|
||||
static uint16_t PIOS_COM_MSG_RxInCallback(uint32_t context, uint8_t * buf, uint16_t buf_len, uint16_t * headroom, bool * need_yield)
|
||||
{
|
||||
struct pios_com_msg_dev * com_dev = (struct pios_com_msg_dev *)context;
|
||||
|
||||
uint16_t bytes_into_fifo = 0;
|
||||
|
||||
if (!com_dev->rx_msg_full && (buf_len >= sizeof(com_dev->rx_msg_buffer))) {
|
||||
memcpy(com_dev->rx_msg_buffer, buf, sizeof(com_dev->rx_msg_buffer));
|
||||
bytes_into_fifo = sizeof(com_dev->rx_msg_buffer);
|
||||
com_dev->rx_msg_full = true;
|
||||
}
|
||||
|
||||
if (headroom) {
|
||||
if (!com_dev->rx_msg_full) {
|
||||
*headroom = sizeof(com_dev->rx_msg_buffer);
|
||||
} else {
|
||||
*headroom = 0;
|
||||
}
|
||||
}
|
||||
|
||||
return (bytes_into_fifo);
|
||||
}
|
||||
|
||||
int32_t PIOS_COM_MSG_Send(uint32_t com_id, const uint8_t *msg, uint16_t msg_len)
|
||||
{
|
||||
PIOS_Assert(msg);
|
||||
PIOS_Assert(msg_len);
|
||||
|
||||
struct pios_com_msg_dev * com_dev = (struct pios_com_msg_dev *)com_id;
|
||||
|
||||
PIOS_Assert(msg_len == sizeof(com_dev->tx_msg_buffer));
|
||||
|
||||
/* Wait forever for room in the tx buffer */
|
||||
while (com_dev->tx_msg_full) {
|
||||
/* Kick the transmitter while we wait */
|
||||
if (com_dev->driver->tx_start) {
|
||||
(com_dev->driver->tx_start)(com_dev->lower_id, sizeof(com_dev->tx_msg_buffer));
|
||||
}
|
||||
}
|
||||
|
||||
memcpy((void *) com_dev->tx_msg_buffer, msg, msg_len);
|
||||
com_dev->tx_msg_full = true;
|
||||
|
||||
/* Kick the transmitter now that we've queued our message */
|
||||
if (com_dev->driver->tx_start) {
|
||||
(com_dev->driver->tx_start)(com_dev->lower_id, sizeof(com_dev->tx_msg_buffer));
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
uint16_t PIOS_COM_MSG_Receive(uint32_t com_id, uint8_t * msg, uint16_t msg_len)
|
||||
{
|
||||
PIOS_Assert(msg);
|
||||
PIOS_Assert(msg_len);
|
||||
|
||||
struct pios_com_msg_dev * com_dev = (struct pios_com_msg_dev *)com_id;
|
||||
|
||||
PIOS_Assert(msg_len == sizeof(com_dev->rx_msg_buffer));
|
||||
|
||||
if (!com_dev->rx_msg_full) {
|
||||
/* There's room in our buffer, kick the receiver */
|
||||
(com_dev->driver->rx_start)(com_dev->lower_id, sizeof(com_dev->rx_msg_buffer));
|
||||
} else {
|
||||
memcpy(msg, com_dev->rx_msg_buffer, msg_len);
|
||||
com_dev->rx_msg_full = false;
|
||||
|
||||
return msg_len;
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
#endif /* PIOS_INCLUDE_COM_MSG */
|
||||
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
@ -81,7 +81,9 @@ int32_t PIOS_FLASHFS_Init()
|
||||
if(object_table_magic != OBJECT_TABLE_MAGIC) {
|
||||
if(magic_fail_count++ > MAX_BADMAGIC) {
|
||||
PIOS_FLASHFS_ClearObjectTableHeader();
|
||||
PIOS_LED_Toggle(LED1);
|
||||
#if defined(PIOS_LED_HEARTBEAT)
|
||||
PIOS_LED_Toggle(PIOS_LED_HEARTBEAT);
|
||||
#endif /* PIOS_LED_HEARTBEAT */
|
||||
magic_fail_count = 0;
|
||||
magic_good = true;
|
||||
} else {
|
||||
|
@ -34,6 +34,8 @@
|
||||
|
||||
#if defined(PIOS_INCLUDE_HMC5843)
|
||||
|
||||
#include <pios_exti.h>
|
||||
|
||||
/* HMC5843 Addresses */
|
||||
#define PIOS_HMC5843_I2C_ADDR 0x1E
|
||||
#define PIOS_HMC5843_CONFIG_REG_A (uint8_t)0x00
|
||||
@ -107,37 +109,48 @@ static void PIOS_HMC5843_Config(PIOS_HMC5843_ConfigTypeDef * HMC5843_Config_Stru
|
||||
static bool PIOS_HMC5843_Read(uint8_t address, uint8_t * buffer, uint8_t len);
|
||||
static bool PIOS_HMC5843_Write(uint8_t address, uint8_t buffer);
|
||||
|
||||
void PIOS_HMC5843_EndOfConversion (void)
|
||||
{
|
||||
pios_hmc5843_data_ready = true;
|
||||
}
|
||||
|
||||
static const struct pios_exti_cfg pios_exti_hmc5843_cfg __exti_config = {
|
||||
.vector = PIOS_HMC5843_EndOfConversion,
|
||||
.line = PIOS_HMC5843_DRDY_EXTI_LINE,
|
||||
.pin = {
|
||||
.gpio = PIOS_HMC5843_DRDY_GPIO_PORT,
|
||||
.init = {
|
||||
.GPIO_Pin = PIOS_HMC5843_DRDY_GPIO_PIN,
|
||||
.GPIO_Mode = GPIO_Mode_IN_FLOATING,
|
||||
},
|
||||
},
|
||||
.irq = {
|
||||
.init = {
|
||||
.NVIC_IRQChannel = PIOS_HMC5843_DRDY_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_HMC5843_DRDY_PRIO,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
.exti = {
|
||||
.init = {
|
||||
.EXTI_Line = PIOS_HMC5843_DRDY_EXTI_LINE,
|
||||
.EXTI_Mode = EXTI_Mode_Interrupt,
|
||||
.EXTI_Trigger = EXTI_Trigger_Rising,
|
||||
.EXTI_LineCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
/**
|
||||
* @brieft Initialise the HMC5843 sensor
|
||||
* @brief Initialise the HMC5843 sensor
|
||||
*/
|
||||
void PIOS_HMC5843_Init(void)
|
||||
{
|
||||
GPIO_InitTypeDef GPIO_InitStructure;
|
||||
EXTI_InitTypeDef EXTI_InitStructure;
|
||||
NVIC_InitTypeDef NVIC_InitStructure;
|
||||
|
||||
/* Enable DRDY GPIO clock */
|
||||
RCC_APB2PeriphClockCmd(PIOS_HMC5843_DRDY_CLK | RCC_APB2Periph_AFIO, ENABLE);
|
||||
|
||||
/* Configure EOC pin as input floating */
|
||||
GPIO_InitStructure.GPIO_Pin = PIOS_HMC5843_DRDY_GPIO_PIN;
|
||||
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN_FLOATING;
|
||||
GPIO_Init(PIOS_HMC5843_DRDY_GPIO_PORT, &GPIO_InitStructure);
|
||||
|
||||
/* Configure the End Of Conversion (EOC) interrupt */
|
||||
GPIO_EXTILineConfig(PIOS_HMC5843_DRDY_PORT_SOURCE, PIOS_HMC5843_DRDY_PIN_SOURCE);
|
||||
EXTI_InitStructure.EXTI_Line = PIOS_HMC5843_DRDY_EXTI_LINE;
|
||||
EXTI_InitStructure.EXTI_Mode = EXTI_Mode_Interrupt;
|
||||
EXTI_InitStructure.EXTI_Trigger = EXTI_Trigger_Rising;
|
||||
EXTI_InitStructure.EXTI_LineCmd = ENABLE;
|
||||
EXTI_Init(&EXTI_InitStructure);
|
||||
|
||||
/* Enable and set EOC EXTI Interrupt to the lowest priority */
|
||||
NVIC_InitStructure.NVIC_IRQChannel = PIOS_HMC5843_DRDY_IRQn;
|
||||
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = PIOS_HMC5843_DRDY_PRIO;
|
||||
NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0;
|
||||
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
|
||||
NVIC_Init(&NVIC_InitStructure);
|
||||
PIOS_EXTI_Init(&pios_exti_hmc5843_cfg);
|
||||
|
||||
/* Configure the HMC5843 Sensor */
|
||||
PIOS_HMC5843_ConfigTypeDef HMC5843_InitStructure;
|
||||
@ -362,11 +375,6 @@ static bool PIOS_HMC5843_Write(uint8_t address, uint8_t buffer)
|
||||
return PIOS_I2C_Transfer(PIOS_I2C_MAIN_ADAPTER, txn_list, NELEMENTS(txn_list));
|
||||
}
|
||||
|
||||
void PIOS_HMC5843_IRQHandler(void)
|
||||
{
|
||||
pios_hmc5843_data_ready = true;
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
@ -93,7 +93,7 @@ bool PIOS_I2C_ESC_SetSpeed(uint8_t speed[4])
|
||||
}
|
||||
};
|
||||
|
||||
return PIOS_I2C_Transfer(PIOS_I2C_MAIN_ADAPTER, txn_list, NELEMENTS(txn_list));
|
||||
return PIOS_I2C_Transfer(PIOS_I2C_ESC_ADAPTER, txn_list, NELEMENTS(txn_list));
|
||||
}
|
||||
|
||||
bool PIOS_SetMKSpeed(uint8_t motornum, uint8_t speed) {
|
||||
@ -115,7 +115,7 @@ bool PIOS_SetMKSpeed(uint8_t motornum, uint8_t speed) {
|
||||
}
|
||||
};
|
||||
|
||||
return PIOS_I2C_Transfer(PIOS_I2C_MAIN_ADAPTER, txn_list, NELEMENTS(txn_list));
|
||||
return PIOS_I2C_Transfer(PIOS_I2C_ESC_ADAPTER, txn_list, NELEMENTS(txn_list));
|
||||
}
|
||||
|
||||
bool PIOS_SetAstec4Address(uint8_t new_address) {
|
||||
@ -134,7 +134,7 @@ bool PIOS_SetAstec4Address(uint8_t new_address) {
|
||||
}
|
||||
};
|
||||
|
||||
return PIOS_I2C_Transfer(PIOS_I2C_MAIN_ADAPTER, txn_list, NELEMENTS(txn_list));
|
||||
return PIOS_I2C_Transfer(PIOS_I2C_ESC_ADAPTER, txn_list, NELEMENTS(txn_list));
|
||||
}
|
||||
|
||||
bool PIOS_SetAstec4Speed(uint8_t motornum, uint8_t speed) {
|
||||
@ -161,7 +161,7 @@ bool PIOS_SetAstec4Speed(uint8_t motornum, uint8_t speed) {
|
||||
}
|
||||
};
|
||||
|
||||
return PIOS_I2C_Transfer(PIOS_I2C_MAIN_ADAPTER, txn_list, NELEMENTS(txn_list));
|
||||
return PIOS_I2C_Transfer(PIOS_I2C_ESC_ADAPTER, txn_list, NELEMENTS(txn_list));
|
||||
}
|
||||
|
||||
#endif
|
||||
|
@ -28,9 +28,12 @@
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
|
||||
#include "pios_usb_board_data.h" /* struct usb_*, USB_* */
|
||||
#include "pios_usb_desc_hid_cdc_priv.h" /* exported API */
|
||||
#include "pios_usb_defs.h" /* struct usb_*, USB_* */
|
||||
#include "pios_usb_board_data.h" /* PIOS_USB_BOARD_* */
|
||||
#include "pios_usbhook.h" /* PIOS_USBHOOK_Register* */
|
||||
|
||||
const struct usb_device_desc PIOS_USB_BOARD_DeviceDescriptor = {
|
||||
static const struct usb_device_desc device_desc = {
|
||||
.bLength = sizeof(struct usb_device_desc),
|
||||
.bDescriptorType = USB_DESC_TYPE_DEVICE,
|
||||
.bcdUSB = htousbs(0x0200),
|
||||
@ -41,17 +44,79 @@ const struct usb_device_desc PIOS_USB_BOARD_DeviceDescriptor = {
|
||||
.idVendor = htousbs(USB_VENDOR_ID_OPENPILOT),
|
||||
.idProduct = htousbs(PIOS_USB_BOARD_PRODUCT_ID),
|
||||
.bcdDevice = htousbs(PIOS_USB_BOARD_DEVICE_VER),
|
||||
.iManufacturer = 1,
|
||||
.iProduct = 2,
|
||||
.iSerialNumber = 3,
|
||||
.iManufacturer = USB_STRING_DESC_VENDOR,
|
||||
.iProduct = USB_STRING_DESC_PRODUCT,
|
||||
.iSerialNumber = USB_STRING_DESC_SERIAL,
|
||||
.bNumConfigurations = 1,
|
||||
};
|
||||
|
||||
const struct usb_board_config PIOS_USB_BOARD_Configuration = {
|
||||
static const uint8_t hid_report_desc[36] = {
|
||||
HID_GLOBAL_ITEM_2 (HID_TAG_GLOBAL_USAGE_PAGE),
|
||||
0x9C, 0xFF, /* Usage Page 0xFF9C (Vendor Defined) */
|
||||
HID_LOCAL_ITEM_1 (HID_TAG_LOCAL_USAGE),
|
||||
0x01, /* Usage ID 0x0001 (0x01-0x1F uaually for top-level collections) */
|
||||
|
||||
HID_MAIN_ITEM_1 (HID_TAG_MAIN_COLLECTION),
|
||||
0x01, /* Application */
|
||||
|
||||
/* Device -> Host emulated serial channel */
|
||||
HID_GLOBAL_ITEM_1 (HID_TAG_GLOBAL_REPORT_ID),
|
||||
0x01, /* OpenPilot emulated serial channel (Device -> Host) */
|
||||
HID_LOCAL_ITEM_1 (HID_TAG_LOCAL_USAGE),
|
||||
0x02,
|
||||
HID_GLOBAL_ITEM_1 (HID_TAG_GLOBAL_LOGICAL_MIN),
|
||||
0x00, /* Values range from min = 0x00 */
|
||||
HID_GLOBAL_ITEM_1 (HID_TAG_GLOBAL_LOGICAL_MAX),
|
||||
0xFF, /* Values range to max = 0xFF */
|
||||
HID_GLOBAL_ITEM_1 (HID_TAG_GLOBAL_REPORT_SIZE),
|
||||
0x08, /* 8 bits wide */
|
||||
HID_GLOBAL_ITEM_1 (HID_TAG_GLOBAL_REPORT_CNT),
|
||||
PIOS_USB_BOARD_HID_DATA_LENGTH-1, /* Need to leave room for a report ID */
|
||||
HID_MAIN_ITEM_1 (HID_TAG_MAIN_INPUT),
|
||||
0x03, /* Variable, Constant (read-only) */
|
||||
|
||||
/* Host -> Host emulated serial channel */
|
||||
HID_GLOBAL_ITEM_1 (HID_TAG_GLOBAL_REPORT_ID),
|
||||
0x02, /* OpenPilot emulated Serial Channel (Host -> Device) */
|
||||
HID_LOCAL_ITEM_1 (HID_TAG_LOCAL_USAGE),
|
||||
0x02,
|
||||
HID_GLOBAL_ITEM_1 (HID_TAG_GLOBAL_LOGICAL_MIN),
|
||||
0x00, /* Values range from min = 0x00 */
|
||||
HID_GLOBAL_ITEM_1 (HID_TAG_GLOBAL_LOGICAL_MAX),
|
||||
0xFF, /* Values range to max = 0xFF */
|
||||
HID_GLOBAL_ITEM_1 (HID_TAG_GLOBAL_REPORT_SIZE),
|
||||
0x08, /* 8 bits wide */
|
||||
HID_GLOBAL_ITEM_1 (HID_TAG_GLOBAL_REPORT_CNT),
|
||||
PIOS_USB_BOARD_HID_DATA_LENGTH-1, /* Need to leave room for a report ID */
|
||||
HID_MAIN_ITEM_1 (HID_TAG_MAIN_OUTPUT),
|
||||
0x82, /* Volatile, Variable */
|
||||
|
||||
HID_MAIN_ITEM_0 (HID_TAG_MAIN_ENDCOLLECTION),
|
||||
};
|
||||
|
||||
struct usb_config_hid_cdc {
|
||||
struct usb_configuration_desc config;
|
||||
struct usb_interface_association_desc iad;
|
||||
struct usb_interface_desc hid_if;
|
||||
struct usb_hid_desc hid;
|
||||
struct usb_endpoint_desc hid_in;
|
||||
struct usb_endpoint_desc hid_out;
|
||||
struct usb_interface_desc cdc_control_if;
|
||||
struct usb_cdc_header_func_desc cdc_header;
|
||||
struct usb_cdc_callmgmt_func_desc cdc_callmgmt;
|
||||
struct usb_cdc_acm_func_desc cdc_acm;
|
||||
struct usb_cdc_union_func_desc cdc_union;
|
||||
struct usb_endpoint_desc cdc_mgmt_in;
|
||||
struct usb_interface_desc cdc_data_if;
|
||||
struct usb_endpoint_desc cdc_in;
|
||||
struct usb_endpoint_desc cdc_out;
|
||||
} __attribute__((packed));
|
||||
|
||||
static const struct usb_config_hid_cdc config_hid_cdc = {
|
||||
.config = {
|
||||
.bLength = sizeof(struct usb_configuration_desc),
|
||||
.bDescriptorType = USB_DESC_TYPE_CONFIGURATION,
|
||||
.wTotalLength = htousbs(sizeof(struct usb_board_config)),
|
||||
.wTotalLength = htousbs(sizeof(struct usb_config_hid_cdc)),
|
||||
.bNumInterfaces = 3,
|
||||
.bConfigurationValue = 1,
|
||||
.iConfiguration = 0,
|
||||
@ -86,7 +151,7 @@ const struct usb_board_config PIOS_USB_BOARD_Configuration = {
|
||||
.bCountryCode = 0,
|
||||
.bNumDescriptors = 1,
|
||||
.bClassDescriptorType = USB_DESC_TYPE_REPORT,
|
||||
.wItemLength = htousbs(sizeof(PIOS_USB_BOARD_HidReportDescriptor)),
|
||||
.wItemLength = htousbs(sizeof(hid_report_desc)),
|
||||
},
|
||||
.hid_in = {
|
||||
.bLength = sizeof(struct usb_endpoint_desc),
|
||||
@ -178,100 +243,14 @@ const struct usb_board_config PIOS_USB_BOARD_Configuration = {
|
||||
},
|
||||
};
|
||||
|
||||
const uint8_t PIOS_USB_BOARD_HidReportDescriptor[] = {
|
||||
HID_GLOBAL_ITEM_2 (HID_TAG_GLOBAL_USAGE_PAGE),
|
||||
0x9C, 0xFF, /* Usage Page 0xFF9C (Vendor Defined) */
|
||||
HID_LOCAL_ITEM_1 (HID_TAG_LOCAL_USAGE),
|
||||
0x01, /* Usage ID 0x0001 (0x01-0x1F uaually for top-level collections) */
|
||||
int32_t PIOS_USB_DESC_HID_CDC_Init(void)
|
||||
{
|
||||
PIOS_USBHOOK_RegisterConfig(1, (uint8_t *)&config_hid_cdc, sizeof(config_hid_cdc));
|
||||
|
||||
HID_MAIN_ITEM_1 (HID_TAG_MAIN_COLLECTION),
|
||||
0x01, /* Application */
|
||||
PIOS_USBHOOK_RegisterDevice((uint8_t *)&device_desc, sizeof(device_desc));
|
||||
|
||||
/* Device -> Host emulated serial channel */
|
||||
HID_GLOBAL_ITEM_1 (HID_TAG_GLOBAL_REPORT_ID),
|
||||
0x01, /* OpenPilot emulated serial channel (Device -> Host) */
|
||||
HID_LOCAL_ITEM_1 (HID_TAG_LOCAL_USAGE),
|
||||
0x02,
|
||||
HID_GLOBAL_ITEM_1 (HID_TAG_GLOBAL_LOGICAL_MIN),
|
||||
0x00, /* Values range from min = 0x00 */
|
||||
HID_GLOBAL_ITEM_1 (HID_TAG_GLOBAL_LOGICAL_MAX),
|
||||
0xFF, /* Values range to max = 0xFF */
|
||||
HID_GLOBAL_ITEM_1 (HID_TAG_GLOBAL_REPORT_SIZE),
|
||||
0x08, /* 8 bits wide */
|
||||
HID_GLOBAL_ITEM_1 (HID_TAG_GLOBAL_REPORT_CNT),
|
||||
PIOS_USB_BOARD_HID_DATA_LENGTH-1, /* Need to leave room for a report ID */
|
||||
HID_MAIN_ITEM_1 (HID_TAG_MAIN_INPUT),
|
||||
0x03, /* Variable, Constant (read-only) */
|
||||
PIOS_USBHOOK_RegisterHidInterface((uint8_t *)&(config_hid_cdc.hid_if), sizeof(config_hid_cdc.hid_if));
|
||||
PIOS_USBHOOK_RegisterHidReport((uint8_t *)hid_report_desc, sizeof(hid_report_desc));
|
||||
|
||||
/* Host -> Host emulated serial channel */
|
||||
HID_GLOBAL_ITEM_1 (HID_TAG_GLOBAL_REPORT_ID),
|
||||
0x02, /* OpenPilot emulated Serial Channel (Host -> Device) */
|
||||
HID_LOCAL_ITEM_1 (HID_TAG_LOCAL_USAGE),
|
||||
0x02,
|
||||
HID_GLOBAL_ITEM_1 (HID_TAG_GLOBAL_LOGICAL_MIN),
|
||||
0x00, /* Values range from min = 0x00 */
|
||||
HID_GLOBAL_ITEM_1 (HID_TAG_GLOBAL_LOGICAL_MAX),
|
||||
0xFF, /* Values range to max = 0xFF */
|
||||
HID_GLOBAL_ITEM_1 (HID_TAG_GLOBAL_REPORT_SIZE),
|
||||
0x08, /* 8 bits wide */
|
||||
HID_GLOBAL_ITEM_1 (HID_TAG_GLOBAL_REPORT_CNT),
|
||||
PIOS_USB_BOARD_HID_DATA_LENGTH-1, /* Need to leave room for a report ID */
|
||||
HID_MAIN_ITEM_1 (HID_TAG_MAIN_OUTPUT),
|
||||
0x82, /* Volatile, Variable */
|
||||
|
||||
HID_MAIN_ITEM_0 (HID_TAG_MAIN_ENDCOLLECTION),
|
||||
};
|
||||
|
||||
const struct usb_string_langid PIOS_USB_BOARD_StringLangID = {
|
||||
.bLength = sizeof(PIOS_USB_BOARD_StringLangID),
|
||||
.bDescriptorType = USB_DESC_TYPE_STRING,
|
||||
.bLangID = htousbs(USB_LANGID_ENGLISH_UK),
|
||||
};
|
||||
|
||||
const uint8_t PIOS_USB_BOARD_StringVendorID[] = {
|
||||
sizeof(PIOS_USB_BOARD_StringVendorID),
|
||||
USB_DESC_TYPE_STRING,
|
||||
'o', 0,
|
||||
'p', 0,
|
||||
'e', 0,
|
||||
'n', 0,
|
||||
'p', 0,
|
||||
'i', 0,
|
||||
'l', 0,
|
||||
'o', 0,
|
||||
't', 0,
|
||||
'.', 0,
|
||||
'o', 0,
|
||||
'r', 0,
|
||||
'g', 0
|
||||
};
|
||||
|
||||
uint8_t PIOS_USB_BOARD_StringSerial[] = {
|
||||
sizeof(PIOS_USB_BOARD_StringSerial),
|
||||
USB_DESC_TYPE_STRING,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0
|
||||
};
|
||||
return 0;
|
||||
}
|
||||
|
@ -28,9 +28,12 @@
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
|
||||
#include "pios_usb_board_data.h" /* struct usb_*, USB_* */
|
||||
#include "pios_usb_desc_hid_only_priv.h" /* exported API */
|
||||
#include "pios_usb_defs.h" /* struct usb_*, USB_* */
|
||||
#include "pios_usb_board_data.h" /* PIOS_USB_BOARD_* */
|
||||
#include "pios_usbhook.h" /* PIOS_USBHOOK_Register* */
|
||||
|
||||
const struct usb_device_desc PIOS_USB_BOARD_DeviceDescriptor = {
|
||||
static const struct usb_device_desc device_desc = {
|
||||
.bLength = sizeof(struct usb_device_desc),
|
||||
.bDescriptorType = USB_DESC_TYPE_DEVICE,
|
||||
.bcdUSB = htousbs(0x0200),
|
||||
@ -47,56 +50,7 @@ const struct usb_device_desc PIOS_USB_BOARD_DeviceDescriptor = {
|
||||
.bNumConfigurations = 1,
|
||||
};
|
||||
|
||||
const struct usb_board_config PIOS_USB_BOARD_Configuration = {
|
||||
.config = {
|
||||
.bLength = sizeof(struct usb_configuration_desc),
|
||||
.bDescriptorType = USB_DESC_TYPE_CONFIGURATION,
|
||||
.wTotalLength = htousbs(sizeof(struct usb_board_config)),
|
||||
.bNumInterfaces = 1,
|
||||
.bConfigurationValue = 1,
|
||||
.iConfiguration = 0,
|
||||
.bmAttributes = 0xC0,
|
||||
.bMaxPower = 250/2, /* in units of 2ma */
|
||||
},
|
||||
.hid_if = {
|
||||
.bLength = sizeof(struct usb_interface_desc),
|
||||
.bDescriptorType = USB_DESC_TYPE_INTERFACE,
|
||||
.bInterfaceNumber = 0,
|
||||
.bAlternateSetting = 0,
|
||||
.bNumEndpoints = 2,
|
||||
.bInterfaceClass = USB_INTERFACE_CLASS_HID,
|
||||
.bInterfaceSubClass = 0, /* no boot */
|
||||
.nInterfaceProtocol = 0, /* none */
|
||||
.iInterface = 0,
|
||||
},
|
||||
.hid = {
|
||||
.bLength = sizeof(struct usb_hid_desc),
|
||||
.bDescriptorType = USB_DESC_TYPE_HID,
|
||||
.bcdHID = htousbs(0x0110),
|
||||
.bCountryCode = 0,
|
||||
.bNumDescriptors = 1,
|
||||
.bClassDescriptorType = USB_DESC_TYPE_REPORT,
|
||||
.wItemLength = htousbs(sizeof(PIOS_USB_BOARD_HidReportDescriptor)),
|
||||
},
|
||||
.hid_in = {
|
||||
.bLength = sizeof(struct usb_endpoint_desc),
|
||||
.bDescriptorType = USB_DESC_TYPE_ENDPOINT,
|
||||
.bEndpointAddress = USB_EP_IN(1),
|
||||
.bmAttributes = USB_EP_ATTR_TT_INTERRUPT,
|
||||
.wMaxPacketSize = htousbs(PIOS_USB_BOARD_HID_DATA_LENGTH),
|
||||
.bInterval = 4, /* ms */
|
||||
},
|
||||
.hid_out = {
|
||||
.bLength = sizeof(struct usb_endpoint_desc),
|
||||
.bDescriptorType = USB_DESC_TYPE_ENDPOINT,
|
||||
.bEndpointAddress = USB_EP_OUT(1),
|
||||
.bmAttributes = USB_EP_ATTR_TT_INTERRUPT,
|
||||
.wMaxPacketSize = htousbs(PIOS_USB_BOARD_HID_DATA_LENGTH),
|
||||
.bInterval = 4, /* ms */
|
||||
},
|
||||
};
|
||||
|
||||
const uint8_t PIOS_USB_BOARD_HidReportDescriptor[] = {
|
||||
static const uint8_t hid_report_desc[36] = {
|
||||
HID_GLOBAL_ITEM_2 (HID_TAG_GLOBAL_USAGE_PAGE),
|
||||
0x9C, 0xFF, /* Usage Page 0xFF9C (Vendor Defined) */
|
||||
HID_LOCAL_ITEM_1 (HID_TAG_LOCAL_USAGE),
|
||||
@ -140,56 +94,71 @@ const uint8_t PIOS_USB_BOARD_HidReportDescriptor[] = {
|
||||
HID_MAIN_ITEM_0 (HID_TAG_MAIN_ENDCOLLECTION),
|
||||
};
|
||||
|
||||
const struct usb_string_langid PIOS_USB_BOARD_StringLangID = {
|
||||
.bLength = sizeof(PIOS_USB_BOARD_StringLangID),
|
||||
.bDescriptorType = USB_DESC_TYPE_STRING,
|
||||
.bLangID = htousbs(USB_LANGID_ENGLISH_UK),
|
||||
struct usb_config_hid_only {
|
||||
struct usb_configuration_desc config;
|
||||
struct usb_interface_desc hid_if;
|
||||
struct usb_hid_desc hid;
|
||||
struct usb_endpoint_desc hid_in;
|
||||
struct usb_endpoint_desc hid_out;
|
||||
} __attribute__((packed));
|
||||
|
||||
const struct usb_config_hid_only config_hid_only = {
|
||||
.config = {
|
||||
.bLength = sizeof(struct usb_configuration_desc),
|
||||
.bDescriptorType = USB_DESC_TYPE_CONFIGURATION,
|
||||
.wTotalLength = htousbs(sizeof(struct usb_config_hid_only)),
|
||||
.bNumInterfaces = 1,
|
||||
.bConfigurationValue = 1,
|
||||
.iConfiguration = 0,
|
||||
.bmAttributes = 0xC0,
|
||||
.bMaxPower = 250/2, /* in units of 2ma */
|
||||
},
|
||||
.hid_if = {
|
||||
.bLength = sizeof(struct usb_interface_desc),
|
||||
.bDescriptorType = USB_DESC_TYPE_INTERFACE,
|
||||
.bInterfaceNumber = 0,
|
||||
.bAlternateSetting = 0,
|
||||
.bNumEndpoints = 2,
|
||||
.bInterfaceClass = USB_INTERFACE_CLASS_HID,
|
||||
.bInterfaceSubClass = 0, /* no boot */
|
||||
.nInterfaceProtocol = 0, /* none */
|
||||
.iInterface = 0,
|
||||
},
|
||||
.hid = {
|
||||
.bLength = sizeof(struct usb_hid_desc),
|
||||
.bDescriptorType = USB_DESC_TYPE_HID,
|
||||
.bcdHID = htousbs(0x0110),
|
||||
.bCountryCode = 0,
|
||||
.bNumDescriptors = 1,
|
||||
.bClassDescriptorType = USB_DESC_TYPE_REPORT,
|
||||
.wItemLength = htousbs(sizeof(hid_report_desc)),
|
||||
},
|
||||
.hid_in = {
|
||||
.bLength = sizeof(struct usb_endpoint_desc),
|
||||
.bDescriptorType = USB_DESC_TYPE_ENDPOINT,
|
||||
.bEndpointAddress = USB_EP_IN(1),
|
||||
.bmAttributes = USB_EP_ATTR_TT_INTERRUPT,
|
||||
.wMaxPacketSize = htousbs(PIOS_USB_BOARD_HID_DATA_LENGTH),
|
||||
.bInterval = 4, /* ms */
|
||||
},
|
||||
.hid_out = {
|
||||
.bLength = sizeof(struct usb_endpoint_desc),
|
||||
.bDescriptorType = USB_DESC_TYPE_ENDPOINT,
|
||||
.bEndpointAddress = USB_EP_OUT(1),
|
||||
.bmAttributes = USB_EP_ATTR_TT_INTERRUPT,
|
||||
.wMaxPacketSize = htousbs(PIOS_USB_BOARD_HID_DATA_LENGTH),
|
||||
.bInterval = 4, /* ms */
|
||||
},
|
||||
};
|
||||
|
||||
const uint8_t PIOS_USB_BOARD_StringVendorID[] = {
|
||||
sizeof(PIOS_USB_BOARD_StringVendorID),
|
||||
USB_DESC_TYPE_STRING,
|
||||
'o', 0,
|
||||
'p', 0,
|
||||
'e', 0,
|
||||
'n', 0,
|
||||
'p', 0,
|
||||
'i', 0,
|
||||
'l', 0,
|
||||
'o', 0,
|
||||
't', 0,
|
||||
'.', 0,
|
||||
'o', 0,
|
||||
'r', 0,
|
||||
'g', 0
|
||||
};
|
||||
int32_t PIOS_USB_DESC_HID_ONLY_Init(void)
|
||||
{
|
||||
PIOS_USBHOOK_RegisterConfig(1, (uint8_t *)&config_hid_only, sizeof(config_hid_only));
|
||||
|
||||
uint8_t PIOS_USB_BOARD_StringSerial[] = {
|
||||
sizeof(PIOS_USB_BOARD_StringSerial),
|
||||
USB_DESC_TYPE_STRING,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0,
|
||||
0, 0
|
||||
};
|
||||
PIOS_USBHOOK_RegisterDevice((uint8_t *)&device_desc, sizeof(device_desc));
|
||||
|
||||
PIOS_USBHOOK_RegisterHidInterface((uint8_t *)&(config_hid_only.hid_if), sizeof(config_hid_only.hid_if));
|
||||
PIOS_USBHOOK_RegisterHidReport((uint8_t *)hid_report_desc, sizeof(hid_report_desc));
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
@ -155,7 +155,7 @@ typedef struct
|
||||
*/
|
||||
|
||||
void EXTI_DeInit(void);
|
||||
void EXTI_Init(EXTI_InitTypeDef* EXTI_InitStruct);
|
||||
void EXTI_Init(const EXTI_InitTypeDef* EXTI_InitStruct);
|
||||
void EXTI_StructInit(EXTI_InitTypeDef* EXTI_InitStruct);
|
||||
void EXTI_GenerateSWInterrupt(uint32_t EXTI_Line);
|
||||
FlagStatus EXTI_GetFlagStatus(uint32_t EXTI_Line);
|
||||
|
@ -97,7 +97,7 @@ void EXTI_DeInit(void)
|
||||
* that contains the configuration information for the EXTI peripheral.
|
||||
* @retval None
|
||||
*/
|
||||
void EXTI_Init(EXTI_InitTypeDef* EXTI_InitStruct)
|
||||
void EXTI_Init(const EXTI_InitTypeDef* EXTI_InitStruct)
|
||||
{
|
||||
uint32_t tmp = 0;
|
||||
|
||||
|
@ -35,7 +35,7 @@ typedef enum _CONTROL_STATE
|
||||
|
||||
typedef struct OneDescriptor
|
||||
{
|
||||
uint8_t *Descriptor;
|
||||
const uint8_t *Descriptor;
|
||||
uint16_t Descriptor_Size;
|
||||
}
|
||||
ONE_DESCRIPTOR, *PONE_DESCRIPTOR;
|
||||
@ -80,7 +80,8 @@ typedef struct _ENDPOINT_INFO
|
||||
uint16_t Usb_wLength;
|
||||
uint16_t Usb_wOffset;
|
||||
uint16_t PacketSize;
|
||||
uint8_t *(*CopyData)(uint16_t Length);
|
||||
const uint8_t *(*CopyDataIn)(uint16_t Length);
|
||||
uint8_t *(*CopyDataOut)(uint16_t Length);
|
||||
}ENDPOINT_INFO;
|
||||
|
||||
/*-*-*-*-*-*-*-*-*-*-*-* Definitions for device level -*-*-*-*-*-*-*-*-*-*-*-*/
|
||||
@ -169,9 +170,9 @@ typedef struct _DEVICE_PROP
|
||||
|
||||
RESULT (*Class_Get_Interface_Setting)(uint8_t Interface, uint8_t AlternateSetting);
|
||||
|
||||
uint8_t* (*GetDeviceDescriptor)(uint16_t Length);
|
||||
uint8_t* (*GetConfigDescriptor)(uint16_t Length);
|
||||
uint8_t* (*GetStringDescriptor)(uint16_t Length);
|
||||
const uint8_t* (*GetDeviceDescriptor)(uint16_t Length);
|
||||
const uint8_t* (*GetConfigDescriptor)(uint16_t Length);
|
||||
const uint8_t* (*GetStringDescriptor)(uint16_t Length);
|
||||
|
||||
/* This field is not used in current library version. It is kept only for
|
||||
compatibility with previous versions */
|
||||
@ -221,13 +222,13 @@ uint8_t In0_Process(void);
|
||||
RESULT Standard_SetEndPointFeature(void);
|
||||
RESULT Standard_SetDeviceFeature(void);
|
||||
|
||||
uint8_t *Standard_GetConfiguration(uint16_t Length);
|
||||
const uint8_t *Standard_GetConfiguration(uint16_t Length);
|
||||
RESULT Standard_SetConfiguration(void);
|
||||
uint8_t *Standard_GetInterface(uint16_t Length);
|
||||
const uint8_t *Standard_GetInterface(uint16_t Length);
|
||||
RESULT Standard_SetInterface(void);
|
||||
uint8_t *Standard_GetDescriptorData(uint16_t Length, const ONE_DESCRIPTOR * pDesc);
|
||||
const uint8_t *Standard_GetDescriptorData(uint16_t Length, ONE_DESCRIPTOR *pDesc);
|
||||
|
||||
uint8_t *Standard_GetStatus(uint16_t Length);
|
||||
const uint8_t *Standard_GetStatus(uint16_t Length);
|
||||
RESULT Standard_ClearFeature(void);
|
||||
void SetDeviceAddress(uint8_t);
|
||||
void NOP_Process(void);
|
||||
|
@ -22,7 +22,7 @@
|
||||
/* Exported constants --------------------------------------------------------*/
|
||||
/* Exported macro ------------------------------------------------------------*/
|
||||
/* Exported functions ------------------------------------------------------- */
|
||||
void UserToPMABufferCopy(uint8_t *pbUsrBuf, uint16_t wPMABufAddr, uint16_t wNBytes);
|
||||
void UserToPMABufferCopy(const uint8_t *pbUsrBuf, uint16_t wPMABufAddr, uint16_t wNBytes);
|
||||
void PMAToUserBufferCopy(uint8_t *pbUsrBuf, uint16_t wPMABufAddr, uint16_t wNBytes);
|
||||
|
||||
/* External variables --------------------------------------------------------*/
|
||||
|
@ -58,7 +58,7 @@ static void Data_Setup0(void);
|
||||
* Return : Return 1 , if the request is invalid when "Length" is 0.
|
||||
* Return "Buffer" if the "Length" is not 0.
|
||||
*******************************************************************************/
|
||||
uint8_t *Standard_GetConfiguration(uint16_t Length)
|
||||
const uint8_t *Standard_GetConfiguration(uint16_t Length)
|
||||
{
|
||||
if (Length == 0)
|
||||
{
|
||||
@ -104,7 +104,7 @@ RESULT Standard_SetConfiguration(void)
|
||||
* Return : Return 0, if the request is invalid when "Length" is 0.
|
||||
* Return "Buffer" if the "Length" is not 0.
|
||||
*******************************************************************************/
|
||||
uint8_t *Standard_GetInterface(uint16_t Length)
|
||||
const uint8_t *Standard_GetInterface(uint16_t Length)
|
||||
{
|
||||
if (Length == 0)
|
||||
{
|
||||
@ -160,7 +160,7 @@ RESULT Standard_SetInterface(void)
|
||||
* Return : Return 0, if the request is at end of data block,
|
||||
* or is invalid when "Length" is 0.
|
||||
*******************************************************************************/
|
||||
uint8_t *Standard_GetStatus(uint16_t Length)
|
||||
const uint8_t *Standard_GetStatus(uint16_t Length)
|
||||
{
|
||||
if (Length == 0)
|
||||
{
|
||||
@ -415,7 +415,7 @@ RESULT Standard_SetDeviceFeature(void)
|
||||
* wOffset The buffer pointed by this address contains at least
|
||||
* Length bytes.
|
||||
*******************************************************************************/
|
||||
uint8_t *Standard_GetDescriptorData(uint16_t Length, const ONE_DESCRIPTOR * pDesc)
|
||||
const uint8_t *Standard_GetDescriptorData(uint16_t Length, PONE_DESCRIPTOR pDesc)
|
||||
{
|
||||
uint32_t wOffset;
|
||||
|
||||
@ -443,7 +443,7 @@ void DataStageOut(void)
|
||||
|
||||
save_rLength = pEPinfo->Usb_rLength;
|
||||
|
||||
if (pEPinfo->CopyData && save_rLength)
|
||||
if (pEPinfo->CopyDataOut && save_rLength)
|
||||
{
|
||||
uint8_t *Buffer;
|
||||
uint32_t Length;
|
||||
@ -454,7 +454,7 @@ void DataStageOut(void)
|
||||
Length = save_rLength;
|
||||
}
|
||||
|
||||
Buffer = (*pEPinfo->CopyData)(Length);
|
||||
Buffer = (*pEPinfo->CopyDataOut)(Length);
|
||||
pEPinfo->Usb_rLength -= Length;
|
||||
pEPinfo->Usb_rOffset += Length;
|
||||
|
||||
@ -503,7 +503,7 @@ void DataStageIn(void)
|
||||
uint32_t save_wLength = pEPinfo->Usb_wLength;
|
||||
uint32_t ControlState = pInformation->ControlState;
|
||||
|
||||
uint8_t *DataBuffer;
|
||||
const uint8_t *DataBuffer;
|
||||
uint32_t Length;
|
||||
|
||||
if ((save_wLength == 0) && (ControlState == LAST_IN_DATA))
|
||||
@ -540,7 +540,7 @@ void DataStageIn(void)
|
||||
Length = save_wLength;
|
||||
}
|
||||
|
||||
DataBuffer = (*pEPinfo->CopyData)(Length);
|
||||
DataBuffer = (*pEPinfo->CopyDataIn)(Length);
|
||||
|
||||
#ifdef STM32F10X_CL
|
||||
PCD_EP_Write (ENDP0, DataBuffer, Length);
|
||||
@ -697,7 +697,7 @@ exit_NoData_Setup0:
|
||||
*******************************************************************************/
|
||||
void Data_Setup0(void)
|
||||
{
|
||||
uint8_t *(*CopyRoutine)(uint16_t);
|
||||
const uint8_t *(*CopyRoutine)(uint16_t);
|
||||
RESULT Result;
|
||||
uint32_t Request_No = pInformation->USBbRequest;
|
||||
|
||||
@ -802,7 +802,7 @@ void Data_Setup0(void)
|
||||
if (CopyRoutine)
|
||||
{
|
||||
pInformation->Ctrl_Info.Usb_wOffset = wOffset;
|
||||
pInformation->Ctrl_Info.CopyData = CopyRoutine;
|
||||
pInformation->Ctrl_Info.CopyDataIn = CopyRoutine;
|
||||
/* sb in the original the cast to word was directly */
|
||||
/* now the cast is made step by step */
|
||||
(*CopyRoutine)(0);
|
||||
|
@ -33,7 +33,7 @@
|
||||
* Output : None.
|
||||
* Return : None .
|
||||
*******************************************************************************/
|
||||
void UserToPMABufferCopy(uint8_t *pbUsrBuf, uint16_t wPMABufAddr, uint16_t wNBytes)
|
||||
void UserToPMABufferCopy(const uint8_t *pbUsrBuf, uint16_t wPMABufAddr, uint16_t wNBytes)
|
||||
{
|
||||
uint32_t n = (wNBytes + 1) >> 1; /* n = (wNBytes + 1) / 2 */
|
||||
uint32_t i, temp1, temp2;
|
||||
|
@ -98,16 +98,9 @@ SECTIONS
|
||||
_init_stack_top = . - 4 ;
|
||||
} > SRAM
|
||||
|
||||
_eram = ORIGIN(SRAM) + LENGTH(SRAM) ;
|
||||
_ebss = _eram ;
|
||||
|
||||
_free_ram = . ;
|
||||
.free_ram (NOLOAD) :
|
||||
{
|
||||
. = ORIGIN(SRAM) + LENGTH(SRAM) - _free_ram ;
|
||||
/* This is used by the startup in order to initialize the .bss section */
|
||||
_ebss = . ;
|
||||
_eram = . ;
|
||||
} > SRAM
|
||||
|
||||
/* keep the heap section at the end of the SRAM
|
||||
* this will allow to claim the remaining bytes not used
|
||||
* at run time! (done by the reset vector).
|
||||
|
@ -275,14 +275,8 @@ SECTIONS
|
||||
_init_stack_top = . - 4 ;
|
||||
} > RAM
|
||||
|
||||
_free_ram = . ;
|
||||
.free_ram (NOLOAD) :
|
||||
{
|
||||
. = ORIGIN(RAM) + LENGTH(RAM) - _free_ram ;
|
||||
/* This is used by the startup in order to initialize the .bss section */
|
||||
_ebss = . ;
|
||||
_eram = . ;
|
||||
} > RAM
|
||||
_eram = ORIGIN(SRAM) + LENGTH(SRAM) ;
|
||||
_ebss = _eram ;
|
||||
|
||||
/* keep the heap section at the end of the SRAM
|
||||
* this will allow to claim the remaining bytes not used
|
||||
|
@ -5,7 +5,6 @@
|
||||
* @{
|
||||
* @addtogroup PIOS_EXTI External Interrupt Handlers
|
||||
* @brief External interrupt handler functions
|
||||
* @note Currently deals with BMP085 readings
|
||||
* @{
|
||||
*
|
||||
* @file pios_exti.c
|
||||
@ -35,61 +34,196 @@
|
||||
|
||||
#if defined(PIOS_INCLUDE_EXTI)
|
||||
|
||||
/**
|
||||
* Handle external lines 15 to 10 interrupt requests
|
||||
*/
|
||||
void EXTI15_10_IRQHandler(void)
|
||||
/* Map EXTI line to full config */
|
||||
#define EXTI_MAX_LINES 16
|
||||
#define PIOS_EXTI_INVALID 0xFF
|
||||
static uint8_t pios_exti_line_to_cfg_map[EXTI_MAX_LINES] = {
|
||||
[0 ... EXTI_MAX_LINES-1] = PIOS_EXTI_INVALID,
|
||||
};
|
||||
|
||||
/* Table of exti configs registered at compile time */
|
||||
extern struct pios_exti_cfg __start__exti __attribute__((weak));
|
||||
extern struct pios_exti_cfg __stop__exti __attribute__((weak));
|
||||
|
||||
static uint8_t PIOS_EXTI_line_to_index (uint32_t line)
|
||||
{
|
||||
#if defined(PIOS_INCLUDE_FREERTOS)
|
||||
portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE;
|
||||
#endif
|
||||
|
||||
#if defined(PIOS_INCLUDE_BMP085)
|
||||
if (EXTI_GetITStatus(PIOS_BMP085_EOC_EXTI_LINE) != RESET) {
|
||||
/* Read the ADC Value */
|
||||
#if defined(PIOS_INCLUDE_FREERTOS)
|
||||
xSemaphoreGiveFromISR(PIOS_BMP085_EOC, &xHigherPriorityTaskWoken);
|
||||
#else
|
||||
PIOS_BMP085_EOC=1;
|
||||
#endif
|
||||
|
||||
/* Clear the EXTI line pending bit */
|
||||
EXTI_ClearITPendingBit(PIOS_BMP085_EOC_EXTI_LINE);
|
||||
switch (line) {
|
||||
case EXTI_Line0: return 0;
|
||||
case EXTI_Line1: return 1;
|
||||
case EXTI_Line2: return 2;
|
||||
case EXTI_Line3: return 3;
|
||||
case EXTI_Line4: return 4;
|
||||
case EXTI_Line5: return 5;
|
||||
case EXTI_Line6: return 6;
|
||||
case EXTI_Line7: return 7;
|
||||
case EXTI_Line8: return 8;
|
||||
case EXTI_Line9: return 9;
|
||||
case EXTI_Line10: return 10;
|
||||
case EXTI_Line11: return 11;
|
||||
case EXTI_Line12: return 12;
|
||||
case EXTI_Line13: return 13;
|
||||
case EXTI_Line14: return 14;
|
||||
case EXTI_Line15: return 15;
|
||||
}
|
||||
#endif
|
||||
|
||||
#if defined(PIOS_INCLUDE_FREERTOS)
|
||||
/* Yield From ISR if needed */
|
||||
portEND_SWITCHING_ISR(xHigherPriorityTaskWoken);
|
||||
#endif
|
||||
PIOS_Assert(0);
|
||||
return 0xFF;
|
||||
}
|
||||
|
||||
/**
|
||||
* Handle external lines 9 to 5 interrupt requests
|
||||
*/
|
||||
extern void PIOS_HMC5843_IRQHandler(void);
|
||||
void EXTI9_5_IRQHandler(void)
|
||||
uint8_t PIOS_EXTI_gpio_port_to_exti_source_port(GPIO_TypeDef * gpio_port)
|
||||
{
|
||||
#if defined(PIOS_INCLUDE_HMC5843)
|
||||
if (EXTI_GetITStatus(PIOS_HMC5843_DRDY_EXTI_LINE) != RESET) {
|
||||
PIOS_HMC5843_IRQHandler();
|
||||
EXTI_ClearITPendingBit(PIOS_HMC5843_DRDY_EXTI_LINE);
|
||||
switch((uint32_t)gpio_port) {
|
||||
case (uint32_t)GPIOA: return (GPIO_PortSourceGPIOA);
|
||||
case (uint32_t)GPIOB: return (GPIO_PortSourceGPIOB);
|
||||
case (uint32_t)GPIOC: return (GPIO_PortSourceGPIOC);
|
||||
case (uint32_t)GPIOD: return (GPIO_PortSourceGPIOD);
|
||||
case (uint32_t)GPIOE: return (GPIO_PortSourceGPIOE);
|
||||
case (uint32_t)GPIOF: return (GPIO_PortSourceGPIOF);
|
||||
case (uint32_t)GPIOG: return (GPIO_PortSourceGPIOG);
|
||||
}
|
||||
#endif
|
||||
|
||||
PIOS_Assert(0);
|
||||
return 0xFF;
|
||||
}
|
||||
|
||||
/**
|
||||
* Handle external line 4 interrupt requests
|
||||
*/
|
||||
#if defined(PIOS_INCLUDE_USB)
|
||||
void EXTI4_IRQHandler(void)
|
||||
uint8_t PIOS_EXTI_gpio_pin_to_exti_source_pin(uint32_t gpio_pin)
|
||||
{
|
||||
if (EXTI_GetITStatus(PIOS_USB_DETECT_EXTI_LINE) != RESET) {
|
||||
/* Clear the EXTI line pending bit */
|
||||
EXTI_ClearITPendingBit(PIOS_USB_DETECT_EXTI_LINE);
|
||||
switch((uint32_t)gpio_pin) {
|
||||
case GPIO_Pin_0: return (GPIO_PinSource0);
|
||||
case GPIO_Pin_1: return (GPIO_PinSource1);
|
||||
case GPIO_Pin_2: return (GPIO_PinSource2);
|
||||
case GPIO_Pin_3: return (GPIO_PinSource3);
|
||||
case GPIO_Pin_4: return (GPIO_PinSource4);
|
||||
case GPIO_Pin_5: return (GPIO_PinSource5);
|
||||
case GPIO_Pin_6: return (GPIO_PinSource6);
|
||||
case GPIO_Pin_7: return (GPIO_PinSource7);
|
||||
case GPIO_Pin_8: return (GPIO_PinSource8);
|
||||
case GPIO_Pin_9: return (GPIO_PinSource9);
|
||||
case GPIO_Pin_10: return (GPIO_PinSource10);
|
||||
case GPIO_Pin_11: return (GPIO_PinSource11);
|
||||
case GPIO_Pin_12: return (GPIO_PinSource12);
|
||||
case GPIO_Pin_13: return (GPIO_PinSource13);
|
||||
case GPIO_Pin_14: return (GPIO_PinSource14);
|
||||
case GPIO_Pin_15: return (GPIO_PinSource15);
|
||||
}
|
||||
|
||||
PIOS_Assert(0);
|
||||
return 0xFF;
|
||||
}
|
||||
#endif
|
||||
|
||||
int32_t PIOS_EXTI_Init(const struct pios_exti_cfg * cfg)
|
||||
{
|
||||
PIOS_Assert(cfg);
|
||||
PIOS_Assert(&__start__exti);
|
||||
PIOS_Assert(cfg >= &__start__exti);
|
||||
PIOS_Assert(cfg < &__stop__exti);
|
||||
|
||||
uint8_t cfg_index = cfg - &__start__exti;
|
||||
|
||||
/* Connect this config to the requested vector */
|
||||
uint8_t line_index = PIOS_EXTI_line_to_index(cfg->line);
|
||||
|
||||
if (pios_exti_line_to_cfg_map[line_index] != PIOS_EXTI_INVALID) {
|
||||
/* Someone else already has this mapped */
|
||||
goto out_fail;
|
||||
}
|
||||
|
||||
/* Bind the config to the exti line */
|
||||
pios_exti_line_to_cfg_map[line_index] = cfg_index;
|
||||
|
||||
/* Initialize the GPIO pin */
|
||||
GPIO_Init(cfg->pin.gpio, &cfg->pin.init);
|
||||
|
||||
/* Set up the EXTI interrupt source */
|
||||
uint8_t exti_source_port = PIOS_EXTI_gpio_port_to_exti_source_port(cfg->pin.gpio);
|
||||
uint8_t exti_source_pin = PIOS_EXTI_gpio_pin_to_exti_source_pin(cfg->pin.init.GPIO_Pin);
|
||||
GPIO_EXTILineConfig(exti_source_port, exti_source_pin);
|
||||
EXTI_Init(&cfg->exti.init);
|
||||
|
||||
/* Enable the interrupt channel */
|
||||
NVIC_Init(&cfg->irq.init);
|
||||
|
||||
return 0;
|
||||
|
||||
out_fail:
|
||||
return -1;
|
||||
}
|
||||
|
||||
static void PIOS_EXTI_generic_irq_handler(uint8_t line_index)
|
||||
{
|
||||
uint8_t cfg_index = pios_exti_line_to_cfg_map[line_index];
|
||||
|
||||
PIOS_Assert(&__start__exti);
|
||||
|
||||
if (cfg_index > NELEMENTS(pios_exti_line_to_cfg_map) ||
|
||||
cfg_index == PIOS_EXTI_INVALID) {
|
||||
/* Unconfigured interrupt just fired! */
|
||||
return;
|
||||
}
|
||||
|
||||
struct pios_exti_cfg * cfg = &__start__exti + cfg_index;
|
||||
cfg->vector();
|
||||
}
|
||||
|
||||
/* Bind Interrupt Handlers */
|
||||
|
||||
#define PIOS_EXTI_HANDLE_LINE(line) \
|
||||
if (EXTI_GetITStatus(EXTI_Line##line) != RESET) { \
|
||||
EXTI_ClearITPendingBit(EXTI_Line##line); \
|
||||
PIOS_EXTI_generic_irq_handler(line); \
|
||||
}
|
||||
|
||||
static void PIOS_EXTI_0_irq_handler (void)
|
||||
{
|
||||
PIOS_EXTI_HANDLE_LINE(0);
|
||||
}
|
||||
void EXTI0_IRQHandler(void) __attribute__ ((alias ("PIOS_EXTI_0_irq_handler")));
|
||||
|
||||
static void PIOS_EXTI_1_irq_handler (void)
|
||||
{
|
||||
PIOS_EXTI_HANDLE_LINE(1);
|
||||
}
|
||||
void EXTI1_IRQHandler(void) __attribute__ ((alias ("PIOS_EXTI_1_irq_handler")));
|
||||
|
||||
static void PIOS_EXTI_2_irq_handler (void)
|
||||
{
|
||||
PIOS_EXTI_HANDLE_LINE(2);
|
||||
}
|
||||
void EXTI2_IRQHandler(void) __attribute__ ((alias ("PIOS_EXTI_2_irq_handler")));
|
||||
|
||||
static void PIOS_EXTI_3_irq_handler (void)
|
||||
{
|
||||
PIOS_EXTI_HANDLE_LINE(3);
|
||||
}
|
||||
void EXTI3_IRQHandler(void) __attribute__ ((alias ("PIOS_EXTI_3_irq_handler")));
|
||||
|
||||
static void PIOS_EXTI_4_irq_handler (void)
|
||||
{
|
||||
PIOS_EXTI_HANDLE_LINE(4);
|
||||
}
|
||||
void EXTI4_IRQHandler(void) __attribute__ ((alias ("PIOS_EXTI_4_irq_handler")));
|
||||
|
||||
static void PIOS_EXTI_9_5_irq_handler (void)
|
||||
{
|
||||
PIOS_EXTI_HANDLE_LINE(5);
|
||||
PIOS_EXTI_HANDLE_LINE(6);
|
||||
PIOS_EXTI_HANDLE_LINE(7);
|
||||
PIOS_EXTI_HANDLE_LINE(8);
|
||||
PIOS_EXTI_HANDLE_LINE(9);
|
||||
}
|
||||
void EXTI9_5_IRQHandler(void) __attribute__ ((alias ("PIOS_EXTI_9_5_irq_handler")));
|
||||
|
||||
static void PIOS_EXTI_15_10_irq_handler (void)
|
||||
{
|
||||
PIOS_EXTI_HANDLE_LINE(10);
|
||||
PIOS_EXTI_HANDLE_LINE(11);
|
||||
PIOS_EXTI_HANDLE_LINE(12);
|
||||
PIOS_EXTI_HANDLE_LINE(13);
|
||||
PIOS_EXTI_HANDLE_LINE(14);
|
||||
PIOS_EXTI_HANDLE_LINE(15);
|
||||
}
|
||||
void EXTI15_10_IRQHandler(void) __attribute__ ((alias ("PIOS_EXTI_15_10_irq_handler")));
|
||||
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
@ -891,6 +891,10 @@ int32_t PIOS_I2C_Init(uint32_t * i2c_id, const struct pios_i2c_adapter_cfg * cfg
|
||||
break;
|
||||
}
|
||||
|
||||
if (i2c_adapter->cfg->remap) {
|
||||
GPIO_PinRemapConfig(i2c_adapter->cfg->remap, ENABLE);
|
||||
}
|
||||
|
||||
/* Initialize the state machine */
|
||||
i2c_adapter_fsm_init(i2c_adapter);
|
||||
|
||||
|
@ -33,57 +33,107 @@
|
||||
|
||||
#if defined(PIOS_INCLUDE_LED)
|
||||
|
||||
/* Private Function Prototypes */
|
||||
#include <pios_led_priv.h>
|
||||
|
||||
/* Local Variables */
|
||||
static GPIO_TypeDef *LED_GPIO_PORT[PIOS_LED_NUM] = PIOS_LED_PORTS;
|
||||
static const uint32_t LED_GPIO_PIN[PIOS_LED_NUM] = PIOS_LED_PINS;
|
||||
static const uint32_t LED_GPIO_CLK[PIOS_LED_NUM] = PIOS_LED_CLKS;
|
||||
const static struct pios_led_cfg * led_cfg;
|
||||
|
||||
/**
|
||||
* Initialises all the LED's
|
||||
*/
|
||||
void PIOS_LED_Init(void)
|
||||
int32_t PIOS_LED_Init(const struct pios_led_cfg * cfg)
|
||||
{
|
||||
GPIO_InitTypeDef GPIO_InitStructure;
|
||||
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_PP;
|
||||
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
|
||||
PIOS_Assert(cfg);
|
||||
|
||||
for (int LEDNum = 0; LEDNum < PIOS_LED_NUM; LEDNum++) {
|
||||
RCC_APB2PeriphClockCmd(LED_GPIO_CLK[LEDNum], ENABLE);
|
||||
GPIO_InitStructure.GPIO_Pin = LED_GPIO_PIN[LEDNum];
|
||||
GPIO_Init(LED_GPIO_PORT[LEDNum], &GPIO_InitStructure);
|
||||
/* Store away the config in a global used by API functions */
|
||||
led_cfg = cfg;
|
||||
|
||||
/* LED's Off */
|
||||
LED_GPIO_PORT[LEDNum]->BSRR = LED_GPIO_PIN[LEDNum];
|
||||
for (uint8_t i = 0; i < cfg->num_leds; i++) {
|
||||
const struct pios_led * led = &(cfg->leds[i]);
|
||||
|
||||
/* Enable the peripheral clock for the GPIO */
|
||||
switch ((uint32_t)led->pin.gpio) {
|
||||
case (uint32_t) GPIOA:
|
||||
RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA, ENABLE);
|
||||
break;
|
||||
case (uint32_t) GPIOB:
|
||||
RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOB, ENABLE);
|
||||
break;
|
||||
case (uint32_t) GPIOC:
|
||||
RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOB, ENABLE);
|
||||
break;
|
||||
default:
|
||||
PIOS_Assert(0);
|
||||
break;
|
||||
}
|
||||
|
||||
if (led->remap) {
|
||||
GPIO_PinRemapConfig(led->remap, ENABLE);
|
||||
}
|
||||
|
||||
GPIO_Init(led->pin.gpio, &led->pin.init);
|
||||
|
||||
PIOS_LED_Off(i);
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* Turn on LED
|
||||
* \param[in] LED LED Name (LED1, LED2)
|
||||
* \param[in] LED LED id
|
||||
*/
|
||||
void PIOS_LED_On(LedTypeDef LED)
|
||||
void PIOS_LED_On(uint32_t led_id)
|
||||
{
|
||||
LED_GPIO_PORT[LED]->BRR = LED_GPIO_PIN[LED];
|
||||
PIOS_Assert(led_cfg);
|
||||
|
||||
if (led_id >= led_cfg->num_leds) {
|
||||
/* LED index out of range */
|
||||
return;
|
||||
}
|
||||
|
||||
const struct pios_led * led = &(led_cfg->leds[led_id]);
|
||||
|
||||
GPIO_ResetBits(led->pin.gpio, led->pin.init.GPIO_Pin);
|
||||
}
|
||||
|
||||
/**
|
||||
* Turn off LED
|
||||
* \param[in] LED LED Name (LED1, LED2)
|
||||
* \param[in] LED LED id
|
||||
*/
|
||||
void PIOS_LED_Off(LedTypeDef LED)
|
||||
void PIOS_LED_Off(uint32_t led_id)
|
||||
{
|
||||
LED_GPIO_PORT[LED]->BSRR = LED_GPIO_PIN[LED];
|
||||
PIOS_Assert(led_cfg);
|
||||
|
||||
if (led_id >= led_cfg->num_leds) {
|
||||
/* LED index out of range */
|
||||
return;
|
||||
}
|
||||
|
||||
const struct pios_led * led = &(led_cfg->leds[led_id]);
|
||||
|
||||
GPIO_SetBits(led->pin.gpio, led->pin.init.GPIO_Pin);
|
||||
}
|
||||
|
||||
/**
|
||||
* Toggle LED on/off
|
||||
* \param[in] LED LED Name (LED1, LED2)
|
||||
* \param[in] LED LED id
|
||||
*/
|
||||
void PIOS_LED_Toggle(LedTypeDef LED)
|
||||
void PIOS_LED_Toggle(uint32_t led_id)
|
||||
{
|
||||
LED_GPIO_PORT[LED]->ODR ^= LED_GPIO_PIN[LED];
|
||||
PIOS_Assert(led_cfg);
|
||||
|
||||
if (led_id >= led_cfg->num_leds) {
|
||||
/* LED index out of range */
|
||||
return;
|
||||
}
|
||||
|
||||
const struct pios_led * led = &(led_cfg->leds[led_id]);
|
||||
|
||||
if (GPIO_ReadOutputDataBit(led->pin.gpio, led->pin.init.GPIO_Pin) == Bit_SET) {
|
||||
PIOS_LED_On(led_id);
|
||||
} else {
|
||||
PIOS_LED_Off(led_id);
|
||||
}
|
||||
}
|
||||
|
||||
#endif
|
||||
|
@ -77,10 +77,6 @@ void PIOS_SYS_Init(void)
|
||||
/* Initialise Basic NVIC */
|
||||
NVIC_Configuration();
|
||||
|
||||
#if defined(PIOS_INCLUDE_LED)
|
||||
/* Initialise LEDs */
|
||||
PIOS_LED_Init();
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
@ -105,16 +101,12 @@ int32_t PIOS_SYS_Reset(void)
|
||||
PIOS_IRQ_Disable();
|
||||
|
||||
// turn off all board LEDs
|
||||
#if (PIOS_LED_NUM == 1)
|
||||
PIOS_LED_Off(LED1);
|
||||
#elif (PIOS_LED_NUM == 2)
|
||||
PIOS_LED_Off(LED1);
|
||||
PIOS_LED_Off(LED2);
|
||||
#endif
|
||||
|
||||
/* Reset STM32 */
|
||||
//RCC_APB2PeriphResetCmd(0xfffffff8, ENABLE); /* MBHP_CORE_STM32: don't reset GPIOA/AF due to USB pins */
|
||||
//RCC_APB1PeriphResetCmd(0xff7fffff, ENABLE); /* don't reset USB, so that the connection can survive! */
|
||||
#if defined(PIOS_LED_HEARTBEAT)
|
||||
PIOS_LED_Off(PIOS_LED_HEARTBEAT);
|
||||
#endif /* PIOS_LED_HEARTBEAT */
|
||||
#if defined(PIOS_LED_ALARM)
|
||||
PIOS_LED_Off(PIOS_LED_ALARM);
|
||||
#endif /* PIOS_LED_ALARM */
|
||||
|
||||
RCC_APB2PeriphResetCmd(0xffffffff, DISABLE);
|
||||
RCC_APB1PeriphResetCmd(0xffffffff, DISABLE);
|
||||
@ -210,13 +202,21 @@ void assert_failed(uint8_t * file, uint32_t line)
|
||||
/* printf("Wrong parameters value: file %s on line %d\r\n", file, line); */
|
||||
|
||||
/* Setup the LEDs to Alternate */
|
||||
PIOS_LED_On(LED1);
|
||||
PIOS_LED_Off(LED2);
|
||||
#if defined(PIOS_LED_HEARTBEAT)
|
||||
PIOS_LED_On(PIOS_LED_HEARTBEAT);
|
||||
#endif /* PIOS_LED_HEARTBEAT */
|
||||
#if defined(PIOS_LED_ALARM)
|
||||
PIOS_LED_Off(PIOS_LED_ALARM);
|
||||
#endif /* PIOS_LED_ALARM */
|
||||
|
||||
/* Infinite loop */
|
||||
while (1) {
|
||||
PIOS_LED_Toggle(LED1);
|
||||
PIOS_LED_Toggle(LED2);
|
||||
#if defined(PIOS_LED_HEARTBEAT)
|
||||
PIOS_LED_Toggle(PIOS_LED_HEARTBEAT);
|
||||
#endif /* PIOS_LED_HEARTBEAT */
|
||||
#if defined(PIOS_LED_ALARM)
|
||||
PIOS_LED_Toggle(PIOS_LED_ALARM);
|
||||
#endif /* PIOS_LED_ALARM */
|
||||
for (int i = 0; i < 1000000; i++) ;
|
||||
}
|
||||
}
|
||||
|
@ -123,13 +123,6 @@ int32_t PIOS_USB_Init(uint32_t * usb_id, const struct pios_usb_cfg * cfg)
|
||||
/* Enable the USB clock */
|
||||
RCC_APB1PeriphClockCmd(RCC_APB1Periph_USB, ENABLE);
|
||||
|
||||
/* Update the USB serial number from the chip */
|
||||
uint8_t sn[25];
|
||||
PIOS_SYS_SerialNumberGet((char *)sn);
|
||||
for (uint8_t i = 0; sn[i] != '\0' && (2 * i) < PIOS_USB_BOARD_StringSerial[0]; i++) {
|
||||
PIOS_USB_BOARD_StringSerial[2 + 2 * i] = sn[i];
|
||||
}
|
||||
|
||||
USB_Init();
|
||||
USB_SIL_Init();
|
||||
|
||||
|
@ -346,7 +346,7 @@ RESULT PIOS_USB_CDC_SetLineCoding(void)
|
||||
return USB_SUCCESS;
|
||||
}
|
||||
|
||||
uint8_t *PIOS_USB_CDC_GetLineCoding(uint16_t Length)
|
||||
const uint8_t *PIOS_USB_CDC_GetLineCoding(uint16_t Length)
|
||||
{
|
||||
struct pios_usb_cdc_dev * usb_cdc_dev = (struct pios_usb_cdc_dev *)pios_usb_cdc_id;
|
||||
|
||||
|
@ -207,9 +207,15 @@ static void PIOS_USB_HID_RxStart(uint32_t usbhid_id, uint16_t rx_bytes_avail) {
|
||||
}
|
||||
|
||||
// If endpoint was stalled and there is now space make it valid
|
||||
#ifdef PIOS_USB_BOARD_BL_HID_HAS_NO_LENGTH_BYTE
|
||||
uint16_t max_payload_length = PIOS_USB_BOARD_HID_DATA_LENGTH - 1;
|
||||
#else
|
||||
uint16_t max_payload_length = PIOS_USB_BOARD_HID_DATA_LENGTH - 2;
|
||||
#endif
|
||||
|
||||
PIOS_IRQ_Disable();
|
||||
if ((GetEPRxStatus(usb_hid_dev->cfg->data_rx_ep) != EP_RX_VALID) &&
|
||||
(rx_bytes_avail >= PIOS_USB_BOARD_HID_DATA_LENGTH)) {
|
||||
(rx_bytes_avail >= max_payload_length)) {
|
||||
SetEPRxStatus(usb_hid_dev->cfg->data_rx_ep, EP_RX_VALID);
|
||||
}
|
||||
PIOS_IRQ_Enable();
|
||||
@ -328,7 +334,15 @@ static void PIOS_USB_HID_EP_OUT_Callback(void)
|
||||
&headroom,
|
||||
&need_yield);
|
||||
#endif
|
||||
if (headroom >= PIOS_USB_BOARD_HID_DATA_LENGTH) {
|
||||
|
||||
#ifdef PIOS_USB_BOARD_BL_HID_HAS_NO_LENGTH_BYTE
|
||||
uint16_t max_payload_length = PIOS_USB_BOARD_HID_DATA_LENGTH - 1;
|
||||
#else
|
||||
uint16_t max_payload_length = PIOS_USB_BOARD_HID_DATA_LENGTH - 2;
|
||||
#endif
|
||||
|
||||
if (headroom >= max_payload_length) {
|
||||
|
||||
/* We have room for a maximum length message */
|
||||
SetEPRxStatus(usb_hid_dev->cfg->data_rx_ep, EP_RX_VALID);
|
||||
} else {
|
||||
|
@ -36,6 +36,48 @@
|
||||
#include "pios_usb_cdc_priv.h" /* PIOS_USB_CDC_* */
|
||||
#include "pios_usb_board_data.h" /* PIOS_USB_BOARD_* */
|
||||
|
||||
static ONE_DESCRIPTOR Device_Descriptor;
|
||||
|
||||
void PIOS_USBHOOK_RegisterDevice(const uint8_t * desc, uint16_t desc_size)
|
||||
{
|
||||
Device_Descriptor.Descriptor = desc;
|
||||
Device_Descriptor.Descriptor_Size = desc_size;
|
||||
}
|
||||
|
||||
static ONE_DESCRIPTOR Config_Descriptor;
|
||||
|
||||
void PIOS_USBHOOK_RegisterConfig(uint8_t config_id, const uint8_t * desc, uint16_t desc_size)
|
||||
{
|
||||
Config_Descriptor.Descriptor = desc;
|
||||
Config_Descriptor.Descriptor_Size = desc_size;
|
||||
}
|
||||
|
||||
static ONE_DESCRIPTOR String_Descriptor[4];
|
||||
|
||||
void PIOS_USBHOOK_RegisterString(enum usb_string_desc string_id, const uint8_t * desc, uint16_t desc_size)
|
||||
{
|
||||
if (string_id < NELEMENTS(String_Descriptor)) {
|
||||
String_Descriptor[string_id].Descriptor = desc;
|
||||
String_Descriptor[string_id].Descriptor_Size = desc_size;
|
||||
}
|
||||
}
|
||||
|
||||
static ONE_DESCRIPTOR Hid_Interface_Descriptor;
|
||||
|
||||
void PIOS_USBHOOK_RegisterHidInterface(const uint8_t * desc, uint16_t desc_size)
|
||||
{
|
||||
Hid_Interface_Descriptor.Descriptor = desc;
|
||||
Hid_Interface_Descriptor.Descriptor_Size = desc_size;
|
||||
}
|
||||
|
||||
static ONE_DESCRIPTOR Hid_Report_Descriptor;
|
||||
|
||||
void PIOS_USBHOOK_RegisterHidReport(const uint8_t * desc, uint16_t desc_size)
|
||||
{
|
||||
Hid_Report_Descriptor.Descriptor = desc;
|
||||
Hid_Report_Descriptor.Descriptor_Size = desc_size;
|
||||
}
|
||||
|
||||
#include "stm32f10x.h" /* __IO */
|
||||
__IO uint8_t EXTI_Enable;
|
||||
|
||||
@ -53,9 +95,9 @@ static void PIOS_USBHOOK_Status_Out(void);
|
||||
static RESULT PIOS_USBHOOK_Data_Setup(uint8_t RequestNo);
|
||||
static RESULT PIOS_USBHOOK_NoData_Setup(uint8_t RequestNo);
|
||||
static RESULT PIOS_USBHOOK_Get_Interface_Setting(uint8_t Interface, uint8_t AlternateSetting);
|
||||
static uint8_t *PIOS_USBHOOK_GetDeviceDescriptor(uint16_t Length);
|
||||
static uint8_t *PIOS_USBHOOK_GetConfigDescriptor(uint16_t Length);
|
||||
static uint8_t *PIOS_USBHOOK_GetStringDescriptor(uint16_t Length);
|
||||
static const uint8_t *PIOS_USBHOOK_GetDeviceDescriptor(uint16_t Length);
|
||||
static const uint8_t *PIOS_USBHOOK_GetConfigDescriptor(uint16_t Length);
|
||||
static const uint8_t *PIOS_USBHOOK_GetStringDescriptor(uint16_t Length);
|
||||
|
||||
DEVICE_PROP Device_Property = {
|
||||
.Init = PIOS_USBHOOK_Init,
|
||||
@ -87,49 +129,10 @@ USER_STANDARD_REQUESTS User_Standard_Requests = {
|
||||
.User_SetDeviceAddress = PIOS_USBHOOK_SetDeviceAddress
|
||||
};
|
||||
|
||||
const static ONE_DESCRIPTOR Device_Descriptor = {
|
||||
(uint8_t *) &PIOS_USB_BOARD_DeviceDescriptor,
|
||||
sizeof(PIOS_USB_BOARD_DeviceDescriptor),
|
||||
};
|
||||
|
||||
static ONE_DESCRIPTOR Config_Descriptor = {
|
||||
(uint8_t *) &PIOS_USB_BOARD_Configuration,
|
||||
sizeof(PIOS_USB_BOARD_Configuration),
|
||||
};
|
||||
|
||||
const static ONE_DESCRIPTOR Hid_Report_Descriptor = {
|
||||
(uint8_t *) &PIOS_USB_BOARD_HidReportDescriptor,
|
||||
sizeof(PIOS_USB_BOARD_HidReportDescriptor),
|
||||
};
|
||||
|
||||
const static ONE_DESCRIPTOR Hid_Interface_Descriptor = {
|
||||
(uint8_t *) &PIOS_USB_BOARD_Configuration.hid_if,
|
||||
sizeof(PIOS_USB_BOARD_Configuration.hid_if),
|
||||
};
|
||||
|
||||
const static ONE_DESCRIPTOR String_Descriptor[] = {
|
||||
{
|
||||
(uint8_t *) &PIOS_USB_BOARD_StringLangID,
|
||||
sizeof(PIOS_USB_BOARD_StringLangID),
|
||||
},
|
||||
{
|
||||
(uint8_t *) PIOS_USB_BOARD_StringVendorID,
|
||||
sizeof(PIOS_USB_BOARD_StringVendorID),
|
||||
},
|
||||
{
|
||||
(uint8_t *) PIOS_USB_BOARD_StringProductID,
|
||||
sizeof(PIOS_USB_BOARD_StringProductID),
|
||||
},
|
||||
{
|
||||
(uint8_t *) PIOS_USB_BOARD_StringSerial,
|
||||
sizeof(PIOS_USB_BOARD_StringSerial),
|
||||
},
|
||||
};
|
||||
|
||||
static RESULT PIOS_USBHOOK_SetProtocol(void);
|
||||
static uint8_t *PIOS_USBHOOK_GetProtocolValue(uint16_t Length);
|
||||
static uint8_t *PIOS_USBHOOK_GetReportDescriptor(uint16_t Length);
|
||||
static uint8_t *PIOS_USBHOOK_GetHIDDescriptor(uint16_t Length);
|
||||
static const uint8_t *PIOS_USBHOOK_GetProtocolValue(uint16_t Length);
|
||||
static const uint8_t *PIOS_USBHOOK_GetReportDescriptor(uint16_t Length);
|
||||
static const uint8_t *PIOS_USBHOOK_GetHIDDescriptor(uint16_t Length);
|
||||
|
||||
/*******************************************************************************
|
||||
* Function Name : PIOS_USBHOOK_Init.
|
||||
@ -140,11 +143,8 @@ static uint8_t *PIOS_USBHOOK_GetHIDDescriptor(uint16_t Length);
|
||||
*******************************************************************************/
|
||||
static void PIOS_USBHOOK_Init(void)
|
||||
{
|
||||
/* Update the serial number string descriptor with the data from the unique
|
||||
ID */
|
||||
//Get_SerialNum();
|
||||
|
||||
pInformation->Current_Configuration = 0;
|
||||
|
||||
/* Connect the device */
|
||||
PowerOn();
|
||||
|
||||
@ -292,7 +292,7 @@ static void PIOS_USBHOOK_Status_Out(void)
|
||||
*******************************************************************************/
|
||||
static RESULT PIOS_USBHOOK_Data_Setup(uint8_t RequestNo)
|
||||
{
|
||||
uint8_t *(*CopyRoutine) (uint16_t);
|
||||
const uint8_t *(*CopyRoutine) (uint16_t);
|
||||
|
||||
CopyRoutine = NULL;
|
||||
|
||||
@ -350,7 +350,7 @@ static RESULT PIOS_USBHOOK_Data_Setup(uint8_t RequestNo)
|
||||
return USB_UNSUPPORT;
|
||||
}
|
||||
|
||||
pInformation->Ctrl_Info.CopyData = CopyRoutine;
|
||||
pInformation->Ctrl_Info.CopyDataIn = CopyRoutine;
|
||||
pInformation->Ctrl_Info.Usb_wOffset = 0;
|
||||
(*CopyRoutine) (0);
|
||||
return USB_SUCCESS;
|
||||
@ -405,7 +405,7 @@ static RESULT PIOS_USBHOOK_NoData_Setup(uint8_t RequestNo)
|
||||
* Output : None.
|
||||
* Return : The address of the device descriptor.
|
||||
*******************************************************************************/
|
||||
static uint8_t *PIOS_USBHOOK_GetDeviceDescriptor(uint16_t Length)
|
||||
static const uint8_t *PIOS_USBHOOK_GetDeviceDescriptor(uint16_t Length)
|
||||
{
|
||||
return Standard_GetDescriptorData(Length, &Device_Descriptor);
|
||||
}
|
||||
@ -417,7 +417,7 @@ static uint8_t *PIOS_USBHOOK_GetDeviceDescriptor(uint16_t Length)
|
||||
* Output : None.
|
||||
* Return : The address of the configuration descriptor.
|
||||
*******************************************************************************/
|
||||
static uint8_t *PIOS_USBHOOK_GetConfigDescriptor(uint16_t Length)
|
||||
static const uint8_t *PIOS_USBHOOK_GetConfigDescriptor(uint16_t Length)
|
||||
{
|
||||
return Standard_GetDescriptorData(Length, &Config_Descriptor);
|
||||
}
|
||||
@ -429,7 +429,7 @@ static uint8_t *PIOS_USBHOOK_GetConfigDescriptor(uint16_t Length)
|
||||
* Output : None.
|
||||
* Return : The address of the string descriptors.
|
||||
*******************************************************************************/
|
||||
static uint8_t *PIOS_USBHOOK_GetStringDescriptor(uint16_t Length)
|
||||
static const uint8_t *PIOS_USBHOOK_GetStringDescriptor(uint16_t Length)
|
||||
{
|
||||
uint8_t wValue0 = pInformation->USBwValue0;
|
||||
if (wValue0 > 4) {
|
||||
@ -446,7 +446,7 @@ static uint8_t *PIOS_USBHOOK_GetStringDescriptor(uint16_t Length)
|
||||
* Output : None.
|
||||
* Return : The address of the configuration descriptor.
|
||||
*******************************************************************************/
|
||||
static uint8_t *PIOS_USBHOOK_GetReportDescriptor(uint16_t Length)
|
||||
static const uint8_t *PIOS_USBHOOK_GetReportDescriptor(uint16_t Length)
|
||||
{
|
||||
return Standard_GetDescriptorData(Length, &Hid_Report_Descriptor);
|
||||
}
|
||||
@ -458,7 +458,7 @@ static uint8_t *PIOS_USBHOOK_GetReportDescriptor(uint16_t Length)
|
||||
* Output : None.
|
||||
* Return : The address of the configuration descriptor.
|
||||
*******************************************************************************/
|
||||
static uint8_t *PIOS_USBHOOK_GetHIDDescriptor(uint16_t Length)
|
||||
static const uint8_t *PIOS_USBHOOK_GetHIDDescriptor(uint16_t Length)
|
||||
{
|
||||
return Standard_GetDescriptorData(Length, &Hid_Interface_Descriptor);
|
||||
}
|
||||
@ -503,7 +503,7 @@ static RESULT PIOS_USBHOOK_SetProtocol(void)
|
||||
* Output : None.
|
||||
* Return : address of the protcol value.
|
||||
*******************************************************************************/
|
||||
static uint8_t *PIOS_USBHOOK_GetProtocolValue(uint16_t Length)
|
||||
static const uint8_t *PIOS_USBHOOK_GetProtocolValue(uint16_t Length)
|
||||
{
|
||||
if (Length == 0) {
|
||||
pInformation->Ctrl_Info.Usb_wLength = 1;
|
||||
|
@ -31,6 +31,9 @@
|
||||
#ifndef PIOS_COM_H
|
||||
#define PIOS_COM_H
|
||||
|
||||
#include <stdint.h> /* uint*_t */
|
||||
#include <stdbool.h> /* bool */
|
||||
|
||||
typedef uint16_t (*pios_com_callback)(uint32_t context, uint8_t * buf, uint16_t buf_len, uint16_t * headroom, bool * task_woken);
|
||||
|
||||
struct pios_com_driver {
|
||||
@ -43,7 +46,6 @@ struct pios_com_driver {
|
||||
};
|
||||
|
||||
/* Public Functions */
|
||||
extern int32_t PIOS_COM_Init(uint32_t * com_id, const struct pios_com_driver * driver, uint32_t lower_id, uint8_t * rx_buffer, uint16_t rx_buffer_len, uint8_t * tx_buffer, uint16_t tx_buffer_len);
|
||||
extern int32_t PIOS_COM_ChangeBaud(uint32_t com_id, uint32_t baud);
|
||||
extern int32_t PIOS_COM_SendCharNonBlocking(uint32_t com_id, char c);
|
||||
extern int32_t PIOS_COM_SendChar(uint32_t com_id, char c);
|
||||
|
45
flight/PiOS/inc/pios_com_msg.h
Normal file
45
flight/PiOS/inc/pios_com_msg.h
Normal file
@ -0,0 +1,45 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup PIOS PIOS Core hardware abstraction layer
|
||||
* @{
|
||||
* @addtogroup PIOS_COM COM MSG layer functions
|
||||
* @brief Hardware communication layer
|
||||
* @{
|
||||
*
|
||||
* @file pios_com_msg.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @brief COM MSG layer functions header
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
*
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* This program is free software; you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation; either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful, but
|
||||
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
|
||||
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
|
||||
* for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License along
|
||||
* with this program; if not, write to the Free Software Foundation, Inc.,
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
|
||||
#ifndef PIOS_COM_MSG_H
|
||||
#define PIOS_COM_MSG_H
|
||||
|
||||
#include <stdint.h> /* uint*_t */
|
||||
|
||||
/* Public Functions */
|
||||
extern int32_t PIOS_COM_MSG_Send(uint32_t com_id, const uint8_t *msg, uint16_t msg_len);
|
||||
extern uint16_t PIOS_COM_MSG_Receive(uint32_t com_id, uint8_t * buf, uint16_t buf_len);
|
||||
|
||||
#endif /* PIOS_COM_MSG_H */
|
||||
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
44
flight/PiOS/inc/pios_com_msg_priv.h
Normal file
44
flight/PiOS/inc/pios_com_msg_priv.h
Normal file
@ -0,0 +1,44 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup PIOS PIOS Core hardware abstraction layer
|
||||
* @{
|
||||
* @addtogroup PIOS_COM COM MSG layer functions
|
||||
* @brief Hardware communication layer
|
||||
* @{
|
||||
*
|
||||
* @file pios_com_msg_priv.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @brief COM MSG private definitions.
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
*
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* This program is free software; you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation; either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful, but
|
||||
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
|
||||
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
|
||||
* for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License along
|
||||
* with this program; if not, write to the Free Software Foundation, Inc.,
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
|
||||
#ifndef PIOS_COM_MSG_PRIV_H
|
||||
#define PIOS_COM_MSG_PRIV_H
|
||||
|
||||
#include <stdint.h> /* uint*_t */
|
||||
#include "pios_com_priv.h" /* struct pios_com_driver */
|
||||
|
||||
extern int32_t PIOS_COM_MSG_Init(uint32_t * com_id, const struct pios_com_driver * driver, uint32_t lower_id);
|
||||
|
||||
#endif /* PIOS_COM_MSG_PRIV_H */
|
||||
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
@ -31,6 +31,8 @@
|
||||
#ifndef PIOS_COM_PRIV_H
|
||||
#define PIOS_COM_PRIV_H
|
||||
|
||||
extern int32_t PIOS_COM_Init(uint32_t * com_id, const struct pios_com_driver * driver, uint32_t lower_id, uint8_t * rx_buffer, uint16_t rx_buffer_len, uint8_t * tx_buffer, uint16_t tx_buffer_len);
|
||||
|
||||
#endif /* PIOS_COM_PRIV_H */
|
||||
|
||||
/**
|
||||
|
@ -33,6 +33,21 @@
|
||||
|
||||
/* Public Functions */
|
||||
|
||||
#include <pios_stm32.h>
|
||||
|
||||
struct pios_exti_cfg {
|
||||
void (* vector)(void);
|
||||
uint32_t line; /* use EXTI_LineN macros */
|
||||
struct stm32_gpio pin;
|
||||
struct stm32_irq irq;
|
||||
struct stm32_exti exti;
|
||||
};
|
||||
|
||||
/* must be added to any pios_exti_cfg definition for it to be valid */
|
||||
#define __exti_config __attribute__((section("_exti")))
|
||||
|
||||
extern int32_t PIOS_EXTI_Init(const struct pios_exti_cfg * cfg);
|
||||
|
||||
#endif /* PIOS_EXTI_H */
|
||||
|
||||
/**
|
||||
|
@ -37,6 +37,7 @@ struct pios_i2c_adapter_cfg {
|
||||
uint32_t transfer_timeout_ms;
|
||||
struct stm32_gpio scl;
|
||||
struct stm32_gpio sda;
|
||||
uint32_t remap;
|
||||
struct stm32_irq event;
|
||||
struct stm32_irq error;
|
||||
};
|
||||
|
@ -30,23 +30,9 @@
|
||||
#ifndef PIOS_LED_H
|
||||
#define PIOS_LED_H
|
||||
|
||||
/* Type Definitions */
|
||||
#if (PIOS_LED_NUM == 1)
|
||||
typedef enum { LED1 = 0 } LedTypeDef;
|
||||
#elif (PIOS_LED_NUM == 2)
|
||||
typedef enum { LED1 = 0, LED2 = 1 } LedTypeDef;
|
||||
#elif (PIOS_LED_NUM == 3)
|
||||
typedef enum { LED1 = 0, LED2 = 1, LED3 = 2 } LedTypeDef;
|
||||
#elif (PIOS_LED_NUM == 4)
|
||||
typedef enum { LED1 = 0, LED2 = 1, LED3 = 2, LED4 = 3 } LedTypeDef;
|
||||
#else
|
||||
#error PIOS_LED_NUM not defined
|
||||
#endif
|
||||
|
||||
/* Public Functions */
|
||||
extern void PIOS_LED_Init(void);
|
||||
extern void PIOS_LED_On(LedTypeDef LED);
|
||||
extern void PIOS_LED_Off(LedTypeDef LED);
|
||||
extern void PIOS_LED_Toggle(LedTypeDef LED);
|
||||
extern void PIOS_LED_On(uint32_t led_id);
|
||||
extern void PIOS_LED_Off(uint32_t led_id);
|
||||
extern void PIOS_LED_Toggle(uint32_t led_id);
|
||||
|
||||
#endif /* PIOS_LED_H */
|
||||
|
Some files were not shown because too many files have changed in this diff Show More
Loading…
x
Reference in New Issue
Block a user