mirror of https://github.com/ArduPilot/ardupilot
Plane:correct metatdata for Q_YAW_ANGLE param
This commit is contained in:
parent
8d30f84e73
commit
ae5d04b696
|
@ -54,7 +54,7 @@ const AP_Param::GroupInfo Tiltrotor::var_info[] = {
|
||||||
|
|
||||||
// @Param: YAW_ANGLE
|
// @Param: YAW_ANGLE
|
||||||
// @DisplayName: Tilt minimum angle for vectored yaw
|
// @DisplayName: Tilt minimum angle for vectored yaw
|
||||||
// @Description: This is the angle of the tilt servos when in VTOL mode and at minimum output. This needs to be set for Q_TILT_TYPE=3 to enable vectored control for yaw of tricopter tilt quadplanes. This is also used to limit the forwards travel of bicopter tilts when in VTOL modes
|
// @Description: This is the angle of the tilt servos when in VTOL mode and at minimum output (fully back). This needs to be set in addition to Q_TILT_TYPE=2, to enable vectored control for yaw in tilt quadplanes. This is also used to limit the forward travel of bicopter tilts(Q_TILT_TYPE=3) when in VTOL modes.
|
||||||
// @Range: 0 30
|
// @Range: 0 30
|
||||||
AP_GROUPINFO("YAW_ANGLE", 7, Tiltrotor, tilt_yaw_angle, 0),
|
AP_GROUPINFO("YAW_ANGLE", 7, Tiltrotor, tilt_yaw_angle, 0),
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue