mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 01:18:29 -04:00
Plane: update Q_OPTIONS docs
Made q_options description a little clearer
This commit is contained in:
parent
1bee1dd210
commit
7d91755bd1
@ -402,7 +402,7 @@ const AP_Param::GroupInfo QuadPlane::var_info[] = {
|
||||
|
||||
// @Param: OPTIONS
|
||||
// @DisplayName: quadplane options
|
||||
// @Description: This provides a set of additional control options for quadplanes. LevelTransition means that the wings should be held level to within LEVEL_ROLL_LIMIT degrees during transition to fixed wing flight. If AllowFWTakeoff is disabled then fixed wing takeoff on quadplanes will instead perform a VTOL takeoff. If AllowFWLand is disabled then fixed wing land on quadplanes will instead perform a VTOL land.
|
||||
// @Description: This provides a set of additional control options for quadplanes. LevelTransition means that the wings should be held level to within LEVEL_ROLL_LIMIT degrees during transition to fixed wing flight. If AllowFWTakeoff bit is not set then fixed wing takeoff on quadplanes will instead perform a VTOL takeoff. If AllowFWLand bit is not set then fixed wing land on quadplanes will instead perform a VTOL land.
|
||||
// @Bitmask: 0:LevelTransition,1:AllowFWTakeoff,2:AllowFWLand
|
||||
AP_GROUPINFO("OPTIONS", 58, QuadPlane, options, 0),
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user