Skip to content

Commit 5e496e2

Browse files
committed
common: added options for hover vs loiter for DO_REPOSITION
this gives the GCS operator the choice of asking the aircraft to either enter a hover or a fixed wing loiter at the target location. In ArduPilot this is controlled at the moment using the Q_GUIDED_MODE parameter, but it will be much better to be able to control this using a UI element in the FlyTo dialog. Note: this also brings in the yaw option from upstream
1 parent 6cd16c5 commit 5e496e2

File tree

1 file changed

+9
-0
lines changed

1 file changed

+9
-0
lines changed

message_definitions/v1.0/common.xml

Lines changed: 9 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -3047,6 +3047,15 @@
30473047
<entry value="1" name="MAV_DO_REPOSITION_FLAGS_CHANGE_MODE">
30483048
<description>The aircraft should immediately transition into guided. This should not be set for follow me applications</description>
30493049
</entry>
3050+
<entry value="2" name="MAV_DO_REPOSITION_FLAGS_RELATIVE_YAW">
3051+
<description>Yaw relative to the vehicle current heading (if not set, relative to North).</description>
3052+
</entry>
3053+
<entry value="4" name="MAV_DO_REPOSITION_FLAGS_VTOL_HOVER">
3054+
<description>If capable, the aircraft should enter a VTOL hover at the target position</description>
3055+
</entry>
3056+
<entry value="8" name="MAV_DO_REPOSITION_FLAGS_FW_LOITER">
3057+
<description>If capable, the aircraft should enter a fixed wing loiter at the target position</description>
3058+
</entry>
30503059
</enum>
30513060
<enum name="SPEED_TYPE">
30523061
<description>Speed setpoint types used in MAV_CMD_DO_CHANGE_SPEED</description>

0 commit comments

Comments
 (0)