1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-21 07:15:18 +03:00

Allow inflight adjustment of pitch/roll (linked) and yaw PID settings.

This commit is contained in:
Dominic Clifton 2014-10-24 23:10:17 +01:00
parent 7548154d25
commit 2df976409d
3 changed files with 66 additions and 5 deletions

View file

@ -70,7 +70,7 @@ void setPIDController(int type); // FIXME PID code needs to be in flight_pid.c/h
void mixerUseConfigs(servoParam_t *servoConfToUse, flight3DConfig_t *flight3DConfigToUse,
escAndServoConfig_t *escAndServoConfigToUse, mixerConfig_t *mixerConfigToUse,
airplaneConfig_t *airplaneConfigToUse, rxConfig_t *rxConfig, gimbalConfig_t *gimbalConfigToUse);
void useRcControlsConfig(modeActivationCondition_t *modeActivationConditions, escAndServoConfig_t *escAndServoConfigToUse);
void useRcControlsConfig(modeActivationCondition_t *modeActivationConditions, escAndServoConfig_t *escAndServoConfigToUse, pidProfile_t *pidProfileToUse);
#define FLASH_TO_RESERVE_FOR_CONFIG 0x800
@ -433,7 +433,7 @@ void activateConfig(void)
generatePitchRollCurve(&currentProfile->controlRateConfig);
generateThrottleCurve(&currentProfile->controlRateConfig, &masterConfig.escAndServoConfig);
useRcControlsConfig(currentProfile->modeActivationConditions, &masterConfig.escAndServoConfig);
useRcControlsConfig(currentProfile->modeActivationConditions, &masterConfig.escAndServoConfig, &currentProfile->pidProfile);
useGyroConfig(&masterConfig.gyroConfig);
#ifdef TELEMETRY