Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

RC/SRV_Channel: Change the minimum PWM setting to 900. #13436

Closed
Closed
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
6 changes: 3 additions & 3 deletions libraries/RC_Channel/RC_Channel.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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),
Expand All @@ -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),
Expand All @@ -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),
Expand Down
6 changes: 3 additions & 3 deletions libraries/SRV_Channel/SRV_Channel.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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),
Expand All @@ -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),
Expand All @@ -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),
Expand Down