Browse Source

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

Mostly for helicopter and airplane that may be using 760uS centered servos
master
ChristopherOlson 7 years ago committed by Randy Mackay
parent
commit
c39a802655
  1. 2
      libraries/SRV_Channel/SRV_Channel.cpp

2
libraries/SRV_Channel/SRV_Channel.cpp

@ -32,7 +32,7 @@ const AP_Param::GroupInfo SRV_Channel::var_info[] = { @@ -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),

Loading…
Cancel
Save