From 9728c4651d4646bd82e8927db99d096705d0ffce Mon Sep 17 00:00:00 2001 From: murata Date: Fri, 31 Jan 2020 09:42:15 +0900 Subject: [PATCH] RC/SRV_Channel: Change the minimum PWM setting to 900. --- libraries/RC_Channel/RC_Channel.cpp | 6 +++--- libraries/SRV_Channel/SRV_Channel.cpp | 6 +++--- 2 files changed, 6 insertions(+), 6 deletions(-) diff --git a/libraries/RC_Channel/RC_Channel.cpp b/libraries/RC_Channel/RC_Channel.cpp index 97d07e8438acb..bcaeb730cb89b 100644 --- a/libraries/RC_Channel/RC_Channel.cpp +++ b/libraries/RC_Channel/RC_Channel.cpp @@ -49,7 +49,7 @@ const AP_Param::GroupInfo RC_Channel::var_info[] = { // @DisplayName: RC min PWM // @Description: RC 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: 900 2200 // @Increment: 1 // @User: Advanced AP_GROUPINFO("MIN", 1, RC_Channel, radio_min, 1100), @@ -58,7 +58,7 @@ const AP_Param::GroupInfo RC_Channel::var_info[] = { // @DisplayName: RC trim PWM // @Description: RC trim (neutral) PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit. // @Units: PWM - // @Range: 800 2200 + // @Range: 900 2200 // @Increment: 1 // @User: Advanced AP_GROUPINFO("TRIM", 2, RC_Channel, radio_trim, 1500), @@ -67,7 +67,7 @@ const AP_Param::GroupInfo RC_Channel::var_info[] = { // @DisplayName: RC max PWM // @Description: RC maximum PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit. // @Units: PWM - // @Range: 800 2200 + // @Range: 900 2200 // @Increment: 1 // @User: Advanced AP_GROUPINFO("MAX", 3, RC_Channel, radio_max, 1900), diff --git a/libraries/SRV_Channel/SRV_Channel.cpp b/libraries/SRV_Channel/SRV_Channel.cpp index 89f9769fa3964..0d79a37bc7d30 100644 --- a/libraries/SRV_Channel/SRV_Channel.cpp +++ b/libraries/SRV_Channel/SRV_Channel.cpp @@ -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: 500 2200 + // @Range: 900 2200 // @Increment: 1 // @User: Standard AP_GROUPINFO("MIN", 1, SRV_Channel, servo_min, 1100), @@ -41,7 +41,7 @@ const AP_Param::GroupInfo SRV_Channel::var_info[] = { // @DisplayName: Maximum PWM // @Description: maximum PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit. // @Units: PWM - // @Range: 800 2200 + // @Range: 900 2200 // @Increment: 1 // @User: Standard AP_GROUPINFO("MAX", 2, SRV_Channel, servo_max, 1900), @@ -50,7 +50,7 @@ const AP_Param::GroupInfo SRV_Channel::var_info[] = { // @DisplayName: Trim PWM // @Description: Trim PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit. // @Units: PWM - // @Range: 800 2200 + // @Range: 900 2200 // @Increment: 1 // @User: Standard AP_GROUPINFO("TRIM", 3, SRV_Channel, servo_trim, 1500),