AP_Motors: Improve the PWM parameters descriptions
This commit is contained in:
parent
eebf26ed9f
commit
1b062d9d29
@ -33,7 +33,7 @@ const AP_Param::GroupInfo AP_MotorsHeli::var_info[] = {
|
||||
|
||||
// @Param: COL_MIN
|
||||
// @DisplayName: Collective Pitch Minimum
|
||||
// @Description: Lowest possible servo position for the swashplate
|
||||
// @Description: Lowest possible servo position in PWM microseconds for the swashplate
|
||||
// @Range: 1000 2000
|
||||
// @Units: PWM
|
||||
// @Increment: 1
|
||||
@ -42,7 +42,7 @@ const AP_Param::GroupInfo AP_MotorsHeli::var_info[] = {
|
||||
|
||||
// @Param: COL_MAX
|
||||
// @DisplayName: Collective Pitch Maximum
|
||||
// @Description: Highest possible servo position for the swashplate
|
||||
// @Description: Highest possible servo position in PWM microseconds for the swashplate
|
||||
// @Range: 1000 2000
|
||||
// @Units: PWM
|
||||
// @Increment: 1
|
||||
@ -51,7 +51,7 @@ const AP_Param::GroupInfo AP_MotorsHeli::var_info[] = {
|
||||
|
||||
// @Param: COL_MID
|
||||
// @DisplayName: Collective Pitch Mid-Point
|
||||
// @Description: Swash servo position corresponding to zero collective pitch (or zero lift for Asymmetrical blades)
|
||||
// @Description: Swash servo position in PWM microseconds corresponding to zero collective pitch (or zero lift for Asymmetrical blades)
|
||||
// @Range: 1000 2000
|
||||
// @Units: PWM
|
||||
// @Increment: 1
|
||||
@ -67,7 +67,7 @@ const AP_Param::GroupInfo AP_MotorsHeli::var_info[] = {
|
||||
|
||||
// @Param: RSC_SETPOINT
|
||||
// @DisplayName: External Motor Governor Setpoint
|
||||
// @Description: PWM passed to the external motor governor when external governor is enabled
|
||||
// @Description: PWM in microseconds passed to the external motor governor when external governor is enabled
|
||||
// @Range: 0 1000
|
||||
// @Units: PWM
|
||||
// @Increment: 10
|
||||
@ -83,7 +83,7 @@ const AP_Param::GroupInfo AP_MotorsHeli::var_info[] = {
|
||||
|
||||
// @Param: LAND_COL_MIN
|
||||
// @DisplayName: Landing Collective Minimum
|
||||
// @Description: Minimum collective position while landed or landing
|
||||
// @Description: Minimum collective position in PWM microseconds while landed or landing
|
||||
// @Range: 0 500
|
||||
// @Units: PWM
|
||||
// @Increment: 1
|
||||
|
@ -147,7 +147,7 @@ const AP_Param::GroupInfo AP_MotorsHeli_Dual::var_info[] = {
|
||||
|
||||
// @Param: COL2_MIN
|
||||
// @DisplayName: Collective Pitch Minimum for rear swashplate
|
||||
// @Description: Lowest possible servo position for the rear swashplate
|
||||
// @Description: Lowest possible servo position in PWM microseconds for the rear swashplate
|
||||
// @Range: 1000 2000
|
||||
// @Units: PWM
|
||||
// @Increment: 1
|
||||
@ -156,7 +156,7 @@ const AP_Param::GroupInfo AP_MotorsHeli_Dual::var_info[] = {
|
||||
|
||||
// @Param: COL2_MAX
|
||||
// @DisplayName: Collective Pitch Maximum for rear swashplate
|
||||
// @Description: Highest possible servo position for the rear swashplate
|
||||
// @Description: Highest possible servo position in PWM microseconds for the rear swashplate
|
||||
// @Range: 1000 2000
|
||||
// @Units: PWM
|
||||
// @Increment: 1
|
||||
@ -165,7 +165,7 @@ const AP_Param::GroupInfo AP_MotorsHeli_Dual::var_info[] = {
|
||||
|
||||
// @Param: COL2_MID
|
||||
// @DisplayName: Collective Pitch Mid-Point for rear swashplate
|
||||
// @Description: Swash servo position corresponding to zero collective pitch for the rear swashplate (or zero lift for Asymmetrical blades)
|
||||
// @Description: Swash servo position in PWM microseconds corresponding to zero collective pitch for the rear swashplate (or zero lift for Asymmetrical blades)
|
||||
// @Range: 1000 2000
|
||||
// @Units: PWM
|
||||
// @Increment: 1
|
||||
|
@ -67,7 +67,7 @@ const AP_Param::GroupInfo AP_MotorsHeli_Single::var_info[] = {
|
||||
|
||||
// @Param: GYR_GAIN
|
||||
// @DisplayName: External Gyro Gain
|
||||
// @Description: PWM sent to external gyro on ch7 when tail type is Servo w/ ExtGyro
|
||||
// @Description: PWM in microseconds sent to external gyro on ch7 when tail type is Servo w/ ExtGyro
|
||||
// @Range: 0 1000
|
||||
// @Units: PWM
|
||||
// @Increment: 1
|
||||
@ -100,7 +100,7 @@ const AP_Param::GroupInfo AP_MotorsHeli_Single::var_info[] = {
|
||||
|
||||
// @Param: TAIL_SPEED
|
||||
// @DisplayName: Direct Drive VarPitch Tail ESC speed
|
||||
// @Description: Direct Drive VarPitch Tail ESC speed. Only used when TailType is DirectDrive VarPitch
|
||||
// @Description: Direct Drive VarPitch Tail ESC speed in PWM microseconds. Only used when TailType is DirectDrive VarPitch
|
||||
// @Range: 0 1000
|
||||
// @Units: PWM
|
||||
// @Increment: 1
|
||||
@ -109,7 +109,7 @@ const AP_Param::GroupInfo AP_MotorsHeli_Single::var_info[] = {
|
||||
|
||||
// @Param: GYR_GAIN_ACRO
|
||||
// @DisplayName: External Gyro Gain for ACRO
|
||||
// @Description: PWM sent to external gyro on ch7 when tail type is Servo w/ ExtGyro. A value of zero means to use H_GYR_GAIN
|
||||
// @Description: PWM in microseconds sent to external gyro on ch7 when tail type is Servo w/ ExtGyro. A value of zero means to use H_GYR_GAIN
|
||||
// @Range: 0 1000
|
||||
// @Units: PWM
|
||||
// @Increment: 1
|
||||
|
@ -32,7 +32,7 @@ const AP_Param::GroupInfo AP_MotorsMulticopter::var_info[] = {
|
||||
|
||||
// @Param: YAW_HEADROOM
|
||||
// @DisplayName: Matrix Yaw Min
|
||||
// @Description: Yaw control is given at least this pwm range
|
||||
// @Description: Yaw control is given at least this pwm in microseconds range
|
||||
// @Range: 0 500
|
||||
// @Units: PWM
|
||||
// @User: Advanced
|
||||
@ -90,7 +90,7 @@ const AP_Param::GroupInfo AP_MotorsMulticopter::var_info[] = {
|
||||
|
||||
// @Param: PWM_MIN
|
||||
// @DisplayName: PWM output miniumum
|
||||
// @Description: This sets the min PWM output value that will ever be output to the motors, 0 = use input RC3_MIN
|
||||
// @Description: This sets the min PWM output value in microseconds that will ever be output to the motors, 0 = use input RC3_MIN
|
||||
// @Units: PWM
|
||||
// @Range: 0 2000
|
||||
// @User: Advanced
|
||||
@ -98,7 +98,7 @@ const AP_Param::GroupInfo AP_MotorsMulticopter::var_info[] = {
|
||||
|
||||
// @Param: PWM_MAX
|
||||
// @DisplayName: PWM output maximum
|
||||
// @Description: This sets the max PWM value that will ever be output to the motors, 0 = use input RC3_MAX
|
||||
// @Description: This sets the max PWM value in microseconds that will ever be output to the motors, 0 = use input RC3_MAX
|
||||
// @Units: PWM
|
||||
// @Range: 0 2000
|
||||
// @User: Advanced
|
||||
|
Loading…
Reference in New Issue
Block a user