mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-23 00:05:33 +03:00
Decoupling imu from config - acc deadband.
This commit is contained in:
parent
51eee3d62c
commit
3643c08475
6 changed files with 18 additions and 12 deletions
|
@ -280,8 +280,8 @@ static void resetConf(void)
|
|||
|
||||
currentProfile.mag_declination = 0;
|
||||
currentProfile.acc_lpf_factor = 4;
|
||||
currentProfile.accz_deadband = 40;
|
||||
currentProfile.accxy_deadband = 40;
|
||||
currentProfile.accDeadband.xy = 40;
|
||||
currentProfile.accDeadband.z = 40;
|
||||
|
||||
resetBarometerConfig(¤tProfile.barometerConfig);
|
||||
|
||||
|
@ -389,7 +389,7 @@ void activateConfig(void)
|
|||
imuRuntimeConfig.gyro_cmpfm_factor = masterConfig.gyro_cmpfm_factor;
|
||||
imuRuntimeConfig.acc_lpf_factor = currentProfile.acc_lpf_factor;
|
||||
|
||||
configureImu(&imuRuntimeConfig, ¤tProfile.pidProfile, ¤tProfile.barometerConfig);
|
||||
configureImu(&imuRuntimeConfig, ¤tProfile.pidProfile, ¤tProfile.barometerConfig, ¤tProfile.accDeadband);
|
||||
|
||||
calculateThrottleAngleScale(currentProfile.throttle_correction_angle);
|
||||
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue