From 271373e1e80d4d54fb92dbdb44a8b39ba2a06178 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 13 Nov 2017 10:29:46 +1100 Subject: [PATCH] Plane: added a not on min slew rate for throttle --- ArduPlane/Parameters.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduPlane/Parameters.cpp b/ArduPlane/Parameters.cpp index 4ccd306885..fb5e2db73b 100644 --- a/ArduPlane/Parameters.cpp +++ b/ArduPlane/Parameters.cpp @@ -436,7 +436,7 @@ const AP_Param::Info Plane::var_info[] = { // @Param: THR_SLEWRATE // @DisplayName: Throttle slew rate - // @Description: maximum percentage change in throttle per second. A setting of 10 means to not change the throttle by more than 10% of the full throttle range in one second. + // @Description: maximum percentage change in throttle per second. A setting of 10 means to not change the throttle by more than 10% of the full throttle range in one second. Note that the minimum throttle change is 1 microsecond per loop, which provides a lower limit on the throttle slew rate, especially for quadplanes that run at 300 loops per second by default. // @Units: %/s // @Range: 0 127 // @Increment: 1