From d149150a452bc395ed3faa6b0cbdbcf58e97c08b Mon Sep 17 00:00:00 2001 From: George Zogopoulos Date: Tue, 8 Oct 2024 20:38:08 +0200 Subject: [PATCH] Plane: Added parameter TKOFF_THR_IDLE --- ArduPlane/Parameters.cpp | 9 +++++++++ ArduPlane/Parameters.h | 1 + ArduPlane/servos.cpp | 5 +++++ 3 files changed, 15 insertions(+) diff --git a/ArduPlane/Parameters.cpp b/ArduPlane/Parameters.cpp index d643d8b013..b2db9099f8 100644 --- a/ArduPlane/Parameters.cpp +++ b/ArduPlane/Parameters.cpp @@ -158,6 +158,15 @@ const AP_Param::Info Plane::var_info[] = { // @User: Standard ASCALAR(takeoff_throttle_min, "TKOFF_THR_MIN", 0), + // @Param: TKOFF_THR_IDLE + // @DisplayName: Takeoff idle throttle + // @Description: The idle throttle to hold after arming and before a takeoff. Applicable in TAKEOFF and AUTO modes. + // @Units: % + // @Range: 0 100 + // @Increment: 1 + // @User: Standard + ASCALAR(takeoff_throttle_idle, "TKOFF_THR_IDLE", 0), + // @Param: TKOFF_OPTIONS // @DisplayName: Takeoff options // @Description: This selects the mode of the takeoff in AUTO and TAKEOFF flight modes. diff --git a/ArduPlane/Parameters.h b/ArduPlane/Parameters.h index d29243d1ef..24645b3b88 100644 --- a/ArduPlane/Parameters.h +++ b/ArduPlane/Parameters.h @@ -359,6 +359,7 @@ public: k_param_autotune_options, k_param_takeoff_throttle_min, k_param_takeoff_options, + k_param_takeoff_throttle_idle, k_param_pullup = 270, }; diff --git a/ArduPlane/servos.cpp b/ArduPlane/servos.cpp index 49e3e07b46..672631e373 100644 --- a/ArduPlane/servos.cpp +++ b/ArduPlane/servos.cpp @@ -619,6 +619,11 @@ void Plane::set_throttle(void) // throttle is suppressed (above) to zero in final flare in auto mode, but we allow instead thr_min if user prefers, eg turbines: SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, aparm.throttle_min.get()); + } else if ((flight_stage == AP_FixedWing::FlightStage::TAKEOFF) + && (aparm.takeoff_throttle_idle.get() > 0) + ) { + // we want to spin at idle throttle before the takeoff conditions are met + SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, aparm.takeoff_throttle_idle.get()); } else { // default SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, 0.0);