mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
SRV_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
This commit is contained in:
parent
8661bdda8a
commit
5e938c8cc0
@ -31,7 +31,7 @@ const AP_Param::GroupInfo SRV_Channel::var_info[] = {
|
||||
// @Param: MIN
|
||||
// @DisplayName: Minimum PWM
|
||||
// @Description: 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: Standard
|
||||
@ -40,7 +40,7 @@ const AP_Param::GroupInfo SRV_Channel::var_info[] = {
|
||||
// @Param: MAX
|
||||
// @DisplayName: Maximum PWM
|
||||
// @Description: 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: Standard
|
||||
@ -49,7 +49,7 @@ const AP_Param::GroupInfo SRV_Channel::var_info[] = {
|
||||
// @Param: TRIM
|
||||
// @DisplayName: Trim PWM
|
||||
// @Description: Trim 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: Standard
|
||||
|
Loading…
Reference in New Issue
Block a user