mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-20 14:55:21 +03:00
Merge with upstream
This commit is contained in:
commit
09862aed78
80 changed files with 2728 additions and 515 deletions
|
@ -447,6 +447,11 @@ static void resetConf(void)
|
|||
applyDefaultLedStripConfig(masterConfig.ledConfigs);
|
||||
#endif
|
||||
|
||||
#ifdef BLACKBOX
|
||||
masterConfig.blackbox_rate_num = 1;
|
||||
masterConfig.blackbox_rate_denom = 1;
|
||||
#endif
|
||||
|
||||
// alternative defaults AlienWii32 (activate via OPTIONS="ALIENWII32" during make for NAZE target)
|
||||
#ifdef ALIENWII32
|
||||
featureSet(FEATURE_RX_SERIAL);
|
||||
|
@ -571,28 +576,37 @@ void activateConfig(void)
|
|||
|
||||
activateControlRateConfig();
|
||||
|
||||
useRcControlsConfig(currentProfile->modeActivationConditions, &masterConfig.escAndServoConfig, ¤tProfile->pidProfile);
|
||||
useRcControlsConfig(
|
||||
currentProfile->modeActivationConditions,
|
||||
&masterConfig.escAndServoConfig,
|
||||
¤tProfile->pidProfile
|
||||
);
|
||||
|
||||
useGyroConfig(&masterConfig.gyroConfig);
|
||||
|
||||
#ifdef TELEMETRY
|
||||
useTelemetryConfig(&masterConfig.telemetryConfig);
|
||||
#endif
|
||||
|
||||
setPIDController(currentProfile->pidController);
|
||||
|
||||
#ifdef GPS
|
||||
gpsUseProfile(¤tProfile->gpsProfile);
|
||||
gpsUsePIDs(¤tProfile->pidProfile);
|
||||
#endif
|
||||
|
||||
useFailsafeConfig(¤tProfile->failsafeConfig);
|
||||
setAccelerationTrims(&masterConfig.accZero);
|
||||
|
||||
mixerUseConfigs(
|
||||
currentProfile->servoConf,
|
||||
&masterConfig.flight3DConfig,
|
||||
&masterConfig.escAndServoConfig,
|
||||
¤tProfile->mixerConfig,
|
||||
&masterConfig.airplaneConfig,
|
||||
&masterConfig.rxConfig,
|
||||
¤tProfile->gimbalConfig
|
||||
);
|
||||
currentProfile->servoConf,
|
||||
&masterConfig.flight3DConfig,
|
||||
&masterConfig.escAndServoConfig,
|
||||
¤tProfile->mixerConfig,
|
||||
&masterConfig.airplaneConfig,
|
||||
&masterConfig.rxConfig,
|
||||
¤tProfile->gimbalConfig
|
||||
);
|
||||
|
||||
imuRuntimeConfig.gyro_cmpf_factor = masterConfig.gyro_cmpf_factor;
|
||||
imuRuntimeConfig.gyro_cmpfm_factor = masterConfig.gyro_cmpfm_factor;
|
||||
|
@ -600,8 +614,18 @@ void activateConfig(void)
|
|||
imuRuntimeConfig.acc_unarmedcal = currentProfile->acc_unarmedcal;;
|
||||
imuRuntimeConfig.small_angle = masterConfig.small_angle;
|
||||
|
||||
configureImu(&imuRuntimeConfig, ¤tProfile->pidProfile, ¤tProfile->accDeadband);
|
||||
configureAltitudeHold(¤tProfile->pidProfile, ¤tProfile->barometerConfig, ¤tProfile->rcControlsConfig, &masterConfig.escAndServoConfig);
|
||||
configureImu(
|
||||
&imuRuntimeConfig,
|
||||
¤tProfile->pidProfile,
|
||||
¤tProfile->accDeadband
|
||||
);
|
||||
|
||||
configureAltitudeHold(
|
||||
¤tProfile->pidProfile,
|
||||
¤tProfile->barometerConfig,
|
||||
¤tProfile->rcControlsConfig,
|
||||
&masterConfig.escAndServoConfig
|
||||
);
|
||||
|
||||
calculateThrottleAngleScale(currentProfile->throttle_correction_angle);
|
||||
calculateAccZLowPassFilterRCTimeConstant(currentProfile->accz_lpf_cutoff);
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue