From 8e693e5cd172ad61ae64009770e9685397c7037a Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Tue, 21 Sep 2021 22:19:19 +0100 Subject: [PATCH] Plane: remove TRIM_AUTO param --- ArduPlane/Parameters.cpp | 7 ------- ArduPlane/Parameters.h | 3 +-- ArduPlane/fence.cpp | 4 ---- ArduPlane/mode.h | 4 ---- ArduPlane/mode_manual.cpp | 7 ------- 5 files changed, 1 insertion(+), 24 deletions(-) diff --git a/ArduPlane/Parameters.cpp b/ArduPlane/Parameters.cpp index 30e3b918c8..f6c883bd16 100644 --- a/ArduPlane/Parameters.cpp +++ b/ArduPlane/Parameters.cpp @@ -569,13 +569,6 @@ const AP_Param::Info Plane::var_info[] = { // @User: Advanced GSCALAR(ground_steer_dps, "GROUND_STEER_DPS", 90), - // @Param: TRIM_AUTO - // @DisplayName: Automatic trim adjustment - // @Description: Enables the setting SERVOn_TRIM values to current levels when switching out of MANUAL mode. Should not be left on as mode switches while the plane is rolling or pitching can cause invalid trim values and subsequent unstable behavior. See newer and safer SERVO_AUTO_TRIM parameter for automated results. - // @Values: 0:Disabled,1:Enabled - // @User: Standard - GSCALAR(auto_trim, "TRIM_AUTO", AUTO_TRIM), - // @Param: MIXING_GAIN // @DisplayName: Mixing Gain // @Description: The gain for the Vtail and elevon output mixers. The default is 0.5, which ensures that the mixer doesn't saturate, allowing both input channels to go to extremes while retaining control over the output. Hardware mixers often have a 1.0 gain, which gives more servo throw, but can saturate. If you don't have enough throw on your servos with VTAIL_OUTPUT or ELEVON_OUTPUT enabled then you can raise the gain using MIXING_GAIN. The mixer allows outputs in the range 900 to 2100 microseconds. diff --git a/ArduPlane/Parameters.h b/ArduPlane/Parameters.h index 0faec5fb6e..5fc36c03ef 100644 --- a/ArduPlane/Parameters.h +++ b/ArduPlane/Parameters.h @@ -51,7 +51,7 @@ public: // Misc // - k_param_auto_trim = 10, + k_param_auto_trim = 10, // unused k_param_log_bitmask_old, // unused k_param_pitch_trim_cd, k_param_mix_mode, @@ -424,7 +424,6 @@ public: // Misc // - AP_Int8 auto_trim; AP_Int8 rudder_only; AP_Float mixing_gain; AP_Int16 mixing_offset; diff --git a/ArduPlane/fence.cpp b/ArduPlane/fence.cpp index e3d010eff8..df2b69c09c 100644 --- a/ArduPlane/fence.cpp +++ b/ArduPlane/fence.cpp @@ -60,15 +60,11 @@ void Plane::fence_check() case AC_FENCE_ACTION_GUIDED: case AC_FENCE_ACTION_GUIDED_THROTTLE_PASS: case AC_FENCE_ACTION_RTL_AND_LAND: - // make sure we don't auto trim the surfaces on this mode change - int8_t saved_auto_trim = g.auto_trim; - g.auto_trim.set(0); if (fence_act == AC_FENCE_ACTION_RTL_AND_LAND) { set_mode(mode_rtl, ModeReason::FENCE_BREACHED); } else { set_mode(mode_guided, ModeReason::FENCE_BREACHED); } - g.auto_trim.set(saved_auto_trim); if (fence.get_return_rally() != 0 || fence_act == AC_FENCE_ACTION_RTL_AND_LAND) { guided_WP_loc = rally.calc_best_rally_or_home_location(current_loc, get_RTL_altitude_cm()); diff --git a/ArduPlane/mode.h b/ArduPlane/mode.h index 52c928e9f6..3e1b19f3e5 100644 --- a/ArduPlane/mode.h +++ b/ArduPlane/mode.h @@ -279,10 +279,6 @@ public: // methods that affect movement of the vehicle in this mode void update() override; - -protected: - - void _exit() override; }; diff --git a/ArduPlane/mode_manual.cpp b/ArduPlane/mode_manual.cpp index 9ddddc45ec..e30954331b 100644 --- a/ArduPlane/mode_manual.cpp +++ b/ArduPlane/mode_manual.cpp @@ -1,13 +1,6 @@ #include "mode.h" #include "Plane.h" -void ModeManual::_exit() -{ - if (plane.g.auto_trim > 0) { - plane.trim_radio(); - } -} - void ModeManual::update() { SRV_Channels::set_output_scaled(SRV_Channel::k_aileron, plane.roll_in_expo(false));