From 8661bdda8a44ed8c7abded180953616efba532dc Mon Sep 17 00:00:00 2001 From: "Dr.-Ing. Amilcar Do Carmo Lucas" Date: Tue, 2 May 2017 15:49:03 +0200 Subject: [PATCH] RC_Channel: Use SI units conventions in parameter units Follow the rules from: http://physics.nist.gov/cuu/Units/units.html http://physics.nist.gov/cuu/Units/outside.html and http://physics.nist.gov/cuu/Units/checklist.html one further constrain is that only printable (7bit) ASCII characters are allowed --- libraries/RC_Channel/RC_Channel.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/libraries/RC_Channel/RC_Channel.cpp b/libraries/RC_Channel/RC_Channel.cpp index 3bc924273e..410662f0d0 100644 --- a/libraries/RC_Channel/RC_Channel.cpp +++ b/libraries/RC_Channel/RC_Channel.cpp @@ -31,7 +31,7 @@ const AP_Param::GroupInfo RC_Channel::var_info[] = { // @Param: MIN // @DisplayName: RC min PWM // @Description: RC minimum PWM pulse width. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit. - // @Units: pwm + // @Units: PWM // @Range: 800 2200 // @Increment: 1 // @User: Advanced @@ -40,7 +40,7 @@ const AP_Param::GroupInfo RC_Channel::var_info[] = { // @Param: TRIM // @DisplayName: RC trim PWM // @Description: RC trim (neutral) PWM pulse width. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit. - // @Units: pwm + // @Units: PWM // @Range: 800 2200 // @Increment: 1 // @User: Advanced @@ -49,7 +49,7 @@ const AP_Param::GroupInfo RC_Channel::var_info[] = { // @Param: MAX // @DisplayName: RC max PWM // @Description: RC maximum PWM pulse width. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit. - // @Units: pwm + // @Units: PWM // @Range: 800 2200 // @Increment: 1 // @User: Advanced @@ -65,7 +65,7 @@ const AP_Param::GroupInfo RC_Channel::var_info[] = { // @Param: DZ // @DisplayName: RC dead-zone // @Description: dead zone around trim or bottom - // @Units: pwm + // @Units: PWM // @Range: 0 200 // @User: Advanced AP_GROUPINFO("DZ", 5, RC_Channel, dead_zone, 0),