SRV_Channel:Servo Library - set allowable min value to 500 pwm uS

Mostly for helicopter and airplane that may be using 760uS centered servos
This commit is contained in:
ChristopherOlson 2018-03-23 14:48:04 -05:00 committed by Randy Mackay
parent 5df2b1a3ac
commit c39a802655
1 changed files with 1 additions and 1 deletions

View File

@ -32,7 +32,7 @@ const AP_Param::GroupInfo SRV_Channel::var_info[] = {
// @DisplayName: Minimum PWM
// @Description: minimum PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
// @Units: PWM
// @Range: 800 2200
// @Range: 500 2200
// @Increment: 1
// @User: Standard
AP_GROUPINFO("MIN", 1, SRV_Channel, servo_min, 1100),