diff --git a/docs/Settings.md b/docs/Settings.md index e0a8c52242..2906667c96 100644 --- a/docs/Settings.md +++ b/docs/Settings.md @@ -122,6 +122,8 @@ | fw_i_yaw | 10 | Fixed-wing rate stabilisation I-gain for YAW | | fw_iterm_limit_stick_position | 0.5 | Iterm is not allowed to grow when stick position is above threshold. This solves the problem of bounceback or followthrough when full stick deflection is applied on poorely tuned fixed wings. In other words, stabilization is partialy disabled when pilot is actively controlling the aircraft and active when sticks are not touched. `0` mean stick is in center position, `1` means it is fully deflected to either side | | fw_iterm_throw_limit | 165 | Limits max/min I-term value in stabilization PID controller in case of Fixed Wing. It solves the problem of servo saturation before take-off/throwing the airplane into the air. By default, error accumulated in I-term can not exceed 1/3 of servo throw (around 165us). Set 0 to disable completely. | +| fw_level_pitch_deadband | 5 | Deadband for automatic self-trimming | +| fw_level_pitch_gain | 10 | I-gain for the pitch trim for self-leveling flight modes. | | fw_level_pitch_trim | 0 | Pitch trim for self-leveling flight modes. In degrees. +5 means airplane nose should be raised 5 deg from level | | fw_loiter_direction | RIGHT | Direction of loitering: center point on right wing (clockwise - default), or center point on left wing (counterclockwise). If equal YAW then can be changed in flight using a yaw stick. | | fw_min_throttle_down_pitch | 0 | Automatic pitch down angle when throttle is at 0 in angle mode. Progressively applied between cruise throttle and zero throttle (decidegrees) | diff --git a/src/main/common/fp_pid.c b/src/main/common/fp_pid.c index 84afe518ae..346c6ace3f 100644 --- a/src/main/common/fp_pid.c +++ b/src/main/common/fp_pid.c @@ -96,7 +96,10 @@ float navPidApply3( pid->output_constrained = outValConstrained; /* Update I-term */ - if (!(pidFlags & PID_ZERO_INTEGRATOR)) { + if ( + !(pidFlags & PID_ZERO_INTEGRATOR) && + !(pidFlags & PID_FREEZE_INTEGRATOR) + ) { const float newIntegrator = pid->integrator + (error * pid->param.kI * gainScaler * dt) + ((outValConstrained - outVal) * pid->param.kT * dt); if (pidFlags & PID_SHRINK_INTEGRATOR) { diff --git a/src/main/fc/fc_msp_box.c b/src/main/fc/fc_msp_box.c index 4f9687f3b9..a8f8438097 100644 --- a/src/main/fc/fc_msp_box.c +++ b/src/main/fc/fc_msp_box.c @@ -367,6 +367,7 @@ void packBoxModeFlags(boxBitmask_t * mspBoxModeFlags) #if defined(USE_RX_MSP) && defined(USE_MSP_RC_OVERRIDE) CHECK_ACTIVE_BOX(IS_ENABLED(IS_RC_MODE_ACTIVE(BOXMSPRCOVERRIDE)), BOXMSPRCOVERRIDE); #endif + CHECK_ACTIVE_BOX(IS_ENABLED(IS_RC_MODE_ACTIVE(BOXAUTOLEVEL)), BOXAUTOLEVEL); memset(mspBoxModeFlags, 0, sizeof(boxBitmask_t)); for (uint32_t i = 0; i < activeBoxIdCount; i++) { diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index f30c248721..c3165231bc 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -84,7 +84,7 @@ tables: "FLOW", "SBUS", "FPORT", "ALWAYS", "SAG_COMP_VOLTAGE", "VIBE", "CRUISE", "REM_FLIGHT_TIME", "SMARTAUDIO", "ACC", "ERPM", "RPM_FILTER", "RPM_FREQ", "NAV_YAW", "DYNAMIC_FILTER", "DYNAMIC_FILTER_FREQUENCY", - "IRLOCK", "CD", "KALMAN_GAIN", "PID_MEASUREMENT", "SPM_CELLS", "SPM_VS600", "SPM_VARIO", "PCF8574", "DYN_GYRO_LPF"] + "IRLOCK", "CD", "KALMAN_GAIN", "PID_MEASUREMENT", "SPM_CELLS", "SPM_VS600", "SPM_VARIO", "PCF8574", "DYN_GYRO_LPF", "AUTOLEVEL"] - name: async_mode values: ["NONE", "GYRO", "ALL"] - name: aux_operator @@ -1882,10 +1882,16 @@ groups: max: 10 - name: fw_level_pitch_gain description: "I-gain for the pitch trim for self-leveling flight modes." - default_value: "0" + default_value: "10" field: fixedWingLevelTrimGain min: 0 max: 20 + - name: fw_level_pitch_deadband + description: "Deadband for automatic self-trimming" + default_value: "5" + field: fixedWingLevelTrimDeadband + min: 0 + max: 20 - name: PG_PID_AUTOTUNE_CONFIG type: pidAutotuneConfig_t diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index 722b5fa52c..a2e7468a82 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -155,6 +155,11 @@ static EXTENDED_FASTRAM filterApplyFnPtr dTermLpfFilterApplyFn; static EXTENDED_FASTRAM filterApplyFnPtr dTermLpf2FilterApplyFn; static EXTENDED_FASTRAM bool levelingEnabled = false; +#define FIXED_WING_LEVEL_TRIM_MAX_ANGLE 10.0f // Max angle auto trimming can demand +#define FIXED_WING_LEVEL_TRIM_DIVIDER 500.0f +#define FIXED_WING_LEVEL_TRIM_MULTIPLIER 1.0f / FIXED_WING_LEVEL_TRIM_DIVIDER +#define FIXED_WING_LEVEL_TRIM_CONTROLLER_LIMIT FIXED_WING_LEVEL_TRIM_DIVIDER * FIXED_WING_LEVEL_TRIM_MAX_ANGLE + static EXTENDED_FASTRAM float fixedWingLevelTrim; static EXTENDED_FASTRAM pidController_t fixedWingLevelTrimController; @@ -285,6 +290,7 @@ PG_RESET_TEMPLATE(pidProfile_t, pidProfile, .kalmanEnabled = 0, .fixedWingLevelTrim = 0, .fixedWingLevelTrimGain = 10, + .fixedWingLevelTrimDeadband = FIXED_WING_LEVEL_TRIM_DEADBAND_DEFAULT, ); bool pidInitFilters(void) @@ -1180,21 +1186,58 @@ uint16_t * getD_FFRefByBank(pidBank_t *pidBank, pidIndex_e pidIndex) void updateFixedWingLevelTrim(timeUs_t currentTimeUs) { + if (!STATE(AIRPLANE)) { + return; + } + static timeUs_t previousUpdateTimeUs; + static bool previousArmingState; const float dT = US2S(currentTimeUs - previousUpdateTimeUs); + /* + * On every ARM reset the controller + */ + if (ARMING_FLAG(ARMED) && !previousArmingState) { + navPidReset(&fixedWingLevelTrimController); + } + + /* + * On disarm update the default value + */ + if (!ARMING_FLAG(ARMED) && previousArmingState) { + pidProfileMutable()->fixedWingLevelTrim = constrainf(fixedWingLevelTrim, -FIXED_WING_LEVEL_TRIM_MAX_ANGLE, FIXED_WING_LEVEL_TRIM_MAX_ANGLE); + } + + /* + * Prepare flags for the PID controller + */ + pidControllerFlags_e flags = PID_LIMIT_INTEGRATOR; + + //Iterm should freeze when pitch stick is deflected + if ( + !IS_RC_MODE_ACTIVE(BOXAUTOLEVEL) || + rxGetChannelValue(PITCH) > (PWM_RANGE_MIDDLE + pidProfile()->fixedWingLevelTrimDeadband) || + rxGetChannelValue(PITCH) < (PWM_RANGE_MIDDLE - pidProfile()->fixedWingLevelTrimDeadband) || + (!FLIGHT_MODE(ANGLE_MODE) && !FLIGHT_MODE(HORIZON_MODE)) || + navigationIsControllingAltitude() + ) { + flags |= PID_FREEZE_INTEGRATOR; + } + const float output = navPidApply3( &fixedWingLevelTrimController, - 0, + 0, //Setpoint is always 0 as we try to keep level flight getEstimatedActualVelocity(Z), dT, - -1000.0f, - 1000.0f, - PID_LIMIT_INTEGRATOR, + -FIXED_WING_LEVEL_TRIM_CONTROLLER_LIMIT, + FIXED_WING_LEVEL_TRIM_CONTROLLER_LIMIT, + flags, 1.0f, 1.0f ); - DEBUG_SET(DEBUG_AUTOLEVEL, 4, output / 100); + DEBUG_SET(DEBUG_AUTOLEVEL, 4, output); + fixedWingLevelTrim = pidProfile()->fixedWingLevelTrim + (output * FIXED_WING_LEVEL_TRIM_MULTIPLIER); + previousArmingState = !!ARMING_FLAG(ARMED); } \ No newline at end of file diff --git a/src/main/flight/pid.h b/src/main/flight/pid.h index 8d9a0238cb..d100f57b50 100644 --- a/src/main/flight/pid.h +++ b/src/main/flight/pid.h @@ -55,6 +55,8 @@ FP-PID has been rescaled to match LuxFloat (and MWRewrite) from Cleanflight 1.13 #define ANTI_GRAVITY_THROTTLE_FILTER_CUTOFF 15 // The anti gravity throttle highpass filter cutoff +#define FIXED_WING_LEVEL_TRIM_DEADBAND_DEFAULT 5 + #define TASK_AUX_RATE_HZ 100 //In Hz typedef enum { @@ -154,6 +156,7 @@ typedef struct pidProfile_s { float fixedWingLevelTrim; float fixedWingLevelTrimGain; + float fixedWingLevelTrimDeadband; } pidProfile_t; typedef struct pidAutotuneConfig_s { diff --git a/src/main/navigation/navigation.c b/src/main/navigation/navigation.c index 01e83e70b7..c0d1b97c1c 100755 --- a/src/main/navigation/navigation.c +++ b/src/main/navigation/navigation.c @@ -3586,6 +3586,11 @@ bool navigationIsControllingThrottle(void) return navigationInAutomaticThrottleMode() && (getMotorStatus() != MOTOR_STOPPED_USER); } +bool navigationIsControllingAltitude(void) { + navigationFSMStateFlags_t stateFlags = navGetCurrentStateFlags(); + return (stateFlags & NAV_CTL_ALT); +} + bool navigationIsFlyingAutonomousMode(void) { navigationFSMStateFlags_t stateFlags = navGetCurrentStateFlags(); diff --git a/src/main/navigation/navigation.h b/src/main/navigation/navigation.h index 50ba6b2632..2afb311a0f 100755 --- a/src/main/navigation/navigation.h +++ b/src/main/navigation/navigation.h @@ -495,6 +495,7 @@ bool navigationIsControllingThrottle(void); bool isFixedWingAutoThrottleManuallyIncreased(void); bool navigationIsFlyingAutonomousMode(void); bool navigationIsExecutingAnEmergencyLanding(void); +bool navigationIsControllingAltitude(void); /* Returns true iff navConfig()->general.flags.rth_allow_landing is NAV_RTH_ALLOW_LANDING_ALWAYS * or if it's NAV_RTH_ALLOW_LANDING_FAILSAFE and failsafe mode is active. */