From c84e5b337ea55caf0925d6b308616e4ae729b0ec Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Thu, 18 Jan 2024 12:11:29 +0000 Subject: [PATCH] Plane: move forward throttle output in VTOL modes to QuadPlane update --- ArduPlane/quadplane.cpp | 9 +++++++++ ArduPlane/servos.cpp | 9 --------- 2 files changed, 9 insertions(+), 9 deletions(-) diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index 70ccd2d10d..1a4fefe7dc 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -1872,6 +1872,15 @@ void QuadPlane::update(void) tiltrotor.update(); + if (in_vtol_mode()) { + // if enabled output forward throttle else 0 + float fwd_thr = 0; + if (allow_forward_throttle_in_vtol_mode()) { + fwd_thr = forward_throttle_pct(); + } + SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, fwd_thr); + } + #if HAL_LOGGING_ENABLED // motors logging if (motors->armed()) { diff --git a/ArduPlane/servos.cpp b/ArduPlane/servos.cpp index 08b102acd9..c4dc017244 100644 --- a/ArduPlane/servos.cpp +++ b/ArduPlane/servos.cpp @@ -605,15 +605,6 @@ void Plane::set_throttle(void) guided_throttle_passthru) { // manual pass through of throttle while in GUIDED SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, get_throttle_input(true)); -#if HAL_QUADPLANE_ENABLED - } else if (quadplane.in_vtol_mode()) { - float fwd_thr = 0; - // if enabled ask quadplane code for forward throttle - if (quadplane.allow_forward_throttle_in_vtol_mode()) { - fwd_thr = quadplane.forward_throttle_pct(); - } - SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, fwd_thr); -#endif // HAL_QUADPLANE_ENABLED } if (control_mode->use_battery_compensation()) {