Plane: remove direct roll/pitch stick mixing support

This commit is contained in:
Iampete1 2023-01-30 02:52:19 +00:00 committed by Andrew Tridgell
parent ccfad8ceea
commit 2d51b2c9b8
3 changed files with 15 additions and 31 deletions

View File

@ -210,39 +210,17 @@ float Plane::stabilize_pitch_get_pitch_out(float speed_scaler)
}
/*
this gives the user control of the aircraft in stabilization modes
this gives the user control of the aircraft in stabilization modes, only used in Stabilize Mode
*/
void Plane::stabilize_stick_mixing_direct()
{
if (!stick_mixing_enabled() ||
control_mode == &mode_acro ||
control_mode == &mode_fbwa ||
control_mode == &mode_autotune ||
control_mode == &mode_fbwb ||
control_mode == &mode_cruise ||
#if HAL_QUADPLANE_ENABLED
control_mode == &mode_qstabilize ||
control_mode == &mode_qhover ||
control_mode == &mode_qloiter ||
control_mode == &mode_qland ||
control_mode == &mode_qrtl ||
control_mode == &mode_qacro ||
#if QAUTOTUNE_ENABLED
control_mode == &mode_qautotune ||
#endif
#endif
control_mode == &mode_training) {
if (!stick_mixing_enabled()) {
return;
}
float aileron = SRV_Channels::get_output_scaled(SRV_Channel::k_aileron);
aileron = channel_roll->stick_mixing(aileron);
SRV_Channels::set_output_scaled(SRV_Channel::k_aileron, aileron);
if ((control_mode == &mode_loiter) && (plane.g2.flight_options & FlightOptions::ENABLE_LOITER_ALT_CONTROL)) {
// loiter is using altitude control based on the pitch stick, don't use it again here
return;
}
float elevator = SRV_Channels::get_output_scaled(SRV_Channel::k_elevator);
elevator = channel_pitch->stick_mixing(elevator);
SRV_Channels::set_output_scaled(SRV_Channel::k_elevator, elevator);
@ -628,6 +606,13 @@ void Plane::stabilize()
#endif
} else if (control_mode == &mode_acro) {
stabilize_acro(speed_scaler);
} else if (control_mode == &mode_stabilize) {
stabilize_roll(speed_scaler);
stabilize_pitch(speed_scaler);
if (allow_stick_mixing) {
stabilize_stick_mixing_direct();
}
stabilize_yaw(speed_scaler);
#if HAL_QUADPLANE_ENABLED
} else if (control_mode->is_vtol_mode() && !quadplane.tailsitter.in_vtol_transition(now)) {
// run controlers specific to this mode
@ -642,14 +627,13 @@ void Plane::stabilize()
}
#endif
} else {
if (allow_stick_mixing && g.stick_mixing == StickMixing::FBW && control_mode != &mode_stabilize) {
// Direct stick mixing functionality has been removed, so as not to remove all stick mixing from the user completely
// the old direct option is now used to enable fbw mixing, this is easier than doing a param conversion.
if (allow_stick_mixing && ((g.stick_mixing == StickMixing::FBW) || (g.stick_mixing == StickMixing::DIRECT_REMOVED))) {
stabilize_stick_mixing_fbw();
}
stabilize_roll(speed_scaler);
stabilize_pitch(speed_scaler);
if (allow_stick_mixing && (g.stick_mixing == StickMixing::DIRECT || control_mode == &mode_stabilize)) {
stabilize_stick_mixing_direct();
}
stabilize_yaw(speed_scaler);
}

View File

@ -99,8 +99,8 @@ const AP_Param::Info Plane::var_info[] = {
// @Param: STICK_MIXING
// @DisplayName: Stick Mixing
// @Description: When enabled, this adds user stick input to the control surfaces in auto modes, allowing the user to have some degree of flight control without changing modes. There are two types of stick mixing available. If you set STICK_MIXING to 1 then it will use "fly by wire" mixing, which controls the roll and pitch in the same way that the FBWA mode does. This is the safest option if you usually fly ArduPlane in FBWA or FBWB mode. If you set STICK_MIXING to 2 then it will enable direct mixing mode, which is what the STABILIZE mode uses. That will allow for much more extreme maneuvers while in AUTO mode. If you set STICK_MIXING to 3 then it will apply to the yaw while in quadplane modes only, such as while doing an automatic VTOL takeoff or landing.
// @Values: 0:Disabled,1:FBWMixing,2:DirectMixing,3:VTOL Yaw only
// @Description: When enabled, this adds user stick input to the control surfaces in auto modes, allowing the user to have some degree of flight control without changing modes. There are two types of stick mixing available. If you set STICK_MIXING to 1 then it will use "fly by wire" mixing, which controls the roll and pitch in the same way that the FBWA mode does. This is the safest option if you usually fly ArduPlane in FBWA or FBWB mode. If you set STICK_MIXING to 3 then it will apply to the yaw while in quadplane modes only, such as while doing an automatic VTOL takeoff or landing.
// @Values: 0:Disabled,1:FBWMixing,3:VTOL Yaw only
// @User: Advanced
GSCALAR(stick_mixing, "STICK_MIXING", uint8_t(StickMixing::FBW)),

View File

@ -48,7 +48,7 @@ enum failsafe_action_long {
enum class StickMixing {
NONE = 0,
FBW = 1,
DIRECT = 2,
DIRECT_REMOVED = 2,
VTOL_YAW = 3,
};