From 3e955d12fa35543161ea21da8ba5f1b4a9ae8c2b Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Fri, 22 Dec 2023 16:07:45 +0000 Subject: [PATCH] Plane: Quadaplane: add helper `allow_forward_throttle_in_vtol_mode` --- ArduPlane/quadplane.cpp | 6 ++++++ ArduPlane/quadplane.h | 5 +++++ ArduPlane/servos.cpp | 6 ++---- 3 files changed, 13 insertions(+), 4 deletions(-) diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index 25c7ff533b..4a372fc15f 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -4742,4 +4742,10 @@ float QuadPlane::get_throttle_input() const return ret; } +// return true if forward throttle from forward_throttle_pct() should be used +bool QuadPlane::allow_forward_throttle_in_vtol_mode() const +{ + return in_vtol_mode() && motors->armed() && (motors->get_desired_spool_state() != AP_Motors::DesiredSpoolState::SHUT_DOWN); +} + #endif // HAL_QUADPLANE_ENABLED diff --git a/ArduPlane/quadplane.h b/ArduPlane/quadplane.h index 2c5a624ff4..140c47e585 100644 --- a/ArduPlane/quadplane.h +++ b/ArduPlane/quadplane.h @@ -729,6 +729,11 @@ private: */ void setup_rp_fw_angle_gains(void); + /* + return true if forward throttle from forward_throttle_pct() should be used + */ + bool allow_forward_throttle_in_vtol_mode() const; + public: void motor_test_output(); MAV_RESULT mavlink_motor_test_start(mavlink_channel_t chan, uint8_t motor_seq, uint8_t throttle_type, diff --git a/ArduPlane/servos.cpp b/ArduPlane/servos.cpp index c8f03bb896..d77ed1a172 100644 --- a/ArduPlane/servos.cpp +++ b/ArduPlane/servos.cpp @@ -591,10 +591,8 @@ void Plane::set_throttle(void) #if HAL_QUADPLANE_ENABLED } else if (quadplane.in_vtol_mode()) { float fwd_thr = 0; - // if armed and not spooled down ask quadplane code for forward throttle - if (quadplane.motors->armed() && - quadplane.motors->get_desired_spool_state() != AP_Motors::DesiredSpoolState::SHUT_DOWN) { - + // if enabled ask quadplane code for forward throttle + if (quadplane.allow_forward_throttle_in_vtol_mode()) { fwd_thr = constrain_float(quadplane.forward_throttle_pct(), min_throttle, max_throttle); } SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, fwd_thr);