renamed orient to align for sensor orientation
implemented battery cell count auto detect (DJI, you can steal this source from me for your next product). automatically finds 2S..6S battery, and sets warning voltage accordingly added new battery config -related stuff in cli, min/max cell voltage for non-lipo users. Defaults for lipo are 4.3V/cell (max) and 3.3V/cell (min). added pid setting stuff into cli from nicodh added 'status' command to cli to print out system info. added build date/time to 'version' in cli, to track down stupid users. config version bumped, settings are cleared again. refactored battery voltage stuff a bit, and got rid of 3 levels of warnings. don't see any benefit at all. git-svn-id: https://afrodevices.googlecode.com/svn/trunk/baseflight@121 7c89a4a9-59b9-e629-4cfe-3a2d53b20e61
This commit is contained in:
parent
8bcbf5e41e
commit
c526d2f3b9
160
baseflight.uvopt
160
baseflight.uvopt
|
@ -161,9 +161,24 @@
|
|||
<Bp>
|
||||
<Number>0</Number>
|
||||
<Type>0</Type>
|
||||
<LineNumber>29</LineNumber>
|
||||
<EnabledFlag>1</EnabledFlag>
|
||||
<Address>134222936</Address>
|
||||
<ByteObject>0</ByteObject>
|
||||
<ManyObjects>0</ManyObjects>
|
||||
<SizeOfObject>0</SizeOfObject>
|
||||
<BreakByAccess>0</BreakByAccess>
|
||||
<BreakIfRCount>1</BreakIfRCount>
|
||||
<Filename></Filename>
|
||||
<ExecCommand></ExecCommand>
|
||||
<Expression>\\baseflight\src/main.c\29</Expression>
|
||||
</Bp>
|
||||
<Bp>
|
||||
<Number>1</Number>
|
||||
<Type>0</Type>
|
||||
<LineNumber>58</LineNumber>
|
||||
<EnabledFlag>1</EnabledFlag>
|
||||
<Address>134242932</Address>
|
||||
<Address>134243320</Address>
|
||||
<ByteObject>0</ByteObject>
|
||||
<ManyObjects>0</ManyObjects>
|
||||
<SizeOfObject>0</SizeOfObject>
|
||||
|
@ -173,12 +188,27 @@
|
|||
<ExecCommand></ExecCommand>
|
||||
<Expression>\\baseflight\src/drv_mpu6050.c\58</Expression>
|
||||
</Bp>
|
||||
<Bp>
|
||||
<Number>2</Number>
|
||||
<Type>0</Type>
|
||||
<LineNumber>66</LineNumber>
|
||||
<EnabledFlag>1</EnabledFlag>
|
||||
<Address>134232692</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\66</Expression>
|
||||
</Bp>
|
||||
</Breakpoint>
|
||||
<WatchWindow1>
|
||||
<Ww>
|
||||
<count>0</count>
|
||||
<WinNumber>1</WinNumber>
|
||||
<ItemText>tri_yaw_middle,0x0A</ItemText>
|
||||
<ItemText>tri_yaw_middle</ItemText>
|
||||
</Ww>
|
||||
<Ww>
|
||||
<count>1</count>
|
||||
|
@ -507,8 +537,8 @@
|
|||
<Focus>0</Focus>
|
||||
<ColumnNumber>0</ColumnNumber>
|
||||
<tvExpOptDlg>0</tvExpOptDlg>
|
||||
<TopLine>1</TopLine>
|
||||
<CurrentLine>1</CurrentLine>
|
||||
<TopLine>60</TopLine>
|
||||
<CurrentLine>78</CurrentLine>
|
||||
<bDave2>0</bDave2>
|
||||
<PathWithFileName>.\src\cli.c</PathWithFileName>
|
||||
<FilenameWithoutPath>cli.c</FilenameWithoutPath>
|
||||
|
@ -519,10 +549,10 @@
|
|||
<FileType>1</FileType>
|
||||
<tvExp>0</tvExp>
|
||||
<Focus>0</Focus>
|
||||
<ColumnNumber>1</ColumnNumber>
|
||||
<ColumnNumber>0</ColumnNumber>
|
||||
<tvExpOptDlg>0</tvExpOptDlg>
|
||||
<TopLine>1</TopLine>
|
||||
<CurrentLine>14</CurrentLine>
|
||||
<TopLine>7</TopLine>
|
||||
<CurrentLine>20</CurrentLine>
|
||||
<bDave2>0</bDave2>
|
||||
<PathWithFileName>.\src\config.c</PathWithFileName>
|
||||
<FilenameWithoutPath>config.c</FilenameWithoutPath>
|
||||
|
@ -549,8 +579,8 @@
|
|||
<Focus>0</Focus>
|
||||
<ColumnNumber>0</ColumnNumber>
|
||||
<tvExpOptDlg>0</tvExpOptDlg>
|
||||
<TopLine>1</TopLine>
|
||||
<CurrentLine>28</CurrentLine>
|
||||
<TopLine>40</TopLine>
|
||||
<CurrentLine>53</CurrentLine>
|
||||
<bDave2>0</bDave2>
|
||||
<PathWithFileName>.\src\main.c</PathWithFileName>
|
||||
<FilenameWithoutPath>main.c</FilenameWithoutPath>
|
||||
|
@ -563,8 +593,8 @@
|
|||
<Focus>0</Focus>
|
||||
<ColumnNumber>0</ColumnNumber>
|
||||
<tvExpOptDlg>0</tvExpOptDlg>
|
||||
<TopLine>266</TopLine>
|
||||
<CurrentLine>279</CurrentLine>
|
||||
<TopLine>271</TopLine>
|
||||
<CurrentLine>302</CurrentLine>
|
||||
<bDave2>0</bDave2>
|
||||
<PathWithFileName>.\src\mixer.c</PathWithFileName>
|
||||
<FilenameWithoutPath>mixer.c</FilenameWithoutPath>
|
||||
|
@ -575,10 +605,10 @@
|
|||
<FileType>1</FileType>
|
||||
<tvExp>0</tvExp>
|
||||
<Focus>0</Focus>
|
||||
<ColumnNumber>50</ColumnNumber>
|
||||
<ColumnNumber>9</ColumnNumber>
|
||||
<tvExpOptDlg>0</tvExpOptDlg>
|
||||
<TopLine>1</TopLine>
|
||||
<CurrentLine>1</CurrentLine>
|
||||
<TopLine>9</TopLine>
|
||||
<CurrentLine>21</CurrentLine>
|
||||
<bDave2>0</bDave2>
|
||||
<PathWithFileName>.\src\mw.c</PathWithFileName>
|
||||
<FilenameWithoutPath>mw.c</FilenameWithoutPath>
|
||||
|
@ -589,10 +619,10 @@
|
|||
<FileType>1</FileType>
|
||||
<tvExp>0</tvExp>
|
||||
<Focus>0</Focus>
|
||||
<ColumnNumber>72</ColumnNumber>
|
||||
<ColumnNumber>25</ColumnNumber>
|
||||
<tvExpOptDlg>0</tvExpOptDlg>
|
||||
<TopLine>235</TopLine>
|
||||
<CurrentLine>253</CurrentLine>
|
||||
<TopLine>1</TopLine>
|
||||
<CurrentLine>9</CurrentLine>
|
||||
<bDave2>0</bDave2>
|
||||
<PathWithFileName>.\src\sensors.c</PathWithFileName>
|
||||
<FilenameWithoutPath>sensors.c</FilenameWithoutPath>
|
||||
|
@ -605,7 +635,7 @@
|
|||
<Focus>0</Focus>
|
||||
<ColumnNumber>18</ColumnNumber>
|
||||
<tvExpOptDlg>0</tvExpOptDlg>
|
||||
<TopLine>43</TopLine>
|
||||
<TopLine>56</TopLine>
|
||||
<CurrentLine>74</CurrentLine>
|
||||
<bDave2>0</bDave2>
|
||||
<PathWithFileName>.\src\serial.c</PathWithFileName>
|
||||
|
@ -619,8 +649,8 @@
|
|||
<Focus>0</Focus>
|
||||
<ColumnNumber>0</ColumnNumber>
|
||||
<tvExpOptDlg>0</tvExpOptDlg>
|
||||
<TopLine>1</TopLine>
|
||||
<CurrentLine>9</CurrentLine>
|
||||
<TopLine>54</TopLine>
|
||||
<CurrentLine>72</CurrentLine>
|
||||
<bDave2>0</bDave2>
|
||||
<PathWithFileName>.\src\board.h</PathWithFileName>
|
||||
<FilenameWithoutPath>board.h</FilenameWithoutPath>
|
||||
|
@ -633,8 +663,8 @@
|
|||
<Focus>0</Focus>
|
||||
<ColumnNumber>0</ColumnNumber>
|
||||
<tvExpOptDlg>0</tvExpOptDlg>
|
||||
<TopLine>159</TopLine>
|
||||
<CurrentLine>180</CurrentLine>
|
||||
<TopLine>37</TopLine>
|
||||
<CurrentLine>37</CurrentLine>
|
||||
<bDave2>0</bDave2>
|
||||
<PathWithFileName>.\src\mw.h</PathWithFileName>
|
||||
<FilenameWithoutPath>mw.h</FilenameWithoutPath>
|
||||
|
@ -652,10 +682,10 @@
|
|||
<FileType>1</FileType>
|
||||
<tvExp>0</tvExp>
|
||||
<Focus>0</Focus>
|
||||
<ColumnNumber>23</ColumnNumber>
|
||||
<ColumnNumber>22</ColumnNumber>
|
||||
<tvExpOptDlg>0</tvExpOptDlg>
|
||||
<TopLine>0</TopLine>
|
||||
<CurrentLine>0</CurrentLine>
|
||||
<TopLine>33</TopLine>
|
||||
<CurrentLine>51</CurrentLine>
|
||||
<bDave2>0</bDave2>
|
||||
<PathWithFileName>.\src\drv_adc.c</PathWithFileName>
|
||||
<FilenameWithoutPath>drv_adc.c</FilenameWithoutPath>
|
||||
|
@ -666,7 +696,7 @@
|
|||
<FileType>1</FileType>
|
||||
<tvExp>0</tvExp>
|
||||
<Focus>0</Focus>
|
||||
<ColumnNumber>31</ColumnNumber>
|
||||
<ColumnNumber>65</ColumnNumber>
|
||||
<tvExpOptDlg>0</tvExpOptDlg>
|
||||
<TopLine>0</TopLine>
|
||||
<CurrentLine>0</CurrentLine>
|
||||
|
@ -694,10 +724,10 @@
|
|||
<FileType>1</FileType>
|
||||
<tvExp>0</tvExp>
|
||||
<Focus>0</Focus>
|
||||
<ColumnNumber>23</ColumnNumber>
|
||||
<ColumnNumber>42</ColumnNumber>
|
||||
<tvExpOptDlg>0</tvExpOptDlg>
|
||||
<TopLine>13</TopLine>
|
||||
<CurrentLine>21</CurrentLine>
|
||||
<CurrentLine>29</CurrentLine>
|
||||
<bDave2>0</bDave2>
|
||||
<PathWithFileName>.\src\drv_hmc5883l.c</PathWithFileName>
|
||||
<FilenameWithoutPath>drv_hmc5883l.c</FilenameWithoutPath>
|
||||
|
@ -708,10 +738,10 @@
|
|||
<FileType>1</FileType>
|
||||
<tvExp>0</tvExp>
|
||||
<Focus>0</Focus>
|
||||
<ColumnNumber>19</ColumnNumber>
|
||||
<ColumnNumber>18</ColumnNumber>
|
||||
<tvExpOptDlg>0</tvExpOptDlg>
|
||||
<TopLine>134</TopLine>
|
||||
<CurrentLine>154</CurrentLine>
|
||||
<TopLine>1</TopLine>
|
||||
<CurrentLine>1</CurrentLine>
|
||||
<bDave2>0</bDave2>
|
||||
<PathWithFileName>.\src\drv_i2c.c</PathWithFileName>
|
||||
<FilenameWithoutPath>drv_i2c.c</FilenameWithoutPath>
|
||||
|
@ -724,8 +754,8 @@
|
|||
<Focus>0</Focus>
|
||||
<ColumnNumber>0</ColumnNumber>
|
||||
<tvExpOptDlg>0</tvExpOptDlg>
|
||||
<TopLine>1</TopLine>
|
||||
<CurrentLine>1</CurrentLine>
|
||||
<TopLine>27</TopLine>
|
||||
<CurrentLine>45</CurrentLine>
|
||||
<bDave2>0</bDave2>
|
||||
<PathWithFileName>.\src\drv_mpu3050.c</PathWithFileName>
|
||||
<FilenameWithoutPath>drv_mpu3050.c</FilenameWithoutPath>
|
||||
|
@ -736,10 +766,10 @@
|
|||
<FileType>1</FileType>
|
||||
<tvExp>0</tvExp>
|
||||
<Focus>0</Focus>
|
||||
<ColumnNumber>5</ColumnNumber>
|
||||
<ColumnNumber>26</ColumnNumber>
|
||||
<tvExpOptDlg>0</tvExpOptDlg>
|
||||
<TopLine>0</TopLine>
|
||||
<CurrentLine>0</CurrentLine>
|
||||
<TopLine>66</TopLine>
|
||||
<CurrentLine>84</CurrentLine>
|
||||
<bDave2>0</bDave2>
|
||||
<PathWithFileName>.\src\drv_pwm.c</PathWithFileName>
|
||||
<FilenameWithoutPath>drv_pwm.c</FilenameWithoutPath>
|
||||
|
@ -750,10 +780,10 @@
|
|||
<FileType>1</FileType>
|
||||
<tvExp>0</tvExp>
|
||||
<Focus>0</Focus>
|
||||
<ColumnNumber>22</ColumnNumber>
|
||||
<ColumnNumber>0</ColumnNumber>
|
||||
<tvExpOptDlg>0</tvExpOptDlg>
|
||||
<TopLine>34</TopLine>
|
||||
<CurrentLine>46</CurrentLine>
|
||||
<TopLine>115</TopLine>
|
||||
<CurrentLine>115</CurrentLine>
|
||||
<bDave2>0</bDave2>
|
||||
<PathWithFileName>.\src\drv_system.c</PathWithFileName>
|
||||
<FilenameWithoutPath>drv_system.c</FilenameWithoutPath>
|
||||
|
@ -788,31 +818,17 @@
|
|||
</File>
|
||||
<File>
|
||||
<GroupNumber>2</GroupNumber>
|
||||
<FileNumber>0</FileNumber>
|
||||
<FileNumber>21</FileNumber>
|
||||
<FileType>1</FileType>
|
||||
<tvExp>0</tvExp>
|
||||
<Focus>0</Focus>
|
||||
<ColumnNumber>21</ColumnNumber>
|
||||
<tvExpOptDlg>0</tvExpOptDlg>
|
||||
<TopLine>0</TopLine>
|
||||
<CurrentLine>0</CurrentLine>
|
||||
<bDave2>0</bDave2>
|
||||
<PathWithFileName>.\src\drv_mpu6050.c</PathWithFileName>
|
||||
<FilenameWithoutPath>drv_mpu6050.c</FilenameWithoutPath>
|
||||
</File>
|
||||
<File>
|
||||
<GroupNumber>2</GroupNumber>
|
||||
<FileNumber>0</FileNumber>
|
||||
<FileType>5</FileType>
|
||||
<tvExp>0</tvExp>
|
||||
<Focus>0</Focus>
|
||||
<ColumnNumber>0</ColumnNumber>
|
||||
<tvExpOptDlg>0</tvExpOptDlg>
|
||||
<TopLine>0</TopLine>
|
||||
<CurrentLine>0</CurrentLine>
|
||||
<bDave2>0</bDave2>
|
||||
<PathWithFileName>.\src\drv_mpu6050.h</PathWithFileName>
|
||||
<FilenameWithoutPath>drv_mpu6050.h</FilenameWithoutPath>
|
||||
<PathWithFileName>.\src\drv_mpu6050.c</PathWithFileName>
|
||||
<FilenameWithoutPath>drv_mpu6050.c</FilenameWithoutPath>
|
||||
</File>
|
||||
</Group>
|
||||
|
||||
|
@ -823,7 +839,7 @@
|
|||
<cbSel>0</cbSel>
|
||||
<File>
|
||||
<GroupNumber>3</GroupNumber>
|
||||
<FileNumber>21</FileNumber>
|
||||
<FileNumber>22</FileNumber>
|
||||
<FileType>1</FileType>
|
||||
<tvExp>0</tvExp>
|
||||
<Focus>0</Focus>
|
||||
|
@ -837,7 +853,7 @@
|
|||
</File>
|
||||
<File>
|
||||
<GroupNumber>3</GroupNumber>
|
||||
<FileNumber>22</FileNumber>
|
||||
<FileNumber>23</FileNumber>
|
||||
<FileType>1</FileType>
|
||||
<tvExp>0</tvExp>
|
||||
<Focus>0</Focus>
|
||||
|
@ -851,7 +867,7 @@
|
|||
</File>
|
||||
<File>
|
||||
<GroupNumber>3</GroupNumber>
|
||||
<FileNumber>23</FileNumber>
|
||||
<FileNumber>24</FileNumber>
|
||||
<FileType>1</FileType>
|
||||
<tvExp>0</tvExp>
|
||||
<Focus>0</Focus>
|
||||
|
@ -865,7 +881,7 @@
|
|||
</File>
|
||||
<File>
|
||||
<GroupNumber>3</GroupNumber>
|
||||
<FileNumber>24</FileNumber>
|
||||
<FileNumber>25</FileNumber>
|
||||
<FileType>1</FileType>
|
||||
<tvExp>0</tvExp>
|
||||
<Focus>0</Focus>
|
||||
|
@ -879,7 +895,7 @@
|
|||
</File>
|
||||
<File>
|
||||
<GroupNumber>3</GroupNumber>
|
||||
<FileNumber>25</FileNumber>
|
||||
<FileNumber>26</FileNumber>
|
||||
<FileType>1</FileType>
|
||||
<tvExp>0</tvExp>
|
||||
<Focus>0</Focus>
|
||||
|
@ -893,7 +909,7 @@
|
|||
</File>
|
||||
<File>
|
||||
<GroupNumber>3</GroupNumber>
|
||||
<FileNumber>26</FileNumber>
|
||||
<FileNumber>27</FileNumber>
|
||||
<FileType>1</FileType>
|
||||
<tvExp>0</tvExp>
|
||||
<Focus>0</Focus>
|
||||
|
@ -907,7 +923,7 @@
|
|||
</File>
|
||||
<File>
|
||||
<GroupNumber>3</GroupNumber>
|
||||
<FileNumber>27</FileNumber>
|
||||
<FileNumber>28</FileNumber>
|
||||
<FileType>1</FileType>
|
||||
<tvExp>0</tvExp>
|
||||
<Focus>0</Focus>
|
||||
|
@ -921,7 +937,7 @@
|
|||
</File>
|
||||
<File>
|
||||
<GroupNumber>3</GroupNumber>
|
||||
<FileNumber>28</FileNumber>
|
||||
<FileNumber>29</FileNumber>
|
||||
<FileType>1</FileType>
|
||||
<tvExp>0</tvExp>
|
||||
<Focus>0</Focus>
|
||||
|
@ -935,7 +951,7 @@
|
|||
</File>
|
||||
<File>
|
||||
<GroupNumber>3</GroupNumber>
|
||||
<FileNumber>29</FileNumber>
|
||||
<FileNumber>30</FileNumber>
|
||||
<FileType>1</FileType>
|
||||
<tvExp>0</tvExp>
|
||||
<Focus>0</Focus>
|
||||
|
@ -949,7 +965,7 @@
|
|||
</File>
|
||||
<File>
|
||||
<GroupNumber>3</GroupNumber>
|
||||
<FileNumber>30</FileNumber>
|
||||
<FileNumber>31</FileNumber>
|
||||
<FileType>1</FileType>
|
||||
<tvExp>0</tvExp>
|
||||
<Focus>0</Focus>
|
||||
|
@ -963,7 +979,7 @@
|
|||
</File>
|
||||
<File>
|
||||
<GroupNumber>3</GroupNumber>
|
||||
<FileNumber>31</FileNumber>
|
||||
<FileNumber>32</FileNumber>
|
||||
<FileType>1</FileType>
|
||||
<tvExp>0</tvExp>
|
||||
<Focus>0</Focus>
|
||||
|
@ -977,7 +993,7 @@
|
|||
</File>
|
||||
<File>
|
||||
<GroupNumber>3</GroupNumber>
|
||||
<FileNumber>32</FileNumber>
|
||||
<FileNumber>33</FileNumber>
|
||||
<FileType>1</FileType>
|
||||
<tvExp>0</tvExp>
|
||||
<Focus>0</Focus>
|
||||
|
@ -991,14 +1007,14 @@
|
|||
</File>
|
||||
<File>
|
||||
<GroupNumber>3</GroupNumber>
|
||||
<FileNumber>33</FileNumber>
|
||||
<FileNumber>34</FileNumber>
|
||||
<FileType>2</FileType>
|
||||
<tvExp>0</tvExp>
|
||||
<Focus>0</Focus>
|
||||
<ColumnNumber>0</ColumnNumber>
|
||||
<ColumnNumber>26</ColumnNumber>
|
||||
<tvExpOptDlg>0</tvExpOptDlg>
|
||||
<TopLine>133</TopLine>
|
||||
<CurrentLine>133</CurrentLine>
|
||||
<TopLine>116</TopLine>
|
||||
<CurrentLine>124</CurrentLine>
|
||||
<bDave2>0</bDave2>
|
||||
<PathWithFileName>.\src\baseflight_startups\startup_stm32f10x_md.s</PathWithFileName>
|
||||
<FilenameWithoutPath>startup_stm32f10x_md.s</FilenameWithoutPath>
|
||||
|
|
|
@ -496,11 +496,6 @@
|
|||
<FileType>1</FileType>
|
||||
<FilePath>.\src\drv_mpu6050.c</FilePath>
|
||||
</File>
|
||||
<File>
|
||||
<FileName>drv_mpu6050.h</FileName>
|
||||
<FileType>5</FileType>
|
||||
<FilePath>.\src\drv_mpu6050.h</FilePath>
|
||||
</File>
|
||||
</Files>
|
||||
</Group>
|
||||
<Group>
|
||||
|
@ -1119,11 +1114,6 @@
|
|||
<FileType>1</FileType>
|
||||
<FilePath>.\src\drv_mpu6050.c</FilePath>
|
||||
</File>
|
||||
<File>
|
||||
<FileName>drv_mpu6050.h</FileName>
|
||||
<FileType>5</FileType>
|
||||
<FilePath>.\src\drv_mpu6050.h</FilePath>
|
||||
</File>
|
||||
</Files>
|
||||
</Group>
|
||||
<Group>
|
||||
|
|
4643
obj/baseflight.hex
4643
obj/baseflight.hex
File diff suppressed because it is too large
Load Diff
|
@ -37,7 +37,7 @@ typedef struct sensor_t
|
|||
{
|
||||
sensorInitFuncPtr init;
|
||||
sensorReadFuncPtr read;
|
||||
sensorReadFuncPtr orient;
|
||||
sensorReadFuncPtr align;
|
||||
} sensor_t;
|
||||
|
||||
#define digitalHi(p, i) { p->BSRR = i; }
|
||||
|
|
47
src/cli.c
47
src/cli.c
|
@ -10,8 +10,12 @@ static void cliHelp(char *cmdline);
|
|||
static void cliMixer(char *cmdline);
|
||||
static void cliSave(char *cmdline);
|
||||
static void cliSet(char *cmdline);
|
||||
static void cliStatus(char *cmdline);
|
||||
static void cliVersion(char *cmdline);
|
||||
|
||||
// from sensors.c
|
||||
extern uint8_t batteryCellCount;
|
||||
|
||||
// buffer
|
||||
static char cliBuffer[32];
|
||||
static uint8_t bufferIndex = 0;
|
||||
|
@ -46,6 +50,7 @@ const clicmd_t cmdTable[] = {
|
|||
{ "mixer", "mixer name or list", cliMixer },
|
||||
{ "save", "save and reboot", cliSave },
|
||||
{ "set", "name=value or blank for list", cliSet },
|
||||
{ "status", "show system status", cliStatus },
|
||||
{ "version", "", cliVersion },
|
||||
};
|
||||
#define CMD_COUNT (sizeof(cmdTable) / sizeof(cmdTable[0]))
|
||||
|
@ -74,6 +79,8 @@ const clivalue_t valueTable[] = {
|
|||
{ "mincheck", VAR_UINT16, &cfg.mincheck, 0, 2000 },
|
||||
{ "maxcheck", VAR_UINT16, &cfg.maxcheck, 0, 2000 },
|
||||
{ "vbatscale", VAR_UINT8, &cfg.vbatscale, 10, 200 },
|
||||
{ "vbatmaxcellvoltage", VAR_UINT8, &cfg.vbatmaxcellvoltage, 10, 50 },
|
||||
{ "vbatmincellvoltage", VAR_UINT8, &cfg.vbatmincellvoltage, 10, 50 },
|
||||
{ "yaw_direction", VAR_INT8, &cfg.yaw_direction, -1, 1 },
|
||||
{ "wing_left_mid", VAR_UINT16, &cfg.wing_left_mid, 0, 2000 },
|
||||
{ "wing_right_mid", VAR_UINT16, &cfg.wing_right_mid, 0, 2000 },
|
||||
|
@ -82,6 +89,18 @@ const clivalue_t valueTable[] = {
|
|||
{ "tri_yaw_max", VAR_UINT16, &cfg.tri_yaw_max, 0, 2000 },
|
||||
{ "tilt_pitch_prop", VAR_INT8, &cfg.tilt_pitch_prop, -100, 100 },
|
||||
{ "tilt_roll_prop", VAR_INT8, &cfg.tilt_roll_prop, -100, 100 },
|
||||
{ "p_pitch", VAR_UINT8, &cfg.P8[PITCH], 0, 200},
|
||||
{ "i_pitch", VAR_UINT8, &cfg.I8[PITCH], 0, 200},
|
||||
{ "d_pitch", VAR_UINT8, &cfg.D8[PITCH], 0, 200},
|
||||
{ "p_roll", VAR_UINT8, &cfg.P8[ROLL], 0, 200},
|
||||
{ "i_roll", VAR_UINT8, &cfg.I8[ROLL], 0, 200},
|
||||
{ "d_roll", VAR_UINT8, &cfg.D8[ROLL], 0, 200},
|
||||
{ "p_yaw", VAR_UINT8, &cfg.P8[YAW], 0, 200},
|
||||
{ "i_yaw", VAR_UINT8, &cfg.I8[YAW], 0, 200},
|
||||
{ "d_yaw", VAR_UINT8, &cfg.D8[YAW], 0, 200},
|
||||
{ "p_level", VAR_UINT8, &cfg.P8[PIDLEVEL], 0, 200},
|
||||
{ "i_level", VAR_UINT8, &cfg.I8[PIDLEVEL], 0, 200},
|
||||
{ "d_level", VAR_UINT8, &cfg.D8[PIDLEVEL], 0, 200},
|
||||
};
|
||||
|
||||
#define VALUE_COUNT (sizeof(valueTable) / sizeof(valueTable[0]))
|
||||
|
@ -365,9 +384,31 @@ static void cliSet(char *cmdline)
|
|||
}
|
||||
}
|
||||
|
||||
static void cliStatus(char *cmdline)
|
||||
{
|
||||
char buf[16];
|
||||
uartPrint("System Uptime: ");
|
||||
itoa(millis() / 1000, buf, 10);
|
||||
uartPrint(buf);
|
||||
uartPrint(" seconds, Voltage: ");
|
||||
itoa(vbat, buf, 10);
|
||||
uartPrint(buf);
|
||||
uartPrint(" * 0.1V (");
|
||||
itoa(batteryCellCount, buf, 10);
|
||||
uartPrint(buf);
|
||||
uartPrint("S battery)\r\n");
|
||||
uartPrint("Cycle Time: ");
|
||||
itoa(cycleTime, buf, 10);
|
||||
uartPrint(buf);
|
||||
uartPrint(", I2C Errors: ");
|
||||
itoa(i2cGetErrorCounter(), buf, 10);
|
||||
uartPrint(buf);
|
||||
uartPrint("\r\n");
|
||||
}
|
||||
|
||||
static void cliVersion(char *cmdline)
|
||||
{
|
||||
uartPrint("Afro32 CLI version 2.0-pre3");
|
||||
uartPrint("Afro32 CLI version 2.0-pre3 " __DATE__ " / " __TIME__);
|
||||
}
|
||||
|
||||
void cliProcess(void)
|
||||
|
@ -380,8 +421,8 @@ void cliProcess(void)
|
|||
|
||||
while (uartAvailable()) {
|
||||
uint8_t c = uartRead();
|
||||
|
||||
if (c == '\t' || c == '?') {
|
||||
// do tab completion
|
||||
const clicmd_t *cmd, *pstart = NULL, *pend = NULL;
|
||||
int i = bufferIndex;
|
||||
for (cmd = cmdTable; cmd < cmdTable + CMD_COUNT; cmd++) {
|
||||
|
@ -406,7 +447,7 @@ void cliProcess(void)
|
|||
if (!bufferIndex || pstart != pend) {
|
||||
/* Print list of ambiguous matches */
|
||||
uartPrint("\r\033[K");
|
||||
for (cmd = pstart;cmd <= pend;cmd++) {
|
||||
for (cmd = pstart; cmd <= pend; cmd++) {
|
||||
uartPrint(cmd->name);
|
||||
uartWrite('\t');
|
||||
}
|
||||
|
|
|
@ -8,7 +8,7 @@
|
|||
config_t cfg;
|
||||
|
||||
static uint32_t enabledSensors = 0;
|
||||
static uint8_t checkNewConf = 5;
|
||||
static uint8_t checkNewConf = 6;
|
||||
|
||||
void readEEPROM(void)
|
||||
{
|
||||
|
@ -103,6 +103,8 @@ void checkFirstTime(bool reset)
|
|||
cfg.gyro_smoothing_factor = 0x00141403; // default factors of 20, 20, 3 for R/P/Y
|
||||
cfg.powerTrigger1 = 0;
|
||||
cfg.vbatscale = 110;
|
||||
cfg.vbatmaxcellvoltage = 43;
|
||||
cfg.vbatmincellvoltage = 33;
|
||||
|
||||
// Radio/ESC
|
||||
cfg.deadband = 0;
|
||||
|
|
|
@ -30,7 +30,7 @@ bool adxl345Detect(sensor_t *acc)
|
|||
|
||||
acc->init = adxl345Init;
|
||||
acc->read = adxl345Read;
|
||||
acc->orient = adxl345Align;
|
||||
acc->align = adxl345Align;
|
||||
return true;
|
||||
}
|
||||
|
||||
|
|
|
@ -41,7 +41,7 @@ bool mpu3050Detect(sensor_t *gyro)
|
|||
|
||||
gyro->init = mpu3050Init;
|
||||
gyro->read = mpu3050Read;
|
||||
gyro->orient = mpu3050Align;
|
||||
gyro->align = mpu3050Align;
|
||||
|
||||
return true;
|
||||
}
|
||||
|
|
|
@ -28,15 +28,15 @@ bool mpu6050Detect(sensor_t *acc, sensor_t *gyro)
|
|||
if (!ack)
|
||||
return false;
|
||||
|
||||
if (sig != 0x68)
|
||||
if (sig != MPU6050_ADDRESS)
|
||||
return false;
|
||||
|
||||
acc->init = mpu6050AccInit;
|
||||
acc->read = mpu6050AccRead;
|
||||
acc->orient = mpu6050AccAlign;
|
||||
acc->align = mpu6050AccAlign;
|
||||
gyro->init = mpu6050GyroInit;
|
||||
gyro->read = mpu6050GyroRead;
|
||||
gyro->orient = mpu6050GyroAlign;
|
||||
gyro->align = mpu6050GyroAlign;
|
||||
|
||||
return true;
|
||||
}
|
||||
|
|
|
@ -24,7 +24,7 @@ int main(void)
|
|||
// We have these sensors
|
||||
sensorsSet(SENSOR_ACC | SENSOR_BARO | SENSOR_MAG);
|
||||
|
||||
mixerInit(); // this will configure FEATURE_SERVO depending on mixer type
|
||||
mixerInit(); // this will set useServo var depending on mixer type
|
||||
pwmInit(feature(FEATURE_PPM), useServo, feature(FEATURE_DIGITAL_SERVO));
|
||||
|
||||
LED1_ON;
|
||||
|
@ -44,6 +44,10 @@ int main(void)
|
|||
sensorsAutodetect();
|
||||
imuInit(); // Mag is initialized inside imuInit
|
||||
|
||||
// Check battery type/voltage
|
||||
if (feature(FEATURE_VBAT))
|
||||
batteryInit();
|
||||
|
||||
previousTime = micros();
|
||||
calibratingG = 400;
|
||||
#if defined(POWERMETER)
|
||||
|
|
33
src/mw.c
33
src/mw.c
|
@ -79,6 +79,8 @@ uint32_t pAlarm; // we scale the eeprom value from [0:255] to this value
|
|||
// uint8_t powerTrigger1 = 0;
|
||||
uint16_t powerValue = 0; // last known current
|
||||
uint16_t intPowerMeterSum, intPowerTrigger1;
|
||||
uint8_t batteryCellCount = 3; // cell count
|
||||
uint16_t batteryWarningVoltage; // annoying buzzer after this one, battery ready to be dead
|
||||
|
||||
void blinkLED(uint8_t num, uint8_t wait, uint8_t repeat)
|
||||
{
|
||||
|
@ -159,6 +161,7 @@ void annexCode(void)
|
|||
rcCommand[ROLL] = rcCommand[ROLL] * cosDiff - rcCommand[PITCH] * sinDiff;
|
||||
rcCommand[PITCH] = rcCommand_PITCH;
|
||||
}
|
||||
|
||||
#if defined(POWERMETER_HARD)
|
||||
if (!(++psensorTimer % PSENSORFREQ)) {
|
||||
pMeterRaw = analogRead(PSENSORPIN);
|
||||
|
@ -180,15 +183,15 @@ void annexCode(void)
|
|||
vbatRawArray[(ind++) % 8] = adcGetBattery();
|
||||
for (i = 0; i < 8; i++)
|
||||
vbatRaw += vbatRawArray[i];
|
||||
vbat = (((vbatRaw / 8) * 3.3f) / 4095) * cfg.vbatscale; // result is Vbatt in 0.1V steps. 3.3V = ADC Vref, 4095 = 12bit adc, 110 = 11:1 voltage divider (10k:1k) * 10 for 0.1V
|
||||
vbat = batteryAdcToVoltage(vbatRaw / 8);
|
||||
}
|
||||
if (rcOptions[BOXBEEPERON]) { // unconditional beeper on via AUXn switch
|
||||
buzzerFreq = 7;
|
||||
} else if (((vbat > VBATLEVEL1_3S)
|
||||
} else if (((vbat > batteryWarningVoltage)
|
||||
#if defined(POWERMETER)
|
||||
&& ((pMeter[PMOTOR_SUM] < pAlarm) || (pAlarm == 0))
|
||||
#endif
|
||||
) || (NO_VBAT > vbat)) // ToLuSe
|
||||
) || (vbat < cfg.vbatmincellvoltage))
|
||||
{ //VBAT ok AND powermeter ok, buzzer off
|
||||
buzzerFreq = 0;
|
||||
buzzerState = 0;
|
||||
|
@ -197,12 +200,8 @@ void annexCode(void)
|
|||
} else if (pMeter[PMOTOR_SUM] > pAlarm) { // sound alarm for powermeter
|
||||
buzzerFreq = 4;
|
||||
#endif
|
||||
} else if (vbat > VBATLEVEL2_3S)
|
||||
buzzerFreq = 1;
|
||||
else if (vbat > VBATLEVEL3_3S)
|
||||
buzzerFreq = 2;
|
||||
else
|
||||
buzzerFreq = 4;
|
||||
} else
|
||||
buzzerFreq = 4; // low battery
|
||||
if (buzzerFreq) {
|
||||
if (buzzerState && (currentTime > buzzerTime + 250000)) {
|
||||
buzzerState = 0;
|
||||
|
@ -268,19 +267,19 @@ void annexCode(void)
|
|||
}
|
||||
#endif
|
||||
|
||||
#if GPS
|
||||
static uint32_t GPSLEDTime;
|
||||
if (currentTime > GPSLEDTime && (GPS_fix_home == 1)) {
|
||||
GPSLEDTime = currentTime + 150000;
|
||||
LEDPIN_TOGGLE;
|
||||
if (sensors(SENSOR_GPS)) {
|
||||
static uint32_t GPSLEDTime;
|
||||
if (currentTime > GPSLEDTime && (GPS_fix_home == 1)) {
|
||||
GPSLEDTime = currentTime + 150000;
|
||||
LED1_TOGGLE;
|
||||
}
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
uint16_t readRawRC(uint8_t chan)
|
||||
{
|
||||
uint16_t data;
|
||||
|
||||
|
||||
failsafeCnt = 0;
|
||||
data = pwmRead(rcChannel[chan]);
|
||||
if (data < 750 || data > 2250)
|
||||
|
@ -294,7 +293,7 @@ void computeRC(void)
|
|||
static int16_t rcData4Values[8][4], rcDataMean[8];
|
||||
static uint8_t rc4ValuesIndex = 0;
|
||||
uint8_t chan, a;
|
||||
|
||||
|
||||
#if defined(SBUS)
|
||||
readSBus();
|
||||
#endif
|
||||
|
|
13
src/mw.h
13
src/mw.h
|
@ -50,15 +50,8 @@
|
|||
#define CAM_TIME_HIGH 1000 // the duration of HIGH state servo expressed in ms
|
||||
#define CAM_TIME_LOW 1000 // the duration of LOW state servo expressed in ms
|
||||
|
||||
/* for V BAT monitoring
|
||||
after the resistor divisor we should get [0V;5V]->[0;1023] on analog V_BATPIN
|
||||
with R1=33k and R2=51k
|
||||
vbat = [0;1023]*16/VBATSCALE */
|
||||
/* for VBAT monitoring frequency */
|
||||
#define VBATFREQ 6 // to read battery voltage - keep equal to PSENSORFREQ (6) unless you know what you are doing
|
||||
#define VBATLEVEL1_3S 107 // 10,7V
|
||||
#define VBATLEVEL2_3S 103 // 10,3V
|
||||
#define VBATLEVEL3_3S 99 // 9.9V
|
||||
#define NO_VBAT 16 // Avoid beeping without any battery
|
||||
|
||||
// Moving Average Gyros by Magnetron1 (Michele Ardito) ########## beta
|
||||
//#define MMGYRO // Active Moving Average Function for Gyros
|
||||
|
@ -155,6 +148,8 @@ typedef struct config_t {
|
|||
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 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)
|
||||
|
||||
// Radio/ESC-related configuration
|
||||
uint8_t deadband; // introduce a deadband around the stick center. Must be greater than zero
|
||||
|
@ -248,6 +243,8 @@ void getEstimatedAltitude(void);
|
|||
|
||||
// Sensors
|
||||
void sensorsAutodetect(void);
|
||||
void batteryInit(void);
|
||||
uint16_t batteryAdcToVoltage(uint16_t src);
|
||||
void ACC_getADC(void);
|
||||
void Baro_update(void);
|
||||
void Gyro_getADC(void);
|
||||
|
|
|
@ -13,6 +13,8 @@ extern int16_t AccInflightCalibrationArmed;
|
|||
extern uint16_t AccInflightCalibrationMeasurementDone;
|
||||
extern uint16_t AccInflightCalibrationSavetoEEProm;
|
||||
extern uint16_t AccInflightCalibrationActive;
|
||||
extern uint16_t batteryWarningVoltage;
|
||||
extern uint8_t batteryCellCount;
|
||||
|
||||
sensor_t acc; // acc access functions
|
||||
sensor_t gyro; // gyro access functions
|
||||
|
@ -45,6 +47,34 @@ void sensorsAutodetect(void)
|
|||
gyro.init();
|
||||
}
|
||||
|
||||
uint16_t batteryAdcToVoltage(uint16_t src)
|
||||
{
|
||||
// calculate battery voltage based on ADC reading
|
||||
// result is Vbatt in 0.1V steps. 3.3V = ADC Vref, 4095 = 12bit adc, 110 = 11:1 voltage divider (10k:1k) * 10 for 0.1V
|
||||
return (((src) * 3.3f) / 4095) * cfg.vbatscale;
|
||||
}
|
||||
|
||||
void batteryInit(void)
|
||||
{
|
||||
uint8_t i;
|
||||
uint32_t voltage = 0;
|
||||
|
||||
for (i = 0; i < 32; i++) {
|
||||
voltage += adcGetBattery();
|
||||
delay(10);
|
||||
}
|
||||
|
||||
voltage = batteryAdcToVoltage((uint16_t)(voltage / 32));
|
||||
|
||||
// autodetect cell count, going from 2S..6S
|
||||
for (i = 2; i < 6; i++) {
|
||||
if (voltage < i * cfg.vbatmaxcellvoltage)
|
||||
break;
|
||||
}
|
||||
batteryCellCount = i;
|
||||
batteryWarningVoltage = i * cfg.vbatmincellvoltage; // 3.3V per cell minimum, configurable in CLI
|
||||
}
|
||||
|
||||
static void ACC_Common(void)
|
||||
{
|
||||
static int32_t a[3];
|
||||
|
@ -132,7 +162,7 @@ static void ACC_Common(void)
|
|||
void ACC_getADC(void)
|
||||
{
|
||||
acc.read(accADC);
|
||||
acc.orient(accADC);
|
||||
acc.align(accADC);
|
||||
|
||||
ACC_Common();
|
||||
}
|
||||
|
@ -237,7 +267,7 @@ void Gyro_getADC(void)
|
|||
{
|
||||
// range: +/- 8192; +/- 2000 deg/sec
|
||||
gyro.read(gyroADC);
|
||||
gyro.orient(gyroADC);
|
||||
gyro.align(gyroADC);
|
||||
|
||||
GYRO_Common();
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue