diff --git a/ArduPlane/Attitude.cpp b/ArduPlane/Attitude.cpp index 6d5948f697..8ed782ef03 100644 --- a/ArduPlane/Attitude.cpp +++ b/ArduPlane/Attitude.cpp @@ -79,8 +79,8 @@ bool Plane::stick_mixing_enabled(void) #endif if (control_mode->does_auto_throttle() && plane.control_mode->does_auto_navigation()) { // we're in an auto mode. Check the stick mixing flag - if (g.stick_mixing != STICK_MIXING_DISABLED && - g.stick_mixing != STICK_MIXING_VTOL_YAW && + if (g.stick_mixing != StickMixing::NONE && + g.stick_mixing != StickMixing::VTOL_YAW && stickmixing && failsafe.state == FAILSAFE_NONE && !rc_failsafe_active()) { @@ -502,12 +502,12 @@ void Plane::stabilize() } #endif } else { - if (allow_stick_mixing && g.stick_mixing == STICK_MIXING_FBW && control_mode != &mode_stabilize) { + if (allow_stick_mixing && g.stick_mixing == StickMixing::FBW && control_mode != &mode_stabilize) { stabilize_stick_mixing_fbw(); } stabilize_roll(speed_scaler); stabilize_pitch(speed_scaler); - if (allow_stick_mixing && (g.stick_mixing == STICK_MIXING_DIRECT || control_mode == &mode_stabilize)) { + if (allow_stick_mixing && (g.stick_mixing == StickMixing::DIRECT || control_mode == &mode_stabilize)) { stabilize_stick_mixing_direct(); } stabilize_yaw(speed_scaler); diff --git a/ArduPlane/GCS_Mavlink.cpp b/ArduPlane/GCS_Mavlink.cpp index c3edf95921..c051a8e528 100644 --- a/ArduPlane/GCS_Mavlink.cpp +++ b/ArduPlane/GCS_Mavlink.cpp @@ -79,8 +79,8 @@ MAV_MODE GCS_MAVLINK_Plane::base_mode() const _base_mode |= MAV_MODE_FLAG_STABILIZE_ENABLED; } - if (plane.g.stick_mixing != STICK_MIXING_DISABLED && plane.control_mode != &plane.mode_initializing) { - if ((plane.g.stick_mixing != STICK_MIXING_VTOL_YAW) || (plane.control_mode == &plane.mode_auto)) { + if (plane.g.stick_mixing != StickMixing::NONE && plane.control_mode != &plane.mode_initializing) { + if ((plane.g.stick_mixing != StickMixing::VTOL_YAW) || (plane.control_mode == &plane.mode_auto)) { // all modes except INITIALISING have some form of manual // override if stick mixing is enabled _base_mode |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED; diff --git a/ArduPlane/Parameters.cpp b/ArduPlane/Parameters.cpp index c2633de3f9..255c88e6cc 100644 --- a/ArduPlane/Parameters.cpp +++ b/ArduPlane/Parameters.cpp @@ -108,7 +108,7 @@ const AP_Param::Info Plane::var_info[] = { // @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 // @User: Advanced - GSCALAR(stick_mixing, "STICK_MIXING", STICK_MIXING_FBW), + GSCALAR(stick_mixing, "STICK_MIXING", uint8_t(StickMixing::FBW)), // @Param: TKOFF_THR_MINSPD // @DisplayName: Takeoff throttle min speed diff --git a/ArduPlane/Parameters.h b/ArduPlane/Parameters.h index 5fc36c03ef..f01dea0060 100644 --- a/ArduPlane/Parameters.h +++ b/ArduPlane/Parameters.h @@ -439,7 +439,7 @@ public: AP_Int8 flap_2_percent; AP_Int8 flap_2_speed; AP_Int8 takeoff_flap_percent; - AP_Int8 stick_mixing; + AP_Enum stick_mixing; AP_Float takeoff_throttle_min_speed; AP_Float takeoff_throttle_min_accel; AP_Int8 takeoff_throttle_delay; diff --git a/ArduPlane/defines.h b/ArduPlane/defines.h index 3a3306c7aa..cdcf5eee32 100644 --- a/ArduPlane/defines.h +++ b/ArduPlane/defines.h @@ -47,11 +47,11 @@ enum failsafe_action_long { }; // type of stick mixing enabled -enum StickMixing { - STICK_MIXING_DISABLED = 0, - STICK_MIXING_FBW = 1, - STICK_MIXING_DIRECT = 2, - STICK_MIXING_VTOL_YAW = 3, +enum class StickMixing { + NONE = 0, + FBW = 1, + DIRECT = 2, + VTOL_YAW = 3, }; enum ChannelMixing { diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index f0339d162e..40872bb1d4 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -1144,7 +1144,7 @@ float QuadPlane::get_pilot_input_yaw_rate_cds(void) const return 0; } - if ((plane.g.stick_mixing == STICK_MIXING_DISABLED) && + if ((plane.g.stick_mixing == StickMixing::NONE) && (plane.control_mode == &plane.mode_qrtl || plane.control_mode->is_guided_mode() || in_vtol_auto())) {