mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-13 19:40:31 +03:00
rearranged accelerometer autodetect code and allow user override by "set acc_hardware" in CLI (0=autodetect,1=adxl345,2=mpu6050,3=mma845x)
added arm/disarm on left/righ roll while throttle down to configuration options and disabled it by default. "set retarded_arm" in CLI put gyro_cmpf_factor into settings. default is 310, can be increased to decrease acc influence. debug use only. dropped acc_lpf_factor back to 4. those who want it at 100, make it so. cleaned up MPU6050 driver with humanreadable register names got rid of MMGYRO crap - no use git-svn-id: https://afrodevices.googlecode.com/svn/trunk/baseflight@159 7c89a4a9-59b9-e629-4cfe-3a2d53b20e61
This commit is contained in:
parent
e124390bb1
commit
49653ec65e
11 changed files with 5397 additions and 5312 deletions
149
baseflight.uvopt
149
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>
|
||||||
|
@ -157,6 +157,23 @@
|
||||||
<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>
|
<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>
|
</SetRegEntry>
|
||||||
</TargetDriverDllRegistry>
|
</TargetDriverDllRegistry>
|
||||||
|
<Breakpoint>
|
||||||
|
<Bp>
|
||||||
|
<Number>0</Number>
|
||||||
|
<Type>0</Type>
|
||||||
|
<LineNumber>161</LineNumber>
|
||||||
|
<EnabledFlag>1</EnabledFlag>
|
||||||
|
<Address>134240712</Address>
|
||||||
|
<ByteObject>0</ByteObject>
|
||||||
|
<ManyObjects>0</ManyObjects>
|
||||||
|
<SizeOfObject>0</SizeOfObject>
|
||||||
|
<BreakByAccess>0</BreakByAccess>
|
||||||
|
<BreakIfRCount>1</BreakIfRCount>
|
||||||
|
<Filename>F:\rc\freeflight\projects\baseflight\src\drv_mpu6050.c</Filename>
|
||||||
|
<ExecCommand></ExecCommand>
|
||||||
|
<Expression></Expression>
|
||||||
|
</Bp>
|
||||||
|
</Breakpoint>
|
||||||
<WatchWindow1>
|
<WatchWindow1>
|
||||||
<Ww>
|
<Ww>
|
||||||
<count>0</count>
|
<count>0</count>
|
||||||
|
@ -277,7 +294,7 @@
|
||||||
<OPTFL>
|
<OPTFL>
|
||||||
<tvExp>1</tvExp>
|
<tvExp>1</tvExp>
|
||||||
<tvExpOptDlg>0</tvExpOptDlg>
|
<tvExpOptDlg>0</tvExpOptDlg>
|
||||||
<IsCurrentTarget>0</IsCurrentTarget>
|
<IsCurrentTarget>1</IsCurrentTarget>
|
||||||
</OPTFL>
|
</OPTFL>
|
||||||
<CpuCode>255</CpuCode>
|
<CpuCode>255</CpuCode>
|
||||||
<Books>
|
<Books>
|
||||||
|
@ -725,10 +742,10 @@
|
||||||
<FileType>1</FileType>
|
<FileType>1</FileType>
|
||||||
<tvExp>0</tvExp>
|
<tvExp>0</tvExp>
|
||||||
<Focus>0</Focus>
|
<Focus>0</Focus>
|
||||||
<ColumnNumber>15</ColumnNumber>
|
<ColumnNumber>3</ColumnNumber>
|
||||||
<tvExpOptDlg>0</tvExpOptDlg>
|
<tvExpOptDlg>0</tvExpOptDlg>
|
||||||
<TopLine>0</TopLine>
|
<TopLine>25</TopLine>
|
||||||
<CurrentLine>0</CurrentLine>
|
<CurrentLine>49</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>
|
||||||
|
@ -739,10 +756,10 @@
|
||||||
<FileType>1</FileType>
|
<FileType>1</FileType>
|
||||||
<tvExp>0</tvExp>
|
<tvExp>0</tvExp>
|
||||||
<Focus>0</Focus>
|
<Focus>0</Focus>
|
||||||
<ColumnNumber>18</ColumnNumber>
|
<ColumnNumber>46</ColumnNumber>
|
||||||
<tvExpOptDlg>0</tvExpOptDlg>
|
<tvExpOptDlg>0</tvExpOptDlg>
|
||||||
<TopLine>0</TopLine>
|
<TopLine>103</TopLine>
|
||||||
<CurrentLine>0</CurrentLine>
|
<CurrentLine>131</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>
|
||||||
|
@ -753,10 +770,10 @@
|
||||||
<FileType>1</FileType>
|
<FileType>1</FileType>
|
||||||
<tvExp>0</tvExp>
|
<tvExp>0</tvExp>
|
||||||
<Focus>0</Focus>
|
<Focus>0</Focus>
|
||||||
<ColumnNumber>0</ColumnNumber>
|
<ColumnNumber>12</ColumnNumber>
|
||||||
<tvExpOptDlg>0</tvExpOptDlg>
|
<tvExpOptDlg>0</tvExpOptDlg>
|
||||||
<TopLine>48</TopLine>
|
<TopLine>211</TopLine>
|
||||||
<CurrentLine>58</CurrentLine>
|
<CurrentLine>224</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>
|
||||||
|
@ -767,10 +784,10 @@
|
||||||
<FileType>1</FileType>
|
<FileType>1</FileType>
|
||||||
<tvExp>0</tvExp>
|
<tvExp>0</tvExp>
|
||||||
<Focus>0</Focus>
|
<Focus>0</Focus>
|
||||||
<ColumnNumber>0</ColumnNumber>
|
<ColumnNumber>33</ColumnNumber>
|
||||||
<tvExpOptDlg>0</tvExpOptDlg>
|
<tvExpOptDlg>0</tvExpOptDlg>
|
||||||
<TopLine>16</TopLine>
|
<TopLine>66</TopLine>
|
||||||
<CurrentLine>34</CurrentLine>
|
<CurrentLine>66</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>
|
||||||
|
@ -795,10 +812,10 @@
|
||||||
<FileType>1</FileType>
|
<FileType>1</FileType>
|
||||||
<tvExp>0</tvExp>
|
<tvExp>0</tvExp>
|
||||||
<Focus>0</Focus>
|
<Focus>0</Focus>
|
||||||
<ColumnNumber>0</ColumnNumber>
|
<ColumnNumber>30</ColumnNumber>
|
||||||
<tvExpOptDlg>0</tvExpOptDlg>
|
<tvExpOptDlg>0</tvExpOptDlg>
|
||||||
<TopLine>0</TopLine>
|
<TopLine>187</TopLine>
|
||||||
<CurrentLine>0</CurrentLine>
|
<CurrentLine>205</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>
|
||||||
|
@ -809,10 +826,10 @@
|
||||||
<FileType>1</FileType>
|
<FileType>1</FileType>
|
||||||
<tvExp>0</tvExp>
|
<tvExp>0</tvExp>
|
||||||
<Focus>0</Focus>
|
<Focus>0</Focus>
|
||||||
<ColumnNumber>5</ColumnNumber>
|
<ColumnNumber>1</ColumnNumber>
|
||||||
<tvExpOptDlg>0</tvExpOptDlg>
|
<tvExpOptDlg>0</tvExpOptDlg>
|
||||||
<TopLine>49</TopLine>
|
<TopLine>72</TopLine>
|
||||||
<CurrentLine>68</CurrentLine>
|
<CurrentLine>106</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>
|
||||||
|
@ -837,10 +854,10 @@
|
||||||
<FileType>5</FileType>
|
<FileType>5</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>6</TopLine>
|
||||||
<CurrentLine>0</CurrentLine>
|
<CurrentLine>31</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>
|
||||||
|
@ -853,8 +870,8 @@
|
||||||
<Focus>0</Focus>
|
<Focus>0</Focus>
|
||||||
<ColumnNumber>0</ColumnNumber>
|
<ColumnNumber>0</ColumnNumber>
|
||||||
<tvExpOptDlg>0</tvExpOptDlg>
|
<tvExpOptDlg>0</tvExpOptDlg>
|
||||||
<TopLine>0</TopLine>
|
<TopLine>45</TopLine>
|
||||||
<CurrentLine>0</CurrentLine>
|
<CurrentLine>56</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>
|
||||||
|
@ -865,10 +882,10 @@
|
||||||
<FileType>1</FileType>
|
<FileType>1</FileType>
|
||||||
<tvExp>0</tvExp>
|
<tvExp>0</tvExp>
|
||||||
<Focus>0</Focus>
|
<Focus>0</Focus>
|
||||||
<ColumnNumber>0</ColumnNumber>
|
<ColumnNumber>45</ColumnNumber>
|
||||||
<tvExpOptDlg>0</tvExpOptDlg>
|
<tvExpOptDlg>0</tvExpOptDlg>
|
||||||
<TopLine>0</TopLine>
|
<TopLine>169</TopLine>
|
||||||
<CurrentLine>0</CurrentLine>
|
<CurrentLine>169</CurrentLine>
|
||||||
<bDave2>0</bDave2>
|
<bDave2>0</bDave2>
|
||||||
<PathWithFileName>.\src\gps.c</PathWithFileName>
|
<PathWithFileName>.\src\gps.c</PathWithFileName>
|
||||||
<FilenameWithoutPath>gps.c</FilenameWithoutPath>
|
<FilenameWithoutPath>gps.c</FilenameWithoutPath>
|
||||||
|
@ -928,10 +945,10 @@
|
||||||
<FileType>1</FileType>
|
<FileType>1</FileType>
|
||||||
<tvExp>0</tvExp>
|
<tvExp>0</tvExp>
|
||||||
<Focus>0</Focus>
|
<Focus>0</Focus>
|
||||||
<ColumnNumber>17</ColumnNumber>
|
<ColumnNumber>20</ColumnNumber>
|
||||||
<tvExpOptDlg>0</tvExpOptDlg>
|
<tvExpOptDlg>0</tvExpOptDlg>
|
||||||
<TopLine>59</TopLine>
|
<TopLine>25</TopLine>
|
||||||
<CurrentLine>71</CurrentLine>
|
<CurrentLine>43</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>
|
||||||
|
@ -944,8 +961,8 @@
|
||||||
<Focus>0</Focus>
|
<Focus>0</Focus>
|
||||||
<ColumnNumber>0</ColumnNumber>
|
<ColumnNumber>0</ColumnNumber>
|
||||||
<tvExpOptDlg>0</tvExpOptDlg>
|
<tvExpOptDlg>0</tvExpOptDlg>
|
||||||
<TopLine>0</TopLine>
|
<TopLine>55</TopLine>
|
||||||
<CurrentLine>0</CurrentLine>
|
<CurrentLine>79</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>
|
||||||
|
@ -956,10 +973,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>0</TopLine>
|
<TopLine>39</TopLine>
|
||||||
<CurrentLine>0</CurrentLine>
|
<CurrentLine>44</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>
|
||||||
|
@ -970,10 +987,10 @@
|
||||||
<FileType>1</FileType>
|
<FileType>1</FileType>
|
||||||
<tvExp>0</tvExp>
|
<tvExp>0</tvExp>
|
||||||
<Focus>0</Focus>
|
<Focus>0</Focus>
|
||||||
<ColumnNumber>34</ColumnNumber>
|
<ColumnNumber>0</ColumnNumber>
|
||||||
<tvExpOptDlg>0</tvExpOptDlg>
|
<tvExpOptDlg>0</tvExpOptDlg>
|
||||||
<TopLine>133</TopLine>
|
<TopLine>133</TopLine>
|
||||||
<CurrentLine>158</CurrentLine>
|
<CurrentLine>143</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>
|
||||||
|
@ -986,7 +1003,7 @@
|
||||||
<Focus>0</Focus>
|
<Focus>0</Focus>
|
||||||
<ColumnNumber>0</ColumnNumber>
|
<ColumnNumber>0</ColumnNumber>
|
||||||
<tvExpOptDlg>0</tvExpOptDlg>
|
<tvExpOptDlg>0</tvExpOptDlg>
|
||||||
<TopLine>73</TopLine>
|
<TopLine>77</TopLine>
|
||||||
<CurrentLine>98</CurrentLine>
|
<CurrentLine>98</CurrentLine>
|
||||||
<bDave2>0</bDave2>
|
<bDave2>0</bDave2>
|
||||||
<PathWithFileName>.\src\drv_mpu3050.c</PathWithFileName>
|
<PathWithFileName>.\src\drv_mpu3050.c</PathWithFileName>
|
||||||
|
@ -1000,8 +1017,8 @@
|
||||||
<Focus>0</Focus>
|
<Focus>0</Focus>
|
||||||
<ColumnNumber>0</ColumnNumber>
|
<ColumnNumber>0</ColumnNumber>
|
||||||
<tvExpOptDlg>0</tvExpOptDlg>
|
<tvExpOptDlg>0</tvExpOptDlg>
|
||||||
<TopLine>0</TopLine>
|
<TopLine>220</TopLine>
|
||||||
<CurrentLine>0</CurrentLine>
|
<CurrentLine>220</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>
|
||||||
|
@ -1014,8 +1031,8 @@
|
||||||
<Focus>0</Focus>
|
<Focus>0</Focus>
|
||||||
<ColumnNumber>0</ColumnNumber>
|
<ColumnNumber>0</ColumnNumber>
|
||||||
<tvExpOptDlg>0</tvExpOptDlg>
|
<tvExpOptDlg>0</tvExpOptDlg>
|
||||||
<TopLine>36</TopLine>
|
<TopLine>38</TopLine>
|
||||||
<CurrentLine>46</CurrentLine>
|
<CurrentLine>59</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>
|
||||||
|
@ -1054,10 +1071,10 @@
|
||||||
<FileType>1</FileType>
|
<FileType>1</FileType>
|
||||||
<tvExp>0</tvExp>
|
<tvExp>0</tvExp>
|
||||||
<Focus>0</Focus>
|
<Focus>0</Focus>
|
||||||
<ColumnNumber>0</ColumnNumber>
|
<ColumnNumber>13</ColumnNumber>
|
||||||
<tvExpOptDlg>0</tvExpOptDlg>
|
<tvExpOptDlg>0</tvExpOptDlg>
|
||||||
<TopLine>149</TopLine>
|
<TopLine>130</TopLine>
|
||||||
<CurrentLine>163</CurrentLine>
|
<CurrentLine>148</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>
|
||||||
|
@ -1092,14 +1109,14 @@
|
||||||
</File>
|
</File>
|
||||||
<File>
|
<File>
|
||||||
<GroupNumber>2</GroupNumber>
|
<GroupNumber>2</GroupNumber>
|
||||||
<FileNumber>0</FileNumber>
|
<FileNumber>27</FileNumber>
|
||||||
<FileType>1</FileType>
|
<FileType>1</FileType>
|
||||||
<tvExp>0</tvExp>
|
<tvExp>0</tvExp>
|
||||||
<Focus>0</Focus>
|
<Focus>0</Focus>
|
||||||
<ColumnNumber>0</ColumnNumber>
|
<ColumnNumber>35</ColumnNumber>
|
||||||
<tvExpOptDlg>0</tvExpOptDlg>
|
<tvExpOptDlg>0</tvExpOptDlg>
|
||||||
<TopLine>57</TopLine>
|
<TopLine>43</TopLine>
|
||||||
<CurrentLine>80</CurrentLine>
|
<CurrentLine>43</CurrentLine>
|
||||||
<bDave2>0</bDave2>
|
<bDave2>0</bDave2>
|
||||||
<PathWithFileName>.\src\drv_mma845x.c</PathWithFileName>
|
<PathWithFileName>.\src\drv_mma845x.c</PathWithFileName>
|
||||||
<FilenameWithoutPath>drv_mma845x.c</FilenameWithoutPath>
|
<FilenameWithoutPath>drv_mma845x.c</FilenameWithoutPath>
|
||||||
|
@ -1113,7 +1130,7 @@
|
||||||
<cbSel>0</cbSel>
|
<cbSel>0</cbSel>
|
||||||
<File>
|
<File>
|
||||||
<GroupNumber>3</GroupNumber>
|
<GroupNumber>3</GroupNumber>
|
||||||
<FileNumber>27</FileNumber>
|
<FileNumber>28</FileNumber>
|
||||||
<FileType>1</FileType>
|
<FileType>1</FileType>
|
||||||
<tvExp>0</tvExp>
|
<tvExp>0</tvExp>
|
||||||
<Focus>0</Focus>
|
<Focus>0</Focus>
|
||||||
|
@ -1127,7 +1144,7 @@
|
||||||
</File>
|
</File>
|
||||||
<File>
|
<File>
|
||||||
<GroupNumber>3</GroupNumber>
|
<GroupNumber>3</GroupNumber>
|
||||||
<FileNumber>28</FileNumber>
|
<FileNumber>29</FileNumber>
|
||||||
<FileType>1</FileType>
|
<FileType>1</FileType>
|
||||||
<tvExp>0</tvExp>
|
<tvExp>0</tvExp>
|
||||||
<Focus>0</Focus>
|
<Focus>0</Focus>
|
||||||
|
@ -1141,7 +1158,7 @@
|
||||||
</File>
|
</File>
|
||||||
<File>
|
<File>
|
||||||
<GroupNumber>3</GroupNumber>
|
<GroupNumber>3</GroupNumber>
|
||||||
<FileNumber>29</FileNumber>
|
<FileNumber>30</FileNumber>
|
||||||
<FileType>1</FileType>
|
<FileType>1</FileType>
|
||||||
<tvExp>0</tvExp>
|
<tvExp>0</tvExp>
|
||||||
<Focus>0</Focus>
|
<Focus>0</Focus>
|
||||||
|
@ -1155,7 +1172,7 @@
|
||||||
</File>
|
</File>
|
||||||
<File>
|
<File>
|
||||||
<GroupNumber>3</GroupNumber>
|
<GroupNumber>3</GroupNumber>
|
||||||
<FileNumber>30</FileNumber>
|
<FileNumber>31</FileNumber>
|
||||||
<FileType>1</FileType>
|
<FileType>1</FileType>
|
||||||
<tvExp>0</tvExp>
|
<tvExp>0</tvExp>
|
||||||
<Focus>0</Focus>
|
<Focus>0</Focus>
|
||||||
|
@ -1169,7 +1186,7 @@
|
||||||
</File>
|
</File>
|
||||||
<File>
|
<File>
|
||||||
<GroupNumber>3</GroupNumber>
|
<GroupNumber>3</GroupNumber>
|
||||||
<FileNumber>31</FileNumber>
|
<FileNumber>32</FileNumber>
|
||||||
<FileType>1</FileType>
|
<FileType>1</FileType>
|
||||||
<tvExp>0</tvExp>
|
<tvExp>0</tvExp>
|
||||||
<Focus>0</Focus>
|
<Focus>0</Focus>
|
||||||
|
@ -1183,7 +1200,7 @@
|
||||||
</File>
|
</File>
|
||||||
<File>
|
<File>
|
||||||
<GroupNumber>3</GroupNumber>
|
<GroupNumber>3</GroupNumber>
|
||||||
<FileNumber>32</FileNumber>
|
<FileNumber>33</FileNumber>
|
||||||
<FileType>1</FileType>
|
<FileType>1</FileType>
|
||||||
<tvExp>0</tvExp>
|
<tvExp>0</tvExp>
|
||||||
<Focus>0</Focus>
|
<Focus>0</Focus>
|
||||||
|
@ -1197,7 +1214,7 @@
|
||||||
</File>
|
</File>
|
||||||
<File>
|
<File>
|
||||||
<GroupNumber>3</GroupNumber>
|
<GroupNumber>3</GroupNumber>
|
||||||
<FileNumber>33</FileNumber>
|
<FileNumber>34</FileNumber>
|
||||||
<FileType>1</FileType>
|
<FileType>1</FileType>
|
||||||
<tvExp>0</tvExp>
|
<tvExp>0</tvExp>
|
||||||
<Focus>0</Focus>
|
<Focus>0</Focus>
|
||||||
|
@ -1211,7 +1228,7 @@
|
||||||
</File>
|
</File>
|
||||||
<File>
|
<File>
|
||||||
<GroupNumber>3</GroupNumber>
|
<GroupNumber>3</GroupNumber>
|
||||||
<FileNumber>34</FileNumber>
|
<FileNumber>35</FileNumber>
|
||||||
<FileType>1</FileType>
|
<FileType>1</FileType>
|
||||||
<tvExp>0</tvExp>
|
<tvExp>0</tvExp>
|
||||||
<Focus>0</Focus>
|
<Focus>0</Focus>
|
||||||
|
@ -1225,7 +1242,7 @@
|
||||||
</File>
|
</File>
|
||||||
<File>
|
<File>
|
||||||
<GroupNumber>3</GroupNumber>
|
<GroupNumber>3</GroupNumber>
|
||||||
<FileNumber>35</FileNumber>
|
<FileNumber>36</FileNumber>
|
||||||
<FileType>1</FileType>
|
<FileType>1</FileType>
|
||||||
<tvExp>0</tvExp>
|
<tvExp>0</tvExp>
|
||||||
<Focus>0</Focus>
|
<Focus>0</Focus>
|
||||||
|
@ -1239,7 +1256,7 @@
|
||||||
</File>
|
</File>
|
||||||
<File>
|
<File>
|
||||||
<GroupNumber>3</GroupNumber>
|
<GroupNumber>3</GroupNumber>
|
||||||
<FileNumber>36</FileNumber>
|
<FileNumber>37</FileNumber>
|
||||||
<FileType>1</FileType>
|
<FileType>1</FileType>
|
||||||
<tvExp>0</tvExp>
|
<tvExp>0</tvExp>
|
||||||
<Focus>0</Focus>
|
<Focus>0</Focus>
|
||||||
|
@ -1253,7 +1270,7 @@
|
||||||
</File>
|
</File>
|
||||||
<File>
|
<File>
|
||||||
<GroupNumber>3</GroupNumber>
|
<GroupNumber>3</GroupNumber>
|
||||||
<FileNumber>37</FileNumber>
|
<FileNumber>38</FileNumber>
|
||||||
<FileType>1</FileType>
|
<FileType>1</FileType>
|
||||||
<tvExp>0</tvExp>
|
<tvExp>0</tvExp>
|
||||||
<Focus>0</Focus>
|
<Focus>0</Focus>
|
||||||
|
@ -1267,7 +1284,7 @@
|
||||||
</File>
|
</File>
|
||||||
<File>
|
<File>
|
||||||
<GroupNumber>3</GroupNumber>
|
<GroupNumber>3</GroupNumber>
|
||||||
<FileNumber>38</FileNumber>
|
<FileNumber>39</FileNumber>
|
||||||
<FileType>1</FileType>
|
<FileType>1</FileType>
|
||||||
<tvExp>0</tvExp>
|
<tvExp>0</tvExp>
|
||||||
<Focus>0</Focus>
|
<Focus>0</Focus>
|
||||||
|
@ -1281,21 +1298,21 @@
|
||||||
</File>
|
</File>
|
||||||
<File>
|
<File>
|
||||||
<GroupNumber>3</GroupNumber>
|
<GroupNumber>3</GroupNumber>
|
||||||
<FileNumber>39</FileNumber>
|
<FileNumber>40</FileNumber>
|
||||||
<FileType>2</FileType>
|
<FileType>2</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>133</TopLine>
|
<TopLine>0</TopLine>
|
||||||
<CurrentLine>133</CurrentLine>
|
<CurrentLine>0</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>
|
<File>
|
||||||
<GroupNumber>3</GroupNumber>
|
<GroupNumber>3</GroupNumber>
|
||||||
<FileNumber>40</FileNumber>
|
<FileNumber>41</FileNumber>
|
||||||
<FileType>2</FileType>
|
<FileType>2</FileType>
|
||||||
<tvExp>0</tvExp>
|
<tvExp>0</tvExp>
|
||||||
<Focus>0</Focus>
|
<Focus>0</Focus>
|
||||||
|
|
5167
obj/baseflight.hex
5167
obj/baseflight.hex
File diff suppressed because it is too large
Load diff
File diff suppressed because it is too large
Load diff
|
@ -26,6 +26,14 @@ typedef enum {
|
||||||
SENSOR_GPS = 1 << 4,
|
SENSOR_GPS = 1 << 4,
|
||||||
} AvailableSensors;
|
} AvailableSensors;
|
||||||
|
|
||||||
|
// Type of accelerometer used/detected
|
||||||
|
typedef enum AccelSensors {
|
||||||
|
ACC_DEFAULT = 0,
|
||||||
|
ACC_ADXL345 = 1,
|
||||||
|
ACC_MPU6050 = 2,
|
||||||
|
ACC_MMA8452 = 3,
|
||||||
|
} AccelSensors;
|
||||||
|
|
||||||
typedef enum {
|
typedef enum {
|
||||||
FEATURE_PPM = 1 << 0,
|
FEATURE_PPM = 1 << 0,
|
||||||
FEATURE_VBAT = 1 << 1,
|
FEATURE_VBAT = 1 << 1,
|
||||||
|
|
|
@ -48,7 +48,7 @@ const char *sensorNames[] = {
|
||||||
|
|
||||||
//
|
//
|
||||||
const char *accNames[] = {
|
const char *accNames[] = {
|
||||||
"ADXL345", "MPU6050", "MMA845x", NULL
|
"", "ADXL345", "MPU6050", "MMA845x", NULL
|
||||||
};
|
};
|
||||||
|
|
||||||
typedef struct {
|
typedef struct {
|
||||||
|
@ -97,6 +97,7 @@ const clivalue_t valueTable[] = {
|
||||||
{ "mincommand", VAR_UINT16, &cfg.mincommand, 0, 2000 },
|
{ "mincommand", VAR_UINT16, &cfg.mincommand, 0, 2000 },
|
||||||
{ "mincheck", VAR_UINT16, &cfg.mincheck, 0, 2000 },
|
{ "mincheck", VAR_UINT16, &cfg.mincheck, 0, 2000 },
|
||||||
{ "maxcheck", VAR_UINT16, &cfg.maxcheck, 0, 2000 },
|
{ "maxcheck", VAR_UINT16, &cfg.maxcheck, 0, 2000 },
|
||||||
|
{ "retarded_arm", VAR_UINT8, &cfg.retarded_arm, 0, 1 },
|
||||||
{ "failsafe_delay", VAR_UINT8, &cfg.failsafe_delay, 0, 200 },
|
{ "failsafe_delay", VAR_UINT8, &cfg.failsafe_delay, 0, 200 },
|
||||||
{ "failsafe_off_delay", VAR_UINT8, &cfg.failsafe_off_delay, 0, 200 },
|
{ "failsafe_off_delay", VAR_UINT8, &cfg.failsafe_off_delay, 0, 200 },
|
||||||
{ "failsafe_throttle", VAR_UINT16, &cfg.failsafe_throttle, 1000, 2000 },
|
{ "failsafe_throttle", VAR_UINT16, &cfg.failsafe_throttle, 1000, 2000 },
|
||||||
|
@ -121,8 +122,10 @@ const clivalue_t valueTable[] = {
|
||||||
{ "gimbal_roll_min", VAR_UINT16, &cfg.gimbal_roll_min, 100, 3000 },
|
{ "gimbal_roll_min", VAR_UINT16, &cfg.gimbal_roll_min, 100, 3000 },
|
||||||
{ "gimbal_roll_max", VAR_UINT16, &cfg.gimbal_roll_max, 100, 3000 },
|
{ "gimbal_roll_max", VAR_UINT16, &cfg.gimbal_roll_max, 100, 3000 },
|
||||||
{ "gimbal_roll_mid", VAR_UINT16, &cfg.gimbal_roll_mid, 100, 3000 },
|
{ "gimbal_roll_mid", VAR_UINT16, &cfg.gimbal_roll_mid, 100, 3000 },
|
||||||
|
{ "acc_hardware", VAR_UINT8, &cfg.acc_hardware, 0, 3 },
|
||||||
{ "acc_lpf_factor", VAR_UINT8, &cfg.acc_lpf_factor, 0, 250 },
|
{ "acc_lpf_factor", VAR_UINT8, &cfg.acc_lpf_factor, 0, 250 },
|
||||||
{ "gyro_lpf", VAR_UINT16, &cfg.gyro_lpf, 0, 256 },
|
{ "gyro_lpf", VAR_UINT16, &cfg.gyro_lpf, 0, 256 },
|
||||||
|
{ "gyro_cmpf_factor", VAR_UINT16, &cfg.gyro_cmpf_factor, 100, 1000 },
|
||||||
{ "mag_declination", VAR_INT16, &cfg.mag_declination, -18000, 18000 },
|
{ "mag_declination", VAR_INT16, &cfg.mag_declination, -18000, 18000 },
|
||||||
{ "gps_baudrate", VAR_UINT32, &cfg.gps_baudrate, 1200, 115200 },
|
{ "gps_baudrate", VAR_UINT32, &cfg.gps_baudrate, 1200, 115200 },
|
||||||
{ "serial_baudrate", VAR_UINT32, &cfg.serial_baudrate, 1200, 115200 },
|
{ "serial_baudrate", VAR_UINT32, &cfg.serial_baudrate, 1200, 115200 },
|
||||||
|
|
|
@ -13,7 +13,7 @@ config_t cfg;
|
||||||
const char rcChannelLetters[] = "AERT1234";
|
const char rcChannelLetters[] = "AERT1234";
|
||||||
|
|
||||||
static uint32_t enabledSensors = 0;
|
static uint32_t enabledSensors = 0;
|
||||||
uint8_t checkNewConf = 17;
|
uint8_t checkNewConf = 18;
|
||||||
|
|
||||||
void parseRcChannels(const char *input)
|
void parseRcChannels(const char *input)
|
||||||
{
|
{
|
||||||
|
@ -128,7 +128,9 @@ void checkFirstTime(bool reset)
|
||||||
cfg.accZero[1] = 0;
|
cfg.accZero[1] = 0;
|
||||||
cfg.accZero[2] = 0;
|
cfg.accZero[2] = 0;
|
||||||
cfg.mag_declination = 0; // For example, -6deg 37min, = -637 Japan, format is [sign]dddmm (degreesminutes) default is zero.
|
cfg.mag_declination = 0; // For example, -6deg 37min, = -637 Japan, format is [sign]dddmm (degreesminutes) default is zero.
|
||||||
cfg.acc_lpf_factor = 100;
|
cfg.acc_hardware = ACC_DEFAULT; // default/autodetect
|
||||||
|
cfg.acc_lpf_factor = 4;
|
||||||
|
cfg.gyro_cmpf_factor = 310; // default MWC
|
||||||
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.vbatscale = 110;
|
cfg.vbatscale = 110;
|
||||||
|
@ -143,6 +145,7 @@ void checkFirstTime(bool reset)
|
||||||
cfg.midrc = 1500;
|
cfg.midrc = 1500;
|
||||||
cfg.mincheck = 1100;
|
cfg.mincheck = 1100;
|
||||||
cfg.maxcheck = 1900;
|
cfg.maxcheck = 1900;
|
||||||
|
cfg.retarded_arm = 0; // disable arm/disarm on roll left/right
|
||||||
|
|
||||||
// Failsafe Variables
|
// Failsafe Variables
|
||||||
cfg.failsafe_delay = 10; // 1sec
|
cfg.failsafe_delay = 10; // 1sec
|
||||||
|
|
|
@ -34,6 +34,7 @@
|
||||||
#define MPU_RA_YA_OFFS_L_TC 0x09
|
#define MPU_RA_YA_OFFS_L_TC 0x09
|
||||||
#define MPU_RA_ZA_OFFS_H 0x0A //[15:0] ZA_OFFS
|
#define MPU_RA_ZA_OFFS_H 0x0A //[15:0] ZA_OFFS
|
||||||
#define MPU_RA_ZA_OFFS_L_TC 0x0B
|
#define MPU_RA_ZA_OFFS_L_TC 0x0B
|
||||||
|
#define MPU_RA_PRODUCT_ID 0x0C // Product ID Register
|
||||||
#define MPU_RA_XG_OFFS_USRH 0x13 //[15:0] XG_OFFS_USR
|
#define MPU_RA_XG_OFFS_USRH 0x13 //[15:0] XG_OFFS_USR
|
||||||
#define MPU_RA_XG_OFFS_USRL 0x14
|
#define MPU_RA_XG_OFFS_USRL 0x14
|
||||||
#define MPU_RA_YG_OFFS_USRH 0x15 //[15:0] YG_OFFS_USR
|
#define MPU_RA_YG_OFFS_USRH 0x15 //[15:0] YG_OFFS_USR
|
||||||
|
@ -114,6 +115,18 @@
|
||||||
// #define MPU6050_DLPF_CFG 0 // 256Hz
|
// #define MPU6050_DLPF_CFG 0 // 256Hz
|
||||||
#define MPU6050_DLPF_CFG 3 // 42Hz
|
#define MPU6050_DLPF_CFG 3 // 42Hz
|
||||||
|
|
||||||
|
#define MPU6000ES_REV_C4 0x14
|
||||||
|
#define MPU6000ES_REV_C5 0x15
|
||||||
|
#define MPU6000ES_REV_D6 0x16
|
||||||
|
#define MPU6000ES_REV_D7 0x17
|
||||||
|
#define MPU6000ES_REV_D8 0x18
|
||||||
|
#define MPU6000_REV_C4 0x54
|
||||||
|
#define MPU6000_REV_C5 0x55
|
||||||
|
#define MPU6000_REV_D6 0x56
|
||||||
|
#define MPU6000_REV_D7 0x57
|
||||||
|
#define MPU6000_REV_D8 0x58
|
||||||
|
#define MPU6000_REV_D9 0x59
|
||||||
|
|
||||||
static void mpu6050AccInit(void);
|
static void mpu6050AccInit(void);
|
||||||
static void mpu6050AccRead(int16_t * accData);
|
static void mpu6050AccRead(int16_t * accData);
|
||||||
static void mpu6050AccAlign(int16_t * accData);
|
static void mpu6050AccAlign(int16_t * accData);
|
||||||
|
@ -128,6 +141,7 @@ int16_t dmpGyroData[3];
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
extern uint16_t acc_1G;
|
extern uint16_t acc_1G;
|
||||||
|
uint8_t mpuProductID = 0;
|
||||||
|
|
||||||
bool mpu6050Detect(sensor_t * acc, sensor_t * gyro)
|
bool mpu6050Detect(sensor_t * acc, sensor_t * gyro)
|
||||||
{
|
{
|
||||||
|
@ -143,6 +157,9 @@ bool mpu6050Detect(sensor_t * acc, sensor_t * gyro)
|
||||||
if (sig != MPU6050_ADDRESS)
|
if (sig != MPU6050_ADDRESS)
|
||||||
return false;
|
return false;
|
||||||
|
|
||||||
|
// get chip revision
|
||||||
|
i2cRead(MPU6050_ADDRESS, MPU_RA_PRODUCT_ID, 1, &mpuProductID);
|
||||||
|
|
||||||
acc->init = mpu6050AccInit;
|
acc->init = mpu6050AccInit;
|
||||||
acc->read = mpu6050AccRead;
|
acc->read = mpu6050AccRead;
|
||||||
acc->align = mpu6050AccAlign;
|
acc->align = mpu6050AccAlign;
|
||||||
|
@ -160,11 +177,15 @@ bool mpu6050Detect(sensor_t * acc, sensor_t * gyro)
|
||||||
static void mpu6050AccInit(void)
|
static void mpu6050AccInit(void)
|
||||||
{
|
{
|
||||||
#ifndef MPU6050_DMP
|
#ifndef MPU6050_DMP
|
||||||
i2cWrite(MPU6050_ADDRESS, 0x1C, 0x10); // ACCEL_CONFIG -- AFS_SEL=2 (Full Scale = +/-8G) ; ACCELL_HPF=0 //note something is wrong in the spec.
|
// Product ID detection code from eosBandi (or rather, DIYClones). This doesn't cover product ID for MPU6050 as far as I can tell
|
||||||
|
if ((mpuProductID == MPU6000ES_REV_C4) || (mpuProductID == MPU6000ES_REV_C5) || (mpuProductID == MPU6000_REV_C4) || (mpuProductID == MPU6000_REV_C5)) {
|
||||||
|
// Accel scale 8g (4096 LSB/g)
|
||||||
|
// Rev C has different scaling than rev D
|
||||||
|
i2cWrite(MPU6050_ADDRESS, MPU_RA_ACCEL_CONFIG, 1 << 3);
|
||||||
|
} else {
|
||||||
|
i2cWrite(MPU6050_ADDRESS, MPU_RA_ACCEL_CONFIG, 2 << 3);
|
||||||
|
}
|
||||||
#endif
|
#endif
|
||||||
// note: something seems to be wrong in the spec here. With AFS=2 1G = 4096 but according to my measurement: 1G=2048 (and 2048/8 = 256)
|
|
||||||
// confirmed here: http://www.multiwii.com/forum/viewtopic.php?f=8&t=1080&start=10#p7480
|
|
||||||
// seems to be not a problem on MPU6000 lol
|
|
||||||
acc_1G = 1023;
|
acc_1G = 1023;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -197,12 +218,12 @@ static void mpu6050AccAlign(int16_t * accData)
|
||||||
static void mpu6050GyroInit(void)
|
static void mpu6050GyroInit(void)
|
||||||
{
|
{
|
||||||
#ifndef MPU6050_DMP
|
#ifndef MPU6050_DMP
|
||||||
i2cWrite(MPU6050_ADDRESS, 0x6B, 0x80); //PWR_MGMT_1 -- DEVICE_RESET 1
|
i2cWrite(MPU6050_ADDRESS, MPU_RA_PWR_MGMT_1, 0x80); //PWR_MGMT_1 -- DEVICE_RESET 1
|
||||||
delay(5);
|
delay(5);
|
||||||
i2cWrite(MPU6050_ADDRESS, 0x19, 0x00); //SMPLRT_DIV -- SMPLRT_DIV = 0 Sample Rate = Gyroscope Output Rate / (1 + SMPLRT_DIV)
|
i2cWrite(MPU6050_ADDRESS, MPU_RA_SMPLRT_DIV, 0x00); //SMPLRT_DIV -- SMPLRT_DIV = 0 Sample Rate = Gyroscope Output Rate / (1 + SMPLRT_DIV)
|
||||||
i2cWrite(MPU6050_ADDRESS, 0x6B, 0x03); //PWR_MGMT_1 -- SLEEP 0; CYCLE 0; TEMP_DIS 0; CLKSEL 3 (PLL with Z Gyro reference)
|
i2cWrite(MPU6050_ADDRESS, MPU_RA_PWR_MGMT_1, 0x03); //PWR_MGMT_1 -- SLEEP 0; CYCLE 0; TEMP_DIS 0; CLKSEL 3 (PLL with Z Gyro reference)
|
||||||
i2cWrite(MPU6050_ADDRESS, 0x1A, MPU6050_DLPF_CFG); //CONFIG -- EXT_SYNC_SET 0 (disable input pin for data sync) ; default DLPF_CFG = 0 => ACC bandwidth = 260Hz GYRO bandwidth = 256Hz)
|
i2cWrite(MPU6050_ADDRESS, MPU_RA_CONFIG, MPU6050_DLPF_CFG); //CONFIG -- EXT_SYNC_SET 0 (disable input pin for data sync) ; default DLPF_CFG = 0 => ACC bandwidth = 260Hz GYRO bandwidth = 256Hz)
|
||||||
i2cWrite(MPU6050_ADDRESS, 0x1B, 0x18); //GYRO_CONFIG -- FS_SEL = 3: Full scale set to 2000 deg/sec
|
i2cWrite(MPU6050_ADDRESS, MPU_RA_GYRO_CONFIG, 0x18); //GYRO_CONFIG -- FS_SEL = 3: Full scale set to 2000 deg/sec
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -121,7 +121,7 @@ void computeIMU(void)
|
||||||
/* Increasing this value would reduce and delay Acc influence on the output of the filter*/
|
/* Increasing this value would reduce and delay Acc influence on the output of the filter*/
|
||||||
/* Default WMC value: 300*/
|
/* Default WMC value: 300*/
|
||||||
// #define GYR_CMPF_FACTOR 310.0f
|
// #define GYR_CMPF_FACTOR 310.0f
|
||||||
#define GYR_CMPF_FACTOR 500.0f
|
// #define GYR_CMPF_FACTOR 500.0f
|
||||||
|
|
||||||
/* Set the Gyro Weight for Gyro/Magnetometer complementary filter */
|
/* Set the Gyro Weight for Gyro/Magnetometer complementary filter */
|
||||||
/* Increasing this value would reduce and delay Magnetometer influence on the output of the filter*/
|
/* Increasing this value would reduce and delay Magnetometer influence on the output of the filter*/
|
||||||
|
@ -130,7 +130,7 @@ void computeIMU(void)
|
||||||
|
|
||||||
//****** end of advanced users settings *************
|
//****** end of advanced users settings *************
|
||||||
|
|
||||||
#define INV_GYR_CMPF_FACTOR (1.0f / (GYR_CMPF_FACTOR + 1.0f))
|
#define INV_GYR_CMPF_FACTOR (1.0f / ((float)cfg.gyro_cmpf_factor + 1.0f))
|
||||||
#define INV_GYR_CMPFM_FACTOR (1.0f / (GYR_CMPFM_FACTOR + 1.0f))
|
#define INV_GYR_CMPFM_FACTOR (1.0f / (GYR_CMPFM_FACTOR + 1.0f))
|
||||||
|
|
||||||
#define GYRO_SCALE ((1998 * M_PI)/((32767.0f / 4.0f ) * 180.0f * 1000000.0f)) // 32767 / 16.4lsb/dps for MPU3000
|
#define GYRO_SCALE ((1998 * M_PI)/((32767.0f / 4.0f ) * 180.0f * 1000000.0f)) // 32767 / 16.4lsb/dps for MPU3000
|
||||||
|
@ -221,7 +221,7 @@ static void getEstimatedAttitude(void)
|
||||||
// To do that, we just skip filter, as EstV already rotated by Gyro
|
// To do that, we just skip filter, as EstV already rotated by Gyro
|
||||||
if ((36 < accMag && accMag < 196) || smallAngle25) {
|
if ((36 < accMag && accMag < 196) || smallAngle25) {
|
||||||
for (axis = 0; axis < 3; axis++)
|
for (axis = 0; axis < 3; axis++)
|
||||||
EstG.A[axis] = (EstG.A[axis] * GYR_CMPF_FACTOR + accSmooth[axis]) * INV_GYR_CMPF_FACTOR;
|
EstG.A[axis] = (EstG.A[axis] * (float)cfg.gyro_cmpf_factor + accSmooth[axis]) * INV_GYR_CMPF_FACTOR;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (sensors(SENSOR_MAG)) {
|
if (sensors(SENSOR_MAG)) {
|
||||||
|
|
4
src/mw.c
4
src/mw.c
|
@ -326,10 +326,10 @@ void loop(void)
|
||||||
} else if (armed)
|
} else if (armed)
|
||||||
armed = 0;
|
armed = 0;
|
||||||
rcDelayCommand = 0;
|
rcDelayCommand = 0;
|
||||||
} else if ((rcData[YAW] < cfg.mincheck || rcData[ROLL] < cfg.mincheck) && armed == 1) {
|
} else if ((rcData[YAW] < cfg.mincheck || rcData[ROLL] < cfg.mincheck) && armed == 1 && cfg.retarded_arm == 1) {
|
||||||
if (rcDelayCommand == 20)
|
if (rcDelayCommand == 20)
|
||||||
armed = 0; // rcDelayCommand = 20 => 20x20ms = 0.4s = time to wait for a specific RC command to be acknowledged
|
armed = 0; // rcDelayCommand = 20 => 20x20ms = 0.4s = time to wait for a specific RC command to be acknowledged
|
||||||
} else if ((rcData[YAW] > cfg.maxcheck || rcData[ROLL] > cfg.maxcheck) && rcData[PITCH] < cfg.maxcheck && armed == 0 && calibratingG == 0 && calibratedACC == 1) {
|
} else if ((rcData[YAW] > cfg.maxcheck || rcData[ROLL] > cfg.maxcheck) && rcData[PITCH] < cfg.maxcheck && armed == 0 && calibratingG == 0 && calibratedACC == 1 && cfg.retarded_arm == 1) {
|
||||||
if (rcDelayCommand == 20) {
|
if (rcDelayCommand == 20) {
|
||||||
armed = 1;
|
armed = 1;
|
||||||
headFreeModeHold = heading;
|
headFreeModeHold = heading;
|
||||||
|
|
10
src/mw.h
10
src/mw.h
|
@ -53,13 +53,6 @@ typedef enum GimbalFlags {
|
||||||
GIMBAL_DISABLEAUX34 = 1 << 2,
|
GIMBAL_DISABLEAUX34 = 1 << 2,
|
||||||
} GimbalFlags;
|
} GimbalFlags;
|
||||||
|
|
||||||
// Type of accelerometer used
|
|
||||||
typedef enum AccelSensors {
|
|
||||||
ADXL345,
|
|
||||||
MPU6050,
|
|
||||||
MMA845x
|
|
||||||
} AccelSensors;
|
|
||||||
|
|
||||||
/*********** RC alias *****************/
|
/*********** RC alias *****************/
|
||||||
#define ROLL 0
|
#define ROLL 0
|
||||||
#define PITCH 1
|
#define PITCH 1
|
||||||
|
@ -120,8 +113,10 @@ typedef struct config_t {
|
||||||
int16_t accTrim[2];
|
int16_t accTrim[2];
|
||||||
|
|
||||||
// sensor-related stuff
|
// sensor-related stuff
|
||||||
|
uint8_t acc_hardware; // Which acc hardware to use on boards with more than one device
|
||||||
uint8_t acc_lpf_factor; // Set the Low Pass Filter factor for ACC. Increasing this value would reduce ACC noise (visible in GUI), but would increase ACC lag time. Zero = no filter
|
uint8_t acc_lpf_factor; // Set the Low Pass Filter factor for ACC. Increasing this value would reduce ACC noise (visible in GUI), but would increase ACC lag time. Zero = no filter
|
||||||
uint16_t gyro_lpf; // mpuX050 LPF setting
|
uint16_t gyro_lpf; // mpuX050 LPF setting
|
||||||
|
uint16_t gyro_cmpf_factor; // Set the Gyro Weight for Gyro/Acc complementary filter. Increasing this value would reduce and delay Acc influence on the output of the filter.
|
||||||
uint32_t gyro_smoothing_factor; // How much to smoothen with per axis (32bit value with Roll, Pitch, Yaw in bits 24, 16, 8 respectively
|
uint32_t gyro_smoothing_factor; // How much to smoothen with per axis (32bit value with Roll, Pitch, Yaw in bits 24, 16, 8 respectively
|
||||||
|
|
||||||
uint16_t activate[CHECKBOXITEMS]; // activate switches
|
uint16_t activate[CHECKBOXITEMS]; // activate switches
|
||||||
|
@ -137,6 +132,7 @@ typedef struct config_t {
|
||||||
uint16_t midrc; // Some radios have not a neutral point centered on 1500. can be changed here
|
uint16_t midrc; // Some radios have not a neutral point centered on 1500. can be changed here
|
||||||
uint16_t mincheck; // minimum rc end
|
uint16_t mincheck; // minimum rc end
|
||||||
uint16_t maxcheck; // maximum rc end
|
uint16_t maxcheck; // maximum rc end
|
||||||
|
uint8_t retarded_arm; // allow disarsm/arm on throttle down + roll left/right
|
||||||
|
|
||||||
// Failsafe related configuration
|
// Failsafe related configuration
|
||||||
uint8_t failsafe_delay; // Guard time for failsafe activation after signal lost. 1 step = 0.1sec - 1sec in example (10)
|
uint8_t failsafe_delay; // Guard time for failsafe activation after signal lost. 1 step = 0.1sec - 1sec in example (10)
|
||||||
|
|
108
src/sensors.c
108
src/sensors.c
|
@ -19,7 +19,7 @@ extern float magneticDeclination;
|
||||||
|
|
||||||
sensor_t acc; // acc access functions
|
sensor_t acc; // acc access functions
|
||||||
sensor_t gyro; // gyro access functions
|
sensor_t gyro; // gyro access functions
|
||||||
uint8_t accHardware = 0; // which accel chip is used.
|
uint8_t accHardware = ACC_DEFAULT; // which accel chip is used/detected
|
||||||
|
|
||||||
#ifdef FY90Q
|
#ifdef FY90Q
|
||||||
// FY90Q analog gyro/acc
|
// FY90Q analog gyro/acc
|
||||||
|
@ -32,49 +32,73 @@ void sensorsAutodetect(void)
|
||||||
void sensorsAutodetect(void)
|
void sensorsAutodetect(void)
|
||||||
{
|
{
|
||||||
int16_t deg, min;
|
int16_t deg, min;
|
||||||
|
|
||||||
drv_adxl345_config_t acc_params;
|
drv_adxl345_config_t acc_params;
|
||||||
|
bool haveMpu6k = false;
|
||||||
|
|
||||||
// configure parameters for ADXL345 driver
|
// Autodetect gyro hardware. We have MPU3050 or MPU6050.
|
||||||
acc_params.useFifo = false;
|
if (mpu6050Detect(&acc, &gyro)) {
|
||||||
acc_params.dataRate = 800; // unused currently
|
// this filled up acc.* struct with init values
|
||||||
|
haveMpu6k = true;
|
||||||
// Detect what's available
|
|
||||||
if (!adxl345Detect(&acc_params, &acc))
|
|
||||||
sensorsClear(SENSOR_ACC);
|
|
||||||
if (!bmp085Init())
|
|
||||||
sensorsClear(SENSOR_BARO);
|
|
||||||
if (!hmc5883lDetect())
|
|
||||||
sensorsClear(SENSOR_MAG);
|
|
||||||
|
|
||||||
// Init sensors
|
|
||||||
if (sensors(SENSOR_ACC)) {
|
|
||||||
acc.init();
|
|
||||||
accHardware = ADXL345;
|
|
||||||
}
|
|
||||||
if (sensors(SENSOR_BARO))
|
|
||||||
bmp085Init();
|
|
||||||
|
|
||||||
// special case for supported gyros - MPU3050 and MPU6050
|
|
||||||
if (mpu6050Detect(&acc, &gyro)) { // first, try MPU6050, and re-enable acc (if ADXL345 is missing) since this chip has it built in
|
|
||||||
sensorsSet(SENSOR_ACC);
|
|
||||||
acc.init();
|
|
||||||
accHardware = MPU6050;
|
|
||||||
} else if (!mpu3050Detect(&gyro)) {
|
} else if (!mpu3050Detect(&gyro)) {
|
||||||
// if this fails, we get a beep + blink pattern. we're doomed, no gyro or i2c error.
|
// if this fails, we get a beep + blink pattern. we're doomed, no gyro or i2c error.
|
||||||
failureMode(3);
|
failureMode(3);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Try to init MMA8452
|
// Accelerometer. Fuck it. Let user break shit.
|
||||||
|
retry:
|
||||||
|
switch (cfg.acc_hardware) {
|
||||||
|
case 0: // autodetect
|
||||||
|
case 1: // ADXL345
|
||||||
|
acc_params.useFifo = false;
|
||||||
|
acc_params.dataRate = 800; // unused currently
|
||||||
|
if (adxl345Detect(&acc_params, &acc))
|
||||||
|
accHardware = ACC_ADXL345;
|
||||||
|
if (cfg.acc_hardware == ACC_ADXL345)
|
||||||
|
break;
|
||||||
|
; // fallthrough
|
||||||
|
case 2: // MPU6050
|
||||||
|
if (haveMpu6k) {
|
||||||
|
mpu6050Detect(&acc, &gyro); // yes, i'm rerunning it again. re-fill acc struct
|
||||||
|
accHardware = ACC_MPU6050;
|
||||||
|
if (cfg.acc_hardware == ACC_MPU6050)
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
; // fallthrough
|
||||||
|
case 3: // MMA8452
|
||||||
if (mma8452Detect(&acc)) {
|
if (mma8452Detect(&acc)) {
|
||||||
sensorsSet(SENSOR_ACC);
|
accHardware = ACC_MMA8452;
|
||||||
acc.init();
|
if (cfg.acc_hardware == ACC_MMA8452)
|
||||||
accHardware = MMA845x;
|
break;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// Found anything? Check if user fucked up or ACC is really missing.
|
||||||
|
if (accHardware == ACC_DEFAULT) {
|
||||||
|
if (cfg.acc_hardware > ACC_DEFAULT) {
|
||||||
|
// Nothing was found and we have a forced sensor type. Stupid user probably chose a sensor that isn't present.
|
||||||
|
cfg.acc_hardware = ACC_DEFAULT;
|
||||||
|
goto retry;
|
||||||
|
} else {
|
||||||
|
// We're really screwed
|
||||||
|
sensorsClear(SENSOR_ACC);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// Detect what else is available
|
||||||
|
if (!bmp085Init())
|
||||||
|
sensorsClear(SENSOR_BARO);
|
||||||
|
if (!hmc5883lDetect())
|
||||||
|
sensorsClear(SENSOR_MAG);
|
||||||
|
|
||||||
|
// Now time to init them, acc first
|
||||||
|
if (sensors(SENSOR_ACC))
|
||||||
|
acc.init();
|
||||||
|
if (sensors(SENSOR_BARO))
|
||||||
|
bmp085Init();
|
||||||
// this is safe because either mpu6050 or mpu3050 sets it, and in case of fail, none do.
|
// this is safe because either mpu6050 or mpu3050 sets it, and in case of fail, none do.
|
||||||
gyro.init();
|
gyro.init();
|
||||||
// todo: this is driver specific :(
|
// todo: this is driver specific :(
|
||||||
|
if (!haveMpu6k)
|
||||||
mpu3050Config(cfg.gyro_lpf);
|
mpu3050Config(cfg.gyro_lpf);
|
||||||
|
|
||||||
// calculate magnetic declination
|
// calculate magnetic declination
|
||||||
|
@ -252,15 +276,6 @@ static void GYRO_Common(void)
|
||||||
static int32_t g[3];
|
static int32_t g[3];
|
||||||
uint8_t axis;
|
uint8_t axis;
|
||||||
|
|
||||||
#if defined MMGYRO
|
|
||||||
// Moving Average Gyros by Magnetron1
|
|
||||||
//---------------------------------------------------
|
|
||||||
static int16_t mediaMobileGyroADC[3][MMGYROVECTORLENGTH];
|
|
||||||
static int32_t mediaMobileGyroADCSum[3];
|
|
||||||
static uint8_t mediaMobileGyroIDX;
|
|
||||||
//---------------------------------------------------
|
|
||||||
#endif
|
|
||||||
|
|
||||||
if (calibratingG > 0) {
|
if (calibratingG > 0) {
|
||||||
for (axis = 0; axis < 3; axis++) {
|
for (axis = 0; axis < 3; axis++) {
|
||||||
// Reset g[axis] at start of calibration
|
// Reset g[axis] at start of calibration
|
||||||
|
@ -279,25 +294,12 @@ static void GYRO_Common(void)
|
||||||
calibratingG--;
|
calibratingG--;
|
||||||
}
|
}
|
||||||
|
|
||||||
#ifdef MMGYRO
|
|
||||||
mediaMobileGyroIDX = ++mediaMobileGyroIDX % MMGYROVECTORLENGTH;
|
|
||||||
for (axis = 0; axis < 3; axis++) {
|
|
||||||
gyroADC[axis] -= gyroZero[axis];
|
|
||||||
mediaMobileGyroADCSum[axis] -= mediaMobileGyroADC[axis][mediaMobileGyroIDX];
|
|
||||||
//anti gyro glitch, limit the variation between two consecutive readings
|
|
||||||
mediaMobileGyroADC[axis][mediaMobileGyroIDX] = constrain(gyroADC[axis], previousGyroADC[axis] - 800, previousGyroADC[axis] + 800);
|
|
||||||
mediaMobileGyroADCSum[axis] += mediaMobileGyroADC[axis][mediaMobileGyroIDX];
|
|
||||||
gyroADC[axis] = mediaMobileGyroADCSum[axis] / MMGYROVECTORLENGTH;
|
|
||||||
previousGyroADC[axis] = gyroADC[axis];
|
|
||||||
}
|
|
||||||
#else
|
|
||||||
for (axis = 0; axis < 3; axis++) {
|
for (axis = 0; axis < 3; axis++) {
|
||||||
gyroADC[axis] -= gyroZero[axis];
|
gyroADC[axis] -= gyroZero[axis];
|
||||||
//anti gyro glitch, limit the variation between two consecutive readings
|
//anti gyro glitch, limit the variation between two consecutive readings
|
||||||
gyroADC[axis] = constrain(gyroADC[axis], previousGyroADC[axis] - 800, previousGyroADC[axis] + 800);
|
gyroADC[axis] = constrain(gyroADC[axis], previousGyroADC[axis] - 800, previousGyroADC[axis] + 800);
|
||||||
previousGyroADC[axis] = gyroADC[axis];
|
previousGyroADC[axis] = gyroADC[axis];
|
||||||
}
|
}
|
||||||
#endif
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void Gyro_getADC(void)
|
void Gyro_getADC(void)
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue