SRV_Channel: Improve the PWM parameters descriptions

This commit is contained in:
Dr.-Ing. Amilcar Do Carmo Lucas 2017-05-16 01:24:01 +02:00 committed by Andrew Tridgell
parent ed07d5b5c9
commit 65cca6ae87

View File

@ -30,7 +30,7 @@ SRV_Channel::servo_mask_t SRV_Channel::have_pwm_mask;
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.
// @Description: minimum PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
// @Units: PWM
// @Range: 800 2200
// @Increment: 1
@ -39,7 +39,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.
// @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
// @Increment: 1
@ -48,7 +48,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.
// @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
// @Increment: 1