From bb1664185f08372afc630b0c571059d59da31bea Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Wed, 30 Oct 2013 20:53:21 +0900 Subject: [PATCH] Copter: correct @Range of MOT_TCRV_MAXPCT parameter --- libraries/AP_Motors/AP_Motors_Class.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_Motors/AP_Motors_Class.cpp b/libraries/AP_Motors/AP_Motors_Class.cpp index b0202b1a47..82e28299d4 100644 --- a/libraries/AP_Motors/AP_Motors_Class.cpp +++ b/libraries/AP_Motors/AP_Motors_Class.cpp @@ -43,7 +43,7 @@ const AP_Param::GroupInfo AP_Motors::var_info[] PROGMEM = { // @Param: TCRV_MAXPCT // @DisplayName: Thrust Curve max thrust percentage // @Description: Set to the lowest pwm position that produces the maximum thrust of the motors. Most motors produce maximum thrust below the maximum pwm value that they accept. - // @Range: 20 80 + // @Range: 50 100 AP_GROUPINFO("TCRV_MAXPCT", 3, AP_Motors, _throttle_curve_max, THROTTLE_CURVE_MAX_THRUST), // @Param: SPIN_ARMED