diff --git a/ArduPlane/servos.cpp b/ArduPlane/servos.cpp index 69d1b2d23e..2d4a676f07 100644 --- a/ArduPlane/servos.cpp +++ b/ArduPlane/servos.cpp @@ -43,6 +43,17 @@ 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 HAL_QUADPLANE_ENABLED + if (g.takeoff_throttle_slewrate != 0 && quadplane.in_transition()) { + slewrate = g.takeoff_throttle_slewrate; + } +#endif // if slew limit rate is set to zero then do not slew limit if (slewrate) { SRV_Channels::limit_slew_rate(func, slewrate, G_Dt);