mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 08:13:56 -04:00
Plane: Quadplane: reinstate THR PWM param discriptions for stable users
This commit is contained in:
parent
67abf23077
commit
e99a5c6ef4
@ -82,7 +82,22 @@ const AP_Param::GroupInfo QuadPlane::var_info[] = {
|
|||||||
// @User: Standard
|
// @User: Standard
|
||||||
AP_GROUPINFO("RC_SPEED", 21, QuadPlane, rc_speed, 490),
|
AP_GROUPINFO("RC_SPEED", 21, QuadPlane, rc_speed, 490),
|
||||||
|
|
||||||
|
// @Param: THR_MIN_PWM
|
||||||
|
// @DisplayName: Minimum PWM output
|
||||||
|
// @Description: This is the minimum PWM output for the quad motors
|
||||||
|
// @Units: PWM
|
||||||
|
// @Range: 800 2200
|
||||||
|
// @Increment: 1
|
||||||
|
// @User: Standard
|
||||||
// 22: THR_MIN_PWM
|
// 22: THR_MIN_PWM
|
||||||
|
|
||||||
|
// @Param: THR_MAX_PWM
|
||||||
|
// @DisplayName: Maximum PWM output
|
||||||
|
// @Description: This is the maximum PWM output for the quad motors
|
||||||
|
// @Units: PWM
|
||||||
|
// @Range: 800 2200
|
||||||
|
// @Increment: 1
|
||||||
|
// @User: Standard
|
||||||
// 23: THR_MAX_PWM
|
// 23: THR_MAX_PWM
|
||||||
|
|
||||||
// @Param: ASSIST_SPEED
|
// @Param: ASSIST_SPEED
|
||||||
|
Loading…
Reference in New Issue
Block a user