main uart baud rate commit before tearing stuff up
git-svn-id: https://afrodevices.googlecode.com/svn/trunk/baseflight@134 7c89a4a9-59b9-e629-4cfe-3a2d53b20e61
This commit is contained in:
parent
da5ac020e1
commit
c98b6b30af
139
baseflight.uvopt
139
baseflight.uvopt
|
@ -73,7 +73,7 @@
|
|||
<OPTFL>
|
||||
<tvExp>1</tvExp>
|
||||
<tvExpOptDlg>0</tvExpOptDlg>
|
||||
<IsCurrentTarget>1</IsCurrentTarget>
|
||||
<IsCurrentTarget>0</IsCurrentTarget>
|
||||
</OPTFL>
|
||||
<CpuCode>255</CpuCode>
|
||||
<Books>
|
||||
|
@ -163,22 +163,7 @@
|
|||
<Type>0</Type>
|
||||
<LineNumber>309</LineNumber>
|
||||
<EnabledFlag>1</EnabledFlag>
|
||||
<Address>0</Address>
|
||||
<ByteObject>0</ByteObject>
|
||||
<ManyObjects>0</ManyObjects>
|
||||
<SizeOfObject>0</SizeOfObject>
|
||||
<BreakByAccess>0</BreakByAccess>
|
||||
<BreakIfRCount>0</BreakIfRCount>
|
||||
<Filename>D:\fly_122\projects\baseflight\src\drv_pwm.c</Filename>
|
||||
<ExecCommand></ExecCommand>
|
||||
<Expression></Expression>
|
||||
</Bp>
|
||||
<Bp>
|
||||
<Number>1</Number>
|
||||
<Type>0</Type>
|
||||
<LineNumber>461</LineNumber>
|
||||
<EnabledFlag>1</EnabledFlag>
|
||||
<Address>134248194</Address>
|
||||
<Address>134244448</Address>
|
||||
<ByteObject>0</ByteObject>
|
||||
<ManyObjects>0</ManyObjects>
|
||||
<SizeOfObject>0</SizeOfObject>
|
||||
|
@ -186,7 +171,7 @@
|
|||
<BreakIfRCount>1</BreakIfRCount>
|
||||
<Filename></Filename>
|
||||
<ExecCommand></ExecCommand>
|
||||
<Expression>\\baseflight\src/drv_mpu6050.c\461</Expression>
|
||||
<Expression>\\baseflight\src/drv_pwm.c\309</Expression>
|
||||
</Bp>
|
||||
</Breakpoint>
|
||||
<WatchWindow1>
|
||||
|
@ -332,7 +317,7 @@
|
|||
<OPTFL>
|
||||
<tvExp>1</tvExp>
|
||||
<tvExpOptDlg>0</tvExpOptDlg>
|
||||
<IsCurrentTarget>0</IsCurrentTarget>
|
||||
<IsCurrentTarget>1</IsCurrentTarget>
|
||||
</OPTFL>
|
||||
<CpuCode>255</CpuCode>
|
||||
<Books>
|
||||
|
@ -562,10 +547,10 @@
|
|||
<FileType>1</FileType>
|
||||
<tvExp>0</tvExp>
|
||||
<Focus>0</Focus>
|
||||
<ColumnNumber>0</ColumnNumber>
|
||||
<ColumnNumber>22</ColumnNumber>
|
||||
<tvExpOptDlg>0</tvExpOptDlg>
|
||||
<TopLine>52</TopLine>
|
||||
<CurrentLine>52</CurrentLine>
|
||||
<TopLine>335</TopLine>
|
||||
<CurrentLine>356</CurrentLine>
|
||||
<bDave2>0</bDave2>
|
||||
<PathWithFileName>.\src\cli.c</PathWithFileName>
|
||||
<FilenameWithoutPath>cli.c</FilenameWithoutPath>
|
||||
|
@ -578,8 +563,8 @@
|
|||
<Focus>0</Focus>
|
||||
<ColumnNumber>0</ColumnNumber>
|
||||
<tvExpOptDlg>0</tvExpOptDlg>
|
||||
<TopLine>108</TopLine>
|
||||
<CurrentLine>122</CurrentLine>
|
||||
<TopLine>135</TopLine>
|
||||
<CurrentLine>153</CurrentLine>
|
||||
<bDave2>0</bDave2>
|
||||
<PathWithFileName>.\src\config.c</PathWithFileName>
|
||||
<FilenameWithoutPath>config.c</FilenameWithoutPath>
|
||||
|
@ -590,10 +575,10 @@
|
|||
<FileType>1</FileType>
|
||||
<tvExp>0</tvExp>
|
||||
<Focus>0</Focus>
|
||||
<ColumnNumber>0</ColumnNumber>
|
||||
<ColumnNumber>35</ColumnNumber>
|
||||
<tvExpOptDlg>0</tvExpOptDlg>
|
||||
<TopLine>0</TopLine>
|
||||
<CurrentLine>0</CurrentLine>
|
||||
<TopLine>238</TopLine>
|
||||
<CurrentLine>267</CurrentLine>
|
||||
<bDave2>0</bDave2>
|
||||
<PathWithFileName>.\src\imu.c</PathWithFileName>
|
||||
<FilenameWithoutPath>imu.c</FilenameWithoutPath>
|
||||
|
@ -606,8 +591,8 @@
|
|||
<Focus>0</Focus>
|
||||
<ColumnNumber>0</ColumnNumber>
|
||||
<tvExpOptDlg>0</tvExpOptDlg>
|
||||
<TopLine>40</TopLine>
|
||||
<CurrentLine>46</CurrentLine>
|
||||
<TopLine>74</TopLine>
|
||||
<CurrentLine>92</CurrentLine>
|
||||
<bDave2>0</bDave2>
|
||||
<PathWithFileName>.\src\main.c</PathWithFileName>
|
||||
<FilenameWithoutPath>main.c</FilenameWithoutPath>
|
||||
|
@ -632,10 +617,10 @@
|
|||
<FileType>1</FileType>
|
||||
<tvExp>0</tvExp>
|
||||
<Focus>0</Focus>
|
||||
<ColumnNumber>0</ColumnNumber>
|
||||
<ColumnNumber>16</ColumnNumber>
|
||||
<tvExpOptDlg>0</tvExpOptDlg>
|
||||
<TopLine>247</TopLine>
|
||||
<CurrentLine>257</CurrentLine>
|
||||
<TopLine>262</TopLine>
|
||||
<CurrentLine>284</CurrentLine>
|
||||
<bDave2>0</bDave2>
|
||||
<PathWithFileName>.\src\mw.c</PathWithFileName>
|
||||
<FilenameWithoutPath>mw.c</FilenameWithoutPath>
|
||||
|
@ -648,7 +633,7 @@
|
|||
<Focus>0</Focus>
|
||||
<ColumnNumber>0</ColumnNumber>
|
||||
<tvExpOptDlg>0</tvExpOptDlg>
|
||||
<TopLine>19</TopLine>
|
||||
<TopLine>33</TopLine>
|
||||
<CurrentLine>51</CurrentLine>
|
||||
<bDave2>0</bDave2>
|
||||
<PathWithFileName>.\src\sensors.c</PathWithFileName>
|
||||
|
@ -676,7 +661,7 @@
|
|||
<Focus>0</Focus>
|
||||
<ColumnNumber>0</ColumnNumber>
|
||||
<tvExpOptDlg>0</tvExpOptDlg>
|
||||
<TopLine>19</TopLine>
|
||||
<TopLine>25</TopLine>
|
||||
<CurrentLine>43</CurrentLine>
|
||||
<bDave2>0</bDave2>
|
||||
<PathWithFileName>.\src\board.h</PathWithFileName>
|
||||
|
@ -688,21 +673,21 @@
|
|||
<FileType>5</FileType>
|
||||
<tvExp>0</tvExp>
|
||||
<Focus>0</Focus>
|
||||
<ColumnNumber>21</ColumnNumber>
|
||||
<ColumnNumber>0</ColumnNumber>
|
||||
<tvExpOptDlg>0</tvExpOptDlg>
|
||||
<TopLine>172</TopLine>
|
||||
<CurrentLine>172</CurrentLine>
|
||||
<TopLine>281</TopLine>
|
||||
<CurrentLine>299</CurrentLine>
|
||||
<bDave2>0</bDave2>
|
||||
<PathWithFileName>.\src\mw.h</PathWithFileName>
|
||||
<FilenameWithoutPath>mw.h</FilenameWithoutPath>
|
||||
</File>
|
||||
<File>
|
||||
<GroupNumber>1</GroupNumber>
|
||||
<FileNumber>0</FileNumber>
|
||||
<FileNumber>11</FileNumber>
|
||||
<FileType>1</FileType>
|
||||
<tvExp>0</tvExp>
|
||||
<Focus>0</Focus>
|
||||
<ColumnNumber>25</ColumnNumber>
|
||||
<ColumnNumber>30</ColumnNumber>
|
||||
<tvExpOptDlg>0</tvExpOptDlg>
|
||||
<TopLine>7</TopLine>
|
||||
<CurrentLine>14</CurrentLine>
|
||||
|
@ -712,13 +697,13 @@
|
|||
</File>
|
||||
<File>
|
||||
<GroupNumber>1</GroupNumber>
|
||||
<FileNumber>0</FileNumber>
|
||||
<FileNumber>12</FileNumber>
|
||||
<FileType>1</FileType>
|
||||
<tvExp>0</tvExp>
|
||||
<Focus>0</Focus>
|
||||
<ColumnNumber>0</ColumnNumber>
|
||||
<tvExpOptDlg>0</tvExpOptDlg>
|
||||
<TopLine>53</TopLine>
|
||||
<TopLine>73</TopLine>
|
||||
<CurrentLine>91</CurrentLine>
|
||||
<bDave2>0</bDave2>
|
||||
<PathWithFileName>.\src\spektrum.c</PathWithFileName>
|
||||
|
@ -733,11 +718,11 @@
|
|||
<cbSel>0</cbSel>
|
||||
<File>
|
||||
<GroupNumber>2</GroupNumber>
|
||||
<FileNumber>11</FileNumber>
|
||||
<FileNumber>13</FileNumber>
|
||||
<FileType>1</FileType>
|
||||
<tvExp>0</tvExp>
|
||||
<Focus>0</Focus>
|
||||
<ColumnNumber>22</ColumnNumber>
|
||||
<ColumnNumber>0</ColumnNumber>
|
||||
<tvExpOptDlg>0</tvExpOptDlg>
|
||||
<TopLine>0</TopLine>
|
||||
<CurrentLine>0</CurrentLine>
|
||||
|
@ -747,7 +732,7 @@
|
|||
</File>
|
||||
<File>
|
||||
<GroupNumber>2</GroupNumber>
|
||||
<FileNumber>12</FileNumber>
|
||||
<FileNumber>14</FileNumber>
|
||||
<FileType>1</FileType>
|
||||
<tvExp>0</tvExp>
|
||||
<Focus>0</Focus>
|
||||
|
@ -761,7 +746,7 @@
|
|||
</File>
|
||||
<File>
|
||||
<GroupNumber>2</GroupNumber>
|
||||
<FileNumber>13</FileNumber>
|
||||
<FileNumber>15</FileNumber>
|
||||
<FileType>1</FileType>
|
||||
<tvExp>0</tvExp>
|
||||
<Focus>0</Focus>
|
||||
|
@ -775,7 +760,7 @@
|
|||
</File>
|
||||
<File>
|
||||
<GroupNumber>2</GroupNumber>
|
||||
<FileNumber>14</FileNumber>
|
||||
<FileNumber>16</FileNumber>
|
||||
<FileType>1</FileType>
|
||||
<tvExp>0</tvExp>
|
||||
<Focus>0</Focus>
|
||||
|
@ -789,23 +774,23 @@
|
|||
</File>
|
||||
<File>
|
||||
<GroupNumber>2</GroupNumber>
|
||||
<FileNumber>15</FileNumber>
|
||||
<FileNumber>17</FileNumber>
|
||||
<FileType>1</FileType>
|
||||
<tvExp>0</tvExp>
|
||||
<Focus>0</Focus>
|
||||
<ColumnNumber>27</ColumnNumber>
|
||||
<ColumnNumber>25</ColumnNumber>
|
||||
<tvExpOptDlg>0</tvExpOptDlg>
|
||||
<TopLine>0</TopLine>
|
||||
<CurrentLine>0</CurrentLine>
|
||||
<TopLine>163</TopLine>
|
||||
<CurrentLine>181</CurrentLine>
|
||||
<bDave2>0</bDave2>
|
||||
<PathWithFileName>.\src\drv_i2c.c</PathWithFileName>
|
||||
<FilenameWithoutPath>drv_i2c.c</FilenameWithoutPath>
|
||||
</File>
|
||||
<File>
|
||||
<GroupNumber>2</GroupNumber>
|
||||
<FileNumber>16</FileNumber>
|
||||
<FileNumber>18</FileNumber>
|
||||
<FileType>1</FileType>
|
||||
<tvExp>1</tvExp>
|
||||
<tvExp>0</tvExp>
|
||||
<Focus>0</Focus>
|
||||
<ColumnNumber>0</ColumnNumber>
|
||||
<tvExpOptDlg>0</tvExpOptDlg>
|
||||
|
@ -817,21 +802,21 @@
|
|||
</File>
|
||||
<File>
|
||||
<GroupNumber>2</GroupNumber>
|
||||
<FileNumber>17</FileNumber>
|
||||
<FileNumber>19</FileNumber>
|
||||
<FileType>1</FileType>
|
||||
<tvExp>0</tvExp>
|
||||
<Focus>0</Focus>
|
||||
<ColumnNumber>12</ColumnNumber>
|
||||
<ColumnNumber>0</ColumnNumber>
|
||||
<tvExpOptDlg>0</tvExpOptDlg>
|
||||
<TopLine>283</TopLine>
|
||||
<CurrentLine>309</CurrentLine>
|
||||
<TopLine>228</TopLine>
|
||||
<CurrentLine>246</CurrentLine>
|
||||
<bDave2>0</bDave2>
|
||||
<PathWithFileName>.\src\drv_pwm.c</PathWithFileName>
|
||||
<FilenameWithoutPath>drv_pwm.c</FilenameWithoutPath>
|
||||
</File>
|
||||
<File>
|
||||
<GroupNumber>2</GroupNumber>
|
||||
<FileNumber>18</FileNumber>
|
||||
<FileNumber>20</FileNumber>
|
||||
<FileType>1</FileType>
|
||||
<tvExp>0</tvExp>
|
||||
<Focus>0</Focus>
|
||||
|
@ -845,13 +830,13 @@
|
|||
</File>
|
||||
<File>
|
||||
<GroupNumber>2</GroupNumber>
|
||||
<FileNumber>19</FileNumber>
|
||||
<FileNumber>21</FileNumber>
|
||||
<FileType>1</FileType>
|
||||
<tvExp>0</tvExp>
|
||||
<Focus>0</Focus>
|
||||
<ColumnNumber>0</ColumnNumber>
|
||||
<tvExpOptDlg>0</tvExpOptDlg>
|
||||
<TopLine>153</TopLine>
|
||||
<TopLine>172</TopLine>
|
||||
<CurrentLine>190</CurrentLine>
|
||||
<bDave2>0</bDave2>
|
||||
<PathWithFileName>.\src\drv_uart.c</PathWithFileName>
|
||||
|
@ -859,11 +844,11 @@
|
|||
</File>
|
||||
<File>
|
||||
<GroupNumber>2</GroupNumber>
|
||||
<FileNumber>20</FileNumber>
|
||||
<FileNumber>22</FileNumber>
|
||||
<FileType>1</FileType>
|
||||
<tvExp>0</tvExp>
|
||||
<Focus>0</Focus>
|
||||
<ColumnNumber>17</ColumnNumber>
|
||||
<ColumnNumber>0</ColumnNumber>
|
||||
<tvExpOptDlg>0</tvExpOptDlg>
|
||||
<TopLine>0</TopLine>
|
||||
<CurrentLine>0</CurrentLine>
|
||||
|
@ -873,11 +858,11 @@
|
|||
</File>
|
||||
<File>
|
||||
<GroupNumber>2</GroupNumber>
|
||||
<FileNumber>21</FileNumber>
|
||||
<FileNumber>23</FileNumber>
|
||||
<FileType>1</FileType>
|
||||
<tvExp>0</tvExp>
|
||||
<Focus>0</Focus>
|
||||
<ColumnNumber>14</ColumnNumber>
|
||||
<ColumnNumber>0</ColumnNumber>
|
||||
<tvExpOptDlg>0</tvExpOptDlg>
|
||||
<TopLine>0</TopLine>
|
||||
<CurrentLine>0</CurrentLine>
|
||||
|
@ -894,7 +879,7 @@
|
|||
<cbSel>0</cbSel>
|
||||
<File>
|
||||
<GroupNumber>3</GroupNumber>
|
||||
<FileNumber>22</FileNumber>
|
||||
<FileNumber>24</FileNumber>
|
||||
<FileType>1</FileType>
|
||||
<tvExp>0</tvExp>
|
||||
<Focus>0</Focus>
|
||||
|
@ -908,7 +893,7 @@
|
|||
</File>
|
||||
<File>
|
||||
<GroupNumber>3</GroupNumber>
|
||||
<FileNumber>23</FileNumber>
|
||||
<FileNumber>25</FileNumber>
|
||||
<FileType>1</FileType>
|
||||
<tvExp>0</tvExp>
|
||||
<Focus>0</Focus>
|
||||
|
@ -922,7 +907,7 @@
|
|||
</File>
|
||||
<File>
|
||||
<GroupNumber>3</GroupNumber>
|
||||
<FileNumber>24</FileNumber>
|
||||
<FileNumber>26</FileNumber>
|
||||
<FileType>1</FileType>
|
||||
<tvExp>0</tvExp>
|
||||
<Focus>0</Focus>
|
||||
|
@ -936,7 +921,7 @@
|
|||
</File>
|
||||
<File>
|
||||
<GroupNumber>3</GroupNumber>
|
||||
<FileNumber>25</FileNumber>
|
||||
<FileNumber>27</FileNumber>
|
||||
<FileType>1</FileType>
|
||||
<tvExp>0</tvExp>
|
||||
<Focus>0</Focus>
|
||||
|
@ -950,7 +935,7 @@
|
|||
</File>
|
||||
<File>
|
||||
<GroupNumber>3</GroupNumber>
|
||||
<FileNumber>26</FileNumber>
|
||||
<FileNumber>28</FileNumber>
|
||||
<FileType>1</FileType>
|
||||
<tvExp>0</tvExp>
|
||||
<Focus>0</Focus>
|
||||
|
@ -964,7 +949,7 @@
|
|||
</File>
|
||||
<File>
|
||||
<GroupNumber>3</GroupNumber>
|
||||
<FileNumber>27</FileNumber>
|
||||
<FileNumber>29</FileNumber>
|
||||
<FileType>1</FileType>
|
||||
<tvExp>0</tvExp>
|
||||
<Focus>0</Focus>
|
||||
|
@ -978,7 +963,7 @@
|
|||
</File>
|
||||
<File>
|
||||
<GroupNumber>3</GroupNumber>
|
||||
<FileNumber>28</FileNumber>
|
||||
<FileNumber>30</FileNumber>
|
||||
<FileType>1</FileType>
|
||||
<tvExp>0</tvExp>
|
||||
<Focus>0</Focus>
|
||||
|
@ -992,7 +977,7 @@
|
|||
</File>
|
||||
<File>
|
||||
<GroupNumber>3</GroupNumber>
|
||||
<FileNumber>29</FileNumber>
|
||||
<FileNumber>31</FileNumber>
|
||||
<FileType>1</FileType>
|
||||
<tvExp>0</tvExp>
|
||||
<Focus>0</Focus>
|
||||
|
@ -1006,7 +991,7 @@
|
|||
</File>
|
||||
<File>
|
||||
<GroupNumber>3</GroupNumber>
|
||||
<FileNumber>30</FileNumber>
|
||||
<FileNumber>32</FileNumber>
|
||||
<FileType>1</FileType>
|
||||
<tvExp>0</tvExp>
|
||||
<Focus>0</Focus>
|
||||
|
@ -1020,7 +1005,7 @@
|
|||
</File>
|
||||
<File>
|
||||
<GroupNumber>3</GroupNumber>
|
||||
<FileNumber>31</FileNumber>
|
||||
<FileNumber>33</FileNumber>
|
||||
<FileType>1</FileType>
|
||||
<tvExp>0</tvExp>
|
||||
<Focus>0</Focus>
|
||||
|
@ -1034,11 +1019,11 @@
|
|||
</File>
|
||||
<File>
|
||||
<GroupNumber>3</GroupNumber>
|
||||
<FileNumber>32</FileNumber>
|
||||
<FileNumber>34</FileNumber>
|
||||
<FileType>1</FileType>
|
||||
<tvExp>0</tvExp>
|
||||
<Focus>0</Focus>
|
||||
<ColumnNumber>32</ColumnNumber>
|
||||
<ColumnNumber>0</ColumnNumber>
|
||||
<tvExpOptDlg>0</tvExpOptDlg>
|
||||
<TopLine>0</TopLine>
|
||||
<CurrentLine>0</CurrentLine>
|
||||
|
@ -1048,7 +1033,7 @@
|
|||
</File>
|
||||
<File>
|
||||
<GroupNumber>3</GroupNumber>
|
||||
<FileNumber>33</FileNumber>
|
||||
<FileNumber>35</FileNumber>
|
||||
<FileType>1</FileType>
|
||||
<tvExp>0</tvExp>
|
||||
<Focus>0</Focus>
|
||||
|
@ -1062,7 +1047,7 @@
|
|||
</File>
|
||||
<File>
|
||||
<GroupNumber>3</GroupNumber>
|
||||
<FileNumber>34</FileNumber>
|
||||
<FileNumber>36</FileNumber>
|
||||
<FileType>2</FileType>
|
||||
<tvExp>0</tvExp>
|
||||
<Focus>0</Focus>
|
||||
|
|
4971
obj/baseflight.hex
4971
obj/baseflight.hex
File diff suppressed because it is too large
Load Diff
22
src/cli.c
22
src/cli.c
|
@ -70,7 +70,8 @@ typedef enum {
|
|||
VAR_UINT8,
|
||||
VAR_INT8,
|
||||
VAR_UINT16,
|
||||
VAR_INT16
|
||||
VAR_INT16,
|
||||
VAR_UINT32
|
||||
} vartype_e;
|
||||
|
||||
typedef struct {
|
||||
|
@ -104,7 +105,8 @@ const clivalue_t valueTable[] = {
|
|||
{ "tilt_roll_prop", VAR_INT8, &cfg.tilt_roll_prop, -100, 100 },
|
||||
{ "acc_lpf_factor", VAR_UINT8, &cfg.acc_lpf_factor, 0, 32 },
|
||||
{ "gyro_lpf", VAR_UINT16, &cfg.gyro_lpf, 0, 256 },
|
||||
{ "gps_baudrate", VAR_UINT16, &cfg.gps_baudrate, 1200, 57600 },
|
||||
{ "gps_baudrate", VAR_UINT32, &cfg.gps_baudrate, 1200, 115200 },
|
||||
{ "serial_baudrate", VAR_UINT32, &cfg.serial_baudrate, 1200, 115200 },
|
||||
{ "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},
|
||||
|
@ -362,6 +364,10 @@ static void cliPrintVar(const clivalue_t *var)
|
|||
case VAR_INT16:
|
||||
value = *(int16_t *)var->ptr;
|
||||
break;
|
||||
|
||||
case VAR_UINT32:
|
||||
value = *(uint32_t *)var->ptr;
|
||||
break;
|
||||
}
|
||||
itoa(value, buf, 10);
|
||||
uartPrint(buf);
|
||||
|
@ -371,19 +377,17 @@ static void cliSetVar(const clivalue_t *var, const int32_t value)
|
|||
{
|
||||
switch (var->type) {
|
||||
case VAR_UINT8:
|
||||
*(uint8_t *)var->ptr = (uint8_t)value;
|
||||
break;
|
||||
|
||||
case VAR_INT8:
|
||||
*(int8_t *)var->ptr = (int8_t)value;
|
||||
*(char *)var->ptr = (char)value;
|
||||
break;
|
||||
|
||||
case VAR_UINT16:
|
||||
*(uint16_t *)var->ptr = (uint16_t)value;
|
||||
case VAR_INT16:
|
||||
*(short *)var->ptr = (short)value;
|
||||
break;
|
||||
|
||||
case VAR_INT16:
|
||||
*(int16_t *)var->ptr = (int16_t)value;
|
||||
case VAR_UINT32:
|
||||
*(int *)var->ptr = (int)value;
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
|
|
@ -13,7 +13,7 @@ config_t cfg;
|
|||
const char rcChannelLetters[] = "AERT1234";
|
||||
|
||||
static uint32_t enabledSensors = 0;
|
||||
static uint8_t checkNewConf = 9;
|
||||
static uint8_t checkNewConf = 10;
|
||||
|
||||
void parseRcChannels(const char *input)
|
||||
{
|
||||
|
@ -151,6 +151,9 @@ void checkFirstTime(bool reset)
|
|||
// gps baud-rate
|
||||
cfg.gps_baudrate = 9600;
|
||||
|
||||
// serial(uart1) baudrate
|
||||
cfg.serial_baudrate = 115200;
|
||||
|
||||
writeParams();
|
||||
}
|
||||
|
||||
|
|
|
@ -102,7 +102,6 @@ void systemInit(void)
|
|||
// Configure the rest of the stuff
|
||||
adcInit();
|
||||
i2cInit(I2C2);
|
||||
uartInit();
|
||||
|
||||
// sleep for 100ms
|
||||
delay(100);
|
||||
|
|
|
@ -37,7 +37,7 @@ void DMA1_Channel4_IRQHandler(void)
|
|||
uartTxDMA();
|
||||
}
|
||||
|
||||
void uartInit(void)
|
||||
void uartInit(uint32_t speed)
|
||||
{
|
||||
GPIO_InitTypeDef GPIO_InitStructure;
|
||||
USART_InitTypeDef USART_InitStructure;
|
||||
|
@ -63,7 +63,7 @@ void uartInit(void)
|
|||
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
|
||||
NVIC_Init(&NVIC_InitStructure);
|
||||
|
||||
USART_InitStructure.USART_BaudRate = 115200;
|
||||
USART_InitStructure.USART_BaudRate = speed;
|
||||
USART_InitStructure.USART_WordLength = USART_WordLength_8b;
|
||||
USART_InitStructure.USART_StopBits = USART_StopBits_1;
|
||||
USART_InitStructure.USART_Parity = USART_Parity_No;
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
#pragma once
|
||||
|
||||
void uartInit(void);
|
||||
void uartInit(uint32_t speed);
|
||||
uint16_t uartAvailable(void);
|
||||
uint8_t uartRead(void);
|
||||
uint8_t uartReadPoll(void);
|
||||
|
|
|
@ -11,7 +11,7 @@ static void GPS_distance(int32_t lat1, int32_t lon1, int32_t lat2, int32_t lon2,
|
|||
|
||||
void gpsInit(uint32_t baudrate)
|
||||
{
|
||||
uart2Init(9600, GPS_NewData);
|
||||
uart2Init(cfg.gps_baudrate, GPS_NewData);
|
||||
sensorsSet(SENSOR_GPS);
|
||||
}
|
||||
|
||||
|
|
|
@ -180,7 +180,6 @@ static void getEstimatedAttitude(void)
|
|||
// Initialization
|
||||
for (axis = 0; axis < 3; axis++) {
|
||||
deltaGyroAngle[axis] = gyroADC[axis] * scale;
|
||||
|
||||
if (cfg.acc_lpf_factor > 0) {
|
||||
accTemp[axis] = (accTemp[axis] - (accTemp[axis] >> cfg.acc_lpf_factor)) + accADC[axis];
|
||||
accSmooth[axis] = accTemp[axis] >> cfg.acc_lpf_factor;
|
||||
|
|
|
@ -48,6 +48,8 @@ int main(void)
|
|||
readEEPROM();
|
||||
checkFirstTime(false);
|
||||
|
||||
serialInit(cfg.serial_baudrate);
|
||||
|
||||
// We have these sensors
|
||||
sensorsSet(SENSOR_ACC | SENSOR_BARO | SENSOR_MAG);
|
||||
|
||||
|
|
5
src/mw.h
5
src/mw.h
|
@ -180,8 +180,10 @@ typedef struct config_t {
|
|||
int8_t tilt_roll_prop; // servo proportional (tied to angle) ; can be negative to invert movement
|
||||
|
||||
// gps baud-rate
|
||||
uint16_t gps_baudrate;
|
||||
uint32_t gps_baudrate;
|
||||
|
||||
// serial(uart1) baudrate
|
||||
uint32_t serial_baudrate;
|
||||
} config_t;
|
||||
|
||||
extern int16_t gyroZero[3];
|
||||
|
@ -270,6 +272,7 @@ void writeAllMotors(int16_t mc);
|
|||
void mixTable(void);
|
||||
|
||||
// Serial
|
||||
void serialInit(uint32_t baudrate);
|
||||
void serialCom(void);
|
||||
|
||||
// Config
|
||||
|
|
|
@ -15,6 +15,11 @@ void serialize8(uint8_t a)
|
|||
uartWrite(a);
|
||||
}
|
||||
|
||||
void serialInit(uint32_t baudrate)
|
||||
{
|
||||
uartInit(baudrate);
|
||||
}
|
||||
|
||||
void serialCom(void)
|
||||
{
|
||||
uint8_t i;
|
||||
|
|
Loading…
Reference in New Issue