Plane: Added parameter TKOFF_THR_IDLE

This commit is contained in:
George Zogopoulos 2024-10-08 20:38:08 +02:00 committed by Andrew Tridgell
parent 9f29606d1c
commit d149150a45
3 changed files with 15 additions and 0 deletions

View File

@ -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.

View File

@ -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,
};

View File

@ -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);