added a fix for roundf() and friends for keil

added float-based acc lpf, acc_lpf_factor values now changed, its 1/factor now, values 60+ and larger filter heavier.
playing with release MPU6050 hardware, looks like acc1G is fucked, as predicted
bug in serial output (forgot to output armed bit to GUI, estalt is /10)

git-svn-id: https://afrodevices.googlecode.com/svn/trunk/baseflight@144 7c89a4a9-59b9-e629-4cfe-3a2d53b20e61
This commit is contained in:
timecop 2012-04-06 02:23:25 +00:00
parent 861b274039
commit 9e5504acd8
8 changed files with 2493 additions and 2478 deletions

View File

@ -402,7 +402,7 @@
<Type>0</Type>
<LineNumber>71</LineNumber>
<EnabledFlag>1</EnabledFlag>
<Address>134232424</Address>
<Address>134232596</Address>
<ByteObject>0</ByteObject>
<ManyObjects>0</ManyObjects>
<SizeOfObject>0</SizeOfObject>
@ -415,9 +415,9 @@
<Bp>
<Number>1</Number>
<Type>0</Type>
<LineNumber>305</LineNumber>
<LineNumber>167</LineNumber>
<EnabledFlag>1</EnabledFlag>
<Address>134236062</Address>
<Address>134229292</Address>
<ByteObject>0</ByteObject>
<ManyObjects>0</ManyObjects>
<SizeOfObject>0</SizeOfObject>
@ -425,7 +425,7 @@
<BreakIfRCount>1</BreakIfRCount>
<Filename></Filename>
<ExecCommand></ExecCommand>
<Expression>\\baseflight\src/drv_pwm.c\305</Expression>
<Expression>\\baseflight\src/sensors.c\167</Expression>
</Bp>
</Breakpoint>
<WatchWindow1>
@ -457,45 +457,44 @@
<Ww>
<count>5</count>
<WinNumber>1</WinNumber>
<ItemText>eep_entry</ItemText>
<ItemText>gyroData,0x0A</ItemText>
</Ww>
<Ww>
<count>6</count>
<WinNumber>1</WinNumber>
<ItemText>gyroData,0x0A</ItemText>
<ItemText>magADC,0x0A</ItemText>
</Ww>
<Ww>
<count>7</count>
<WinNumber>1</WinNumber>
<ItemText>magADC,0x0A</ItemText>
<ItemText>dmpdata</ItemText>
</Ww>
<Ww>
<count>8</count>
<WinNumber>1</WinNumber>
<ItemText>maginv</ItemText>
<ItemText>angle,0x0A</ItemText>
</Ww>
<Ww>
<count>9</count>
<WinNumber>1</WinNumber>
<ItemText>magaxis</ItemText>
<ItemText>dmpFifoLevel,0x0A</ItemText>
</Ww>
<Ww>
<count>10</count>
<WinNumber>1</WinNumber>
<ItemText>rawMagADC,0x0A</ItemText>
<ItemText>accData</ItemText>
</Ww>
<Ww>
<count>11</count>
<WinNumber>1</WinNumber>
<ItemText>spekChannelData
</ItemText>
<ItemText>accADC</ItemText>
</Ww>
</WatchWindow1>
<MemoryWindow1>
<Mm>
<WinNumber>1</WinNumber>
<SubType>0</SubType>
<ItemText>\\baseflight\sensors.c\magaxis</ItemText>
<ItemText>accData</ItemText>
</Mm>
</MemoryWindow1>
<MemoryWindow2>
@ -508,7 +507,7 @@
<DebugFlag>
<trace>0</trace>
<periodic>1</periodic>
<aLwin>1</aLwin>
<aLwin>0</aLwin>
<aCover>0</aCover>
<aSer1>0</aSer1>
<aSer2>0</aSer2>
@ -547,10 +546,10 @@
<FileType>1</FileType>
<tvExp>0</tvExp>
<Focus>0</Focus>
<ColumnNumber>22</ColumnNumber>
<ColumnNumber>19</ColumnNumber>
<tvExpOptDlg>0</tvExpOptDlg>
<TopLine>335</TopLine>
<CurrentLine>356</CurrentLine>
<TopLine>82</TopLine>
<CurrentLine>97</CurrentLine>
<bDave2>0</bDave2>
<PathWithFileName>.\src\cli.c</PathWithFileName>
<FilenameWithoutPath>cli.c</FilenameWithoutPath>
@ -561,10 +560,10 @@
<FileType>1</FileType>
<tvExp>0</tvExp>
<Focus>0</Focus>
<ColumnNumber>0</ColumnNumber>
<ColumnNumber>14</ColumnNumber>
<tvExpOptDlg>0</tvExpOptDlg>
<TopLine>135</TopLine>
<CurrentLine>153</CurrentLine>
<TopLine>16</TopLine>
<CurrentLine>31</CurrentLine>
<bDave2>0</bDave2>
<PathWithFileName>.\src\config.c</PathWithFileName>
<FilenameWithoutPath>config.c</FilenameWithoutPath>
@ -575,10 +574,10 @@
<FileType>1</FileType>
<tvExp>0</tvExp>
<Focus>0</Focus>
<ColumnNumber>35</ColumnNumber>
<ColumnNumber>0</ColumnNumber>
<tvExpOptDlg>0</tvExpOptDlg>
<TopLine>238</TopLine>
<CurrentLine>267</CurrentLine>
<TopLine>253</TopLine>
<CurrentLine>253</CurrentLine>
<bDave2>0</bDave2>
<PathWithFileName>.\src\imu.c</PathWithFileName>
<FilenameWithoutPath>imu.c</FilenameWithoutPath>
@ -589,10 +588,10 @@
<FileType>1</FileType>
<tvExp>0</tvExp>
<Focus>0</Focus>
<ColumnNumber>0</ColumnNumber>
<ColumnNumber>14</ColumnNumber>
<tvExpOptDlg>0</tvExpOptDlg>
<TopLine>74</TopLine>
<CurrentLine>92</CurrentLine>
<TopLine>26</TopLine>
<CurrentLine>35</CurrentLine>
<bDave2>0</bDave2>
<PathWithFileName>.\src\main.c</PathWithFileName>
<FilenameWithoutPath>main.c</FilenameWithoutPath>
@ -603,10 +602,10 @@
<FileType>1</FileType>
<tvExp>0</tvExp>
<Focus>0</Focus>
<ColumnNumber>8</ColumnNumber>
<ColumnNumber>20</ColumnNumber>
<tvExpOptDlg>0</tvExpOptDlg>
<TopLine>0</TopLine>
<CurrentLine>0</CurrentLine>
<TopLine>99</TopLine>
<CurrentLine>123</CurrentLine>
<bDave2>0</bDave2>
<PathWithFileName>.\src\mixer.c</PathWithFileName>
<FilenameWithoutPath>mixer.c</FilenameWithoutPath>
@ -617,10 +616,10 @@
<FileType>1</FileType>
<tvExp>0</tvExp>
<Focus>0</Focus>
<ColumnNumber>16</ColumnNumber>
<ColumnNumber>35</ColumnNumber>
<tvExpOptDlg>0</tvExpOptDlg>
<TopLine>262</TopLine>
<CurrentLine>284</CurrentLine>
<TopLine>1</TopLine>
<CurrentLine>17</CurrentLine>
<bDave2>0</bDave2>
<PathWithFileName>.\src\mw.c</PathWithFileName>
<FilenameWithoutPath>mw.c</FilenameWithoutPath>
@ -631,10 +630,10 @@
<FileType>1</FileType>
<tvExp>0</tvExp>
<Focus>0</Focus>
<ColumnNumber>0</ColumnNumber>
<ColumnNumber>24</ColumnNumber>
<tvExpOptDlg>0</tvExpOptDlg>
<TopLine>33</TopLine>
<CurrentLine>51</CurrentLine>
<TopLine>178</TopLine>
<CurrentLine>207</CurrentLine>
<bDave2>0</bDave2>
<PathWithFileName>.\src\sensors.c</PathWithFileName>
<FilenameWithoutPath>sensors.c</FilenameWithoutPath>
@ -645,10 +644,10 @@
<FileType>1</FileType>
<tvExp>0</tvExp>
<Focus>0</Focus>
<ColumnNumber>0</ColumnNumber>
<ColumnNumber>16</ColumnNumber>
<tvExpOptDlg>0</tvExpOptDlg>
<TopLine>0</TopLine>
<CurrentLine>0</CurrentLine>
<TopLine>133</TopLine>
<CurrentLine>151</CurrentLine>
<bDave2>0</bDave2>
<PathWithFileName>.\src\serial.c</PathWithFileName>
<FilenameWithoutPath>serial.c</FilenameWithoutPath>
@ -661,8 +660,8 @@
<Focus>0</Focus>
<ColumnNumber>0</ColumnNumber>
<tvExpOptDlg>0</tvExpOptDlg>
<TopLine>25</TopLine>
<CurrentLine>43</CurrentLine>
<TopLine>1</TopLine>
<CurrentLine>17</CurrentLine>
<bDave2>0</bDave2>
<PathWithFileName>.\src\board.h</PathWithFileName>
<FilenameWithoutPath>board.h</FilenameWithoutPath>
@ -675,8 +674,8 @@
<Focus>0</Focus>
<ColumnNumber>0</ColumnNumber>
<tvExpOptDlg>0</tvExpOptDlg>
<TopLine>281</TopLine>
<CurrentLine>299</CurrentLine>
<TopLine>135</TopLine>
<CurrentLine>146</CurrentLine>
<bDave2>0</bDave2>
<PathWithFileName>.\src\mw.h</PathWithFileName>
<FilenameWithoutPath>mw.h</FilenameWithoutPath>
@ -687,10 +686,10 @@
<FileType>1</FileType>
<tvExp>0</tvExp>
<Focus>0</Focus>
<ColumnNumber>30</ColumnNumber>
<ColumnNumber>0</ColumnNumber>
<tvExpOptDlg>0</tvExpOptDlg>
<TopLine>7</TopLine>
<CurrentLine>14</CurrentLine>
<TopLine>0</TopLine>
<CurrentLine>0</CurrentLine>
<bDave2>0</bDave2>
<PathWithFileName>.\src\gps.c</PathWithFileName>
<FilenameWithoutPath>gps.c</FilenameWithoutPath>
@ -703,8 +702,8 @@
<Focus>0</Focus>
<ColumnNumber>0</ColumnNumber>
<tvExpOptDlg>0</tvExpOptDlg>
<TopLine>73</TopLine>
<CurrentLine>91</CurrentLine>
<TopLine>0</TopLine>
<CurrentLine>0</CurrentLine>
<bDave2>0</bDave2>
<PathWithFileName>.\src\spektrum.c</PathWithFileName>
<FilenameWithoutPath>spektrum.c</FilenameWithoutPath>
@ -764,7 +763,7 @@
<FileType>1</FileType>
<tvExp>0</tvExp>
<Focus>0</Focus>
<ColumnNumber>0</ColumnNumber>
<ColumnNumber>32</ColumnNumber>
<tvExpOptDlg>0</tvExpOptDlg>
<TopLine>0</TopLine>
<CurrentLine>0</CurrentLine>
@ -778,10 +777,10 @@
<FileType>1</FileType>
<tvExp>0</tvExp>
<Focus>0</Focus>
<ColumnNumber>25</ColumnNumber>
<ColumnNumber>0</ColumnNumber>
<tvExpOptDlg>0</tvExpOptDlg>
<TopLine>163</TopLine>
<CurrentLine>181</CurrentLine>
<TopLine>266</TopLine>
<CurrentLine>293</CurrentLine>
<bDave2>0</bDave2>
<PathWithFileName>.\src\drv_i2c.c</PathWithFileName>
<FilenameWithoutPath>drv_i2c.c</FilenameWithoutPath>
@ -794,8 +793,8 @@
<Focus>0</Focus>
<ColumnNumber>0</ColumnNumber>
<tvExpOptDlg>0</tvExpOptDlg>
<TopLine>20</TopLine>
<CurrentLine>20</CurrentLine>
<TopLine>1</TopLine>
<CurrentLine>5</CurrentLine>
<bDave2>0</bDave2>
<PathWithFileName>.\src\drv_mpu3050.c</PathWithFileName>
<FilenameWithoutPath>drv_mpu3050.c</FilenameWithoutPath>
@ -808,8 +807,8 @@
<Focus>0</Focus>
<ColumnNumber>0</ColumnNumber>
<tvExpOptDlg>0</tvExpOptDlg>
<TopLine>228</TopLine>
<CurrentLine>246</CurrentLine>
<TopLine>297</TopLine>
<CurrentLine>307</CurrentLine>
<bDave2>0</bDave2>
<PathWithFileName>.\src\drv_pwm.c</PathWithFileName>
<FilenameWithoutPath>drv_pwm.c</FilenameWithoutPath>
@ -822,8 +821,8 @@
<Focus>0</Focus>
<ColumnNumber>0</ColumnNumber>
<tvExpOptDlg>0</tvExpOptDlg>
<TopLine>1</TopLine>
<CurrentLine>1</CurrentLine>
<TopLine>133</TopLine>
<CurrentLine>133</CurrentLine>
<bDave2>0</bDave2>
<PathWithFileName>.\src\drv_system.c</PathWithFileName>
<FilenameWithoutPath>drv_system.c</FilenameWithoutPath>
@ -836,8 +835,8 @@
<Focus>0</Focus>
<ColumnNumber>0</ColumnNumber>
<tvExpOptDlg>0</tvExpOptDlg>
<TopLine>172</TopLine>
<CurrentLine>190</CurrentLine>
<TopLine>1</TopLine>
<CurrentLine>1</CurrentLine>
<bDave2>0</bDave2>
<PathWithFileName>.\src\drv_uart.c</PathWithFileName>
<FilenameWithoutPath>drv_uart.c</FilenameWithoutPath>
@ -864,8 +863,8 @@
<Focus>0</Focus>
<ColumnNumber>0</ColumnNumber>
<tvExpOptDlg>0</tvExpOptDlg>
<TopLine>0</TopLine>
<CurrentLine>0</CurrentLine>
<TopLine>472</TopLine>
<CurrentLine>486</CurrentLine>
<bDave2>0</bDave2>
<PathWithFileName>.\src\drv_mpu6050.c</PathWithFileName>
<FilenameWithoutPath>drv_mpu6050.c</FilenameWithoutPath>
@ -1011,8 +1010,8 @@
<Focus>0</Focus>
<ColumnNumber>9</ColumnNumber>
<tvExpOptDlg>0</tvExpOptDlg>
<TopLine>609</TopLine>
<CurrentLine>609</CurrentLine>
<TopLine>0</TopLine>
<CurrentLine>0</CurrentLine>
<bDave2>0</bDave2>
<PathWithFileName>.\lib\STM32F10x_StdPeriph_Driver\src\stm32f10x_usart.c</PathWithFileName>
<FilenameWithoutPath>stm32f10x_usart.c</FilenameWithoutPath>

File diff suppressed because it is too large Load Diff

View File

@ -1,5 +1,8 @@
#pragma once
// for roundf()
#define __USE_C99_MATH
#include <stdbool.h>
#include <stdlib.h>
#include <stdint.h>

View File

@ -110,7 +110,7 @@ const clivalue_t valueTable[] = {
{ "gimbal_roll_min", VAR_UINT16, &cfg.gimbal_roll_min, 100, 3000 },
{ "gimbal_roll_max", VAR_UINT16, &cfg.gimbal_roll_max, 100, 3000 },
{ "gimbal_roll_mid", VAR_UINT16, &cfg.gimbal_roll_mid, 100, 3000 },
{ "acc_lpf_factor", VAR_UINT8, &cfg.acc_lpf_factor, 0, 32 },
{ "acc_lpf_factor", VAR_UINT8, &cfg.acc_lpf_factor, 0, 250 },
{ "gyro_lpf", VAR_UINT16, &cfg.gyro_lpf, 0, 256 },
{ "gps_baudrate", VAR_UINT32, &cfg.gps_baudrate, 1200, 115200 },
{ "serial_baudrate", VAR_UINT32, &cfg.serial_baudrate, 1200, 115200 },

View File

@ -164,7 +164,7 @@ static void mpu6050AccInit(void)
// 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 = 512; // 1023;
}
static void mpu6050AccRead(int16_t * accData)

View File

@ -169,7 +169,7 @@ static void getEstimatedAttitude(void)
#if defined(MG_LPF_FACTOR)
static int16_t mgSmooth[3];
#endif
static int16_t accTemp[3]; //projection of smoothed and normalized magnetic vector on x/y/z axis, as measured by magnetometer
static float accTemp[3]; // projection of smoothed and normalized magnetic vector on x/y/z axis, as measured by magnetometer
static uint32_t previousT;
uint32_t currentT = micros();
float scale, deltaGyroAngle[3];
@ -181,8 +181,10 @@ static void getEstimatedAttitude(void)
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;
accTemp[axis] = accTemp[axis] * (1.0f - (1.0f / cfg.acc_lpf_factor)) + accADC[axis] * (1.0f / cfg.acc_lpf_factor);
accSmooth[axis] = roundf(accTemp[axis]);
// accTemp[axis] = (accTemp[axis] - (accTemp[axis] >> cfg.acc_lpf_factor)) + accADC[axis];
// accSmooth[axis] = accTemp[axis] >> cfg.acc_lpf_factor;
} else {
accSmooth[axis] = accADC[axis];
}
@ -214,8 +216,8 @@ static void getEstimatedAttitude(void)
// To do that, we just skip filter, as EstV already rotated by Gyro
if ((36 < accMag && accMag < 196) || smallAngle25) {
for (axis = 0; axis < 3; axis++) {
int16_t acc = accSmooth[axis];
EstG.A[axis] = (EstG.A[axis] * GYR_CMPF_FACTOR + acc) * INV_GYR_CMPF_FACTOR;
// int16_t acc = accSmooth[axis];
EstG.A[axis] = (EstG.A[axis] * GYR_CMPF_FACTOR + accTemp[axis]) * INV_GYR_CMPF_FACTOR;
}
}

View File

@ -106,8 +106,8 @@ typedef enum MultiType
#define CHECKBOXITEMS 11
#define PIDITEMS 8
#define ACC_ORIENTATION(X, Y, Z) { accADC[ROLL] = Y; accADC[PITCH] = -X; accADC[YAW] = Z; }
#define GYRO_ORIENTATION(X, Y, Z) { gyroADC[ROLL] = -Y; gyroADC[PITCH] = X; gyroADC[YAW] = Z; }
// #define ACC_ORIENTATION(X, Y, Z) { accADC[ROLL] = Y; accADC[PITCH] = -X; accADC[YAW] = Z; }
// #define GYRO_ORIENTATION(X, Y, Z) { gyroADC[ROLL] = -Y; gyroADC[PITCH] = X; gyroADC[YAW] = Z; }
#define min(a,b) ((a)<(b)?(a):(b))
#define max(a,b) ((a)>(b)?(a):(b))

View File

@ -148,7 +148,7 @@ void serialCom(void)
serialize16(gyroData[i]);
for (i = 0; i < 3; i++)
serialize16(magADC[i]);
serialize16(EstAlt);
serialize16(EstAlt / 10);
serialize16(heading); // compass
for (i = 0; i < 8; i++)
serialize16(servo[i]);
@ -157,7 +157,7 @@ void serialCom(void)
for (i = 0; i < 8; i++)
serialize16(rcData[i]);
serialize8(sensors(SENSOR_ACC) << 1 | sensors(SENSOR_BARO) << 2 | sensors(SENSOR_MAG) << 3 | sensors(SENSOR_GPS) << 4);
serialize8(accMode | baroMode << 1 | magMode << 2 | GPSModeHome << 3 | GPSModeHold << 4);
serialize8(accMode | baroMode << 1 | magMode << 2 | GPSModeHome << 3 | GPSModeHold << 4 | armed << 5);
#if defined(LOG_VALUES)
serialize16(cycleTimeMax);
cycleTimeMax = 0;