1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-17 05:15:25 +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:
timecop 2012-05-31 17:28:05 +00:00
parent e124390bb1
commit 49653ec65e
11 changed files with 5397 additions and 5312 deletions

View file

@ -13,7 +13,7 @@ config_t cfg;
const char rcChannelLetters[] = "AERT1234";
static uint32_t enabledSensors = 0;
uint8_t checkNewConf = 17;
uint8_t checkNewConf = 18;
void parseRcChannels(const char *input)
{
@ -128,7 +128,9 @@ void checkFirstTime(bool reset)
cfg.accZero[1] = 0;
cfg.accZero[2] = 0;
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_smoothing_factor = 0x00141403; // default factors of 20, 20, 3 for R/P/Y
cfg.vbatscale = 110;
@ -143,6 +145,7 @@ void checkFirstTime(bool reset)
cfg.midrc = 1500;
cfg.mincheck = 1100;
cfg.maxcheck = 1900;
cfg.retarded_arm = 0; // disable arm/disarm on roll left/right
// Failsafe Variables
cfg.failsafe_delay = 10; // 1sec