From ea139ddd1ebcec61134d17dbfcadbca44144d29b Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 9 Nov 2021 14:34:28 +1100 Subject: [PATCH] Plane: enable fixed wing autotune switch --- ArduPlane/RC_Channel.cpp | 5 +++++ ArduPlane/control_modes.cpp | 2 ++ 2 files changed, 7 insertions(+) diff --git a/ArduPlane/RC_Channel.cpp b/ArduPlane/RC_Channel.cpp index 9599a3b413..4bce7ce1c5 100644 --- a/ArduPlane/RC_Channel.cpp +++ b/ArduPlane/RC_Channel.cpp @@ -161,6 +161,7 @@ void RC_Channel_Plane::init_aux_function(const RC_Channel::aux_func_t ch_option, case AUX_FUNC::LANDING_FLARE: case AUX_FUNC::PARACHUTE_RELEASE: case AUX_FUNC::MODE_SWITCH_RESET: + case AUX_FUNC::FW_AUTOTUNE: break; case AUX_FUNC::Q_ASSIST: @@ -318,6 +319,10 @@ case AUX_FUNC::ARSPD_CALIBRATE: plane.reset_control_switch(); break; + case AUX_FUNC::FW_AUTOTUNE: + plane.autotune_enable(ch_flag == AuxSwitchPos::HIGH); + break; + default: return RC_Channel::do_aux_function(ch_option, ch_flag); } diff --git a/ArduPlane/control_modes.cpp b/ArduPlane/control_modes.cpp index 05268dec92..d66edf9b4a 100644 --- a/ArduPlane/control_modes.cpp +++ b/ArduPlane/control_modes.cpp @@ -148,6 +148,7 @@ void Plane::reset_control_switch() */ void Plane::autotune_start(void) { + gcs().send_text(MAV_SEVERITY_INFO, "Started autotune"); rollController.autotune_start(); pitchController.autotune_start(); } @@ -159,6 +160,7 @@ void Plane::autotune_restore(void) { rollController.autotune_restore(); pitchController.autotune_restore(); + gcs().send_text(MAV_SEVERITY_INFO, "Stopped autotune"); } /*