Copter: update @Units to pwm on throttle params
This commit is contained in:
parent
78acea820f
commit
c98d375e49
@ -241,7 +241,7 @@ const AP_Param::Info var_info[] PROGMEM = {
|
|||||||
// @Param: THR_MIN
|
// @Param: THR_MIN
|
||||||
// @DisplayName: Minimum Throttle
|
// @DisplayName: Minimum Throttle
|
||||||
// @Description: The minimum throttle that will be sent to the motors to keep them spinning
|
// @Description: The minimum throttle that will be sent to the motors to keep them spinning
|
||||||
// @Units: ms
|
// @Units: pwm
|
||||||
// @Range: 0 300
|
// @Range: 0 300
|
||||||
// @Increment: 1
|
// @Increment: 1
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
@ -250,7 +250,7 @@ const AP_Param::Info var_info[] PROGMEM = {
|
|||||||
// @Param: THR_MAX
|
// @Param: THR_MAX
|
||||||
// @DisplayName: Maximum Throttle
|
// @DisplayName: Maximum Throttle
|
||||||
// @Description: The maximum throttle that will be sent to the motors
|
// @Description: The maximum throttle that will be sent to the motors
|
||||||
// @Units: ms
|
// @Units: pwm
|
||||||
// @Range: 0 1000
|
// @Range: 0 1000
|
||||||
// @Increment: 1
|
// @Increment: 1
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
@ -267,7 +267,7 @@ const AP_Param::Info var_info[] PROGMEM = {
|
|||||||
// @DisplayName: Throttle Failsafe Value
|
// @DisplayName: Throttle Failsafe Value
|
||||||
// @Description: The PWM level on channel 3 below which throttle sailsafe triggers
|
// @Description: The PWM level on channel 3 below which throttle sailsafe triggers
|
||||||
// @Range: 925 1100
|
// @Range: 925 1100
|
||||||
// @Units: ms
|
// @Units: pwm
|
||||||
// @Increment: 1
|
// @Increment: 1
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
GSCALAR(failsafe_throttle_value, "FS_THR_VALUE", FS_THR_VALUE_DEFAULT),
|
GSCALAR(failsafe_throttle_value, "FS_THR_VALUE", FS_THR_VALUE_DEFAULT),
|
||||||
@ -276,7 +276,7 @@ const AP_Param::Info var_info[] PROGMEM = {
|
|||||||
// @DisplayName: Throttle Trim
|
// @DisplayName: Throttle Trim
|
||||||
// @Description: The autopilot's estimate of the throttle required to maintain a level hover. Calculated automatically from the pilot's throttle input while in stabilize mode
|
// @Description: The autopilot's estimate of the throttle required to maintain a level hover. Calculated automatically from the pilot's throttle input while in stabilize mode
|
||||||
// @Range: 0 1000
|
// @Range: 0 1000
|
||||||
// @Units: ms
|
// @Units: pwm
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
GSCALAR(throttle_cruise, "TRIM_THROTTLE", THROTTLE_CRUISE),
|
GSCALAR(throttle_cruise, "TRIM_THROTTLE", THROTTLE_CRUISE),
|
||||||
|
|
||||||
@ -285,6 +285,7 @@ const AP_Param::Info var_info[] PROGMEM = {
|
|||||||
// @Description: The throttle output (0 ~ 1000) when throttle stick is in mid position. Used to scale the manual throttle so that the mid throttle stick position is close to the throttle required to hover
|
// @Description: The throttle output (0 ~ 1000) when throttle stick is in mid position. Used to scale the manual throttle so that the mid throttle stick position is close to the throttle required to hover
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
// @Range: 300 700
|
// @Range: 300 700
|
||||||
|
// @Units: pwm
|
||||||
// @Increment: 1
|
// @Increment: 1
|
||||||
GSCALAR(throttle_mid, "THR_MID", THR_MID_DEFAULT),
|
GSCALAR(throttle_mid, "THR_MID", THR_MID_DEFAULT),
|
||||||
|
|
||||||
@ -569,7 +570,7 @@ const AP_Param::Info var_info[] PROGMEM = {
|
|||||||
// @Description: Roll axis rate controller I gain maximum. Constrains the maximum motor output that the I gain will output
|
// @Description: Roll axis rate controller I gain maximum. Constrains the maximum motor output that the I gain will output
|
||||||
// @Range: 0 500
|
// @Range: 0 500
|
||||||
// @Increment: 10
|
// @Increment: 10
|
||||||
// @Units: ms
|
// @Units: pwm
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
|
|
||||||
// @Param: RATE_RLL_D
|
// @Param: RATE_RLL_D
|
||||||
@ -599,7 +600,7 @@ const AP_Param::Info var_info[] PROGMEM = {
|
|||||||
// @Description: Pitch axis rate controller I gain maximum. Constrains the maximum motor output that the I gain will output
|
// @Description: Pitch axis rate controller I gain maximum. Constrains the maximum motor output that the I gain will output
|
||||||
// @Range: 0 500
|
// @Range: 0 500
|
||||||
// @Increment: 10
|
// @Increment: 10
|
||||||
// @Units: ms
|
// @Units: pwm
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
|
|
||||||
// @Param: RATE_PIT_D
|
// @Param: RATE_PIT_D
|
||||||
@ -629,7 +630,7 @@ const AP_Param::Info var_info[] PROGMEM = {
|
|||||||
// @Description: Yaw axis rate controller I gain maximum. Constrains the maximum motor output that the I gain will output
|
// @Description: Yaw axis rate controller I gain maximum. Constrains the maximum motor output that the I gain will output
|
||||||
// @Range: 0 500
|
// @Range: 0 500
|
||||||
// @Increment: 10
|
// @Increment: 10
|
||||||
// @Units: ms
|
// @Units: pwm
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
|
|
||||||
// @Param: RATE_YAW_D
|
// @Param: RATE_YAW_D
|
||||||
@ -742,7 +743,7 @@ const AP_Param::Info var_info[] PROGMEM = {
|
|||||||
// @DisplayName: Throttle acceleration controller I gain maximum
|
// @DisplayName: Throttle acceleration controller I gain maximum
|
||||||
// @Description: Throttle acceleration controller I gain maximum. Constrains the maximum pwm that the I term will generate
|
// @Description: Throttle acceleration controller I gain maximum. Constrains the maximum pwm that the I term will generate
|
||||||
// @Range: 0 500
|
// @Range: 0 500
|
||||||
// @Units: ms
|
// @Units: pwm
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
|
|
||||||
// @Param: THR_ACCEL_D
|
// @Param: THR_ACCEL_D
|
||||||
|
Loading…
Reference in New Issue
Block a user