1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-23 00:05:33 +03:00

Changed Level defaults

This commit is contained in:
borisbstyle 2015-11-07 00:33:45 +01:00
parent 394e6be4a6
commit 5c8970e41a

View file

@ -166,8 +166,8 @@ static void resetPidProfile(pidProfile_t *pidProfile)
pidProfile->P8[PIDNAVR] = 25; // NAV_P * 10; pidProfile->P8[PIDNAVR] = 25; // NAV_P * 10;
pidProfile->I8[PIDNAVR] = 33; // NAV_I * 100; pidProfile->I8[PIDNAVR] = 33; // NAV_I * 100;
pidProfile->D8[PIDNAVR] = 83; // NAV_D * 1000; pidProfile->D8[PIDNAVR] = 83; // NAV_D * 1000;
pidProfile->P8[PIDLEVEL] = 90; pidProfile->P8[PIDLEVEL] = 20;
pidProfile->I8[PIDLEVEL] = 10; pidProfile->I8[PIDLEVEL] = 20;
pidProfile->D8[PIDLEVEL] = 100; pidProfile->D8[PIDLEVEL] = 100;
pidProfile->P8[PIDMAG] = 40; pidProfile->P8[PIDMAG] = 40;
pidProfile->P8[PIDVEL] = 120; pidProfile->P8[PIDVEL] = 120;
@ -406,7 +406,7 @@ static void resetConf(void)
masterConfig.boardAlignment.pitchDegrees = 0; masterConfig.boardAlignment.pitchDegrees = 0;
masterConfig.boardAlignment.yawDegrees = 0; masterConfig.boardAlignment.yawDegrees = 0;
masterConfig.acc_hardware = ACC_DEFAULT; // default/autodetect masterConfig.acc_hardware = ACC_DEFAULT; // default/autodetect
masterConfig.max_angle_inclination = 600; // 50 degrees masterConfig.max_angle_inclination = 700; // 70 degrees
masterConfig.yaw_control_direction = 1; masterConfig.yaw_control_direction = 1;
masterConfig.gyroConfig.gyroMovementCalibrationThreshold = 32; masterConfig.gyroConfig.gyroMovementCalibrationThreshold = 32;