mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-23 08:15:30 +03:00
Moved configuring of IMU all into one function call.
This commit is contained in:
parent
be03ed95fa
commit
d691f72849
3 changed files with 28 additions and 12 deletions
|
@ -616,7 +616,9 @@ void activateConfig(void)
|
|||
configureIMU(
|
||||
&imuRuntimeConfig,
|
||||
¤tProfile->pidProfile,
|
||||
¤tProfile->accDeadband
|
||||
¤tProfile->accDeadband,
|
||||
currentProfile->accz_lpf_cutoff,
|
||||
currentProfile->throttle_correction_angle
|
||||
);
|
||||
|
||||
configureAltitudeHold(
|
||||
|
@ -626,9 +628,6 @@ void activateConfig(void)
|
|||
&masterConfig.escAndServoConfig
|
||||
);
|
||||
|
||||
calculateThrottleAngleScale(currentProfile->throttle_correction_angle);
|
||||
calculateAccZLowPassFilterRCTimeConstant(currentProfile->accz_lpf_cutoff);
|
||||
|
||||
#ifdef BARO
|
||||
useBarometerConfig(¤tProfile->barometerConfig);
|
||||
#endif
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue