From 697c3860750eda6116cba8c083da462839cfa0c2 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 28 Nov 2012 11:42:05 +1100 Subject: [PATCH] Plane: use correct throttle range in slewrate --- ArduPlane/Attitude.pde | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/ArduPlane/Attitude.pde b/ArduPlane/Attitude.pde index 454c1f9956..56e149cf3e 100644 --- a/ArduPlane/Attitude.pde +++ b/ArduPlane/Attitude.pde @@ -284,9 +284,10 @@ static void calc_nav_roll() static void throttle_slew_limit() { static int16_t last = 1000; - if(g.throttle_slewrate) { // if slew limit rate is set to zero then do not slew limit - - float temp = g.throttle_slewrate * G_Dt * 10.f; // * 10 to scale % to pwm range of 1000 to 2000 + // if slew limit rate is set to zero then do not slew limit + if (g.throttle_slewrate) { + // limit throttle change by the given percentage per second + float temp = g.throttle_slewrate * G_Dt * 0.01 * fabs(g.channel_throttle.radio_max - g.channel_throttle.radio_min); g.channel_throttle.radio_out = constrain(g.channel_throttle.radio_out, last - (int)temp, last + (int)temp); last = g.channel_throttle.radio_out; }