mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-15 20:35:33 +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
|
@ -121,7 +121,7 @@ void computeIMU(void)
|
|||
/* Increasing this value would reduce and delay Acc influence on the output of the filter*/
|
||||
/* Default WMC value: 300*/
|
||||
// #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 */
|
||||
/* 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 *************
|
||||
|
||||
#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 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
|
||||
if ((36 < accMag && accMag < 196) || smallAngle25) {
|
||||
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)) {
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue