From 0c84b8abf1c1825dcc5b077b6f88bbd471f271eb Mon Sep 17 00:00:00 2001 From: Michael Oborne Date: Wed, 21 Nov 2012 07:42:53 +0800 Subject: [PATCH] fix unit max. and unit type --- ArduCopter/Parameters.pde | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/ArduCopter/Parameters.pde b/ArduCopter/Parameters.pde index c5aab2e71b..302a091e0e 100644 --- a/ArduCopter/Parameters.pde +++ b/ArduCopter/Parameters.pde @@ -189,8 +189,8 @@ const AP_Param::Info var_info[] PROGMEM = { // @Param: THR_MIN // @DisplayName: Minimum Throttle // @Description: The minimum throttle which the autopilot will apply. - // @Units: Percent - // @Range: 0 100 + // @Units: ms + // @Range: 0 1000 // @Increment: 1 // @User: Standard GSCALAR(throttle_min, "THR_MIN", MINIMUM_THROTTLE), @@ -198,8 +198,8 @@ const AP_Param::Info var_info[] PROGMEM = { // @Param: THR_MAX // @DisplayName: Maximum Throttle // @Description: The maximum throttle which the autopilot will apply. - // @Units: Percent - // @Range: 0 100 + // @Units: ms + // @Range: 0 1000 // @Increment: 1 // @User: Standard GSCALAR(throttle_max, "THR_MAX", MAXIMUM_THROTTLE),