From 1a56659eec8cded5d5c99d0e21d3b1b7b7290cef Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 1 Dec 2018 21:18:01 +1100 Subject: [PATCH] Plane: apply throttle slew to dual-motor setups thanks to Alex for noticing this issue --- ArduPlane/servos.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/ArduPlane/servos.cpp b/ArduPlane/servos.cpp index b5901de69c..3e6655d6a6 100644 --- a/ArduPlane/servos.cpp +++ b/ArduPlane/servos.cpp @@ -35,6 +35,8 @@ void Plane::throttle_slew_limit(void) // if slew limit rate is set to zero then do not slew limit if (slewrate) { SRV_Channels::limit_slew_rate(SRV_Channel::k_throttle, slewrate, G_Dt); + SRV_Channels::limit_slew_rate(SRV_Channel::k_throttleLeft, slewrate, G_Dt); + SRV_Channels::limit_slew_rate(SRV_Channel::k_throttleRight, slewrate, G_Dt); } }