mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-13 11:29:58 +03:00
fixed acczero offsets to 0 on initial eeprom cleanup
added fifo mode to adxl345 driver, currently disabled. work in progress. fixed output for PWM 5-8 when used with PPM + camstab + abovequad configs. fixed baro, now alt-hold actually works. silly copypaste typo. trashed all remaining parts of power meter and lcd configuration stuff. useless. git-svn-id: https://afrodevices.googlecode.com/svn/trunk/baseflight@145 7c89a4a9-59b9-e629-4cfe-3a2d53b20e61
This commit is contained in:
parent
9e5504acd8
commit
cb334ecf47
13 changed files with 2849 additions and 3020 deletions
600
baseflight.uvopt
600
baseflight.uvopt
|
@ -24,250 +24,6 @@
|
||||||
<TargetName>STM32</TargetName>
|
<TargetName>STM32</TargetName>
|
||||||
<ToolsetNumber>0x4</ToolsetNumber>
|
<ToolsetNumber>0x4</ToolsetNumber>
|
||||||
<ToolsetName>ARM-ADS</ToolsetName>
|
<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>0</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>-pSTM32F103C8</SimDlgDllArguments>
|
|
||||||
<TargetDllName>SARMCM3.DLL</TargetDllName>
|
|
||||||
<TargetDllArguments></TargetDllArguments>
|
|
||||||
<TargetDlgDllName>TARMSTM.DLL</TargetDlgDllName>
|
|
||||||
<TargetDlgDllArguments>-pSTM32F103C8</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>ST-LINKIII-KEIL</Key>
|
|
||||||
<Name>-S</Name>
|
|
||||||
</SetRegEntry>
|
|
||||||
<SetRegEntry>
|
|
||||||
<Number>0</Number>
|
|
||||||
<Key>DLGTARM</Key>
|
|
||||||
<Name>(1010=333,106,699,649,0)(1007=-1,-1,-1,-1,0)(1008=90,117,456,339,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=-1,-1,-1,-1,0)(121=-1,-1,-1,-1,0)(122=-1,-1,-1,-1,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=791,309,1258,816,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=570,175,1163,795,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) -TO2 -TC72000000 -TP21 -TDS800B -TDT0 -TDC1F -TIEFFFFFFFF -TIP8 -TB1 -TFE0 -FO11 -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 -TC72000000 -TP21 -TDS803D -TDT0 -TDC1F -TIEFFFFFFFF -TIP8 -FO11 -FD20000000 -FC800 -FN1 -FF0STM32F10x_128 -FS08000000 -FL010000</Name>
|
|
||||||
</SetRegEntry>
|
|
||||||
</TargetDriverDllRegistry>
|
|
||||||
<Breakpoint>
|
|
||||||
<Bp>
|
|
||||||
<Number>0</Number>
|
|
||||||
<Type>0</Type>
|
|
||||||
<LineNumber>309</LineNumber>
|
|
||||||
<EnabledFlag>1</EnabledFlag>
|
|
||||||
<Address>134244448</Address>
|
|
||||||
<ByteObject>0</ByteObject>
|
|
||||||
<ManyObjects>0</ManyObjects>
|
|
||||||
<SizeOfObject>0</SizeOfObject>
|
|
||||||
<BreakByAccess>0</BreakByAccess>
|
|
||||||
<BreakIfRCount>1</BreakIfRCount>
|
|
||||||
<Filename></Filename>
|
|
||||||
<ExecCommand></ExecCommand>
|
|
||||||
<Expression>\\baseflight\src/drv_pwm.c\309</Expression>
|
|
||||||
</Bp>
|
|
||||||
</Breakpoint>
|
|
||||||
<WatchWindow1>
|
|
||||||
<Ww>
|
|
||||||
<count>0</count>
|
|
||||||
<WinNumber>1</WinNumber>
|
|
||||||
<ItemText>cycleTime,0x0A</ItemText>
|
|
||||||
</Ww>
|
|
||||||
<Ww>
|
|
||||||
<count>1</count>
|
|
||||||
<WinNumber>1</WinNumber>
|
|
||||||
<ItemText>Inputs
|
|
||||||
</ItemText>
|
|
||||||
</Ww>
|
|
||||||
<Ww>
|
|
||||||
<count>2</count>
|
|
||||||
<WinNumber>1</WinNumber>
|
|
||||||
<ItemText>Inputs
|
|
||||||
</ItemText>
|
|
||||||
</Ww>
|
|
||||||
<Ww>
|
|
||||||
<count>3</count>
|
|
||||||
<WinNumber>1</WinNumber>
|
|
||||||
<ItemText>rcData,0x0A</ItemText>
|
|
||||||
</Ww>
|
|
||||||
<Ww>
|
|
||||||
<count>4</count>
|
|
||||||
<WinNumber>1</WinNumber>
|
|
||||||
<ItemText>incoming</ItemText>
|
|
||||||
</Ww>
|
|
||||||
<Ww>
|
|
||||||
<count>5</count>
|
|
||||||
<WinNumber>1</WinNumber>
|
|
||||||
<ItemText>dmpdata
|
|
||||||
</ItemText>
|
|
||||||
</Ww>
|
|
||||||
<Ww>
|
|
||||||
<count>6</count>
|
|
||||||
<WinNumber>1</WinNumber>
|
|
||||||
<ItemText>dmpdata</ItemText>
|
|
||||||
</Ww>
|
|
||||||
<Ww>
|
|
||||||
<count>7</count>
|
|
||||||
<WinNumber>1</WinNumber>
|
|
||||||
<ItemText>dmp_fifoCountL</ItemText>
|
|
||||||
</Ww>
|
|
||||||
</WatchWindow1>
|
|
||||||
<MemoryWindow1>
|
|
||||||
<Mm>
|
|
||||||
<WinNumber>1</WinNumber>
|
|
||||||
<SubType>0</SubType>
|
|
||||||
<ItemText>20000000</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>
|
|
||||||
|
|
||||||
<Target>
|
|
||||||
<TargetName>STM32-Release</TargetName>
|
|
||||||
<ToolsetNumber>0x4</ToolsetNumber>
|
|
||||||
<ToolsetName>ARM-ADS</ToolsetName>
|
|
||||||
<TargetOption>
|
<TargetOption>
|
||||||
<CLKADS>8000000</CLKADS>
|
<CLKADS>8000000</CLKADS>
|
||||||
<OPTTT>
|
<OPTTT>
|
||||||
|
@ -369,6 +125,253 @@
|
||||||
<tIfile></tIfile>
|
<tIfile></tIfile>
|
||||||
<pMon>BIN\UL2CM3.DLL</pMon>
|
<pMon>BIN\UL2CM3.DLL</pMon>
|
||||||
</DebugOpt>
|
</DebugOpt>
|
||||||
|
<TargetDriverDllRegistry>
|
||||||
|
<SetRegEntry>
|
||||||
|
<Number>0</Number>
|
||||||
|
<Key>ST-LINKIII-KEIL</Key>
|
||||||
|
<Name>-S</Name>
|
||||||
|
</SetRegEntry>
|
||||||
|
<SetRegEntry>
|
||||||
|
<Number>0</Number>
|
||||||
|
<Key>DLGTARM</Key>
|
||||||
|
<Name>(1010=333,106,699,649,0)(1007=-1,-1,-1,-1,0)(1008=90,117,456,339,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=-1,-1,-1,-1,0)(121=-1,-1,-1,-1,0)(122=-1,-1,-1,-1,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=791,309,1258,816,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=570,175,1163,795,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) -TO2 -TC72000000 -TP21 -TDS800B -TDT0 -TDC1F -TIEFFFFFFFF -TIP8 -TB1 -TFE0 -FO11 -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 -TC72000000 -TP21 -TDS803D -TDT0 -TDC1F -TIEFFFFFFFF -TIP8 -FO11 -FD20000000 -FC800 -FN1 -FF0STM32F10x_128 -FS08000000 -FL010000</Name>
|
||||||
|
</SetRegEntry>
|
||||||
|
</TargetDriverDllRegistry>
|
||||||
|
<WatchWindow1>
|
||||||
|
<Ww>
|
||||||
|
<count>0</count>
|
||||||
|
<WinNumber>1</WinNumber>
|
||||||
|
<ItemText>cycleTime,0x0A</ItemText>
|
||||||
|
</Ww>
|
||||||
|
<Ww>
|
||||||
|
<count>1</count>
|
||||||
|
<WinNumber>1</WinNumber>
|
||||||
|
<ItemText>Inputs
|
||||||
|
</ItemText>
|
||||||
|
</Ww>
|
||||||
|
<Ww>
|
||||||
|
<count>2</count>
|
||||||
|
<WinNumber>1</WinNumber>
|
||||||
|
<ItemText>Inputs
|
||||||
|
</ItemText>
|
||||||
|
</Ww>
|
||||||
|
<Ww>
|
||||||
|
<count>3</count>
|
||||||
|
<WinNumber>1</WinNumber>
|
||||||
|
<ItemText>rcData,0x0A</ItemText>
|
||||||
|
</Ww>
|
||||||
|
<Ww>
|
||||||
|
<count>4</count>
|
||||||
|
<WinNumber>1</WinNumber>
|
||||||
|
<ItemText>incoming</ItemText>
|
||||||
|
</Ww>
|
||||||
|
<Ww>
|
||||||
|
<count>5</count>
|
||||||
|
<WinNumber>1</WinNumber>
|
||||||
|
<ItemText>dmpdata
|
||||||
|
</ItemText>
|
||||||
|
</Ww>
|
||||||
|
<Ww>
|
||||||
|
<count>6</count>
|
||||||
|
<WinNumber>1</WinNumber>
|
||||||
|
<ItemText>dmpdata</ItemText>
|
||||||
|
</Ww>
|
||||||
|
<Ww>
|
||||||
|
<count>7</count>
|
||||||
|
<WinNumber>1</WinNumber>
|
||||||
|
<ItemText>dmp_fifoCountL</ItemText>
|
||||||
|
</Ww>
|
||||||
|
<Ww>
|
||||||
|
<count>8</count>
|
||||||
|
<WinNumber>1</WinNumber>
|
||||||
|
<ItemText>smallAngle25</ItemText>
|
||||||
|
</Ww>
|
||||||
|
<Ww>
|
||||||
|
<count>9</count>
|
||||||
|
<WinNumber>1</WinNumber>
|
||||||
|
<ItemText>accSmooth,0x0A</ItemText>
|
||||||
|
</Ww>
|
||||||
|
<Ww>
|
||||||
|
<count>10</count>
|
||||||
|
<WinNumber>1</WinNumber>
|
||||||
|
<ItemText>accADC,0x0A</ItemText>
|
||||||
|
</Ww>
|
||||||
|
<Ww>
|
||||||
|
<count>11</count>
|
||||||
|
<WinNumber>1</WinNumber>
|
||||||
|
<ItemText>acc_samples</ItemText>
|
||||||
|
</Ww>
|
||||||
|
</WatchWindow1>
|
||||||
|
<MemoryWindow1>
|
||||||
|
<Mm>
|
||||||
|
<WinNumber>1</WinNumber>
|
||||||
|
<SubType>0</SubType>
|
||||||
|
<ItemText>20000000</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>
|
||||||
|
|
||||||
|
<Target>
|
||||||
|
<TargetName>STM32-Release</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>0</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>-pSTM32F103C8</SimDlgDllArguments>
|
||||||
|
<TargetDllName>SARMCM3.DLL</TargetDllName>
|
||||||
|
<TargetDllArguments></TargetDllArguments>
|
||||||
|
<TargetDlgDllName>TARMSTM.DLL</TargetDlgDllName>
|
||||||
|
<TargetDlgDllArguments>-pSTM32F103C8</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>
|
<TargetDriverDllRegistry>
|
||||||
<SetRegEntry>
|
<SetRegEntry>
|
||||||
<Number>0</Number>
|
<Number>0</Number>
|
||||||
|
@ -412,21 +415,6 @@
|
||||||
<ExecCommand></ExecCommand>
|
<ExecCommand></ExecCommand>
|
||||||
<Expression>\\baseflight\src/spektrum.c\71</Expression>
|
<Expression>\\baseflight\src/spektrum.c\71</Expression>
|
||||||
</Bp>
|
</Bp>
|
||||||
<Bp>
|
|
||||||
<Number>1</Number>
|
|
||||||
<Type>0</Type>
|
|
||||||
<LineNumber>167</LineNumber>
|
|
||||||
<EnabledFlag>1</EnabledFlag>
|
|
||||||
<Address>134229292</Address>
|
|
||||||
<ByteObject>0</ByteObject>
|
|
||||||
<ManyObjects>0</ManyObjects>
|
|
||||||
<SizeOfObject>0</SizeOfObject>
|
|
||||||
<BreakByAccess>0</BreakByAccess>
|
|
||||||
<BreakIfRCount>1</BreakIfRCount>
|
|
||||||
<Filename></Filename>
|
|
||||||
<ExecCommand></ExecCommand>
|
|
||||||
<Expression>\\baseflight\src/sensors.c\167</Expression>
|
|
||||||
</Bp>
|
|
||||||
</Breakpoint>
|
</Breakpoint>
|
||||||
<WatchWindow1>
|
<WatchWindow1>
|
||||||
<Ww>
|
<Ww>
|
||||||
|
@ -507,7 +495,7 @@
|
||||||
<DebugFlag>
|
<DebugFlag>
|
||||||
<trace>0</trace>
|
<trace>0</trace>
|
||||||
<periodic>1</periodic>
|
<periodic>1</periodic>
|
||||||
<aLwin>0</aLwin>
|
<aLwin>1</aLwin>
|
||||||
<aCover>0</aCover>
|
<aCover>0</aCover>
|
||||||
<aSer1>0</aSer1>
|
<aSer1>0</aSer1>
|
||||||
<aSer2>0</aSer2>
|
<aSer2>0</aSer2>
|
||||||
|
@ -546,10 +534,10 @@
|
||||||
<FileType>1</FileType>
|
<FileType>1</FileType>
|
||||||
<tvExp>0</tvExp>
|
<tvExp>0</tvExp>
|
||||||
<Focus>0</Focus>
|
<Focus>0</Focus>
|
||||||
<ColumnNumber>19</ColumnNumber>
|
<ColumnNumber>64</ColumnNumber>
|
||||||
<tvExpOptDlg>0</tvExpOptDlg>
|
<tvExpOptDlg>0</tvExpOptDlg>
|
||||||
<TopLine>82</TopLine>
|
<TopLine>0</TopLine>
|
||||||
<CurrentLine>97</CurrentLine>
|
<CurrentLine>0</CurrentLine>
|
||||||
<bDave2>0</bDave2>
|
<bDave2>0</bDave2>
|
||||||
<PathWithFileName>.\src\cli.c</PathWithFileName>
|
<PathWithFileName>.\src\cli.c</PathWithFileName>
|
||||||
<FilenameWithoutPath>cli.c</FilenameWithoutPath>
|
<FilenameWithoutPath>cli.c</FilenameWithoutPath>
|
||||||
|
@ -560,10 +548,10 @@
|
||||||
<FileType>1</FileType>
|
<FileType>1</FileType>
|
||||||
<tvExp>0</tvExp>
|
<tvExp>0</tvExp>
|
||||||
<Focus>0</Focus>
|
<Focus>0</Focus>
|
||||||
<ColumnNumber>14</ColumnNumber>
|
<ColumnNumber>0</ColumnNumber>
|
||||||
<tvExpOptDlg>0</tvExpOptDlg>
|
<tvExpOptDlg>0</tvExpOptDlg>
|
||||||
<TopLine>16</TopLine>
|
<TopLine>0</TopLine>
|
||||||
<CurrentLine>31</CurrentLine>
|
<CurrentLine>0</CurrentLine>
|
||||||
<bDave2>0</bDave2>
|
<bDave2>0</bDave2>
|
||||||
<PathWithFileName>.\src\config.c</PathWithFileName>
|
<PathWithFileName>.\src\config.c</PathWithFileName>
|
||||||
<FilenameWithoutPath>config.c</FilenameWithoutPath>
|
<FilenameWithoutPath>config.c</FilenameWithoutPath>
|
||||||
|
@ -574,10 +562,10 @@
|
||||||
<FileType>1</FileType>
|
<FileType>1</FileType>
|
||||||
<tvExp>0</tvExp>
|
<tvExp>0</tvExp>
|
||||||
<Focus>0</Focus>
|
<Focus>0</Focus>
|
||||||
<ColumnNumber>0</ColumnNumber>
|
<ColumnNumber>16</ColumnNumber>
|
||||||
<tvExpOptDlg>0</tvExpOptDlg>
|
<tvExpOptDlg>0</tvExpOptDlg>
|
||||||
<TopLine>253</TopLine>
|
<TopLine>25</TopLine>
|
||||||
<CurrentLine>253</CurrentLine>
|
<CurrentLine>50</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>
|
||||||
|
@ -588,10 +576,10 @@
|
||||||
<FileType>1</FileType>
|
<FileType>1</FileType>
|
||||||
<tvExp>0</tvExp>
|
<tvExp>0</tvExp>
|
||||||
<Focus>0</Focus>
|
<Focus>0</Focus>
|
||||||
<ColumnNumber>14</ColumnNumber>
|
<ColumnNumber>12</ColumnNumber>
|
||||||
<tvExpOptDlg>0</tvExpOptDlg>
|
<tvExpOptDlg>0</tvExpOptDlg>
|
||||||
<TopLine>26</TopLine>
|
<TopLine>53</TopLine>
|
||||||
<CurrentLine>35</CurrentLine>
|
<CurrentLine>67</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>
|
||||||
|
@ -602,10 +590,10 @@
|
||||||
<FileType>1</FileType>
|
<FileType>1</FileType>
|
||||||
<tvExp>0</tvExp>
|
<tvExp>0</tvExp>
|
||||||
<Focus>0</Focus>
|
<Focus>0</Focus>
|
||||||
<ColumnNumber>20</ColumnNumber>
|
<ColumnNumber>0</ColumnNumber>
|
||||||
<tvExpOptDlg>0</tvExpOptDlg>
|
<tvExpOptDlg>0</tvExpOptDlg>
|
||||||
<TopLine>99</TopLine>
|
<TopLine>0</TopLine>
|
||||||
<CurrentLine>123</CurrentLine>
|
<CurrentLine>0</CurrentLine>
|
||||||
<bDave2>0</bDave2>
|
<bDave2>0</bDave2>
|
||||||
<PathWithFileName>.\src\mixer.c</PathWithFileName>
|
<PathWithFileName>.\src\mixer.c</PathWithFileName>
|
||||||
<FilenameWithoutPath>mixer.c</FilenameWithoutPath>
|
<FilenameWithoutPath>mixer.c</FilenameWithoutPath>
|
||||||
|
@ -616,10 +604,10 @@
|
||||||
<FileType>1</FileType>
|
<FileType>1</FileType>
|
||||||
<tvExp>0</tvExp>
|
<tvExp>0</tvExp>
|
||||||
<Focus>0</Focus>
|
<Focus>0</Focus>
|
||||||
<ColumnNumber>35</ColumnNumber>
|
<ColumnNumber>0</ColumnNumber>
|
||||||
<tvExpOptDlg>0</tvExpOptDlg>
|
<tvExpOptDlg>0</tvExpOptDlg>
|
||||||
<TopLine>1</TopLine>
|
<TopLine>466</TopLine>
|
||||||
<CurrentLine>17</CurrentLine>
|
<CurrentLine>489</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>
|
||||||
|
@ -630,10 +618,10 @@
|
||||||
<FileType>1</FileType>
|
<FileType>1</FileType>
|
||||||
<tvExp>0</tvExp>
|
<tvExp>0</tvExp>
|
||||||
<Focus>0</Focus>
|
<Focus>0</Focus>
|
||||||
<ColumnNumber>24</ColumnNumber>
|
<ColumnNumber>0</ColumnNumber>
|
||||||
<tvExpOptDlg>0</tvExpOptDlg>
|
<tvExpOptDlg>0</tvExpOptDlg>
|
||||||
<TopLine>178</TopLine>
|
<TopLine>1</TopLine>
|
||||||
<CurrentLine>207</CurrentLine>
|
<CurrentLine>4</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>
|
||||||
|
@ -644,10 +632,10 @@
|
||||||
<FileType>1</FileType>
|
<FileType>1</FileType>
|
||||||
<tvExp>0</tvExp>
|
<tvExp>0</tvExp>
|
||||||
<Focus>0</Focus>
|
<Focus>0</Focus>
|
||||||
<ColumnNumber>16</ColumnNumber>
|
<ColumnNumber>31</ColumnNumber>
|
||||||
<tvExpOptDlg>0</tvExpOptDlg>
|
<tvExpOptDlg>0</tvExpOptDlg>
|
||||||
<TopLine>133</TopLine>
|
<TopLine>82</TopLine>
|
||||||
<CurrentLine>151</CurrentLine>
|
<CurrentLine>98</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>
|
||||||
|
@ -660,8 +648,8 @@
|
||||||
<Focus>0</Focus>
|
<Focus>0</Focus>
|
||||||
<ColumnNumber>0</ColumnNumber>
|
<ColumnNumber>0</ColumnNumber>
|
||||||
<tvExpOptDlg>0</tvExpOptDlg>
|
<tvExpOptDlg>0</tvExpOptDlg>
|
||||||
<TopLine>1</TopLine>
|
<TopLine>31</TopLine>
|
||||||
<CurrentLine>17</CurrentLine>
|
<CurrentLine>48</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>
|
||||||
|
@ -674,8 +662,8 @@
|
||||||
<Focus>0</Focus>
|
<Focus>0</Focus>
|
||||||
<ColumnNumber>0</ColumnNumber>
|
<ColumnNumber>0</ColumnNumber>
|
||||||
<tvExpOptDlg>0</tvExpOptDlg>
|
<tvExpOptDlg>0</tvExpOptDlg>
|
||||||
<TopLine>135</TopLine>
|
<TopLine>1</TopLine>
|
||||||
<CurrentLine>146</CurrentLine>
|
<CurrentLine>1</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>
|
||||||
|
@ -737,8 +725,8 @@
|
||||||
<Focus>0</Focus>
|
<Focus>0</Focus>
|
||||||
<ColumnNumber>0</ColumnNumber>
|
<ColumnNumber>0</ColumnNumber>
|
||||||
<tvExpOptDlg>0</tvExpOptDlg>
|
<tvExpOptDlg>0</tvExpOptDlg>
|
||||||
<TopLine>0</TopLine>
|
<TopLine>67</TopLine>
|
||||||
<CurrentLine>0</CurrentLine>
|
<CurrentLine>84</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>
|
||||||
|
@ -763,10 +751,10 @@
|
||||||
<FileType>1</FileType>
|
<FileType>1</FileType>
|
||||||
<tvExp>0</tvExp>
|
<tvExp>0</tvExp>
|
||||||
<Focus>0</Focus>
|
<Focus>0</Focus>
|
||||||
<ColumnNumber>32</ColumnNumber>
|
<ColumnNumber>21</ColumnNumber>
|
||||||
<tvExpOptDlg>0</tvExpOptDlg>
|
<tvExpOptDlg>0</tvExpOptDlg>
|
||||||
<TopLine>0</TopLine>
|
<TopLine>1</TopLine>
|
||||||
<CurrentLine>0</CurrentLine>
|
<CurrentLine>23</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,8 +767,8 @@
|
||||||
<Focus>0</Focus>
|
<Focus>0</Focus>
|
||||||
<ColumnNumber>0</ColumnNumber>
|
<ColumnNumber>0</ColumnNumber>
|
||||||
<tvExpOptDlg>0</tvExpOptDlg>
|
<tvExpOptDlg>0</tvExpOptDlg>
|
||||||
<TopLine>266</TopLine>
|
<TopLine>132</TopLine>
|
||||||
<CurrentLine>293</CurrentLine>
|
<CurrentLine>150</CurrentLine>
|
||||||
<bDave2>0</bDave2>
|
<bDave2>0</bDave2>
|
||||||
<PathWithFileName>.\src\drv_i2c.c</PathWithFileName>
|
<PathWithFileName>.\src\drv_i2c.c</PathWithFileName>
|
||||||
<FilenameWithoutPath>drv_i2c.c</FilenameWithoutPath>
|
<FilenameWithoutPath>drv_i2c.c</FilenameWithoutPath>
|
||||||
|
@ -793,8 +781,8 @@
|
||||||
<Focus>0</Focus>
|
<Focus>0</Focus>
|
||||||
<ColumnNumber>0</ColumnNumber>
|
<ColumnNumber>0</ColumnNumber>
|
||||||
<tvExpOptDlg>0</tvExpOptDlg>
|
<tvExpOptDlg>0</tvExpOptDlg>
|
||||||
<TopLine>1</TopLine>
|
<TopLine>77</TopLine>
|
||||||
<CurrentLine>5</CurrentLine>
|
<CurrentLine>117</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>
|
||||||
|
@ -805,10 +793,10 @@
|
||||||
<FileType>1</FileType>
|
<FileType>1</FileType>
|
||||||
<tvExp>0</tvExp>
|
<tvExp>0</tvExp>
|
||||||
<Focus>0</Focus>
|
<Focus>0</Focus>
|
||||||
<ColumnNumber>0</ColumnNumber>
|
<ColumnNumber>6</ColumnNumber>
|
||||||
<tvExpOptDlg>0</tvExpOptDlg>
|
<tvExpOptDlg>0</tvExpOptDlg>
|
||||||
<TopLine>297</TopLine>
|
<TopLine>253</TopLine>
|
||||||
<CurrentLine>307</CurrentLine>
|
<CurrentLine>278</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>
|
||||||
|
@ -821,8 +809,8 @@
|
||||||
<Focus>0</Focus>
|
<Focus>0</Focus>
|
||||||
<ColumnNumber>0</ColumnNumber>
|
<ColumnNumber>0</ColumnNumber>
|
||||||
<tvExpOptDlg>0</tvExpOptDlg>
|
<tvExpOptDlg>0</tvExpOptDlg>
|
||||||
<TopLine>133</TopLine>
|
<TopLine>32</TopLine>
|
||||||
<CurrentLine>133</CurrentLine>
|
<CurrentLine>39</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>
|
||||||
|
@ -835,8 +823,8 @@
|
||||||
<Focus>0</Focus>
|
<Focus>0</Focus>
|
||||||
<ColumnNumber>0</ColumnNumber>
|
<ColumnNumber>0</ColumnNumber>
|
||||||
<tvExpOptDlg>0</tvExpOptDlg>
|
<tvExpOptDlg>0</tvExpOptDlg>
|
||||||
<TopLine>1</TopLine>
|
<TopLine>0</TopLine>
|
||||||
<CurrentLine>1</CurrentLine>
|
<CurrentLine>0</CurrentLine>
|
||||||
<bDave2>0</bDave2>
|
<bDave2>0</bDave2>
|
||||||
<PathWithFileName>.\src\drv_uart.c</PathWithFileName>
|
<PathWithFileName>.\src\drv_uart.c</PathWithFileName>
|
||||||
<FilenameWithoutPath>drv_uart.c</FilenameWithoutPath>
|
<FilenameWithoutPath>drv_uart.c</FilenameWithoutPath>
|
||||||
|
@ -863,8 +851,8 @@
|
||||||
<Focus>0</Focus>
|
<Focus>0</Focus>
|
||||||
<ColumnNumber>0</ColumnNumber>
|
<ColumnNumber>0</ColumnNumber>
|
||||||
<tvExpOptDlg>0</tvExpOptDlg>
|
<tvExpOptDlg>0</tvExpOptDlg>
|
||||||
<TopLine>472</TopLine>
|
<TopLine>192</TopLine>
|
||||||
<CurrentLine>486</CurrentLine>
|
<CurrentLine>223</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>
|
||||||
|
|
4897
obj/baseflight.hex
4897
obj/baseflight.hex
File diff suppressed because it is too large
Load diff
|
@ -33,10 +33,6 @@ void readEEPROM(void)
|
||||||
// Read flash
|
// Read flash
|
||||||
memcpy(&cfg, (char *)FLASH_WRITE_ADDR, sizeof(config_t));
|
memcpy(&cfg, (char *)FLASH_WRITE_ADDR, sizeof(config_t));
|
||||||
|
|
||||||
#if defined(POWERMETER)
|
|
||||||
pAlarm = (uint32_t) cfg.powerTrigger1 *(uint32_t) PLEVELSCALE *(uint32_t) PLEVELDIV; // need to cast before multiplying
|
|
||||||
#endif
|
|
||||||
|
|
||||||
for (i = 0; i < 7; i++)
|
for (i = 0; i < 7; i++)
|
||||||
lookupRX[i] = (2500 + cfg.rcExpo8 * (i * i - 25)) * i * (int32_t) cfg.rcRate8 / 1250;
|
lookupRX[i] = (2500 + cfg.rcExpo8 * (i * i - 25)) * i * (int32_t) cfg.rcRate8 / 1250;
|
||||||
|
|
||||||
|
@ -116,10 +112,12 @@ void checkFirstTime(bool reset)
|
||||||
}
|
}
|
||||||
cfg.accTrim[0] = 0;
|
cfg.accTrim[0] = 0;
|
||||||
cfg.accTrim[1] = 0;
|
cfg.accTrim[1] = 0;
|
||||||
|
cfg.accZero[0] = 0;
|
||||||
|
cfg.accZero[1] = 0;
|
||||||
|
cfg.accZero[2] = 0;
|
||||||
cfg.acc_lpf_factor = 4;
|
cfg.acc_lpf_factor = 4;
|
||||||
cfg.gyro_lpf = 42;
|
cfg.gyro_lpf = 42;
|
||||||
cfg.gyro_smoothing_factor = 0x00141403; // default factors of 20, 20, 3 for R/P/Y
|
cfg.gyro_smoothing_factor = 0x00141403; // default factors of 20, 20, 3 for R/P/Y
|
||||||
cfg.powerTrigger1 = 0;
|
|
||||||
cfg.vbatscale = 110;
|
cfg.vbatscale = 110;
|
||||||
cfg.vbatmaxcellvoltage = 43;
|
cfg.vbatmaxcellvoltage = 43;
|
||||||
cfg.vbatmincellvoltage = 33;
|
cfg.vbatmincellvoltage = 33;
|
||||||
|
|
|
@ -3,6 +3,7 @@
|
||||||
// ADXL345, Alternative address mode 0x53
|
// ADXL345, Alternative address mode 0x53
|
||||||
#define ADXL345_ADDRESS 0x53
|
#define ADXL345_ADDRESS 0x53
|
||||||
|
|
||||||
|
// Registers
|
||||||
#define ADXL345_BW_RATE 0x2C
|
#define ADXL345_BW_RATE 0x2C
|
||||||
#define ADXL345_POWER_CTL 0x2D
|
#define ADXL345_POWER_CTL 0x2D
|
||||||
#define ADXL345_INT_ENABLE 0x2E
|
#define ADXL345_INT_ENABLE 0x2E
|
||||||
|
@ -10,16 +11,32 @@
|
||||||
#define ADXL345_DATA_OUT 0x32
|
#define ADXL345_DATA_OUT 0x32
|
||||||
#define ADXL345_FIFO_CTL 0x38
|
#define ADXL345_FIFO_CTL 0x38
|
||||||
|
|
||||||
#define ADXL345_BW_RATE_200 0x0B
|
// BW_RATE values
|
||||||
|
#define ADXL345_RATE_50 0x09
|
||||||
|
#define ADXL345_RATE_100 0x0A
|
||||||
|
#define ADXL345_RATE_200 0x0B
|
||||||
|
#define ADXL345_RATE_400 0x0C
|
||||||
|
#define ADXL345_RATE_800 0x0D
|
||||||
|
#define ADXL345_RATE_1600 0x0E
|
||||||
|
#define ADXL345_RATE_3200 0x0F
|
||||||
|
|
||||||
|
// various register values
|
||||||
#define ADXL345_POWER_MEAS 0x08
|
#define ADXL345_POWER_MEAS 0x08
|
||||||
#define ADXL345_FULL_RANGE 0x08
|
#define ADXL345_FULL_RANGE 0x08
|
||||||
|
#define ADXL345_RANGE_2G 0x00
|
||||||
|
#define ADXL345_RANGE_4G 0x01
|
||||||
|
#define ADXL345_RANGE_8G 0x02
|
||||||
#define ADXL345_RANGE_16G 0x03
|
#define ADXL345_RANGE_16G 0x03
|
||||||
|
#define ADXL345_FIFO_STREAM 0x80
|
||||||
|
|
||||||
|
|
||||||
static void adxl345Init(void);
|
static void adxl345Init(void);
|
||||||
static void adxl345Read(int16_t *accelData);
|
static void adxl345Read(int16_t *accelData);
|
||||||
static void adxl345Align(int16_t *accelData);
|
static void adxl345Align(int16_t *accelData);
|
||||||
|
|
||||||
bool adxl345Detect(sensor_t *acc)
|
static bool useFifo = false;
|
||||||
|
|
||||||
|
bool adxl345Detect(drv_adxl345_config_t *init, sensor_t *acc)
|
||||||
{
|
{
|
||||||
bool ack = false;
|
bool ack = false;
|
||||||
uint8_t sig = 0;
|
uint8_t sig = 0;
|
||||||
|
@ -28,49 +45,62 @@ bool adxl345Detect(sensor_t *acc)
|
||||||
if (!ack || sig != 0xE5)
|
if (!ack || sig != 0xE5)
|
||||||
return false;
|
return false;
|
||||||
|
|
||||||
|
// use ADXL345's fifo to filter data or not
|
||||||
|
useFifo = init->useFifo;
|
||||||
|
|
||||||
acc->init = adxl345Init;
|
acc->init = adxl345Init;
|
||||||
acc->read = adxl345Read;
|
acc->read = adxl345Read;
|
||||||
acc->align = adxl345Align;
|
acc->align = adxl345Align;
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
#define ADXL_RATE_100 0x0A
|
|
||||||
#define ADXL_RATE_200 0x0B
|
|
||||||
#define ADXL_RATE_400 0x0C
|
|
||||||
#define ADXL_RATE_800 0x0D
|
|
||||||
#define ADXL_RATE_1600 0x0E
|
|
||||||
#define ADXL_RATE_3200 0x0F
|
|
||||||
#define ADXL_FULL_RES 0x08
|
|
||||||
#define ADXL_RANGE_2G 0x00
|
|
||||||
#define ADXL_RANGE_4G 0x01
|
|
||||||
#define ADXL_RANGE_8G 0x02
|
|
||||||
#define ADXL_RANGE_16G 0x03
|
|
||||||
|
|
||||||
static void adxl345Init(void)
|
static void adxl345Init(void)
|
||||||
{
|
{
|
||||||
#ifdef FREEFLIGHT
|
if (useFifo) {
|
||||||
i2cWrite(ADXL345_ADDRESS, ADXL345_BW_RATE, ADXL345_BW_RATE_200);
|
uint8_t fifoDepth = 16;
|
||||||
i2cWrite(ADXL345_ADDRESS, ADXL345_POWER_CTL, ADXL345_POWER_MEAS);
|
i2cWrite(ADXL345_ADDRESS, ADXL345_POWER_CTL, ADXL345_POWER_MEAS);
|
||||||
i2cWrite(ADXL345_ADDRESS, ADXL345_INT_ENABLE, 0);
|
i2cWrite(ADXL345_ADDRESS, ADXL345_DATA_FORMAT, ADXL345_FULL_RANGE | ADXL345_RANGE_8G);
|
||||||
i2cWrite(ADXL345_ADDRESS, ADXL345_DATA_FORMAT, ADXL345_FULL_RANGE | ADXL345_RANGE_16G);
|
i2cWrite(ADXL345_ADDRESS, ADXL345_BW_RATE, ADXL345_RATE_400);
|
||||||
i2cWrite(ADXL345_ADDRESS, ADXL345_FIFO_CTL, 0);
|
i2cWrite(ADXL345_ADDRESS, ADXL345_FIFO_CTL, (fifoDepth & 0x1F) | ADXL345_FIFO_STREAM);
|
||||||
#else
|
} else {
|
||||||
// MWC defaults
|
i2cWrite(ADXL345_ADDRESS, ADXL345_POWER_CTL, ADXL345_POWER_MEAS);
|
||||||
i2cWrite(ADXL345_ADDRESS, ADXL345_POWER_CTL, 1 << 3); // register: Power CTRL -- value: Set measure bit 3 on
|
i2cWrite(ADXL345_ADDRESS, ADXL345_DATA_FORMAT, ADXL345_FULL_RANGE | ADXL345_RANGE_8G);
|
||||||
i2cWrite(ADXL345_ADDRESS, ADXL345_DATA_FORMAT, 0x0B); // register: DATA_FORMAT -- value: Set bits 3(full range) and 1 0 on (+/- 16g-range)
|
i2cWrite(ADXL345_ADDRESS, ADXL345_BW_RATE, ADXL345_RATE_100);
|
||||||
i2cWrite(ADXL345_ADDRESS, ADXL345_BW_RATE, 0x09); // register: BW_RATE -- value: rate=50hz, bw=20hz
|
|
||||||
#endif /* FreeFlight */
|
|
||||||
}
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
uint8_t acc_samples = 0;
|
||||||
|
|
||||||
static void adxl345Read(int16_t *accelData)
|
static void adxl345Read(int16_t *accelData)
|
||||||
{
|
{
|
||||||
static uint8_t buf[6];
|
uint8_t buf[8];
|
||||||
|
|
||||||
|
if (useFifo) {
|
||||||
|
int32_t x = 0;
|
||||||
|
int32_t y = 0;
|
||||||
|
int32_t z = 0;
|
||||||
|
uint8_t i = 0;
|
||||||
|
uint8_t samples_remaining;
|
||||||
|
|
||||||
|
do {
|
||||||
|
i++;
|
||||||
|
i2cRead(ADXL345_ADDRESS, ADXL345_DATA_OUT, 8, buf);
|
||||||
|
x += (int16_t)(buf[0] + (buf[1] << 8));
|
||||||
|
y += (int16_t)(buf[2] + (buf[3] << 8));
|
||||||
|
z += (int16_t)(buf[4] + (buf[5] << 8));
|
||||||
|
samples_remaining = buf[7] & 0x7F;
|
||||||
|
} while ((i < 32) && (samples_remaining > 0));
|
||||||
|
accelData[0] = x / i;
|
||||||
|
accelData[1] = y / i;
|
||||||
|
accelData[2] = z / i;
|
||||||
|
acc_samples = i;
|
||||||
|
} else {
|
||||||
i2cRead(ADXL345_ADDRESS, ADXL345_DATA_OUT, 6, buf);
|
i2cRead(ADXL345_ADDRESS, ADXL345_DATA_OUT, 6, buf);
|
||||||
accelData[0] = buf[0] + (buf[1] << 8);
|
accelData[0] = buf[0] + (buf[1] << 8);
|
||||||
accelData[1] = buf[2] + (buf[3] << 8);
|
accelData[1] = buf[2] + (buf[3] << 8);
|
||||||
accelData[2] = buf[4] + (buf[5] << 8);
|
accelData[2] = buf[4] + (buf[5] << 8);
|
||||||
}
|
}
|
||||||
|
}
|
||||||
|
|
||||||
static void adxl345Align(int16_t *accData)
|
static void adxl345Align(int16_t *accData)
|
||||||
{
|
{
|
||||||
|
|
|
@ -1,3 +1,8 @@
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
bool adxl345Detect(sensor_t *acc);
|
typedef struct drv_adxl345_config_t {
|
||||||
|
bool useFifo;
|
||||||
|
uint16_t dataRate;
|
||||||
|
} drv_adxl345_config_t;
|
||||||
|
|
||||||
|
bool adxl345Detect(drv_adxl345_config_t *init, sensor_t *acc);
|
||||||
|
|
|
@ -353,6 +353,13 @@ bool pwmInit(drv_pwm_config_t *init)
|
||||||
// turn on more motor outputs if we're using ppm / not using pwm input
|
// turn on more motor outputs if we're using ppm / not using pwm input
|
||||||
if (!init->enableInput || init->usePPM) {
|
if (!init->enableInput || init->usePPM) {
|
||||||
// PWM 7,8,9,10
|
// PWM 7,8,9,10
|
||||||
|
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_6 | GPIO_Pin_7;
|
||||||
|
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP;
|
||||||
|
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
|
||||||
|
GPIO_Init(GPIOA, &GPIO_InitStructure);
|
||||||
|
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_0 | GPIO_Pin_1;
|
||||||
|
GPIO_Init(GPIOB, &GPIO_InitStructure);
|
||||||
|
|
||||||
TIM_TimeBaseStructure.TIM_Period = (1000000 / init->motorPwmRate) - 1;
|
TIM_TimeBaseStructure.TIM_Period = (1000000 / init->motorPwmRate) - 1;
|
||||||
TIM_TimeBaseInit(TIM3, &TIM_TimeBaseStructure);
|
TIM_TimeBaseInit(TIM3, &TIM_TimeBaseStructure);
|
||||||
|
|
||||||
|
|
|
@ -246,8 +246,8 @@ void getEstimatedAltitude(void)
|
||||||
static uint32_t deadLine = INIT_DELAY;
|
static uint32_t deadLine = INIT_DELAY;
|
||||||
static int16_t BaroHistTab[BARO_TAB_SIZE];
|
static int16_t BaroHistTab[BARO_TAB_SIZE];
|
||||||
static int8_t BaroHistIdx;
|
static int8_t BaroHistIdx;
|
||||||
int32_t BaroHigh = 0;
|
static int32_t BaroHigh = 0;
|
||||||
int32_t BaroLow = 0;
|
static int32_t BaroLow = 0;
|
||||||
int32_t temp32;
|
int32_t temp32;
|
||||||
int16_t last;
|
int16_t last;
|
||||||
|
|
||||||
|
|
|
@ -101,10 +101,6 @@ int main(void)
|
||||||
|
|
||||||
previousTime = micros();
|
previousTime = micros();
|
||||||
calibratingG = 400;
|
calibratingG = 400;
|
||||||
#if defined(POWERMETER)
|
|
||||||
for (i = 0; i <= PMOTOR_SUM; i++)
|
|
||||||
pMeter[i] = 0;
|
|
||||||
#endif
|
|
||||||
|
|
||||||
// loopy
|
// loopy
|
||||||
while (1) {
|
while (1) {
|
||||||
|
|
20
src/mixer.c
20
src/mixer.c
|
@ -285,24 +285,4 @@ void mixTable(void)
|
||||||
if (armed == 0)
|
if (armed == 0)
|
||||||
motor[i] = cfg.mincommand;
|
motor[i] = cfg.mincommand;
|
||||||
}
|
}
|
||||||
|
|
||||||
#if (LOG_VALUES == 2) || defined(POWERMETER_SOFT)
|
|
||||||
uint32_t amp;
|
|
||||||
/* true cubic function; when divided by vbat_max=126 (12.6V) for 3 cell battery this gives maximum value of ~ 500 */
|
|
||||||
/* Lookup table moved to PROGMEM 11/21/2001 by Danal */
|
|
||||||
static uint16_t amperes[64] = {
|
|
||||||
0, 2, 6, 15, 30, 52, 82, 123, 175, 240, 320, 415, 528, 659, 811, 984, 1181, 1402, 1648, 1923, 2226, 2559, 2924, 3322, 3755, 4224, 4730, 5276, 5861, 6489, 7160, 7875, 8637, 9446, 10304, 11213, 12173, 13187, 14256, 15381, 16564, 17805, 19108, 20472, 21900, 23392, 24951, 26578, 28274, 30041, 31879, 33792, 35779, 37843, 39984, 42205, 44507, 46890, 49358, 51910, 54549, 57276, 60093, 63000};
|
|
||||||
|
|
||||||
if (vbat) { // by all means - must avoid division by zero
|
|
||||||
for (i = 0; i < NUMBER_MOTOR; i++) {
|
|
||||||
amp = amperes[((motor[i] - 1000) >> 4)] / vbat; // range mapped from [1000:2000] => [0:1000]; then break that up into 64 ranges; lookup amp
|
|
||||||
#if (LOG_VALUES == 2)
|
|
||||||
pMeter[i] += amp; // sum up over time the mapped ESC input
|
|
||||||
#endif
|
|
||||||
#if defined(POWERMETER_SOFT)
|
|
||||||
pMeter[PMOTOR_SUM] += amp; // total sum over all motors
|
|
||||||
#endif
|
|
||||||
}
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
}
|
}
|
||||||
|
|
93
src/mw.c
93
src/mw.c
|
@ -60,15 +60,7 @@ uint16_t AccInflightCalibrationMeasurementDone = 0;
|
||||||
uint16_t AccInflightCalibrationSavetoEEProm = 0;
|
uint16_t AccInflightCalibrationSavetoEEProm = 0;
|
||||||
uint16_t AccInflightCalibrationActive = 0;
|
uint16_t AccInflightCalibrationActive = 0;
|
||||||
|
|
||||||
// **********************
|
// Battery monitoring stuff
|
||||||
// power meter
|
|
||||||
// **********************
|
|
||||||
#define PMOTOR_SUM 8 // index into pMeter[] for sum
|
|
||||||
uint32_t pMeter[PMOTOR_SUM + 1]; // we use [0:7] for eight motors,one extra for sum
|
|
||||||
uint8_t pMeterV; // dummy to satisfy the paramStruct logic in ConfigurationLoop()
|
|
||||||
uint32_t pAlarm; // we scale the eeprom value from [0:255] to this value we can directly compare to the sum in pMeter[6]
|
|
||||||
uint16_t powerValue = 0; // last known current
|
|
||||||
uint16_t intPowerMeterSum, intPowerTrigger1;
|
|
||||||
uint8_t batteryCellCount = 3; // cell count
|
uint8_t batteryCellCount = 3; // cell count
|
||||||
uint16_t batteryWarningVoltage; // annoying buzzer after this one, battery ready to be dead
|
uint16_t batteryWarningVoltage; // annoying buzzer after this one, battery ready to be dead
|
||||||
|
|
||||||
|
@ -91,19 +83,9 @@ void blinkLED(uint8_t num, uint8_t wait, uint8_t repeat)
|
||||||
void annexCode(void)
|
void annexCode(void)
|
||||||
{
|
{
|
||||||
static uint32_t buzzerTime, calibratedAccTime;
|
static uint32_t buzzerTime, calibratedAccTime;
|
||||||
#if defined(LCD_TELEMETRY)
|
|
||||||
static uint16_t telemetryTimer = 0, telemetryAutoTimer = 0, psensorTimer = 0;
|
|
||||||
#endif
|
|
||||||
#if defined(LCD_TELEMETRY)
|
|
||||||
static uint8_t telemetryAutoIndex = 0;
|
|
||||||
static char telemetryAutoSequence[] = LCD_TELEMETRY_AUTO;
|
|
||||||
#endif
|
|
||||||
static uint8_t vbatTimer = 0;
|
static uint8_t vbatTimer = 0;
|
||||||
static uint8_t buzzerFreq; //delay between buzzer ring
|
static uint8_t buzzerFreq; //delay between buzzer ring
|
||||||
uint8_t axis, prop1, prop2;
|
uint8_t axis, prop1, prop2;
|
||||||
#if defined(POWERMETER_HARD)
|
|
||||||
uint16_t pMeterRaw; //used for current reading
|
|
||||||
#endif
|
|
||||||
static uint8_t ind = 0;
|
static uint8_t ind = 0;
|
||||||
uint16_t vbatRaw = 0;
|
uint16_t vbatRaw = 0;
|
||||||
static uint16_t vbatRawArray[8];
|
static uint16_t vbatRawArray[8];
|
||||||
|
@ -159,21 +141,6 @@ void annexCode(void)
|
||||||
rcCommand[ROLL] = rcCommand[ROLL] * cosDiff - rcCommand[PITCH] * sinDiff;
|
rcCommand[ROLL] = rcCommand[ROLL] * cosDiff - rcCommand[PITCH] * sinDiff;
|
||||||
rcCommand[PITCH] = rcCommand_PITCH;
|
rcCommand[PITCH] = rcCommand_PITCH;
|
||||||
}
|
}
|
||||||
#if defined(POWERMETER_HARD)
|
|
||||||
if (!(++psensorTimer % PSENSORFREQ)) {
|
|
||||||
pMeterRaw = analogRead(PSENSORPIN);
|
|
||||||
powerValue = (PSENSORNULL > pMeterRaw ? PSENSORNULL - pMeterRaw : pMeterRaw - PSENSORNULL); // do not use abs(), it would induce implicit cast to uint and overrun
|
|
||||||
if (powerValue < 333) { // only accept reasonable values. 333 is empirical
|
|
||||||
#ifdef LOG_VALUES
|
|
||||||
if (powerValue > powerMax)
|
|
||||||
powerMax = powerValue;
|
|
||||||
#endif
|
|
||||||
} else {
|
|
||||||
powerValue = 333;
|
|
||||||
}
|
|
||||||
pMeter[PMOTOR_SUM] += (uint32_t) powerValue;
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
|
|
||||||
if (feature(FEATURE_VBAT)) {
|
if (feature(FEATURE_VBAT)) {
|
||||||
if (!(++vbatTimer % VBATFREQ)) {
|
if (!(++vbatTimer % VBATFREQ)) {
|
||||||
|
@ -184,18 +151,10 @@ void annexCode(void)
|
||||||
}
|
}
|
||||||
if (rcOptions[BOXBEEPERON]) { // unconditional beeper on via AUXn switch
|
if (rcOptions[BOXBEEPERON]) { // unconditional beeper on via AUXn switch
|
||||||
buzzerFreq = 7;
|
buzzerFreq = 7;
|
||||||
} else if (((vbat > batteryWarningVoltage)
|
} else if ((vbat > batteryWarningVoltage) || (vbat < cfg.vbatmincellvoltage)) { //VBAT ok, buzzer off
|
||||||
#if defined(POWERMETER)
|
|
||||||
&& ((pMeter[PMOTOR_SUM] < pAlarm) || (pAlarm == 0))
|
|
||||||
#endif
|
|
||||||
) || (vbat < cfg.vbatmincellvoltage)) { //VBAT ok AND powermeter ok, buzzer off
|
|
||||||
buzzerFreq = 0;
|
buzzerFreq = 0;
|
||||||
buzzerState = 0;
|
buzzerState = 0;
|
||||||
BEEP_OFF;
|
BEEP_OFF;
|
||||||
#if defined(POWERMETER)
|
|
||||||
} else if (pMeter[PMOTOR_SUM] > pAlarm) { // sound alarm for powermeter
|
|
||||||
buzzerFreq = 4;
|
|
||||||
#endif
|
|
||||||
} else
|
} else
|
||||||
buzzerFreq = 4; // low battery
|
buzzerFreq = 4; // low battery
|
||||||
if (buzzerFreq) {
|
if (buzzerFreq) {
|
||||||
|
@ -241,28 +200,6 @@ void annexCode(void)
|
||||||
|
|
||||||
serialCom();
|
serialCom();
|
||||||
|
|
||||||
#if defined(POWERMETER)
|
|
||||||
intPowerMeterSum = (pMeter[PMOTOR_SUM] / PLEVELDIV);
|
|
||||||
intPowerTrigger1 = cfg.powerTrigger1 * PLEVELSCALE;
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifdef LCD_TELEMETRY_AUTO
|
|
||||||
if ((telemetry_auto)
|
|
||||||
&& (!(++telemetryAutoTimer % LCD_TELEMETRY_AUTO_FREQ))) {
|
|
||||||
telemetry = telemetryAutoSequence[++telemetryAutoIndex % strlen(telemetryAutoSequence)];
|
|
||||||
LCDclear(); // make sure to clear away remnants
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
#ifdef LCD_TELEMETRY
|
|
||||||
if (!(++telemetryTimer % LCD_TELEMETRY_FREQ)) {
|
|
||||||
#if (LCD_TELEMETRY_DEBUG+0 > 0)
|
|
||||||
telemetry = LCD_TELEMETRY_DEBUG;
|
|
||||||
#endif
|
|
||||||
if (telemetry)
|
|
||||||
lcd_telemetry();
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
|
|
||||||
if (sensors(SENSOR_GPS)) {
|
if (sensors(SENSOR_GPS)) {
|
||||||
static uint32_t GPSLEDTime;
|
static uint32_t GPSLEDTime;
|
||||||
if (currentTime > GPSLEDTime && (GPS_fix_home == 1)) {
|
if (currentTime > GPSLEDTime && (GPS_fix_home == 1)) {
|
||||||
|
@ -353,21 +290,6 @@ void loop(void)
|
||||||
if (rcData[YAW] < cfg.mincheck && rcData[PITCH] < cfg.mincheck && armed == 0) {
|
if (rcData[YAW] < cfg.mincheck && rcData[PITCH] < cfg.mincheck && armed == 0) {
|
||||||
if (rcDelayCommand == 20)
|
if (rcDelayCommand == 20)
|
||||||
calibratingG = 400;
|
calibratingG = 400;
|
||||||
} else if (rcData[YAW] > cfg.maxcheck && rcData[PITCH] > cfg.maxcheck && armed == 0) {
|
|
||||||
if (rcDelayCommand == 20) {
|
|
||||||
if (cfg.mixerConfiguration == MULTITYPE_TRI) {
|
|
||||||
servo[5] = 1500; // we center the yaw servo in conf mode
|
|
||||||
writeServos();
|
|
||||||
} else if (cfg.mixerConfiguration == MULTITYPE_FLYING_WING) {
|
|
||||||
servo[0] = cfg.wing_left_mid;
|
|
||||||
servo[1] = cfg.wing_right_mid;
|
|
||||||
writeServos();
|
|
||||||
}
|
|
||||||
#if defined(LCD_CONF)
|
|
||||||
configurationLoop(); //beginning LCD configuration
|
|
||||||
#endif
|
|
||||||
previousTime = micros();
|
|
||||||
}
|
|
||||||
} else if (feature(FEATURE_INFLIGHT_ACC_CAL) && (armed == 0 && rcData[YAW] < cfg.mincheck && rcData[PITCH] > cfg.maxcheck && rcData[ROLL] > cfg.maxcheck)) {
|
} else if (feature(FEATURE_INFLIGHT_ACC_CAL) && (armed == 0 && rcData[YAW] < cfg.mincheck && rcData[PITCH] > cfg.maxcheck && rcData[ROLL] > cfg.maxcheck)) {
|
||||||
if (rcDelayCommand == 20) {
|
if (rcDelayCommand == 20) {
|
||||||
if (AccInflightCalibrationMeasurementDone) { // trigger saving into eeprom after landing
|
if (AccInflightCalibrationMeasurementDone) { // trigger saving into eeprom after landing
|
||||||
|
@ -397,16 +319,6 @@ void loop(void)
|
||||||
armed = 1;
|
armed = 1;
|
||||||
headFreeModeHold = heading;
|
headFreeModeHold = heading;
|
||||||
}
|
}
|
||||||
#ifdef LCD_TELEMETRY_AUTO
|
|
||||||
} else if (rcData[ROLL] < cfg.mincheck && rcData[PITCH] > cfg.maxcheck && armed == 0) {
|
|
||||||
if (rcDelayCommand == 20) {
|
|
||||||
if (telemetry_auto) {
|
|
||||||
telemetry_auto = 0;
|
|
||||||
telemetry = 0;
|
|
||||||
} else
|
|
||||||
telemetry_auto = 1;
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
} else
|
} else
|
||||||
rcDelayCommand = 0;
|
rcDelayCommand = 0;
|
||||||
} else if (rcData[THROTTLE] > cfg.maxcheck && armed == 0) {
|
} else if (rcData[THROTTLE] > cfg.maxcheck && armed == 0) {
|
||||||
|
@ -502,6 +414,7 @@ void loop(void)
|
||||||
} else
|
} else
|
||||||
baroMode = 0;
|
baroMode = 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (sensors(SENSOR_MAG)) {
|
if (sensors(SENSOR_MAG)) {
|
||||||
if (rcOptions[BOXMAG]) {
|
if (rcOptions[BOXMAG]) {
|
||||||
if (magMode == 0) {
|
if (magMode == 0) {
|
||||||
|
|
5
src/mw.h
5
src/mw.h
|
@ -106,9 +106,6 @@ typedef enum MultiType
|
||||||
#define CHECKBOXITEMS 11
|
#define CHECKBOXITEMS 11
|
||||||
#define PIDITEMS 8
|
#define PIDITEMS 8
|
||||||
|
|
||||||
// #define ACC_ORIENTATION(X, Y, Z) { accADC[ROLL] = Y; accADC[PITCH] = -X; accADC[YAW] = Z; }
|
|
||||||
// #define GYRO_ORIENTATION(X, Y, Z) { gyroADC[ROLL] = -Y; gyroADC[PITCH] = X; gyroADC[YAW] = Z; }
|
|
||||||
|
|
||||||
#define min(a, b) ((a) < (b) ? (a) : (b))
|
#define min(a, b) ((a) < (b) ? (a) : (b))
|
||||||
#define max(a, b) ((a) > (b) ? (a) : (b))
|
#define max(a, b) ((a) > (b) ? (a) : (b))
|
||||||
#define abs(x) ((x) > 0 ? (x) : -(x))
|
#define abs(x) ((x) > 0 ? (x) : -(x))
|
||||||
|
@ -140,7 +137,6 @@ typedef struct config_t {
|
||||||
|
|
||||||
uint8_t activate1[CHECKBOXITEMS];
|
uint8_t activate1[CHECKBOXITEMS];
|
||||||
uint8_t activate2[CHECKBOXITEMS];
|
uint8_t activate2[CHECKBOXITEMS];
|
||||||
uint8_t powerTrigger1; // trigger for alarm based on power consumption
|
|
||||||
uint8_t vbatscale; // adjust this to match battery voltage to reported value
|
uint8_t vbatscale; // adjust this to match battery voltage to reported value
|
||||||
uint8_t vbatmaxcellvoltage; // maximum voltage per cell, used for auto-detecting battery voltage in 0.1V units, default is 43 (4.3V)
|
uint8_t vbatmaxcellvoltage; // maximum voltage per cell, used for auto-detecting battery voltage in 0.1V units, default is 43 (4.3V)
|
||||||
uint8_t vbatmincellvoltage; // minimum voltage per cell, this triggers battery out alarms, in 0.1V units, default is 33 (3.3V)
|
uint8_t vbatmincellvoltage; // minimum voltage per cell, this triggers battery out alarms, in 0.1V units, default is 33 (3.3V)
|
||||||
|
@ -224,7 +220,6 @@ extern int16_t rcData[8];
|
||||||
extern uint8_t accMode;
|
extern uint8_t accMode;
|
||||||
extern uint8_t magMode;
|
extern uint8_t magMode;
|
||||||
extern uint8_t baroMode;
|
extern uint8_t baroMode;
|
||||||
extern uint16_t intPowerMeterSum, intPowerTrigger1;
|
|
||||||
extern int32_t GPS_latitude, GPS_longitude;
|
extern int32_t GPS_latitude, GPS_longitude;
|
||||||
extern int32_t GPS_latitude_home, GPS_longitude_home;
|
extern int32_t GPS_latitude_home, GPS_longitude_home;
|
||||||
extern int32_t GPS_latitude_hold, GPS_longitude_hold;
|
extern int32_t GPS_latitude_hold, GPS_longitude_hold;
|
||||||
|
|
|
@ -21,8 +21,14 @@ sensor_t gyro; // gyro access functions
|
||||||
|
|
||||||
void sensorsAutodetect(void)
|
void sensorsAutodetect(void)
|
||||||
{
|
{
|
||||||
|
drv_adxl345_config_t acc_params;
|
||||||
|
|
||||||
|
// configure parameters for ADXL345 driver
|
||||||
|
acc_params.useFifo = false;
|
||||||
|
acc_params.dataRate = 800; // unused currently
|
||||||
|
|
||||||
// Detect what's available
|
// Detect what's available
|
||||||
if (!adxl345Detect(&acc))
|
if (!adxl345Detect(&acc_params, &acc))
|
||||||
sensorsClear(SENSOR_ACC);
|
sensorsClear(SENSOR_ACC);
|
||||||
if (!bmp085Init())
|
if (!bmp085Init())
|
||||||
sensorsClear(SENSOR_BARO);
|
sensorsClear(SENSOR_BARO);
|
||||||
|
|
108
src/serial.c
108
src/serial.c
|
@ -35,7 +35,6 @@ void serialCom(void)
|
||||||
case '#':
|
case '#':
|
||||||
cliProcess();
|
cliProcess();
|
||||||
break;
|
break;
|
||||||
|
|
||||||
#ifdef BTSERIAL
|
#ifdef BTSERIAL
|
||||||
case 'K': // receive RC data from Bluetooth Serial adapter as a remote
|
case 'K': // receive RC data from Bluetooth Serial adapter as a remote
|
||||||
rcData[THROTTLE] = (SerialRead(0) * 4) + 1000;
|
rcData[THROTTLE] = (SerialRead(0) * 4) + 1000;
|
||||||
|
@ -44,100 +43,6 @@ void serialCom(void)
|
||||||
rcData[YAW] = (SerialRead(0) * 4) + 1000;
|
rcData[YAW] = (SerialRead(0) * 4) + 1000;
|
||||||
rcData[AUX1] = (SerialRead(0) * 4) + 1000;
|
rcData[AUX1] = (SerialRead(0) * 4) + 1000;
|
||||||
break;
|
break;
|
||||||
#endif
|
|
||||||
#ifdef LCD_TELEMETRY
|
|
||||||
case 'A': // button A press
|
|
||||||
case '1':
|
|
||||||
if (telemetry == 1)
|
|
||||||
telemetry = 0;
|
|
||||||
else {
|
|
||||||
telemetry = 1;
|
|
||||||
LCDclear();
|
|
||||||
}
|
|
||||||
break;
|
|
||||||
case 'B': // button B press
|
|
||||||
case '2':
|
|
||||||
if (telemetry == 2)
|
|
||||||
telemetry = 0;
|
|
||||||
else {
|
|
||||||
telemetry = 2;
|
|
||||||
LCDclear();
|
|
||||||
}
|
|
||||||
break;
|
|
||||||
case 'C': // button C press
|
|
||||||
case '3':
|
|
||||||
if (telemetry == 3)
|
|
||||||
telemetry = 0;
|
|
||||||
else {
|
|
||||||
telemetry = 3;
|
|
||||||
LCDclear();
|
|
||||||
#if defined(LOG_VALUES) && defined(DEBUG)
|
|
||||||
cycleTimeMax = 0; // reset min/max on transition on->off
|
|
||||||
cycleTimeMin = 65535;
|
|
||||||
#endif
|
|
||||||
}
|
|
||||||
break;
|
|
||||||
case 'D': // button D press
|
|
||||||
case '4':
|
|
||||||
if (telemetry == 4)
|
|
||||||
telemetry = 0;
|
|
||||||
else {
|
|
||||||
telemetry = 4;
|
|
||||||
LCDclear();
|
|
||||||
}
|
|
||||||
break;
|
|
||||||
case '5':
|
|
||||||
if (telemetry == 5)
|
|
||||||
telemetry = 0;
|
|
||||||
else {
|
|
||||||
telemetry = 5;
|
|
||||||
LCDclear();
|
|
||||||
}
|
|
||||||
break;
|
|
||||||
case '6':
|
|
||||||
if (telemetry == 6)
|
|
||||||
telemetry = 0;
|
|
||||||
else {
|
|
||||||
telemetry = 6;
|
|
||||||
LCDclear();
|
|
||||||
}
|
|
||||||
break;
|
|
||||||
case '7':
|
|
||||||
if (telemetry == 7)
|
|
||||||
telemetry = 0;
|
|
||||||
else {
|
|
||||||
telemetry = 7;
|
|
||||||
LCDclear();
|
|
||||||
}
|
|
||||||
break;
|
|
||||||
#if defined(LOG_VALUES) && defined(DEBUG)
|
|
||||||
case 'R':
|
|
||||||
//Reset logvalues
|
|
||||||
if (telemetry == 'R')
|
|
||||||
telemetry = 0;
|
|
||||||
else {
|
|
||||||
telemetry = 'R';
|
|
||||||
LCDclear();
|
|
||||||
}
|
|
||||||
break;
|
|
||||||
#endif
|
|
||||||
#ifdef DEBUG
|
|
||||||
case 'F':
|
|
||||||
{
|
|
||||||
if (telemetry == 'F')
|
|
||||||
telemetry = 0;
|
|
||||||
else {
|
|
||||||
telemetry = 'F';
|
|
||||||
LCDclear();
|
|
||||||
}
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
case 'a': // button A release
|
|
||||||
case 'b': // button B release
|
|
||||||
case 'c': // button C release
|
|
||||||
case 'd': // button D release
|
|
||||||
break;
|
|
||||||
#endif
|
#endif
|
||||||
case 'M': // Multiwii @ arduino to GUI all data
|
case 'M': // Multiwii @ arduino to GUI all data
|
||||||
serialize8('M');
|
serialize8('M');
|
||||||
|
@ -181,15 +86,14 @@ void serialCom(void)
|
||||||
for (i = 0; i < CHECKBOXITEMS; i++) {
|
for (i = 0; i < CHECKBOXITEMS; i++) {
|
||||||
serialize8(cfg.activate1[i]);
|
serialize8(cfg.activate1[i]);
|
||||||
serialize8(cfg.activate2[i] | (rcOptions[i] << 7)); // use highest bit to transport state in mwc
|
serialize8(cfg.activate2[i] | (rcOptions[i] << 7)); // use highest bit to transport state in mwc
|
||||||
|
|
||||||
}
|
}
|
||||||
serialize16(GPS_distanceToHome);
|
serialize16(GPS_distanceToHome);
|
||||||
serialize16(GPS_directionToHome + 180);
|
serialize16(GPS_directionToHome + 180);
|
||||||
serialize8(GPS_numSat);
|
serialize8(GPS_numSat);
|
||||||
serialize8(GPS_fix);
|
serialize8(GPS_fix);
|
||||||
serialize8(GPS_update);
|
serialize8(GPS_update);
|
||||||
serialize16(intPowerMeterSum);
|
serialize16(0); // power meter, removed
|
||||||
serialize16(intPowerTrigger1);
|
serialize16(0); // power meter, removed
|
||||||
serialize8(vbat);
|
serialize8(vbat);
|
||||||
serialize16(BaroAlt / 10); // 4 variables are here for general monitoring purpose
|
serialize16(BaroAlt / 10); // 4 variables are here for general monitoring purpose
|
||||||
serialize16(debug2); // debug2
|
serialize16(debug2); // debug2
|
||||||
|
@ -245,12 +149,8 @@ void serialCom(void)
|
||||||
cfg.activate1[i] = uartReadPoll();
|
cfg.activate1[i] = uartReadPoll();
|
||||||
cfg.activate2[i] = uartReadPoll();
|
cfg.activate2[i] = uartReadPoll();
|
||||||
}
|
}
|
||||||
#if defined(POWERMETER)
|
uartReadPoll(); // power meter crap, removed
|
||||||
cfg.powerTrigger1 = (uartReadPoll() + 256 * uartReadPoll()) / PLEVELSCALE; // we rely on writeParams() to compute corresponding pAlarm value
|
uartReadPoll(); // power meter crap, removed
|
||||||
#else
|
|
||||||
uartReadPoll();
|
|
||||||
uartReadPoll(); //7 so we unload the two bytes
|
|
||||||
#endif
|
|
||||||
writeParams();
|
writeParams();
|
||||||
break;
|
break;
|
||||||
case 'S': // GUI to arduino ACC calibration request
|
case 'S': // GUI to arduino ACC calibration request
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue