Initial support for FY90Q hardware
git-svn-id: https://afrodevices.googlecode.com/svn/trunk/baseflight@146 7c89a4a9-59b9-e629-4cfe-3a2d53b20e61
This commit is contained in:
parent
cb334ecf47
commit
d9920756d9
375
baseflight.uvopt
375
baseflight.uvopt
|
@ -73,7 +73,7 @@
|
||||||
<OPTFL>
|
<OPTFL>
|
||||||
<tvExp>1</tvExp>
|
<tvExp>1</tvExp>
|
||||||
<tvExpOptDlg>0</tvExpOptDlg>
|
<tvExpOptDlg>0</tvExpOptDlg>
|
||||||
<IsCurrentTarget>1</IsCurrentTarget>
|
<IsCurrentTarget>0</IsCurrentTarget>
|
||||||
</OPTFL>
|
</OPTFL>
|
||||||
<CpuCode>255</CpuCode>
|
<CpuCode>255</CpuCode>
|
||||||
<Books>
|
<Books>
|
||||||
|
@ -523,6 +523,257 @@
|
||||||
</TargetOption>
|
</TargetOption>
|
||||||
</Target>
|
</Target>
|
||||||
|
|
||||||
|
<Target>
|
||||||
|
<TargetName>STM32-FY90Q</TargetName>
|
||||||
|
<ToolsetNumber>0x4</ToolsetNumber>
|
||||||
|
<ToolsetName>ARM-ADS</ToolsetName>
|
||||||
|
<TargetOption>
|
||||||
|
<CLKADS>8000000</CLKADS>
|
||||||
|
<OPTTT>
|
||||||
|
<gFlags>1</gFlags>
|
||||||
|
<BeepAtEnd>1</BeepAtEnd>
|
||||||
|
<RunSim>1</RunSim>
|
||||||
|
<RunTarget>0</RunTarget>
|
||||||
|
</OPTTT>
|
||||||
|
<OPTHX>
|
||||||
|
<HexSelection>1</HexSelection>
|
||||||
|
<FlashByte>65535</FlashByte>
|
||||||
|
<HexRangeLowAddress>0</HexRangeLowAddress>
|
||||||
|
<HexRangeHighAddress>0</HexRangeHighAddress>
|
||||||
|
<HexOffset>0</HexOffset>
|
||||||
|
</OPTHX>
|
||||||
|
<OPTLEX>
|
||||||
|
<PageWidth>79</PageWidth>
|
||||||
|
<PageLength>66</PageLength>
|
||||||
|
<TabStop>8</TabStop>
|
||||||
|
<ListingPath>.\obj\</ListingPath>
|
||||||
|
</OPTLEX>
|
||||||
|
<ListingPage>
|
||||||
|
<CreateCListing>1</CreateCListing>
|
||||||
|
<CreateAListing>1</CreateAListing>
|
||||||
|
<CreateLListing>1</CreateLListing>
|
||||||
|
<CreateIListing>0</CreateIListing>
|
||||||
|
<AsmCond>1</AsmCond>
|
||||||
|
<AsmSymb>1</AsmSymb>
|
||||||
|
<AsmXref>0</AsmXref>
|
||||||
|
<CCond>1</CCond>
|
||||||
|
<CCode>0</CCode>
|
||||||
|
<CListInc>0</CListInc>
|
||||||
|
<CSymb>0</CSymb>
|
||||||
|
<LinkerCodeListing>0</LinkerCodeListing>
|
||||||
|
</ListingPage>
|
||||||
|
<OPTXL>
|
||||||
|
<LMap>1</LMap>
|
||||||
|
<LComments>1</LComments>
|
||||||
|
<LGenerateSymbols>1</LGenerateSymbols>
|
||||||
|
<LLibSym>1</LLibSym>
|
||||||
|
<LLines>1</LLines>
|
||||||
|
<LLocSym>1</LLocSym>
|
||||||
|
<LPubSym>1</LPubSym>
|
||||||
|
<LXref>0</LXref>
|
||||||
|
<LExpSel>0</LExpSel>
|
||||||
|
</OPTXL>
|
||||||
|
<OPTFL>
|
||||||
|
<tvExp>1</tvExp>
|
||||||
|
<tvExpOptDlg>0</tvExpOptDlg>
|
||||||
|
<IsCurrentTarget>1</IsCurrentTarget>
|
||||||
|
</OPTFL>
|
||||||
|
<CpuCode>255</CpuCode>
|
||||||
|
<Books>
|
||||||
|
<Book>
|
||||||
|
<Number>0</Number>
|
||||||
|
<Title>Reference Manual</Title>
|
||||||
|
<Path>DATASHTS\ST\STM32F10xxx.PDF</Path>
|
||||||
|
</Book>
|
||||||
|
</Books>
|
||||||
|
<DllOpt>
|
||||||
|
<SimDllName>SARMCM3.DLL</SimDllName>
|
||||||
|
<SimDllArguments></SimDllArguments>
|
||||||
|
<SimDlgDllName>DARMSTM.DLL</SimDlgDllName>
|
||||||
|
<SimDlgDllArguments>-pSTM32F103RB</SimDlgDllArguments>
|
||||||
|
<TargetDllName>SARMCM3.DLL</TargetDllName>
|
||||||
|
<TargetDllArguments></TargetDllArguments>
|
||||||
|
<TargetDlgDllName>TARMSTM.DLL</TargetDlgDllName>
|
||||||
|
<TargetDlgDllArguments>-pSTM32F103RB</TargetDlgDllArguments>
|
||||||
|
</DllOpt>
|
||||||
|
<DebugOpt>
|
||||||
|
<uSim>0</uSim>
|
||||||
|
<uTrg>1</uTrg>
|
||||||
|
<sLdApp>1</sLdApp>
|
||||||
|
<sGomain>1</sGomain>
|
||||||
|
<sRbreak>1</sRbreak>
|
||||||
|
<sRwatch>1</sRwatch>
|
||||||
|
<sRmem>1</sRmem>
|
||||||
|
<sRfunc>1</sRfunc>
|
||||||
|
<sRbox>1</sRbox>
|
||||||
|
<tLdApp>1</tLdApp>
|
||||||
|
<tGomain>1</tGomain>
|
||||||
|
<tRbreak>1</tRbreak>
|
||||||
|
<tRwatch>1</tRwatch>
|
||||||
|
<tRmem>1</tRmem>
|
||||||
|
<tRfunc>0</tRfunc>
|
||||||
|
<tRbox>1</tRbox>
|
||||||
|
<sRunDeb>0</sRunDeb>
|
||||||
|
<sLrtime>0</sLrtime>
|
||||||
|
<nTsel>1</nTsel>
|
||||||
|
<sDll></sDll>
|
||||||
|
<sDllPa></sDllPa>
|
||||||
|
<sDlgDll></sDlgDll>
|
||||||
|
<sDlgPa></sDlgPa>
|
||||||
|
<sIfile></sIfile>
|
||||||
|
<tDll></tDll>
|
||||||
|
<tDllPa></tDllPa>
|
||||||
|
<tDlgDll></tDlgDll>
|
||||||
|
<tDlgPa></tDlgPa>
|
||||||
|
<tIfile></tIfile>
|
||||||
|
<pMon>BIN\UL2CM3.DLL</pMon>
|
||||||
|
</DebugOpt>
|
||||||
|
<TargetDriverDllRegistry>
|
||||||
|
<SetRegEntry>
|
||||||
|
<Number>0</Number>
|
||||||
|
<Key>DLGTARM</Key>
|
||||||
|
<Name>(1010=333,106,699,649,0)(1007=-1,-1,-1,-1,0)(1008=-1,-1,-1,-1,0)(1009=-1,-1,-1,-1,0)(100=-1,-1,-1,-1,0)(110=-1,-1,-1,-1,0)(111=-1,-1,-1,-1,0)(1011=-1,-1,-1,-1,0)(180=-1,-1,-1,-1,0)(120=1068,219,1479,610,0)(121=-1,-1,-1,-1,0)(122=828,316,1239,707,0)(123=-1,-1,-1,-1,0)(140=-1,-1,-1,-1,0)(240=-1,-1,-1,-1,0)(190=-1,-1,-1,-1,0)(200=-1,-1,-1,-1,0)(170=-1,-1,-1,-1,0)(130=582,118,1166,798,0)(131=549,135,1133,815,0)(132=-1,-1,-1,-1,0)(133=-1,-1,-1,-1,0)(160=-1,-1,-1,-1,0)(161=-1,-1,-1,-1,0)(162=-1,-1,-1,-1,0)(210=-1,-1,-1,-1,0)(211=-1,-1,-1,-1,0)(220=-1,-1,-1,-1,0)(221=-1,-1,-1,-1,0)(230=-1,-1,-1,-1,0)(231=-1,-1,-1,-1,0)(232=-1,-1,-1,-1,0)(233=-1,-1,-1,-1,0)(150=-1,-1,-1,-1,0)(151=-1,-1,-1,-1,0)</Name>
|
||||||
|
</SetRegEntry>
|
||||||
|
<SetRegEntry>
|
||||||
|
<Number>0</Number>
|
||||||
|
<Key>ARMDBGFLAGS</Key>
|
||||||
|
<Name></Name>
|
||||||
|
</SetRegEntry>
|
||||||
|
<SetRegEntry>
|
||||||
|
<Number>0</Number>
|
||||||
|
<Key>DLGUARM</Key>
|
||||||
|
<Name>(105=-1,-1,-1,-1,0)(106=-1,-1,-1,-1,0)(107=-1,-1,-1,-1,0)</Name>
|
||||||
|
</SetRegEntry>
|
||||||
|
<SetRegEntry>
|
||||||
|
<Number>0</Number>
|
||||||
|
<Key>JL2CM3</Key>
|
||||||
|
<Name>-U5800306 -O110 -S8 -A0 -C0 -JU1 -JI127.0.0.1 -JP0 -RST0 -N00("ARM CoreSight SW-DP") -D00(1BA01477) -L00(0) -TO18 -TC72000000 -TP21 -TDS800B -TDT0 -TDC1F -TIEFFFFFFFF -TIP8 -TB1 -TFE0 -FO3 -FD20000000 -FC800 -FN1 -FF0STM32F10x_128 -FS08000000 -FL020000</Name>
|
||||||
|
</SetRegEntry>
|
||||||
|
<SetRegEntry>
|
||||||
|
<Number>0</Number>
|
||||||
|
<Key>UL2CM3</Key>
|
||||||
|
<Name>-UV0168AVR -O206 -S8 -C0 -N00("ARM CoreSight SW-DP") -D00(1BA01477) -L00(0) -TO18 -TC10000000 -TP21 -TDS8007 -TDT0 -TDC1F -TIEFFFFFFFF -TIP8 -FO15 -FD20000000 -FC800 -FN1 -FF0STM32F10x_128 -FS08000000 -FL020000</Name>
|
||||||
|
</SetRegEntry>
|
||||||
|
</TargetDriverDllRegistry>
|
||||||
|
<Breakpoint>
|
||||||
|
<Bp>
|
||||||
|
<Number>0</Number>
|
||||||
|
<Type>0</Type>
|
||||||
|
<LineNumber>71</LineNumber>
|
||||||
|
<EnabledFlag>1</EnabledFlag>
|
||||||
|
<Address>134237162</Address>
|
||||||
|
<ByteObject>0</ByteObject>
|
||||||
|
<ManyObjects>0</ManyObjects>
|
||||||
|
<SizeOfObject>0</SizeOfObject>
|
||||||
|
<BreakByAccess>0</BreakByAccess>
|
||||||
|
<BreakIfRCount>1</BreakIfRCount>
|
||||||
|
<Filename></Filename>
|
||||||
|
<ExecCommand></ExecCommand>
|
||||||
|
<Expression>\\baseflight\src/spektrum.c\71</Expression>
|
||||||
|
</Bp>
|
||||||
|
<Bp>
|
||||||
|
<Number>1</Number>
|
||||||
|
<Type>0</Type>
|
||||||
|
<LineNumber>157</LineNumber>
|
||||||
|
<EnabledFlag>1</EnabledFlag>
|
||||||
|
<Address>134250840</Address>
|
||||||
|
<ByteObject>0</ByteObject>
|
||||||
|
<ManyObjects>0</ManyObjects>
|
||||||
|
<SizeOfObject>0</SizeOfObject>
|
||||||
|
<BreakByAccess>0</BreakByAccess>
|
||||||
|
<BreakIfRCount>1</BreakIfRCount>
|
||||||
|
<Filename></Filename>
|
||||||
|
<ExecCommand></ExecCommand>
|
||||||
|
<Expression>\\baseflight\src/baseflight_startups/startup_stm32f10x_md_fy90q.s\157</Expression>
|
||||||
|
</Bp>
|
||||||
|
</Breakpoint>
|
||||||
|
<WatchWindow1>
|
||||||
|
<Ww>
|
||||||
|
<count>0</count>
|
||||||
|
<WinNumber>1</WinNumber>
|
||||||
|
<ItemText>gyroADC,0x0A</ItemText>
|
||||||
|
</Ww>
|
||||||
|
<Ww>
|
||||||
|
<count>1</count>
|
||||||
|
<WinNumber>1</WinNumber>
|
||||||
|
<ItemText>accADC,0x0A</ItemText>
|
||||||
|
</Ww>
|
||||||
|
<Ww>
|
||||||
|
<count>2</count>
|
||||||
|
<WinNumber>1</WinNumber>
|
||||||
|
<ItemText>cycleTime,0x0A</ItemText>
|
||||||
|
</Ww>
|
||||||
|
<Ww>
|
||||||
|
<count>3</count>
|
||||||
|
<WinNumber>1</WinNumber>
|
||||||
|
<ItemText>gyroData,0x0A</ItemText>
|
||||||
|
</Ww>
|
||||||
|
<Ww>
|
||||||
|
<count>4</count>
|
||||||
|
<WinNumber>1</WinNumber>
|
||||||
|
<ItemText>magADC,0x0A</ItemText>
|
||||||
|
</Ww>
|
||||||
|
<Ww>
|
||||||
|
<count>5</count>
|
||||||
|
<WinNumber>1</WinNumber>
|
||||||
|
<ItemText>angle,0x0A</ItemText>
|
||||||
|
</Ww>
|
||||||
|
<Ww>
|
||||||
|
<count>6</count>
|
||||||
|
<WinNumber>1</WinNumber>
|
||||||
|
<ItemText>accData</ItemText>
|
||||||
|
</Ww>
|
||||||
|
<Ww>
|
||||||
|
<count>7</count>
|
||||||
|
<WinNumber>1</WinNumber>
|
||||||
|
<ItemText>adcData,0x0A</ItemText>
|
||||||
|
</Ww>
|
||||||
|
</WatchWindow1>
|
||||||
|
<MemoryWindow1>
|
||||||
|
<Mm>
|
||||||
|
<WinNumber>1</WinNumber>
|
||||||
|
<SubType>0</SubType>
|
||||||
|
<ItemText>\\baseflight\src/drv_adc_fy90q.c\adcData</ItemText>
|
||||||
|
</Mm>
|
||||||
|
</MemoryWindow1>
|
||||||
|
<MemoryWindow2>
|
||||||
|
<Mm>
|
||||||
|
<WinNumber>2</WinNumber>
|
||||||
|
<SubType>0</SubType>
|
||||||
|
<ItemText>\\baseflight\sensors.c\maginv</ItemText>
|
||||||
|
</Mm>
|
||||||
|
</MemoryWindow2>
|
||||||
|
<DebugFlag>
|
||||||
|
<trace>0</trace>
|
||||||
|
<periodic>1</periodic>
|
||||||
|
<aLwin>1</aLwin>
|
||||||
|
<aCover>0</aCover>
|
||||||
|
<aSer1>0</aSer1>
|
||||||
|
<aSer2>0</aSer2>
|
||||||
|
<aPa>0</aPa>
|
||||||
|
<viewmode>1</viewmode>
|
||||||
|
<vrSel>0</vrSel>
|
||||||
|
<aSym>0</aSym>
|
||||||
|
<aTbox>0</aTbox>
|
||||||
|
<AscS1>0</AscS1>
|
||||||
|
<AscS2>0</AscS2>
|
||||||
|
<AscS3>0</AscS3>
|
||||||
|
<aSer3>0</aSer3>
|
||||||
|
<eProf>0</eProf>
|
||||||
|
<aLa>0</aLa>
|
||||||
|
<aPa1>0</aPa1>
|
||||||
|
<AscS4>0</AscS4>
|
||||||
|
<aSer4>0</aSer4>
|
||||||
|
<StkLoc>0</StkLoc>
|
||||||
|
<TrcWin>0</TrcWin>
|
||||||
|
<newCpu>0</newCpu>
|
||||||
|
<uProt>0</uProt>
|
||||||
|
</DebugFlag>
|
||||||
|
<LintExecutable></LintExecutable>
|
||||||
|
<LintConfigFile></LintConfigFile>
|
||||||
|
</TargetOption>
|
||||||
|
</Target>
|
||||||
|
|
||||||
<Group>
|
<Group>
|
||||||
<GroupName>App</GroupName>
|
<GroupName>App</GroupName>
|
||||||
<tvExp>1</tvExp>
|
<tvExp>1</tvExp>
|
||||||
|
@ -562,10 +813,10 @@
|
||||||
<FileType>1</FileType>
|
<FileType>1</FileType>
|
||||||
<tvExp>0</tvExp>
|
<tvExp>0</tvExp>
|
||||||
<Focus>0</Focus>
|
<Focus>0</Focus>
|
||||||
<ColumnNumber>16</ColumnNumber>
|
<ColumnNumber>0</ColumnNumber>
|
||||||
<tvExpOptDlg>0</tvExpOptDlg>
|
<tvExpOptDlg>0</tvExpOptDlg>
|
||||||
<TopLine>25</TopLine>
|
<TopLine>46</TopLine>
|
||||||
<CurrentLine>50</CurrentLine>
|
<CurrentLine>56</CurrentLine>
|
||||||
<bDave2>0</bDave2>
|
<bDave2>0</bDave2>
|
||||||
<PathWithFileName>.\src\imu.c</PathWithFileName>
|
<PathWithFileName>.\src\imu.c</PathWithFileName>
|
||||||
<FilenameWithoutPath>imu.c</FilenameWithoutPath>
|
<FilenameWithoutPath>imu.c</FilenameWithoutPath>
|
||||||
|
@ -578,8 +829,8 @@
|
||||||
<Focus>0</Focus>
|
<Focus>0</Focus>
|
||||||
<ColumnNumber>12</ColumnNumber>
|
<ColumnNumber>12</ColumnNumber>
|
||||||
<tvExpOptDlg>0</tvExpOptDlg>
|
<tvExpOptDlg>0</tvExpOptDlg>
|
||||||
<TopLine>53</TopLine>
|
<TopLine>1</TopLine>
|
||||||
<CurrentLine>67</CurrentLine>
|
<CurrentLine>17</CurrentLine>
|
||||||
<bDave2>0</bDave2>
|
<bDave2>0</bDave2>
|
||||||
<PathWithFileName>.\src\main.c</PathWithFileName>
|
<PathWithFileName>.\src\main.c</PathWithFileName>
|
||||||
<FilenameWithoutPath>main.c</FilenameWithoutPath>
|
<FilenameWithoutPath>main.c</FilenameWithoutPath>
|
||||||
|
@ -604,10 +855,10 @@
|
||||||
<FileType>1</FileType>
|
<FileType>1</FileType>
|
||||||
<tvExp>0</tvExp>
|
<tvExp>0</tvExp>
|
||||||
<Focus>0</Focus>
|
<Focus>0</Focus>
|
||||||
<ColumnNumber>0</ColumnNumber>
|
<ColumnNumber>10</ColumnNumber>
|
||||||
<tvExpOptDlg>0</tvExpOptDlg>
|
<tvExpOptDlg>0</tvExpOptDlg>
|
||||||
<TopLine>466</TopLine>
|
<TopLine>497</TopLine>
|
||||||
<CurrentLine>489</CurrentLine>
|
<CurrentLine>507</CurrentLine>
|
||||||
<bDave2>0</bDave2>
|
<bDave2>0</bDave2>
|
||||||
<PathWithFileName>.\src\mw.c</PathWithFileName>
|
<PathWithFileName>.\src\mw.c</PathWithFileName>
|
||||||
<FilenameWithoutPath>mw.c</FilenameWithoutPath>
|
<FilenameWithoutPath>mw.c</FilenameWithoutPath>
|
||||||
|
@ -618,10 +869,10 @@
|
||||||
<FileType>1</FileType>
|
<FileType>1</FileType>
|
||||||
<tvExp>0</tvExp>
|
<tvExp>0</tvExp>
|
||||||
<Focus>0</Focus>
|
<Focus>0</Focus>
|
||||||
<ColumnNumber>0</ColumnNumber>
|
<ColumnNumber>17</ColumnNumber>
|
||||||
<tvExpOptDlg>0</tvExpOptDlg>
|
<tvExpOptDlg>0</tvExpOptDlg>
|
||||||
<TopLine>1</TopLine>
|
<TopLine>23</TopLine>
|
||||||
<CurrentLine>4</CurrentLine>
|
<CurrentLine>26</CurrentLine>
|
||||||
<bDave2>0</bDave2>
|
<bDave2>0</bDave2>
|
||||||
<PathWithFileName>.\src\sensors.c</PathWithFileName>
|
<PathWithFileName>.\src\sensors.c</PathWithFileName>
|
||||||
<FilenameWithoutPath>sensors.c</FilenameWithoutPath>
|
<FilenameWithoutPath>sensors.c</FilenameWithoutPath>
|
||||||
|
@ -634,8 +885,8 @@
|
||||||
<Focus>0</Focus>
|
<Focus>0</Focus>
|
||||||
<ColumnNumber>31</ColumnNumber>
|
<ColumnNumber>31</ColumnNumber>
|
||||||
<tvExpOptDlg>0</tvExpOptDlg>
|
<tvExpOptDlg>0</tvExpOptDlg>
|
||||||
<TopLine>82</TopLine>
|
<TopLine>0</TopLine>
|
||||||
<CurrentLine>98</CurrentLine>
|
<CurrentLine>0</CurrentLine>
|
||||||
<bDave2>0</bDave2>
|
<bDave2>0</bDave2>
|
||||||
<PathWithFileName>.\src\serial.c</PathWithFileName>
|
<PathWithFileName>.\src\serial.c</PathWithFileName>
|
||||||
<FilenameWithoutPath>serial.c</FilenameWithoutPath>
|
<FilenameWithoutPath>serial.c</FilenameWithoutPath>
|
||||||
|
@ -648,8 +899,8 @@
|
||||||
<Focus>0</Focus>
|
<Focus>0</Focus>
|
||||||
<ColumnNumber>0</ColumnNumber>
|
<ColumnNumber>0</ColumnNumber>
|
||||||
<tvExpOptDlg>0</tvExpOptDlg>
|
<tvExpOptDlg>0</tvExpOptDlg>
|
||||||
<TopLine>31</TopLine>
|
<TopLine>55</TopLine>
|
||||||
<CurrentLine>48</CurrentLine>
|
<CurrentLine>66</CurrentLine>
|
||||||
<bDave2>0</bDave2>
|
<bDave2>0</bDave2>
|
||||||
<PathWithFileName>.\src\board.h</PathWithFileName>
|
<PathWithFileName>.\src\board.h</PathWithFileName>
|
||||||
<FilenameWithoutPath>board.h</FilenameWithoutPath>
|
<FilenameWithoutPath>board.h</FilenameWithoutPath>
|
||||||
|
@ -662,8 +913,8 @@
|
||||||
<Focus>0</Focus>
|
<Focus>0</Focus>
|
||||||
<ColumnNumber>0</ColumnNumber>
|
<ColumnNumber>0</ColumnNumber>
|
||||||
<tvExpOptDlg>0</tvExpOptDlg>
|
<tvExpOptDlg>0</tvExpOptDlg>
|
||||||
<TopLine>1</TopLine>
|
<TopLine>7</TopLine>
|
||||||
<CurrentLine>1</CurrentLine>
|
<CurrentLine>7</CurrentLine>
|
||||||
<bDave2>0</bDave2>
|
<bDave2>0</bDave2>
|
||||||
<PathWithFileName>.\src\mw.h</PathWithFileName>
|
<PathWithFileName>.\src\mw.h</PathWithFileName>
|
||||||
<FilenameWithoutPath>mw.h</FilenameWithoutPath>
|
<FilenameWithoutPath>mw.h</FilenameWithoutPath>
|
||||||
|
@ -725,8 +976,8 @@
|
||||||
<Focus>0</Focus>
|
<Focus>0</Focus>
|
||||||
<ColumnNumber>0</ColumnNumber>
|
<ColumnNumber>0</ColumnNumber>
|
||||||
<tvExpOptDlg>0</tvExpOptDlg>
|
<tvExpOptDlg>0</tvExpOptDlg>
|
||||||
<TopLine>67</TopLine>
|
<TopLine>0</TopLine>
|
||||||
<CurrentLine>84</CurrentLine>
|
<CurrentLine>0</CurrentLine>
|
||||||
<bDave2>0</bDave2>
|
<bDave2>0</bDave2>
|
||||||
<PathWithFileName>.\src\drv_adxl345.c</PathWithFileName>
|
<PathWithFileName>.\src\drv_adxl345.c</PathWithFileName>
|
||||||
<FilenameWithoutPath>drv_adxl345.c</FilenameWithoutPath>
|
<FilenameWithoutPath>drv_adxl345.c</FilenameWithoutPath>
|
||||||
|
@ -737,10 +988,10 @@
|
||||||
<FileType>1</FileType>
|
<FileType>1</FileType>
|
||||||
<tvExp>0</tvExp>
|
<tvExp>0</tvExp>
|
||||||
<Focus>0</Focus>
|
<Focus>0</Focus>
|
||||||
<ColumnNumber>0</ColumnNumber>
|
<ColumnNumber>15</ColumnNumber>
|
||||||
<tvExpOptDlg>0</tvExpOptDlg>
|
<tvExpOptDlg>0</tvExpOptDlg>
|
||||||
<TopLine>0</TopLine>
|
<TopLine>1</TopLine>
|
||||||
<CurrentLine>0</CurrentLine>
|
<CurrentLine>19</CurrentLine>
|
||||||
<bDave2>0</bDave2>
|
<bDave2>0</bDave2>
|
||||||
<PathWithFileName>.\src\drv_bmp085.c</PathWithFileName>
|
<PathWithFileName>.\src\drv_bmp085.c</PathWithFileName>
|
||||||
<FilenameWithoutPath>drv_bmp085.c</FilenameWithoutPath>
|
<FilenameWithoutPath>drv_bmp085.c</FilenameWithoutPath>
|
||||||
|
@ -753,8 +1004,8 @@
|
||||||
<Focus>0</Focus>
|
<Focus>0</Focus>
|
||||||
<ColumnNumber>21</ColumnNumber>
|
<ColumnNumber>21</ColumnNumber>
|
||||||
<tvExpOptDlg>0</tvExpOptDlg>
|
<tvExpOptDlg>0</tvExpOptDlg>
|
||||||
<TopLine>1</TopLine>
|
<TopLine>0</TopLine>
|
||||||
<CurrentLine>23</CurrentLine>
|
<CurrentLine>0</CurrentLine>
|
||||||
<bDave2>0</bDave2>
|
<bDave2>0</bDave2>
|
||||||
<PathWithFileName>.\src\drv_hmc5883l.c</PathWithFileName>
|
<PathWithFileName>.\src\drv_hmc5883l.c</PathWithFileName>
|
||||||
<FilenameWithoutPath>drv_hmc5883l.c</FilenameWithoutPath>
|
<FilenameWithoutPath>drv_hmc5883l.c</FilenameWithoutPath>
|
||||||
|
@ -779,10 +1030,10 @@
|
||||||
<FileType>1</FileType>
|
<FileType>1</FileType>
|
||||||
<tvExp>0</tvExp>
|
<tvExp>0</tvExp>
|
||||||
<Focus>0</Focus>
|
<Focus>0</Focus>
|
||||||
<ColumnNumber>0</ColumnNumber>
|
<ColumnNumber>26</ColumnNumber>
|
||||||
<tvExpOptDlg>0</tvExpOptDlg>
|
<tvExpOptDlg>0</tvExpOptDlg>
|
||||||
<TopLine>77</TopLine>
|
<TopLine>0</TopLine>
|
||||||
<CurrentLine>117</CurrentLine>
|
<CurrentLine>0</CurrentLine>
|
||||||
<bDave2>0</bDave2>
|
<bDave2>0</bDave2>
|
||||||
<PathWithFileName>.\src\drv_mpu3050.c</PathWithFileName>
|
<PathWithFileName>.\src\drv_mpu3050.c</PathWithFileName>
|
||||||
<FilenameWithoutPath>drv_mpu3050.c</FilenameWithoutPath>
|
<FilenameWithoutPath>drv_mpu3050.c</FilenameWithoutPath>
|
||||||
|
@ -793,10 +1044,10 @@
|
||||||
<FileType>1</FileType>
|
<FileType>1</FileType>
|
||||||
<tvExp>0</tvExp>
|
<tvExp>0</tvExp>
|
||||||
<Focus>0</Focus>
|
<Focus>0</Focus>
|
||||||
<ColumnNumber>6</ColumnNumber>
|
<ColumnNumber>0</ColumnNumber>
|
||||||
<tvExpOptDlg>0</tvExpOptDlg>
|
<tvExpOptDlg>0</tvExpOptDlg>
|
||||||
<TopLine>253</TopLine>
|
<TopLine>1</TopLine>
|
||||||
<CurrentLine>278</CurrentLine>
|
<CurrentLine>1</CurrentLine>
|
||||||
<bDave2>0</bDave2>
|
<bDave2>0</bDave2>
|
||||||
<PathWithFileName>.\src\drv_pwm.c</PathWithFileName>
|
<PathWithFileName>.\src\drv_pwm.c</PathWithFileName>
|
||||||
<FilenameWithoutPath>drv_pwm.c</FilenameWithoutPath>
|
<FilenameWithoutPath>drv_pwm.c</FilenameWithoutPath>
|
||||||
|
@ -809,8 +1060,8 @@
|
||||||
<Focus>0</Focus>
|
<Focus>0</Focus>
|
||||||
<ColumnNumber>0</ColumnNumber>
|
<ColumnNumber>0</ColumnNumber>
|
||||||
<tvExpOptDlg>0</tvExpOptDlg>
|
<tvExpOptDlg>0</tvExpOptDlg>
|
||||||
<TopLine>32</TopLine>
|
<TopLine>38</TopLine>
|
||||||
<CurrentLine>39</CurrentLine>
|
<CurrentLine>50</CurrentLine>
|
||||||
<bDave2>0</bDave2>
|
<bDave2>0</bDave2>
|
||||||
<PathWithFileName>.\src\drv_system.c</PathWithFileName>
|
<PathWithFileName>.\src\drv_system.c</PathWithFileName>
|
||||||
<FilenameWithoutPath>drv_system.c</FilenameWithoutPath>
|
<FilenameWithoutPath>drv_system.c</FilenameWithoutPath>
|
||||||
|
@ -845,18 +1096,46 @@
|
||||||
</File>
|
</File>
|
||||||
<File>
|
<File>
|
||||||
<GroupNumber>2</GroupNumber>
|
<GroupNumber>2</GroupNumber>
|
||||||
<FileNumber>23</FileNumber>
|
<FileNumber>0</FileNumber>
|
||||||
<FileType>1</FileType>
|
<FileType>1</FileType>
|
||||||
<tvExp>0</tvExp>
|
<tvExp>0</tvExp>
|
||||||
<Focus>0</Focus>
|
<Focus>0</Focus>
|
||||||
<ColumnNumber>0</ColumnNumber>
|
<ColumnNumber>0</ColumnNumber>
|
||||||
<tvExpOptDlg>0</tvExpOptDlg>
|
<tvExpOptDlg>0</tvExpOptDlg>
|
||||||
<TopLine>192</TopLine>
|
<TopLine>146</TopLine>
|
||||||
<CurrentLine>223</CurrentLine>
|
<CurrentLine>168</CurrentLine>
|
||||||
<bDave2>0</bDave2>
|
<bDave2>0</bDave2>
|
||||||
<PathWithFileName>.\src\drv_mpu6050.c</PathWithFileName>
|
<PathWithFileName>.\src\drv_mpu6050.c</PathWithFileName>
|
||||||
<FilenameWithoutPath>drv_mpu6050.c</FilenameWithoutPath>
|
<FilenameWithoutPath>drv_mpu6050.c</FilenameWithoutPath>
|
||||||
</File>
|
</File>
|
||||||
|
<File>
|
||||||
|
<GroupNumber>2</GroupNumber>
|
||||||
|
<FileNumber>0</FileNumber>
|
||||||
|
<FileType>1</FileType>
|
||||||
|
<tvExp>0</tvExp>
|
||||||
|
<Focus>0</Focus>
|
||||||
|
<ColumnNumber>0</ColumnNumber>
|
||||||
|
<tvExpOptDlg>0</tvExpOptDlg>
|
||||||
|
<TopLine>1</TopLine>
|
||||||
|
<CurrentLine>24</CurrentLine>
|
||||||
|
<bDave2>0</bDave2>
|
||||||
|
<PathWithFileName>.\src\drv_adc_fy90q.c</PathWithFileName>
|
||||||
|
<FilenameWithoutPath>drv_adc_fy90q.c</FilenameWithoutPath>
|
||||||
|
</File>
|
||||||
|
<File>
|
||||||
|
<GroupNumber>2</GroupNumber>
|
||||||
|
<FileNumber>0</FileNumber>
|
||||||
|
<FileType>1</FileType>
|
||||||
|
<tvExp>0</tvExp>
|
||||||
|
<Focus>0</Focus>
|
||||||
|
<ColumnNumber>0</ColumnNumber>
|
||||||
|
<tvExpOptDlg>0</tvExpOptDlg>
|
||||||
|
<TopLine>231</TopLine>
|
||||||
|
<CurrentLine>245</CurrentLine>
|
||||||
|
<bDave2>0</bDave2>
|
||||||
|
<PathWithFileName>.\src\drv_pwm_fy90q.c</PathWithFileName>
|
||||||
|
<FilenameWithoutPath>drv_pwm_fy90q.c</FilenameWithoutPath>
|
||||||
|
</File>
|
||||||
</Group>
|
</Group>
|
||||||
|
|
||||||
<Group>
|
<Group>
|
||||||
|
@ -912,10 +1191,10 @@
|
||||||
<FileType>1</FileType>
|
<FileType>1</FileType>
|
||||||
<tvExp>0</tvExp>
|
<tvExp>0</tvExp>
|
||||||
<Focus>0</Focus>
|
<Focus>0</Focus>
|
||||||
<ColumnNumber>0</ColumnNumber>
|
<ColumnNumber>19</ColumnNumber>
|
||||||
<tvExpOptDlg>0</tvExpOptDlg>
|
<tvExpOptDlg>0</tvExpOptDlg>
|
||||||
<TopLine>0</TopLine>
|
<TopLine>656</TopLine>
|
||||||
<CurrentLine>0</CurrentLine>
|
<CurrentLine>656</CurrentLine>
|
||||||
<bDave2>0</bDave2>
|
<bDave2>0</bDave2>
|
||||||
<PathWithFileName>.\lib\STM32F10x_StdPeriph_Driver\src\stm32f10x_adc.c</PathWithFileName>
|
<PathWithFileName>.\lib\STM32F10x_StdPeriph_Driver\src\stm32f10x_adc.c</PathWithFileName>
|
||||||
<FilenameWithoutPath>stm32f10x_adc.c</FilenameWithoutPath>
|
<FilenameWithoutPath>stm32f10x_adc.c</FilenameWithoutPath>
|
||||||
|
@ -1040,12 +1319,26 @@
|
||||||
<Focus>0</Focus>
|
<Focus>0</Focus>
|
||||||
<ColumnNumber>0</ColumnNumber>
|
<ColumnNumber>0</ColumnNumber>
|
||||||
<tvExpOptDlg>0</tvExpOptDlg>
|
<tvExpOptDlg>0</tvExpOptDlg>
|
||||||
<TopLine>133</TopLine>
|
<TopLine>145</TopLine>
|
||||||
<CurrentLine>133</CurrentLine>
|
<CurrentLine>166</CurrentLine>
|
||||||
<bDave2>0</bDave2>
|
<bDave2>0</bDave2>
|
||||||
<PathWithFileName>.\src\baseflight_startups\startup_stm32f10x_md.s</PathWithFileName>
|
<PathWithFileName>.\src\baseflight_startups\startup_stm32f10x_md.s</PathWithFileName>
|
||||||
<FilenameWithoutPath>startup_stm32f10x_md.s</FilenameWithoutPath>
|
<FilenameWithoutPath>startup_stm32f10x_md.s</FilenameWithoutPath>
|
||||||
</File>
|
</File>
|
||||||
|
<File>
|
||||||
|
<GroupNumber>3</GroupNumber>
|
||||||
|
<FileNumber>0</FileNumber>
|
||||||
|
<FileType>2</FileType>
|
||||||
|
<tvExp>0</tvExp>
|
||||||
|
<Focus>0</Focus>
|
||||||
|
<ColumnNumber>0</ColumnNumber>
|
||||||
|
<tvExpOptDlg>0</tvExpOptDlg>
|
||||||
|
<TopLine>125</TopLine>
|
||||||
|
<CurrentLine>133</CurrentLine>
|
||||||
|
<bDave2>0</bDave2>
|
||||||
|
<PathWithFileName>.\src\baseflight_startups\startup_stm32f10x_md_fy90q.s</PathWithFileName>
|
||||||
|
<FilenameWithoutPath>startup_stm32f10x_md_fy90q.s</FilenameWithoutPath>
|
||||||
|
</File>
|
||||||
</Group>
|
</Group>
|
||||||
|
|
||||||
</ProjectOpt>
|
</ProjectOpt>
|
||||||
|
|
1243
baseflight.uvproj
1243
baseflight.uvproj
File diff suppressed because it is too large
Load Diff
4184
obj/baseflight.hex
4184
obj/baseflight.hex
File diff suppressed because it is too large
Load Diff
File diff suppressed because it is too large
Load Diff
|
@ -0,0 +1,359 @@
|
||||||
|
;******************** (C) COPYRIGHT 2011 STMicroelectronics ********************
|
||||||
|
;* File Name : startup_stm32f10x_md.s
|
||||||
|
;* Author : MCD Application Team
|
||||||
|
;* Version : V3.5.0
|
||||||
|
;* Date : 11-March-2011
|
||||||
|
;* Description : STM32F10x Medium Density Devices vector table for MDK-ARM
|
||||||
|
;* toolchain.
|
||||||
|
;* This module performs:
|
||||||
|
;* - Set the initial SP
|
||||||
|
;* - Set the initial PC == Reset_Handler
|
||||||
|
;* - Set the vector table entries with the exceptions ISR address
|
||||||
|
;* - Configure the clock system
|
||||||
|
;* - Branches to __main in the C library (which eventually
|
||||||
|
;* calls main()).
|
||||||
|
;* After Reset the CortexM3 processor is in Thread mode,
|
||||||
|
;* priority is Privileged, and the Stack is set to Main.
|
||||||
|
;* <<< Use Configuration Wizard in Context Menu >>>
|
||||||
|
;*******************************************************************************
|
||||||
|
; THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
|
||||||
|
; WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME.
|
||||||
|
; AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT,
|
||||||
|
; INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE
|
||||||
|
; CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING
|
||||||
|
; INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
|
||||||
|
;*******************************************************************************
|
||||||
|
|
||||||
|
; Amount of memory (in bytes) allocated for Stack
|
||||||
|
; Tailor this value to your application needs
|
||||||
|
; <h> Stack Configuration
|
||||||
|
; <o> Stack Size (in Bytes) <0x0-0xFFFFFFFF:8>
|
||||||
|
; </h>
|
||||||
|
|
||||||
|
Stack_Size EQU 0x00001000
|
||||||
|
|
||||||
|
AREA STACK, NOINIT, READWRITE, ALIGN=3
|
||||||
|
Stack_Mem SPACE Stack_Size
|
||||||
|
__initial_sp
|
||||||
|
|
||||||
|
|
||||||
|
; <h> Heap Configuration
|
||||||
|
; <o> Heap Size (in Bytes) <0x0-0xFFFFFFFF:8>
|
||||||
|
; </h>
|
||||||
|
|
||||||
|
Heap_Size EQU 0x00000200
|
||||||
|
|
||||||
|
AREA HEAP, NOINIT, READWRITE, ALIGN=3
|
||||||
|
__heap_base
|
||||||
|
Heap_Mem SPACE Heap_Size
|
||||||
|
__heap_limit
|
||||||
|
|
||||||
|
PRESERVE8
|
||||||
|
THUMB
|
||||||
|
|
||||||
|
|
||||||
|
; Vector Table Mapped to Address 0 at Reset
|
||||||
|
AREA RESET, DATA, READONLY
|
||||||
|
EXPORT __Vectors
|
||||||
|
EXPORT __Vectors_End
|
||||||
|
EXPORT __Vectors_Size
|
||||||
|
|
||||||
|
__Vectors DCD __initial_sp ; Top of Stack
|
||||||
|
DCD Reset_Handler ; Reset Handler
|
||||||
|
DCD NMI_Handler ; NMI Handler
|
||||||
|
DCD HardFault_Handler ; Hard Fault Handler
|
||||||
|
DCD MemManage_Handler ; MPU Fault Handler
|
||||||
|
DCD BusFault_Handler ; Bus Fault Handler
|
||||||
|
DCD UsageFault_Handler ; Usage Fault Handler
|
||||||
|
DCD 0 ; Reserved
|
||||||
|
DCD 0 ; Reserved
|
||||||
|
DCD 0 ; Reserved
|
||||||
|
DCD 0 ; Reserved
|
||||||
|
DCD SVC_Handler ; SVCall Handler
|
||||||
|
DCD DebugMon_Handler ; Debug Monitor Handler
|
||||||
|
DCD 0 ; Reserved
|
||||||
|
DCD PendSV_Handler ; PendSV Handler
|
||||||
|
DCD SysTick_Handler ; SysTick Handler
|
||||||
|
|
||||||
|
; External Interrupts
|
||||||
|
DCD WWDG_IRQHandler ; Window Watchdog
|
||||||
|
DCD PVD_IRQHandler ; PVD through EXTI Line detect
|
||||||
|
DCD TAMPER_IRQHandler ; Tamper
|
||||||
|
DCD RTC_IRQHandler ; RTC
|
||||||
|
DCD FLASH_IRQHandler ; Flash
|
||||||
|
DCD RCC_IRQHandler ; RCC
|
||||||
|
DCD EXTI0_IRQHandler ; EXTI Line 0
|
||||||
|
DCD EXTI1_IRQHandler ; EXTI Line 1
|
||||||
|
DCD EXTI2_IRQHandler ; EXTI Line 2
|
||||||
|
DCD EXTI3_IRQHandler ; EXTI Line 3
|
||||||
|
DCD EXTI4_IRQHandler ; EXTI Line 4
|
||||||
|
DCD DMA1_Channel1_IRQHandler ; DMA1 Channel 1
|
||||||
|
DCD DMA1_Channel2_IRQHandler ; DMA1 Channel 2
|
||||||
|
DCD DMA1_Channel3_IRQHandler ; DMA1 Channel 3
|
||||||
|
DCD DMA1_Channel4_IRQHandler ; DMA1 Channel 4
|
||||||
|
DCD DMA1_Channel5_IRQHandler ; DMA1 Channel 5
|
||||||
|
DCD DMA1_Channel6_IRQHandler ; DMA1 Channel 6
|
||||||
|
DCD DMA1_Channel7_IRQHandler ; DMA1 Channel 7
|
||||||
|
DCD ADC1_2_IRQHandler ; ADC1_2
|
||||||
|
DCD USB_HP_CAN1_TX_IRQHandler ; USB High Priority or CAN1 TX
|
||||||
|
DCD USB_LP_CAN1_RX0_IRQHandler ; USB Low Priority or CAN1 RX0
|
||||||
|
DCD CAN1_RX1_IRQHandler ; CAN1 RX1
|
||||||
|
DCD CAN1_SCE_IRQHandler ; CAN1 SCE
|
||||||
|
DCD EXTI9_5_IRQHandler ; EXTI Line 9..5
|
||||||
|
DCD TIM1_BRK_IRQHandler ; TIM1 Break
|
||||||
|
DCD TIM1_UP_IRQHandler ; TIM1 Update
|
||||||
|
DCD TIM1_TRG_COM_IRQHandler ; TIM1 Trigger and Commutation
|
||||||
|
DCD TIM1_CC_IRQHandler ; TIM1 Capture Compare
|
||||||
|
DCD TIM2_IRQHandler ; TIM2
|
||||||
|
DCD TIM3_IRQHandler ; TIM3
|
||||||
|
DCD TIM4_IRQHandler ; TIM4
|
||||||
|
DCD I2C1_EV_IRQHandler ; I2C1 Event
|
||||||
|
DCD I2C1_ER_IRQHandler ; I2C1 Error
|
||||||
|
DCD I2C2_EV_IRQHandler ; I2C2 Event
|
||||||
|
DCD I2C2_ER_IRQHandler ; I2C2 Error
|
||||||
|
DCD SPI1_IRQHandler ; SPI1
|
||||||
|
DCD SPI2_IRQHandler ; SPI2
|
||||||
|
DCD USART1_IRQHandler ; USART1
|
||||||
|
DCD USART2_IRQHandler ; USART2
|
||||||
|
DCD USART3_IRQHandler ; USART3
|
||||||
|
DCD EXTI15_10_IRQHandler ; EXTI Line 15..10
|
||||||
|
DCD RTCAlarm_IRQHandler ; RTC Alarm through EXTI Line
|
||||||
|
DCD USBWakeUp_IRQHandler ; USB Wakeup from suspend
|
||||||
|
__Vectors_End
|
||||||
|
|
||||||
|
__Vectors_Size EQU __Vectors_End - __Vectors
|
||||||
|
|
||||||
|
AREA |.text|, CODE, READONLY
|
||||||
|
|
||||||
|
; Reset handler
|
||||||
|
Reset_Handler PROC
|
||||||
|
EXPORT Reset_Handler [WEAK]
|
||||||
|
IMPORT __main
|
||||||
|
IMPORT SystemInit
|
||||||
|
LDR R0, =0x20004FF0
|
||||||
|
LDR R1, =0xDEADBEEF
|
||||||
|
LDR R2, [R0, #0]
|
||||||
|
STR R0, [R0, #0] ; Invalidate
|
||||||
|
CMP R2, R1
|
||||||
|
BEQ Reboot_Loader
|
||||||
|
LDR R0, =SystemInit
|
||||||
|
BLX R0
|
||||||
|
LDR R0, =__main
|
||||||
|
BX R0
|
||||||
|
ENDP
|
||||||
|
|
||||||
|
RCC_APB2ENR EQU 0x40021018
|
||||||
|
GPIO_AFIO_MASK EQU 0x00000015
|
||||||
|
GPIOA_CRH EQU 0x40010804
|
||||||
|
GPIOA_BRR EQU 0x40010814
|
||||||
|
GPIOC_CRH EQU 0x40011004
|
||||||
|
GPIOC_BRR EQU 0x40011014
|
||||||
|
AFIO_MAPR EQU 0x40010004
|
||||||
|
|
||||||
|
Reboot_Loader PROC
|
||||||
|
EXPORT Reboot_Loader
|
||||||
|
|
||||||
|
; RCC Enable GPIOA+C+AFIO
|
||||||
|
LDR R6, =RCC_APB2ENR
|
||||||
|
LDR R0, =GPIO_AFIO_MASK
|
||||||
|
STR R0, [R6]
|
||||||
|
; MAPR pt1
|
||||||
|
LDR R0, =AFIO_MAPR
|
||||||
|
LDR R1, [R0]
|
||||||
|
BIC R1, R1, #0xF000000
|
||||||
|
STR R1, [R0]
|
||||||
|
; MAPR pt2
|
||||||
|
LSLS R1, R0, #9
|
||||||
|
STR R1, [R0]
|
||||||
|
; GPIO A BRR
|
||||||
|
LDR R4, =GPIOA_BRR
|
||||||
|
MOVS R0, #0x8000
|
||||||
|
STR R0, [R4]
|
||||||
|
; GPIO A CRL
|
||||||
|
LDR R1, =GPIOA_CRH
|
||||||
|
LDR R0, =0x34444444
|
||||||
|
STR R0, [R1]
|
||||||
|
; GPIO C BRR
|
||||||
|
LDR R4, =GPIOC_BRR
|
||||||
|
MOVS R0, #0x1000
|
||||||
|
STR R0, [R4]
|
||||||
|
; GPIO C CRL
|
||||||
|
LDR R1, =GPIOC_CRH
|
||||||
|
LDR R0, =0x44434444
|
||||||
|
STR R0, [R1]
|
||||||
|
; Reboot to ROM
|
||||||
|
LDR R0, =0x1FFFF000
|
||||||
|
LDR SP,[R0, #0]
|
||||||
|
LDR R0,[R0, #4]
|
||||||
|
BX R0
|
||||||
|
ENDP
|
||||||
|
|
||||||
|
; Dummy Exception Handlers (infinite loops which can be modified)
|
||||||
|
|
||||||
|
NMI_Handler PROC
|
||||||
|
EXPORT NMI_Handler [WEAK]
|
||||||
|
B .
|
||||||
|
ENDP
|
||||||
|
HardFault_Handler\
|
||||||
|
PROC
|
||||||
|
EXPORT HardFault_Handler [WEAK]
|
||||||
|
B .
|
||||||
|
ENDP
|
||||||
|
MemManage_Handler\
|
||||||
|
PROC
|
||||||
|
EXPORT MemManage_Handler [WEAK]
|
||||||
|
B .
|
||||||
|
ENDP
|
||||||
|
BusFault_Handler\
|
||||||
|
PROC
|
||||||
|
EXPORT BusFault_Handler [WEAK]
|
||||||
|
B .
|
||||||
|
ENDP
|
||||||
|
UsageFault_Handler\
|
||||||
|
PROC
|
||||||
|
EXPORT UsageFault_Handler [WEAK]
|
||||||
|
B .
|
||||||
|
ENDP
|
||||||
|
SVC_Handler PROC
|
||||||
|
EXPORT SVC_Handler [WEAK]
|
||||||
|
B .
|
||||||
|
ENDP
|
||||||
|
DebugMon_Handler\
|
||||||
|
PROC
|
||||||
|
EXPORT DebugMon_Handler [WEAK]
|
||||||
|
B .
|
||||||
|
ENDP
|
||||||
|
PendSV_Handler PROC
|
||||||
|
EXPORT PendSV_Handler [WEAK]
|
||||||
|
B .
|
||||||
|
ENDP
|
||||||
|
SysTick_Handler PROC
|
||||||
|
EXPORT SysTick_Handler [WEAK]
|
||||||
|
B .
|
||||||
|
ENDP
|
||||||
|
|
||||||
|
Default_Handler PROC
|
||||||
|
|
||||||
|
EXPORT WWDG_IRQHandler [WEAK]
|
||||||
|
EXPORT PVD_IRQHandler [WEAK]
|
||||||
|
EXPORT TAMPER_IRQHandler [WEAK]
|
||||||
|
EXPORT RTC_IRQHandler [WEAK]
|
||||||
|
EXPORT FLASH_IRQHandler [WEAK]
|
||||||
|
EXPORT RCC_IRQHandler [WEAK]
|
||||||
|
EXPORT EXTI0_IRQHandler [WEAK]
|
||||||
|
EXPORT EXTI1_IRQHandler [WEAK]
|
||||||
|
EXPORT EXTI2_IRQHandler [WEAK]
|
||||||
|
EXPORT EXTI3_IRQHandler [WEAK]
|
||||||
|
EXPORT EXTI4_IRQHandler [WEAK]
|
||||||
|
EXPORT DMA1_Channel1_IRQHandler [WEAK]
|
||||||
|
EXPORT DMA1_Channel2_IRQHandler [WEAK]
|
||||||
|
EXPORT DMA1_Channel3_IRQHandler [WEAK]
|
||||||
|
EXPORT DMA1_Channel4_IRQHandler [WEAK]
|
||||||
|
EXPORT DMA1_Channel5_IRQHandler [WEAK]
|
||||||
|
EXPORT DMA1_Channel6_IRQHandler [WEAK]
|
||||||
|
EXPORT DMA1_Channel7_IRQHandler [WEAK]
|
||||||
|
EXPORT ADC1_2_IRQHandler [WEAK]
|
||||||
|
EXPORT USB_HP_CAN1_TX_IRQHandler [WEAK]
|
||||||
|
EXPORT USB_LP_CAN1_RX0_IRQHandler [WEAK]
|
||||||
|
EXPORT CAN1_RX1_IRQHandler [WEAK]
|
||||||
|
EXPORT CAN1_SCE_IRQHandler [WEAK]
|
||||||
|
EXPORT EXTI9_5_IRQHandler [WEAK]
|
||||||
|
EXPORT TIM1_BRK_IRQHandler [WEAK]
|
||||||
|
EXPORT TIM1_UP_IRQHandler [WEAK]
|
||||||
|
EXPORT TIM1_TRG_COM_IRQHandler [WEAK]
|
||||||
|
EXPORT TIM1_CC_IRQHandler [WEAK]
|
||||||
|
EXPORT TIM2_IRQHandler [WEAK]
|
||||||
|
EXPORT TIM3_IRQHandler [WEAK]
|
||||||
|
EXPORT TIM4_IRQHandler [WEAK]
|
||||||
|
EXPORT I2C1_EV_IRQHandler [WEAK]
|
||||||
|
EXPORT I2C1_ER_IRQHandler [WEAK]
|
||||||
|
EXPORT I2C2_EV_IRQHandler [WEAK]
|
||||||
|
EXPORT I2C2_ER_IRQHandler [WEAK]
|
||||||
|
EXPORT SPI1_IRQHandler [WEAK]
|
||||||
|
EXPORT SPI2_IRQHandler [WEAK]
|
||||||
|
EXPORT USART1_IRQHandler [WEAK]
|
||||||
|
EXPORT USART2_IRQHandler [WEAK]
|
||||||
|
EXPORT USART3_IRQHandler [WEAK]
|
||||||
|
EXPORT EXTI15_10_IRQHandler [WEAK]
|
||||||
|
EXPORT RTCAlarm_IRQHandler [WEAK]
|
||||||
|
EXPORT USBWakeUp_IRQHandler [WEAK]
|
||||||
|
|
||||||
|
WWDG_IRQHandler
|
||||||
|
PVD_IRQHandler
|
||||||
|
TAMPER_IRQHandler
|
||||||
|
RTC_IRQHandler
|
||||||
|
FLASH_IRQHandler
|
||||||
|
RCC_IRQHandler
|
||||||
|
EXTI0_IRQHandler
|
||||||
|
EXTI1_IRQHandler
|
||||||
|
EXTI2_IRQHandler
|
||||||
|
EXTI3_IRQHandler
|
||||||
|
EXTI4_IRQHandler
|
||||||
|
DMA1_Channel1_IRQHandler
|
||||||
|
DMA1_Channel2_IRQHandler
|
||||||
|
DMA1_Channel3_IRQHandler
|
||||||
|
DMA1_Channel4_IRQHandler
|
||||||
|
DMA1_Channel5_IRQHandler
|
||||||
|
DMA1_Channel6_IRQHandler
|
||||||
|
DMA1_Channel7_IRQHandler
|
||||||
|
ADC1_2_IRQHandler
|
||||||
|
USB_HP_CAN1_TX_IRQHandler
|
||||||
|
USB_LP_CAN1_RX0_IRQHandler
|
||||||
|
CAN1_RX1_IRQHandler
|
||||||
|
CAN1_SCE_IRQHandler
|
||||||
|
EXTI9_5_IRQHandler
|
||||||
|
TIM1_BRK_IRQHandler
|
||||||
|
TIM1_UP_IRQHandler
|
||||||
|
TIM1_TRG_COM_IRQHandler
|
||||||
|
TIM1_CC_IRQHandler
|
||||||
|
TIM2_IRQHandler
|
||||||
|
TIM3_IRQHandler
|
||||||
|
TIM4_IRQHandler
|
||||||
|
I2C1_EV_IRQHandler
|
||||||
|
I2C1_ER_IRQHandler
|
||||||
|
I2C2_EV_IRQHandler
|
||||||
|
I2C2_ER_IRQHandler
|
||||||
|
SPI1_IRQHandler
|
||||||
|
SPI2_IRQHandler
|
||||||
|
USART1_IRQHandler
|
||||||
|
USART2_IRQHandler
|
||||||
|
USART3_IRQHandler
|
||||||
|
EXTI15_10_IRQHandler
|
||||||
|
RTCAlarm_IRQHandler
|
||||||
|
USBWakeUp_IRQHandler
|
||||||
|
|
||||||
|
B .
|
||||||
|
|
||||||
|
ENDP
|
||||||
|
|
||||||
|
ALIGN
|
||||||
|
|
||||||
|
;*******************************************************************************
|
||||||
|
; User Stack and Heap initialization
|
||||||
|
;*******************************************************************************
|
||||||
|
IF :DEF:__MICROLIB
|
||||||
|
|
||||||
|
EXPORT __initial_sp
|
||||||
|
EXPORT __heap_base
|
||||||
|
EXPORT __heap_limit
|
||||||
|
|
||||||
|
ELSE
|
||||||
|
|
||||||
|
IMPORT __use_two_region_memory
|
||||||
|
EXPORT __user_initial_stackheap
|
||||||
|
|
||||||
|
__user_initial_stackheap
|
||||||
|
|
||||||
|
LDR R0, = Heap_Mem
|
||||||
|
LDR R1, =(Stack_Mem + Stack_Size)
|
||||||
|
LDR R2, = (Heap_Mem + Heap_Size)
|
||||||
|
LDR R3, = Stack_Mem
|
||||||
|
BX LR
|
||||||
|
|
||||||
|
ALIGN
|
||||||
|
|
||||||
|
ENDIF
|
||||||
|
|
||||||
|
END
|
||||||
|
|
||||||
|
;******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE*****
|
42
src/board.h
42
src/board.h
|
@ -55,7 +55,20 @@ typedef struct sensor_t
|
||||||
#define digitalLo(p, i) { p->BRR = i; }
|
#define digitalLo(p, i) { p->BRR = i; }
|
||||||
#define digitalToggle(p, i) { p->ODR ^= i; }
|
#define digitalToggle(p, i) { p->ODR ^= i; }
|
||||||
|
|
||||||
// Hardware GPIO
|
// Hardware definitions and GPIO
|
||||||
|
|
||||||
|
#ifdef FY90Q
|
||||||
|
// FY90Q
|
||||||
|
#define LED0_GPIO GPIOC
|
||||||
|
#define LED0_PIN GPIO_Pin_12
|
||||||
|
#define LED1_GPIO GPIOA
|
||||||
|
#define LED1_PIN GPIO_Pin_15
|
||||||
|
|
||||||
|
#define GYRO
|
||||||
|
#define ACC
|
||||||
|
|
||||||
|
#else
|
||||||
|
// Afroflight32
|
||||||
#define LED0_GPIO GPIOB
|
#define LED0_GPIO GPIOB
|
||||||
#define LED0_PIN GPIO_Pin_3
|
#define LED0_PIN GPIO_Pin_3
|
||||||
#define LED1_GPIO GPIOB
|
#define LED1_GPIO GPIOB
|
||||||
|
@ -65,6 +78,14 @@ typedef struct sensor_t
|
||||||
#define BARO_GPIO GPIOC
|
#define BARO_GPIO GPIOC
|
||||||
#define BARO_PIN GPIO_Pin_13
|
#define BARO_PIN GPIO_Pin_13
|
||||||
|
|
||||||
|
#define GYRO
|
||||||
|
#define ACC
|
||||||
|
#define MAG
|
||||||
|
#define BARO
|
||||||
|
#define LEDRING
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
||||||
// Helpful macros
|
// Helpful macros
|
||||||
#define LED0_TOGGLE digitalToggle(LED0_GPIO, LED0_PIN);
|
#define LED0_TOGGLE digitalToggle(LED0_GPIO, LED0_PIN);
|
||||||
#define LED0_OFF digitalHi(LED0_GPIO, LED0_PIN);
|
#define LED0_OFF digitalHi(LED0_GPIO, LED0_PIN);
|
||||||
|
@ -74,13 +95,26 @@ typedef struct sensor_t
|
||||||
#define LED1_OFF digitalHi(LED1_GPIO, LED1_PIN);
|
#define LED1_OFF digitalHi(LED1_GPIO, LED1_PIN);
|
||||||
#define LED1_ON digitalLo(LED1_GPIO, LED1_PIN);
|
#define LED1_ON digitalLo(LED1_GPIO, LED1_PIN);
|
||||||
|
|
||||||
|
#ifdef BEEP_GPIO
|
||||||
#define BEEP_TOGGLE digitalToggle(BEEP_GPIO, BEEP_PIN);
|
#define BEEP_TOGGLE digitalToggle(BEEP_GPIO, BEEP_PIN);
|
||||||
#define BEEP_OFF digitalHi(BEEP_GPIO, BEEP_PIN);
|
#define BEEP_OFF digitalHi(BEEP_GPIO, BEEP_PIN);
|
||||||
#define BEEP_ON digitalLo(BEEP_GPIO, BEEP_PIN);
|
#define BEEP_ON digitalLo(BEEP_GPIO, BEEP_PIN);
|
||||||
|
#else
|
||||||
|
#define BEEP_TOGGLE ;
|
||||||
|
#define BEEP_OFF ;
|
||||||
|
#define BEEP_ON ;
|
||||||
|
#endif
|
||||||
|
|
||||||
#define BARO_OFF digitalLo(BARO_GPIO, BARO_PIN);
|
#ifdef FY90Q
|
||||||
#define BARO_ON digitalHi(BARO_GPIO, BARO_PIN);
|
// FY90Q
|
||||||
|
#include "drv_system.h" // timers, delays, etc
|
||||||
|
#include "drv_adc.h"
|
||||||
|
#include "drv_i2c.h"
|
||||||
|
#include "drv_pwm.h"
|
||||||
|
#include "drv_uart.h"
|
||||||
|
|
||||||
|
#else
|
||||||
|
// AfroFlight32
|
||||||
#include "drv_system.h" // timers, delays, etc
|
#include "drv_system.h" // timers, delays, etc
|
||||||
#include "drv_adc.h"
|
#include "drv_adc.h"
|
||||||
#include "drv_adxl345.h"
|
#include "drv_adxl345.h"
|
||||||
|
@ -92,3 +126,5 @@ typedef struct sensor_t
|
||||||
#include "drv_mpu6050.h"
|
#include "drv_mpu6050.h"
|
||||||
#include "drv_pwm.h"
|
#include "drv_pwm.h"
|
||||||
#include "drv_uart.h"
|
#include "drv_uart.h"
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
|
@ -2,3 +2,6 @@
|
||||||
|
|
||||||
void adcInit(void);
|
void adcInit(void);
|
||||||
uint16_t adcGetBattery(void);
|
uint16_t adcGetBattery(void);
|
||||||
|
#ifdef FY90Q
|
||||||
|
void adcSensorInit(sensor_t *acc, sensor_t *gyro);
|
||||||
|
#endif
|
||||||
|
|
|
@ -0,0 +1,130 @@
|
||||||
|
#include "board.h"
|
||||||
|
|
||||||
|
#define ADC_CHANNELS 10
|
||||||
|
|
||||||
|
volatile uint16_t adcData[ADC_CHANNELS] = { 0, };
|
||||||
|
extern uint16_t acc_1G;
|
||||||
|
|
||||||
|
static void adcAccRead(int16_t *accelData);
|
||||||
|
static void adcAccAlign(int16_t *accelData);
|
||||||
|
static void adcGyroRead(int16_t *gyroData);
|
||||||
|
static void adcGyroAlign(int16_t *gyroData);
|
||||||
|
static void adcDummyInit(void);
|
||||||
|
|
||||||
|
void adcSensorInit(sensor_t *acc, sensor_t *gyro)
|
||||||
|
{
|
||||||
|
acc->init = adcDummyInit;
|
||||||
|
acc->read = adcAccRead;
|
||||||
|
acc->align = adcAccAlign;
|
||||||
|
|
||||||
|
gyro->init = adcDummyInit;
|
||||||
|
gyro->read = adcGyroRead;
|
||||||
|
gyro->align = adcGyroAlign;
|
||||||
|
|
||||||
|
acc_1G = 376;
|
||||||
|
}
|
||||||
|
|
||||||
|
void adcCalibrateADC(ADC_TypeDef *ADCx, int n)
|
||||||
|
{
|
||||||
|
while (n > 0) {
|
||||||
|
delay(5);
|
||||||
|
// Enable ADC reset calibration register
|
||||||
|
ADC_ResetCalibration(ADCx);
|
||||||
|
// Check the end of ADC reset calibration register
|
||||||
|
while(ADC_GetResetCalibrationStatus(ADCx));
|
||||||
|
// Start ADC calibration
|
||||||
|
ADC_StartCalibration(ADCx);
|
||||||
|
// Check the end of ADC calibration
|
||||||
|
while(ADC_GetCalibrationStatus(ADCx));
|
||||||
|
n--;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void adcInit(void)
|
||||||
|
{
|
||||||
|
ADC_InitTypeDef ADC_InitStructure;
|
||||||
|
DMA_InitTypeDef DMA_InitStructure;
|
||||||
|
|
||||||
|
// ADC assumes all the GPIO was already placed in 'AIN' mode
|
||||||
|
DMA_DeInit(DMA1_Channel1);
|
||||||
|
DMA_InitStructure.DMA_PeripheralBaseAddr = (uint32_t)&ADC1->DR;
|
||||||
|
DMA_InitStructure.DMA_MemoryBaseAddr = (uint32_t)&adcData;
|
||||||
|
DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralSRC;
|
||||||
|
DMA_InitStructure.DMA_BufferSize = ADC_CHANNELS;
|
||||||
|
DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable;
|
||||||
|
DMA_InitStructure.DMA_MemoryInc = DMA_MemoryInc_Enable;
|
||||||
|
DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_HalfWord;
|
||||||
|
DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_HalfWord;
|
||||||
|
DMA_InitStructure.DMA_Mode = DMA_Mode_Circular;
|
||||||
|
DMA_InitStructure.DMA_Priority = DMA_Priority_High;
|
||||||
|
DMA_InitStructure.DMA_M2M = DMA_M2M_Disable;
|
||||||
|
DMA_Init(DMA1_Channel1, &DMA_InitStructure);
|
||||||
|
/* Enable DMA1 channel1 */
|
||||||
|
DMA_Cmd(DMA1_Channel1, ENABLE);
|
||||||
|
|
||||||
|
ADC_InitStructure.ADC_Mode = ADC_Mode_Independent;
|
||||||
|
ADC_InitStructure.ADC_ScanConvMode = ENABLE;
|
||||||
|
ADC_InitStructure.ADC_ContinuousConvMode = ENABLE;
|
||||||
|
ADC_InitStructure.ADC_ExternalTrigConv = ADC_ExternalTrigConv_None;
|
||||||
|
ADC_InitStructure.ADC_DataAlign = ADC_DataAlign_Right;
|
||||||
|
ADC_InitStructure.ADC_NbrOfChannel = ADC_CHANNELS;
|
||||||
|
ADC_Init(ADC1, &ADC_InitStructure);
|
||||||
|
|
||||||
|
ADC_RegularChannelConfig(ADC1, ADC_Channel_10, 1, ADC_SampleTime_28Cycles5); // GY_X
|
||||||
|
ADC_RegularChannelConfig(ADC1, ADC_Channel_11, 2, ADC_SampleTime_28Cycles5); // GY_Y
|
||||||
|
ADC_RegularChannelConfig(ADC1, ADC_Channel_12, 3, ADC_SampleTime_28Cycles5); // GY_Z
|
||||||
|
|
||||||
|
ADC_RegularChannelConfig(ADC1, ADC_Channel_13, 4, ADC_SampleTime_28Cycles5); // ACC_X
|
||||||
|
ADC_RegularChannelConfig(ADC1, ADC_Channel_14, 5, ADC_SampleTime_28Cycles5); // ACC_Y
|
||||||
|
ADC_RegularChannelConfig(ADC1, ADC_Channel_15, 6, ADC_SampleTime_28Cycles5); // ACC_Z
|
||||||
|
|
||||||
|
ADC_RegularChannelConfig(ADC1, ADC_Channel_5, 7, ADC_SampleTime_28Cycles5); // POT_ELE
|
||||||
|
ADC_RegularChannelConfig(ADC1, ADC_Channel_6, 8, ADC_SampleTime_28Cycles5); // POT_AIL
|
||||||
|
ADC_RegularChannelConfig(ADC1, ADC_Channel_7, 9, ADC_SampleTime_28Cycles5); // POT_RUD
|
||||||
|
|
||||||
|
ADC_RegularChannelConfig(ADC1, ADC_Channel_5, 10, ADC_SampleTime_28Cycles5); // Power Monitor??
|
||||||
|
|
||||||
|
ADC_DMACmd(ADC1, ENABLE);
|
||||||
|
|
||||||
|
ADC_Cmd(ADC1, ENABLE);
|
||||||
|
|
||||||
|
// Calibrate ADC
|
||||||
|
adcCalibrateADC(ADC1, 2);
|
||||||
|
|
||||||
|
// Fire off ADC
|
||||||
|
ADC_SoftwareStartConvCmd(ADC1, ENABLE);
|
||||||
|
}
|
||||||
|
|
||||||
|
static void adcAccRead(int16_t *accelData)
|
||||||
|
{
|
||||||
|
accelData[0] = adcData[3];
|
||||||
|
accelData[1] = adcData[4];
|
||||||
|
accelData[2] = adcData[5];
|
||||||
|
}
|
||||||
|
|
||||||
|
static void adcAccAlign(int16_t *accelData)
|
||||||
|
{
|
||||||
|
// align OK
|
||||||
|
}
|
||||||
|
|
||||||
|
static void adcGyroRead(int16_t *gyroData)
|
||||||
|
{
|
||||||
|
gyroData[0] = adcData[0] * 2;
|
||||||
|
gyroData[1] = adcData[1] * 2;
|
||||||
|
gyroData[2] = adcData[2] * 2;
|
||||||
|
}
|
||||||
|
|
||||||
|
static void adcGyroAlign(int16_t *gyroData)
|
||||||
|
{
|
||||||
|
// align OK
|
||||||
|
}
|
||||||
|
|
||||||
|
static void adcDummyInit(void)
|
||||||
|
{
|
||||||
|
// nothing to init here
|
||||||
|
}
|
||||||
|
|
||||||
|
uint16_t adcGetBattery(void)
|
||||||
|
{
|
||||||
|
return adcData[9];
|
||||||
|
}
|
|
@ -1,9 +1,11 @@
|
||||||
#include "board.h"
|
#include "board.h"
|
||||||
|
|
||||||
// BMP085, Standard address 0x77
|
// BMP085, Standard address 0x77
|
||||||
|
|
||||||
static bool convDone = false;
|
static bool convDone = false;
|
||||||
|
|
||||||
|
#define BARO_OFF digitalLo(BARO_GPIO, BARO_PIN);
|
||||||
|
#define BARO_ON digitalHi(BARO_GPIO, BARO_PIN);
|
||||||
|
|
||||||
// EXTI14 for BMP085 End of Conversion Interrupt
|
// EXTI14 for BMP085 End of Conversion Interrupt
|
||||||
void EXTI15_10_IRQHandler(void)
|
void EXTI15_10_IRQHandler(void)
|
||||||
{
|
{
|
||||||
|
|
|
@ -0,0 +1,328 @@
|
||||||
|
#include "board.h"
|
||||||
|
|
||||||
|
#define PULSE_1MS (1000) // 1ms pulse width
|
||||||
|
// #define PULSE_PERIOD (2500) // pulse period (400Hz)
|
||||||
|
// #define PULSE_PERIOD_SERVO_DIGITAL (5000) // pulse period for digital servo (200Hz)
|
||||||
|
// #define PULSE_PERIOD_SERVO_ANALOG (20000) // pulse period for analog servo (50Hz)
|
||||||
|
|
||||||
|
// Forward declaration
|
||||||
|
static void pwmIRQHandler(TIM_TypeDef *tim);
|
||||||
|
static void ppmIRQHandler(TIM_TypeDef *tim);
|
||||||
|
|
||||||
|
// local vars
|
||||||
|
static struct TIM_Channel {
|
||||||
|
TIM_TypeDef *tim;
|
||||||
|
uint16_t channel;
|
||||||
|
uint16_t cc;
|
||||||
|
} Channels[] = {
|
||||||
|
{ TIM2, TIM_Channel_1, TIM_IT_CC1 },
|
||||||
|
{ TIM2, TIM_Channel_2, TIM_IT_CC2 },
|
||||||
|
{ TIM2, TIM_Channel_3, TIM_IT_CC3 },
|
||||||
|
{ TIM2, TIM_Channel_4, TIM_IT_CC4 },
|
||||||
|
{ TIM3, TIM_Channel_1, TIM_IT_CC1 },
|
||||||
|
{ TIM3, TIM_Channel_2, TIM_IT_CC2 },
|
||||||
|
{ TIM3, TIM_Channel_3, TIM_IT_CC3 },
|
||||||
|
{ TIM3, TIM_Channel_4, TIM_IT_CC4 },
|
||||||
|
};
|
||||||
|
|
||||||
|
static volatile uint16_t *OutputChannels[] = {
|
||||||
|
&(TIM4->CCR1),
|
||||||
|
&(TIM4->CCR2),
|
||||||
|
&(TIM4->CCR3),
|
||||||
|
&(TIM4->CCR4),
|
||||||
|
// Extended use during CPPM input (TODO)
|
||||||
|
&(TIM3->CCR1),
|
||||||
|
&(TIM3->CCR2),
|
||||||
|
&(TIM3->CCR3),
|
||||||
|
&(TIM3->CCR4),
|
||||||
|
};
|
||||||
|
|
||||||
|
static struct PWM_State {
|
||||||
|
uint8_t state;
|
||||||
|
uint16_t rise;
|
||||||
|
uint16_t fall;
|
||||||
|
uint16_t capture;
|
||||||
|
} Inputs[8] = { { 0, } };
|
||||||
|
|
||||||
|
static TIM_ICInitTypeDef TIM_ICInitStructure = { 0, };
|
||||||
|
static bool usePPMFlag = false;
|
||||||
|
static uint8_t numOutputChannels = 0;
|
||||||
|
static volatile bool rcActive = false;
|
||||||
|
|
||||||
|
void TIM2_IRQHandler(void)
|
||||||
|
{
|
||||||
|
if (usePPMFlag)
|
||||||
|
ppmIRQHandler(TIM2);
|
||||||
|
else
|
||||||
|
pwmIRQHandler(TIM2);
|
||||||
|
}
|
||||||
|
|
||||||
|
static void ppmIRQHandler(TIM_TypeDef *tim)
|
||||||
|
{
|
||||||
|
uint16_t diff;
|
||||||
|
static uint16_t now;
|
||||||
|
static uint16_t last = 0;
|
||||||
|
static uint8_t chan = 0;
|
||||||
|
|
||||||
|
if (TIM_GetITStatus(tim, TIM_IT_CC1) == SET) {
|
||||||
|
last = now;
|
||||||
|
now = TIM_GetCapture1(tim);
|
||||||
|
rcActive = true;
|
||||||
|
}
|
||||||
|
|
||||||
|
TIM_ClearITPendingBit(tim, TIM_IT_CC1);
|
||||||
|
|
||||||
|
if (now > last) {
|
||||||
|
diff = (now - last);
|
||||||
|
} else {
|
||||||
|
diff = ((0xFFFF - last) + now);
|
||||||
|
}
|
||||||
|
|
||||||
|
if (diff > 4000) {
|
||||||
|
chan = 0;
|
||||||
|
} else {
|
||||||
|
if (diff > 750 && diff < 2250 && chan < 8) { // 750 to 2250 ms is our 'valid' channel range
|
||||||
|
Inputs[chan].capture = diff;
|
||||||
|
}
|
||||||
|
chan++;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
static void pwmIRQHandler(TIM_TypeDef *tim)
|
||||||
|
{
|
||||||
|
uint8_t i;
|
||||||
|
uint16_t val = 0;
|
||||||
|
|
||||||
|
for (i = 0; i < 8; i++) {
|
||||||
|
struct TIM_Channel channel = Channels[i];
|
||||||
|
struct PWM_State *state = &Inputs[i];
|
||||||
|
|
||||||
|
if (channel.tim == tim && (TIM_GetITStatus(tim, channel.cc) == SET)) {
|
||||||
|
TIM_ClearITPendingBit(channel.tim, channel.cc);
|
||||||
|
if (i == 0)
|
||||||
|
rcActive = true;
|
||||||
|
|
||||||
|
switch (channel.channel) {
|
||||||
|
case TIM_Channel_1:
|
||||||
|
val = TIM_GetCapture1(channel.tim);
|
||||||
|
break;
|
||||||
|
case TIM_Channel_2:
|
||||||
|
val = TIM_GetCapture2(channel.tim);
|
||||||
|
break;
|
||||||
|
case TIM_Channel_3:
|
||||||
|
val = TIM_GetCapture3(channel.tim);
|
||||||
|
break;
|
||||||
|
case TIM_Channel_4:
|
||||||
|
val = TIM_GetCapture4(channel.tim);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (state->state == 0)
|
||||||
|
state->rise = val;
|
||||||
|
else
|
||||||
|
state->fall = val;
|
||||||
|
|
||||||
|
if (state->state == 0) {
|
||||||
|
// switch states
|
||||||
|
state->state = 1;
|
||||||
|
|
||||||
|
TIM_ICInitStructure.TIM_ICPolarity = TIM_ICPolarity_Falling;
|
||||||
|
TIM_ICInitStructure.TIM_Channel = channel.channel;
|
||||||
|
TIM_ICInit(channel.tim, &TIM_ICInitStructure);
|
||||||
|
} else {
|
||||||
|
// compute capture
|
||||||
|
if (state->fall > state->rise)
|
||||||
|
state->capture = (state->fall - state->rise);
|
||||||
|
else
|
||||||
|
state->capture = ((0xffff - state->rise) + state->fall);
|
||||||
|
|
||||||
|
// switch state
|
||||||
|
state->state = 0;
|
||||||
|
|
||||||
|
TIM_ICInitStructure.TIM_ICPolarity = TIM_ICPolarity_Rising;
|
||||||
|
TIM_ICInitStructure.TIM_Channel = channel.channel;
|
||||||
|
TIM_ICInit(channel.tim, &TIM_ICInitStructure);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
static void pwmInitializeInput(bool usePPM)
|
||||||
|
{
|
||||||
|
GPIO_InitTypeDef GPIO_InitStructure = { 0, };
|
||||||
|
TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure = { 0, };
|
||||||
|
NVIC_InitTypeDef NVIC_InitStructure = { 0, };
|
||||||
|
uint8_t i;
|
||||||
|
|
||||||
|
// Input pins
|
||||||
|
if (usePPM) {
|
||||||
|
// Configure TIM2_CH1 for PPM input
|
||||||
|
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_0;
|
||||||
|
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IPD;
|
||||||
|
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
|
||||||
|
GPIO_Init(GPIOA, &GPIO_InitStructure);
|
||||||
|
|
||||||
|
// Input timer on TIM2 only for PPM
|
||||||
|
NVIC_InitStructure.NVIC_IRQChannel = TIM2_IRQn;
|
||||||
|
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 0;
|
||||||
|
NVIC_InitStructure.NVIC_IRQChannelSubPriority = 1;
|
||||||
|
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
|
||||||
|
NVIC_Init(&NVIC_InitStructure);
|
||||||
|
|
||||||
|
// TIM2 timebase
|
||||||
|
TIM_TimeBaseStructInit(&TIM_TimeBaseStructure);
|
||||||
|
TIM_TimeBaseStructure.TIM_Prescaler = (72 - 1);
|
||||||
|
TIM_TimeBaseStructure.TIM_Period = 0xffff;
|
||||||
|
TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up;
|
||||||
|
TIM_TimeBaseInit(TIM2, &TIM_TimeBaseStructure);
|
||||||
|
|
||||||
|
// Input capture on TIM2_CH1 for PPM
|
||||||
|
TIM_ICInitStructure.TIM_ICPolarity = TIM_ICPolarity_Rising;
|
||||||
|
TIM_ICInitStructure.TIM_ICSelection = TIM_ICSelection_DirectTI;
|
||||||
|
TIM_ICInitStructure.TIM_ICPrescaler = TIM_ICPSC_DIV1;
|
||||||
|
TIM_ICInitStructure.TIM_ICFilter = 0x0;
|
||||||
|
TIM_ICInitStructure.TIM_Channel = TIM_Channel_1;
|
||||||
|
TIM_ICInit(TIM2, &TIM_ICInitStructure);
|
||||||
|
|
||||||
|
// TIM2_CH1 capture compare interrupt enable
|
||||||
|
TIM_ITConfig(TIM2, TIM_IT_CC1, ENABLE);
|
||||||
|
TIM_Cmd(TIM2, ENABLE);
|
||||||
|
|
||||||
|
// configure number of PWM outputs, in PPM mode, we use bottom 4 channels more more motors
|
||||||
|
numOutputChannels = 10;
|
||||||
|
} else {
|
||||||
|
// Configure TIM2 all 4 channels
|
||||||
|
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_0 | GPIO_Pin_1 | GPIO_Pin_2 | GPIO_Pin_3 | GPIO_Pin_4;
|
||||||
|
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IPD;
|
||||||
|
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
|
||||||
|
GPIO_Init(GPIOA, &GPIO_InitStructure);
|
||||||
|
|
||||||
|
// TODO Configure EXTI4 1 channel
|
||||||
|
|
||||||
|
// Input timers on TIM2 for PWM
|
||||||
|
NVIC_InitStructure.NVIC_IRQChannel = TIM2_IRQn;
|
||||||
|
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 0;
|
||||||
|
NVIC_InitStructure.NVIC_IRQChannelSubPriority = 1;
|
||||||
|
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
|
||||||
|
NVIC_Init(&NVIC_InitStructure);
|
||||||
|
|
||||||
|
// TIM2 timebase
|
||||||
|
TIM_TimeBaseStructInit(&TIM_TimeBaseStructure);
|
||||||
|
TIM_TimeBaseStructure.TIM_Prescaler = (72 - 1);
|
||||||
|
TIM_TimeBaseStructure.TIM_Period = 0xffff;
|
||||||
|
TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up;
|
||||||
|
TIM_TimeBaseInit(TIM2, &TIM_TimeBaseStructure);
|
||||||
|
|
||||||
|
// PWM Input capture
|
||||||
|
TIM_ICInitStructure.TIM_ICPolarity = TIM_ICPolarity_Rising;
|
||||||
|
TIM_ICInitStructure.TIM_ICSelection = TIM_ICSelection_DirectTI;
|
||||||
|
TIM_ICInitStructure.TIM_ICPrescaler = TIM_ICPSC_DIV1;
|
||||||
|
TIM_ICInitStructure.TIM_ICFilter = 0x0;
|
||||||
|
|
||||||
|
for (i = 0; i < 4; i++) {
|
||||||
|
TIM_ICInitStructure.TIM_Channel = Channels[i].channel;
|
||||||
|
TIM_ICInit(Channels[i].tim, &TIM_ICInitStructure);
|
||||||
|
}
|
||||||
|
|
||||||
|
// TODO EXTI4
|
||||||
|
|
||||||
|
TIM_ITConfig(TIM2, TIM_IT_CC1 | TIM_IT_CC2 | TIM_IT_CC3 | TIM_IT_CC4, ENABLE);
|
||||||
|
// TODO EXTI4
|
||||||
|
TIM_Cmd(TIM2, ENABLE);
|
||||||
|
|
||||||
|
// In PWM input mode, all 4 channels are wasted
|
||||||
|
numOutputChannels = 4;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
bool pwmInit(drv_pwm_config_t *init)
|
||||||
|
{
|
||||||
|
GPIO_InitTypeDef GPIO_InitStructure = { 0, };
|
||||||
|
TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure = { 0, };
|
||||||
|
TIM_OCInitTypeDef TIM_OCInitStructure = { 0, };
|
||||||
|
|
||||||
|
uint8_t i;
|
||||||
|
|
||||||
|
// Inputs
|
||||||
|
|
||||||
|
// RX1 TIM2_CH1 PA0 [also PPM] [also used for throttle calibration]
|
||||||
|
// RX2 TIM2_CH2 PA1
|
||||||
|
// RX3 TIM2_CH3 PA2 [also UART2_TX]
|
||||||
|
// RX4 TIM2_CH4 PA3 [also UART2_RX]
|
||||||
|
// RX5 TIM3_CH1 PA6 [also ADC_IN6]
|
||||||
|
// RX6 TIM3_CH2 PA7 [also ADC_IN7]
|
||||||
|
// RX7 TIM3_CH3 PB0 [also ADC_IN8]
|
||||||
|
// RX8 TIM3_CH4 PB1 [also ADC_IN9]
|
||||||
|
|
||||||
|
// Outputs
|
||||||
|
// PWM1 TIM1_CH1 PA8
|
||||||
|
// PWM2 TIM1_CH4 PA11
|
||||||
|
// PWM3 TIM4_CH1 PB6 [also I2C1_SCL]
|
||||||
|
// PWM4 TIM4_CH2 PB7 [also I2C1_SDA]
|
||||||
|
// PWM5 TIM4_CH3 PB8
|
||||||
|
// PWM6 TIM4_CH4 PB9
|
||||||
|
|
||||||
|
// use PPM or PWM input
|
||||||
|
usePPMFlag = init->usePPM;
|
||||||
|
|
||||||
|
// preset channels to center
|
||||||
|
for (i = 0; i < 8; i++)
|
||||||
|
Inputs[i].capture = 1500;
|
||||||
|
|
||||||
|
// Timers run at 1mhz.
|
||||||
|
// TODO: clean this shit up. Make it all dynamic etc.
|
||||||
|
if (init->enableInput)
|
||||||
|
pwmInitializeInput(usePPMFlag);
|
||||||
|
|
||||||
|
// Output pins (4x)
|
||||||
|
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_6 | GPIO_Pin_7 | GPIO_Pin_8 | GPIO_Pin_9;
|
||||||
|
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP;
|
||||||
|
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
|
||||||
|
GPIO_Init(GPIOB, &GPIO_InitStructure);
|
||||||
|
|
||||||
|
// Output timer
|
||||||
|
TIM_TimeBaseStructInit(&TIM_TimeBaseStructure);
|
||||||
|
TIM_TimeBaseStructure.TIM_Prescaler = (72 - 1);
|
||||||
|
|
||||||
|
TIM_TimeBaseStructure.TIM_Period = (1000000 / init->motorPwmRate) - 1;
|
||||||
|
TIM_TimeBaseInit(TIM4, &TIM_TimeBaseStructure);
|
||||||
|
|
||||||
|
TIM_OCInitStructure.TIM_OCMode = TIM_OCMode_PWM2;
|
||||||
|
TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable;
|
||||||
|
TIM_OCInitStructure.TIM_OutputNState = TIM_OutputNState_Disable;
|
||||||
|
TIM_OCInitStructure.TIM_Pulse = PULSE_1MS;
|
||||||
|
TIM_OCInitStructure.TIM_OCPolarity = TIM_OCPolarity_Low;
|
||||||
|
TIM_OCInitStructure.TIM_OCIdleState = TIM_OCIdleState_Set;
|
||||||
|
|
||||||
|
// PWM1,2,3,4
|
||||||
|
TIM_OC1Init(TIM4, &TIM_OCInitStructure);
|
||||||
|
TIM_OC2Init(TIM4, &TIM_OCInitStructure);
|
||||||
|
TIM_OC3Init(TIM4, &TIM_OCInitStructure);
|
||||||
|
TIM_OC4Init(TIM4, &TIM_OCInitStructure);
|
||||||
|
|
||||||
|
TIM_Cmd(TIM4, ENABLE);
|
||||||
|
TIM_CtrlPWMOutputs(TIM4, ENABLE);
|
||||||
|
|
||||||
|
// turn on more motor outputs if we're using ppm / not using pwm input
|
||||||
|
if (!init->enableInput || init->usePPM) {
|
||||||
|
// TODO
|
||||||
|
}
|
||||||
|
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
void pwmWrite(uint8_t channel, uint16_t value)
|
||||||
|
{
|
||||||
|
if (channel < numOutputChannels)
|
||||||
|
*OutputChannels[channel] = value;
|
||||||
|
}
|
||||||
|
|
||||||
|
uint16_t pwmRead(uint8_t channel)
|
||||||
|
{
|
||||||
|
return Inputs[channel].capture;
|
||||||
|
}
|
||||||
|
|
||||||
|
uint8_t pwmGetNumOutputChannels(void)
|
||||||
|
{
|
||||||
|
return numOutputChannels;
|
||||||
|
}
|
|
@ -5,6 +5,13 @@
|
||||||
#define DWT_CYCCNT ((volatile uint32_t *)0xE0001004)
|
#define DWT_CYCCNT ((volatile uint32_t *)0xE0001004)
|
||||||
#define CYCCNTENA (1 << 0)
|
#define CYCCNTENA (1 << 0)
|
||||||
|
|
||||||
|
typedef struct gpio_config_t
|
||||||
|
{
|
||||||
|
GPIO_TypeDef *gpio;
|
||||||
|
uint16_t pin;
|
||||||
|
GPIOMode_TypeDef mode;
|
||||||
|
} gpio_config_t;
|
||||||
|
|
||||||
// cycles per microsecond
|
// cycles per microsecond
|
||||||
static volatile uint32_t usTicks = 0;
|
static volatile uint32_t usTicks = 0;
|
||||||
// current uptime for 1kHz systick timer. will rollover after 49 days. hopefully we won't care.
|
// current uptime for 1kHz systick timer. will rollover after 49 days. hopefully we won't care.
|
||||||
|
@ -52,6 +59,16 @@ uint32_t millis(void)
|
||||||
void systemInit(void)
|
void systemInit(void)
|
||||||
{
|
{
|
||||||
GPIO_InitTypeDef GPIO_InitStructure;
|
GPIO_InitTypeDef GPIO_InitStructure;
|
||||||
|
uint8_t i;
|
||||||
|
|
||||||
|
gpio_config_t gpio_cfg[] = {
|
||||||
|
{ LED0_GPIO, LED0_PIN, GPIO_Mode_Out_PP }, // PB3 (LED)
|
||||||
|
{ LED1_GPIO, LED1_PIN, GPIO_Mode_Out_PP }, // PB4 (LED)
|
||||||
|
#ifndef FY90Q
|
||||||
|
{ BEEP_GPIO, BEEP_PIN, GPIO_Mode_Out_OD }, // PA12 (Buzzer)
|
||||||
|
#endif
|
||||||
|
};
|
||||||
|
uint8_t gpio_count = sizeof(gpio_cfg) / sizeof(gpio_cfg[0]);
|
||||||
|
|
||||||
// Turn on clocks for stuff we use
|
// Turn on clocks for stuff we use
|
||||||
RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA | RCC_APB2Periph_GPIOB | RCC_APB2Periph_GPIOC | RCC_APB2Periph_AFIO, ENABLE);
|
RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA | RCC_APB2Periph_GPIOB | RCC_APB2Periph_GPIOC | RCC_APB2Periph_AFIO, ENABLE);
|
||||||
|
@ -77,20 +94,15 @@ void systemInit(void)
|
||||||
GPIO_PinRemapConfig(GPIO_Remap_SWJ_JTAGDisable, ENABLE);
|
GPIO_PinRemapConfig(GPIO_Remap_SWJ_JTAGDisable, ENABLE);
|
||||||
|
|
||||||
// Configure gpio
|
// Configure gpio
|
||||||
|
for (i = 0; i < gpio_count; i++) {
|
||||||
|
GPIO_InitStructure.GPIO_Pin = gpio_cfg[i].pin;
|
||||||
|
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
|
||||||
|
GPIO_InitStructure.GPIO_Mode = gpio_cfg[i].mode;
|
||||||
|
GPIO_Init(gpio_cfg[i].gpio, &GPIO_InitStructure);
|
||||||
|
}
|
||||||
|
|
||||||
// PB3, PB4 (LEDs)
|
|
||||||
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_3 | GPIO_Pin_4;
|
|
||||||
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
|
|
||||||
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_PP;
|
|
||||||
GPIO_Init(GPIOB, &GPIO_InitStructure);
|
|
||||||
LED0_OFF;
|
LED0_OFF;
|
||||||
LED1_OFF;
|
LED1_OFF;
|
||||||
|
|
||||||
// PA12 (Buzzer)
|
|
||||||
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_12;
|
|
||||||
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
|
|
||||||
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_OD;
|
|
||||||
GPIO_Init(GPIOA, &GPIO_InitStructure);
|
|
||||||
BEEP_OFF;
|
BEEP_OFF;
|
||||||
|
|
||||||
// Init cycle counter
|
// Init cycle counter
|
||||||
|
@ -101,7 +113,9 @@ void systemInit(void)
|
||||||
|
|
||||||
// Configure the rest of the stuff
|
// Configure the rest of the stuff
|
||||||
adcInit();
|
adcInit();
|
||||||
|
#ifndef FY90Q
|
||||||
i2cInit(I2C2);
|
i2cInit(I2C2);
|
||||||
|
#endif
|
||||||
|
|
||||||
// sleep for 100ms
|
// sleep for 100ms
|
||||||
delay(100);
|
delay(100);
|
||||||
|
|
|
@ -23,9 +23,11 @@ void imuInit(void)
|
||||||
{
|
{
|
||||||
acc_25deg = acc_1G * 0.423f;
|
acc_25deg = acc_1G * 0.423f;
|
||||||
|
|
||||||
|
#ifdef MAG
|
||||||
// if mag sensor is enabled, use it
|
// if mag sensor is enabled, use it
|
||||||
if (sensors(SENSOR_MAG))
|
if (sensors(SENSOR_MAG))
|
||||||
Mag_init();
|
Mag_init();
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
void computeIMU(void)
|
void computeIMU(void)
|
||||||
|
@ -230,12 +232,15 @@ static void getEstimatedAttitude(void)
|
||||||
angle[ROLL] = _atan2f(EstG.V.X, EstG.V.Z);
|
angle[ROLL] = _atan2f(EstG.V.X, EstG.V.Z);
|
||||||
angle[PITCH] = _atan2f(EstG.V.Y, EstG.V.Z);
|
angle[PITCH] = _atan2f(EstG.V.Y, EstG.V.Z);
|
||||||
|
|
||||||
|
#ifdef MAG
|
||||||
if (sensors(SENSOR_MAG)) {
|
if (sensors(SENSOR_MAG)) {
|
||||||
// Attitude of the cross product vector GxM
|
// Attitude of the cross product vector GxM
|
||||||
heading = _atan2f(EstG.V.X * EstM.V.Z - EstG.V.Z * EstM.V.X, EstG.V.Z * EstM.V.Y - EstG.V.Y * EstM.V.Z) / 10;
|
heading = _atan2f(EstG.V.X * EstM.V.Z - EstG.V.Z * EstM.V.X, EstG.V.Z * EstM.V.Y - EstG.V.Y * EstM.V.Z) / 10;
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#ifdef BARO
|
||||||
#define UPDATE_INTERVAL 25000 // 40hz update rate (20hz LPF on acc)
|
#define UPDATE_INTERVAL 25000 // 40hz update rate (20hz LPF on acc)
|
||||||
#define INIT_DELAY 4000000 // 4 sec initialization delay
|
#define INIT_DELAY 4000000 // 4 sec initialization delay
|
||||||
#define BARO_TAB_SIZE 40
|
#define BARO_TAB_SIZE 40
|
||||||
|
@ -288,3 +293,4 @@ void getEstimatedAltitude(void)
|
||||||
temp32 = errorAltitudeI / 500; // I in range +/-60
|
temp32 = errorAltitudeI / 500; // I in range +/-60
|
||||||
BaroPID += temp32;
|
BaroPID += temp32;
|
||||||
}
|
}
|
||||||
|
#endif /* BARO */
|
||||||
|
|
20
src/main.c
20
src/main.c
|
@ -35,6 +35,20 @@ int main(void)
|
||||||
uint8_t i;
|
uint8_t i;
|
||||||
drv_pwm_config_t pwm_params;
|
drv_pwm_config_t pwm_params;
|
||||||
|
|
||||||
|
#if 0
|
||||||
|
// PC12, PA15
|
||||||
|
// using this to write asm for bootloader :)
|
||||||
|
RCC->APB2ENR |= RCC_APB2Periph_GPIOA | RCC_APB2Periph_GPIOC | RCC_APB2Periph_AFIO; // GPIOA/C+AFIO only
|
||||||
|
AFIO->MAPR &= 0xF0FFFFFF;
|
||||||
|
AFIO->MAPR = 0x02000000;
|
||||||
|
GPIOA->CRH = 0x34444444; // PIN 15 Output 50MHz
|
||||||
|
GPIOA->BRR = 0x8000; // set low 15
|
||||||
|
GPIOC->CRH = 0x44434444; // PIN 12 Output 50MHz
|
||||||
|
GPIOC->BRR = 0x1000; // set low 12
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
||||||
|
|
||||||
#if 0
|
#if 0
|
||||||
// using this to write asm for bootloader :)
|
// using this to write asm for bootloader :)
|
||||||
RCC->APB2ENR |= RCC_APB2Periph_GPIOB | RCC_APB2Periph_AFIO; // GPIOB + AFIO
|
RCC->APB2ENR |= RCC_APB2Periph_GPIOB | RCC_APB2Periph_AFIO; // GPIOB + AFIO
|
||||||
|
@ -52,7 +66,13 @@ int main(void)
|
||||||
serialInit(cfg.serial_baudrate);
|
serialInit(cfg.serial_baudrate);
|
||||||
|
|
||||||
// We have these sensors
|
// We have these sensors
|
||||||
|
#ifndef FY90Q
|
||||||
|
// AfroFlight32
|
||||||
sensorsSet(SENSOR_ACC | SENSOR_BARO | SENSOR_MAG);
|
sensorsSet(SENSOR_ACC | SENSOR_BARO | SENSOR_MAG);
|
||||||
|
#else
|
||||||
|
// FY90Q
|
||||||
|
sensorsSet(SENSOR_ACC);
|
||||||
|
#endif
|
||||||
|
|
||||||
mixerInit(); // this will set useServo var depending on mixer type
|
mixerInit(); // this will set useServo var depending on mixer type
|
||||||
// pwmInit returns true if throttle calibration is requested. if so, do it here. throttleCalibration() does NOT return - for safety.
|
// pwmInit returns true if throttle calibration is requested. if so, do it here. throttleCalibration() does NOT return - for safety.
|
||||||
|
|
26
src/mw.c
26
src/mw.c
|
@ -181,6 +181,7 @@ void annexCode(void)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#ifdef LEDRING
|
||||||
if (feature(FEATURE_LED_RING)) {
|
if (feature(FEATURE_LED_RING)) {
|
||||||
static uint32_t LEDTime;
|
static uint32_t LEDTime;
|
||||||
if (currentTime > LEDTime) {
|
if (currentTime > LEDTime) {
|
||||||
|
@ -188,6 +189,7 @@ void annexCode(void)
|
||||||
ledringState();
|
ledringState();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
if (currentTime > calibratedAccTime) {
|
if (currentTime > calibratedAccTime) {
|
||||||
if (smallAngle25 == 0) {
|
if (smallAngle25 == 0) {
|
||||||
|
@ -333,23 +335,31 @@ void loop(void)
|
||||||
} else if (rcData[PITCH] > cfg.maxcheck) {
|
} else if (rcData[PITCH] > cfg.maxcheck) {
|
||||||
cfg.accTrim[PITCH] += 2;
|
cfg.accTrim[PITCH] += 2;
|
||||||
writeParams();
|
writeParams();
|
||||||
|
#ifdef LEDRING
|
||||||
if (feature(FEATURE_LED_RING))
|
if (feature(FEATURE_LED_RING))
|
||||||
ledringBlink();
|
ledringBlink();
|
||||||
|
#endif
|
||||||
} else if (rcData[PITCH] < cfg.mincheck) {
|
} else if (rcData[PITCH] < cfg.mincheck) {
|
||||||
cfg.accTrim[PITCH] -= 2;
|
cfg.accTrim[PITCH] -= 2;
|
||||||
writeParams();
|
writeParams();
|
||||||
|
#ifdef LEDRING
|
||||||
if (feature(FEATURE_LED_RING))
|
if (feature(FEATURE_LED_RING))
|
||||||
ledringBlink();
|
ledringBlink();
|
||||||
|
#endif
|
||||||
} else if (rcData[ROLL] > cfg.maxcheck) {
|
} else if (rcData[ROLL] > cfg.maxcheck) {
|
||||||
cfg.accTrim[ROLL] += 2;
|
cfg.accTrim[ROLL] += 2;
|
||||||
writeParams();
|
writeParams();
|
||||||
|
#ifdef LEDRING
|
||||||
if (feature(FEATURE_LED_RING))
|
if (feature(FEATURE_LED_RING))
|
||||||
ledringBlink();
|
ledringBlink();
|
||||||
|
#endif
|
||||||
} else if (rcData[ROLL] < cfg.mincheck) {
|
} else if (rcData[ROLL] < cfg.mincheck) {
|
||||||
cfg.accTrim[ROLL] -= 2;
|
cfg.accTrim[ROLL] -= 2;
|
||||||
writeParams();
|
writeParams();
|
||||||
|
#ifdef LEDRING
|
||||||
if (feature(FEATURE_LED_RING))
|
if (feature(FEATURE_LED_RING))
|
||||||
ledringBlink();
|
ledringBlink();
|
||||||
|
#endif
|
||||||
} else {
|
} else {
|
||||||
rcDelayCommand = 0;
|
rcDelayCommand = 0;
|
||||||
}
|
}
|
||||||
|
@ -402,6 +412,7 @@ void loop(void)
|
||||||
LED1_OFF;
|
LED1_OFF;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#ifdef BARO
|
||||||
if (sensors(SENSOR_BARO)) {
|
if (sensors(SENSOR_BARO)) {
|
||||||
if (rcOptions[BOXBARO]) {
|
if (rcOptions[BOXBARO]) {
|
||||||
if (baroMode == 0) {
|
if (baroMode == 0) {
|
||||||
|
@ -414,7 +425,9 @@ void loop(void)
|
||||||
} else
|
} else
|
||||||
baroMode = 0;
|
baroMode = 0;
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef MAG
|
||||||
if (sensors(SENSOR_MAG)) {
|
if (sensors(SENSOR_MAG)) {
|
||||||
if (rcOptions[BOXMAG]) {
|
if (rcOptions[BOXMAG]) {
|
||||||
if (magMode == 0) {
|
if (magMode == 0) {
|
||||||
|
@ -430,6 +443,7 @@ void loop(void)
|
||||||
} else
|
} else
|
||||||
headFreeMode = 0;
|
headFreeMode = 0;
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
if (sensors(SENSOR_GPS)) {
|
if (sensors(SENSOR_GPS)) {
|
||||||
if (rcOptions[BOXGPSHOME]) {
|
if (rcOptions[BOXGPSHOME]) {
|
||||||
|
@ -456,18 +470,24 @@ void loop(void)
|
||||||
switch (taskOrder) {
|
switch (taskOrder) {
|
||||||
case 0:
|
case 0:
|
||||||
taskOrder++;
|
taskOrder++;
|
||||||
|
#ifdef MAG
|
||||||
if (sensors(SENSOR_MAG))
|
if (sensors(SENSOR_MAG))
|
||||||
Mag_getADC();
|
Mag_getADC();
|
||||||
|
#endif
|
||||||
break;
|
break;
|
||||||
case 1:
|
case 1:
|
||||||
taskOrder++;
|
taskOrder++;
|
||||||
|
#ifdef BARO
|
||||||
if (sensors(SENSOR_BARO))
|
if (sensors(SENSOR_BARO))
|
||||||
Baro_update();
|
Baro_update();
|
||||||
|
#endif
|
||||||
break;
|
break;
|
||||||
case 2:
|
case 2:
|
||||||
taskOrder++;
|
taskOrder++;
|
||||||
|
#ifdef BARO
|
||||||
if (sensors(SENSOR_BARO))
|
if (sensors(SENSOR_BARO))
|
||||||
getEstimatedAltitude();
|
getEstimatedAltitude();
|
||||||
|
#endif
|
||||||
break;
|
break;
|
||||||
case 3:
|
case 3:
|
||||||
taskOrder++;
|
taskOrder++;
|
||||||
|
@ -487,8 +507,11 @@ void loop(void)
|
||||||
cycleTime = currentTime - previousTime;
|
cycleTime = currentTime - previousTime;
|
||||||
previousTime = currentTime;
|
previousTime = currentTime;
|
||||||
|
|
||||||
|
#ifdef MPU6050_DMP
|
||||||
mpu6050DmpLoop();
|
mpu6050DmpLoop();
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef MAG
|
||||||
if (sensors(SENSOR_MAG)) {
|
if (sensors(SENSOR_MAG)) {
|
||||||
if (abs(rcCommand[YAW]) < 70 && magMode) {
|
if (abs(rcCommand[YAW]) < 70 && magMode) {
|
||||||
int16_t dif = heading - magHold;
|
int16_t dif = heading - magHold;
|
||||||
|
@ -501,7 +524,9 @@ void loop(void)
|
||||||
} else
|
} else
|
||||||
magHold = heading;
|
magHold = heading;
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef BARO
|
||||||
if (sensors(SENSOR_BARO)) {
|
if (sensors(SENSOR_BARO)) {
|
||||||
if (baroMode) {
|
if (baroMode) {
|
||||||
if (abs(rcCommand[THROTTLE] - initialThrottleHold) > 20) {
|
if (abs(rcCommand[THROTTLE] - initialThrottleHold) > 20) {
|
||||||
|
@ -510,6 +535,7 @@ void loop(void)
|
||||||
rcCommand[THROTTLE] = initialThrottleHold + BaroPID;
|
rcCommand[THROTTLE] = initialThrottleHold + BaroPID;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
if (sensors(SENSOR_GPS)) {
|
if (sensors(SENSOR_GPS)) {
|
||||||
uint16_t GPS_dist = 0;
|
uint16_t GPS_dist = 0;
|
||||||
|
|
|
@ -19,6 +19,14 @@ extern uint8_t batteryCellCount;
|
||||||
sensor_t acc; // acc access functions
|
sensor_t acc; // acc access functions
|
||||||
sensor_t gyro; // gyro access functions
|
sensor_t gyro; // gyro access functions
|
||||||
|
|
||||||
|
#ifdef FY90Q
|
||||||
|
// FY90Q analog gyro/acc
|
||||||
|
void sensorsAutodetect(void)
|
||||||
|
{
|
||||||
|
adcSensorInit(&acc, &gyro);
|
||||||
|
}
|
||||||
|
#else
|
||||||
|
// AfroFlight32 i2c sensors
|
||||||
void sensorsAutodetect(void)
|
void sensorsAutodetect(void)
|
||||||
{
|
{
|
||||||
drv_adxl345_config_t acc_params;
|
drv_adxl345_config_t acc_params;
|
||||||
|
@ -54,6 +62,7 @@ void sensorsAutodetect(void)
|
||||||
// todo: this is driver specific :(
|
// todo: this is driver specific :(
|
||||||
mpu3050Config(cfg.gyro_lpf);
|
mpu3050Config(cfg.gyro_lpf);
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
uint16_t batteryAdcToVoltage(uint16_t src)
|
uint16_t batteryAdcToVoltage(uint16_t src)
|
||||||
{
|
{
|
||||||
|
@ -175,6 +184,7 @@ void ACC_getADC(void)
|
||||||
ACC_Common();
|
ACC_Common();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#ifdef BARO
|
||||||
static uint32_t baroDeadline = 0;
|
static uint32_t baroDeadline = 0;
|
||||||
static uint8_t baroState = 0;
|
static uint8_t baroState = 0;
|
||||||
static uint16_t baroUT = 0;
|
static uint16_t baroUT = 0;
|
||||||
|
@ -214,6 +224,7 @@ void Baro_update(void)
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
#endif /* BARO */
|
||||||
|
|
||||||
static void GYRO_Common(void)
|
static void GYRO_Common(void)
|
||||||
{
|
{
|
||||||
|
@ -278,6 +289,7 @@ void Gyro_getADC(void)
|
||||||
GYRO_Common();
|
GYRO_Common();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#ifdef MAG
|
||||||
static float magCal[3] = { 1.0, 1.0, 1.0 }; // gain for each axis, populated at sensor init
|
static float magCal[3] = { 1.0, 1.0, 1.0 }; // gain for each axis, populated at sensor init
|
||||||
static uint8_t magInit = 0;
|
static uint8_t magInit = 0;
|
||||||
|
|
||||||
|
@ -359,3 +371,4 @@ void Mag_getADC(void)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
Loading…
Reference in New Issue