mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-30 20:48:33 -04:00
SRV_Channel: Change the minimum value of minimum PWM for servo output
This commit is contained in:
parent
8360a3c247
commit
f3da373beb
@ -31,7 +31,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: 500 2200
|
||||
// @Range: 800 2200
|
||||
// @Increment: 1
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("MIN", 1, SRV_Channel, servo_min, 1100),
|
||||
|
Loading…
Reference in New Issue
Block a user