diff --git a/ArduPlane/AP_Arming.cpp b/ArduPlane/AP_Arming.cpp index a774b778f5f590..643f93a6c17cc9 100644 --- a/ArduPlane/AP_Arming.cpp +++ b/ArduPlane/AP_Arming.cpp @@ -370,12 +370,8 @@ bool AP_Arming_Plane::disarm(const AP_Arming::Method method, bool do_disarm_chec change_arm_state(); #if QAUTOTUNE_ENABLED - //save qautotune gains if enabled and success - if (plane.control_mode == &plane.mode_qautotune) { - plane.quadplane.qautotune.save_tuning_gains(); - } else { - plane.quadplane.qautotune.reset(); - } + // Possibly save auto tuned parameters + plane.quadplane.qautotune.disarmed(plane.control_mode == &plane.mode_qautotune); #endif // re-initialize speed variable used in AUTO and GUIDED for diff --git a/ArduPlane/RC_Channel.cpp b/ArduPlane/RC_Channel.cpp index cd1d63e04a09f8..a8925258fb7dce 100644 --- a/ArduPlane/RC_Channel.cpp +++ b/ArduPlane/RC_Channel.cpp @@ -169,6 +169,9 @@ void RC_Channel_Plane::init_aux_function(const RC_Channel::AUX_FUNC ch_option, case AUX_FUNC::FW_AUTOTUNE: case AUX_FUNC::VFWD_THR_OVERRIDE: case AUX_FUNC::PRECISION_LOITER: +#if QAUTOTUNE_ENABLED + case AUX_FUNC::AUTOTUNE_SWITCH: +#endif break; case AUX_FUNC::SOARING: @@ -439,6 +442,12 @@ bool RC_Channel_Plane::do_aux_function(const AUX_FUNC ch_option, const AuxSwitch // handled by lua scripting, just ignore here break; +#if QAUTOTUNE_ENABLED + case AUX_FUNC::AUTOTUNE_SWITCH: + plane.quadplane.qautotune.do_aux_function(ch_flag); + break; +#endif + default: return RC_Channel::do_aux_function(ch_option, ch_flag); }