From 11fbeb9b8f7857777150d5b6e4900912932983b0 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 9 Oct 2021 20:28:16 +1100 Subject: [PATCH] Plane: apply the takeoff throttle slew limit to quadplanes this applies the limit when we are in a fwd transition, both in AUTO modes and stabilized modes --- ArduPlane/servos.cpp | 9 +++++++++ 1 file changed, 9 insertions(+) diff --git a/ArduPlane/servos.cpp b/ArduPlane/servos.cpp index 4d197eff6c..1992f13e43 100644 --- a/ArduPlane/servos.cpp +++ b/ArduPlane/servos.cpp @@ -37,6 +37,15 @@ void Plane::throttle_slew_limit(SRV_Channel::Aux_servo_function_t func) slewrate = landing.get_throttle_slewrate(); } } + if (g.takeoff_throttle_slewrate != 0 && + (flight_stage == AP_Vehicle::FixedWing::FLIGHT_TAKEOFF || + flight_stage == AP_Vehicle::FixedWing::FLIGHT_VTOL)) { + // for VTOL we use takeoff slewrate, which helps with transition + slewrate = g.takeoff_throttle_slewrate; + } + if (g.takeoff_throttle_slewrate != 0 && quadplane.in_transition()) { + slewrate = g.takeoff_throttle_slewrate; + } // if slew limit rate is set to zero then do not slew limit if (slewrate) { SRV_Channels::limit_slew_rate(func, slewrate, G_Dt);