diff --git a/ArduPlane/Parameters.pde b/ArduPlane/Parameters.pde index 602a5d3c47..daf03f670c 100644 --- a/ArduPlane/Parameters.pde +++ b/ArduPlane/Parameters.pde @@ -201,7 +201,7 @@ const AP_Param::Info var_info[] PROGMEM = { // @DisplayName: Takeoff throttle slew rate // @Description: This parameter sets the slew rate for the throttle during auto takeoff. When this is zero the THR_SLEWRATE parameter is used during takeoff. For rolling takeoffs it can be a good idea to set a lower slewrate for takeoff to give a slower acceleration which can improve ground steering control. The value is a percentage throttle change per second, so a value of 20 means to advance the throttle over 5 seconds on takeoff. Values below 20 are not recommended as they may cause the plane to try to climb out with too little throttle. // @Units: percent - // @Range: 0 100 + // @Range: 0 127 // @Increment: 1 // @User: User GSCALAR(takeoff_throttle_slewrate, "TKOFF_THR_SLEW", 0), @@ -454,7 +454,7 @@ const AP_Param::Info var_info[] PROGMEM = { // @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. // @Units: Percent - // @Range: 0 100 + // @Range: 0 127 // @Increment: 1 // @User: Standard ASCALAR(throttle_slewrate, "THR_SLEWRATE", 100),