Plane: When stick mixing is disabled do not apply stick mixing to quadplane modes

This commit is contained in:
Michael du Breuil 2020-03-30 20:49:40 -07:00 committed by Andrew Tridgell
parent 7919bafc86
commit 37be15b3cd
5 changed files with 14 additions and 6 deletions

View File

@ -57,6 +57,7 @@ bool Plane::stick_mixing_enabled(void)
if (auto_throttle_mode && auto_navigation_mode) { if (auto_throttle_mode && auto_navigation_mode) {
// we're in an auto mode. Check the stick mixing flag // we're in an auto mode. Check the stick mixing flag
if (g.stick_mixing != STICK_MIXING_DISABLED && if (g.stick_mixing != STICK_MIXING_DISABLED &&
g.stick_mixing != STICK_MIXING_VTOL_YAW &&
geofence_stickmixing() && geofence_stickmixing() &&
failsafe.state == FAILSAFE_NONE && failsafe.state == FAILSAFE_NONE &&
!rc_failsafe_active()) { !rc_failsafe_active()) {

View File

@ -66,9 +66,11 @@ MAV_MODE GCS_MAVLINK_Plane::base_mode() const
} }
if (plane.g.stick_mixing != STICK_MIXING_DISABLED && plane.control_mode != &plane.mode_initializing) { if (plane.g.stick_mixing != STICK_MIXING_DISABLED && plane.control_mode != &plane.mode_initializing) {
// all modes except INITIALISING have some form of manual if ((plane.g.stick_mixing != STICK_MIXING_VTOL_YAW) || (plane.control_mode == &plane.mode_auto)) {
// override if stick mixing is enabled // all modes except INITIALISING have some form of manual
_base_mode |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED; // override if stick mixing is enabled
_base_mode |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED;
}
} }
#if HIL_SUPPORT #if HIL_SUPPORT

View File

@ -105,8 +105,8 @@ const AP_Param::Info Plane::var_info[] = {
// @Param: STICK_MIXING // @Param: STICK_MIXING
// @DisplayName: 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. // @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 // @Values: 0:Disabled,1:FBWMixing,2:DirectMixing,3:VTOL Yaw only
// @User: Advanced // @User: Advanced
GSCALAR(stick_mixing, "STICK_MIXING", STICK_MIXING_FBW), GSCALAR(stick_mixing, "STICK_MIXING", STICK_MIXING_FBW),

View File

@ -49,7 +49,8 @@ enum failsafe_action_long {
enum StickMixing { enum StickMixing {
STICK_MIXING_DISABLED = 0, STICK_MIXING_DISABLED = 0,
STICK_MIXING_FBW = 1, STICK_MIXING_FBW = 1,
STICK_MIXING_DIRECT = 2 STICK_MIXING_DIRECT = 2,
STICK_MIXING_VTOL_YAW = 3,
}; };
enum ChannelMixing { enum ChannelMixing {

View File

@ -1308,6 +1308,10 @@ float QuadPlane::get_pilot_input_yaw_rate_cds(void) const
return 0; return 0;
} }
if (plane.g.stick_mixing == STICK_MIXING_DISABLED) {
return 0;
}
// add in rudder input // add in rudder input
float max_rate = yaw_rate_max; float max_rate = yaw_rate_max;
if (is_tailsitter() && if (is_tailsitter() &&