mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-05-23 05:47:35 +08:00
mission: publish "work item" as current sub flight mode
This commit is contained in:
@@ -6,10 +6,17 @@ uint16 sequence_current # Sequence of the current mission item
|
||||
|
||||
uint16 nav_cmd
|
||||
|
||||
uint8 MISSION_SUBMODE_NONE = 0
|
||||
uint8 MISSION_SUBMODE_PRECLAND = 1
|
||||
# Work Item corresponds to the sub-mode set on the "MAV_CMD_DO_SET_MODE" MAVLink message
|
||||
uint8 WORK_ITEM_TYPE_DEFAULT = 0 # Default mission item
|
||||
uint8 WORK_ITEM_TYPE_TAKEOFF = 1 # Takeoff before moving to waypoint
|
||||
uint8 WORK_ITEM_TYPE_MOVE_TO_LAND = 2 # Move to land waypoint before descent
|
||||
uint8 WORK_ITEM_TYPE_ALIGN = 3 # Align for next waypoint
|
||||
uint8 WORK_ITEM_TYPE_TRANSITON_AFTER_TAKEOFF = 4 # VTOL specific
|
||||
uint8 WORK_ITEM_TYPE_MOVE_TO_LAND_AFTER_TRANSITION = 5 # VTOL specific
|
||||
uint8 WORK_ITEM_TYPE_PRECISION_LAND = 6 # Precision Landing for Multicopters using external aid
|
||||
|
||||
uint8 nav_sub_cmd # sub-command, for example AUTO_PRECLAND in main command AUTO_MISSION
|
||||
uint8 nav_sub_cmd # Synonymous to "work_item_type" in Navigator. Will be renamed eventually in navigator.
|
||||
# sub-command, for example AUTO_PRECLAND in main command AUTO_MISSION
|
||||
|
||||
float32 latitude
|
||||
float32 longitude
|
||||
|
||||
Reference in New Issue
Block a user