Skip to content
Open
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
43 changes: 39 additions & 4 deletions message_definitions/v1.0/common.xml
Original file line number Diff line number Diff line change
Expand Up @@ -746,6 +746,33 @@
<description>Autotune yaw axis.</description>
</entry>
</enum>
<enum name="REBOOT_SHUTDOWN_ACTION">
<description>Reboot/shutdown action for selected component in MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN.</description>
<entry value="0" name="REBOOT_SHUTDOWN_ACTION_NONE">
<description>Do nothing.</description>
</entry>
<entry value="1" name="REBOOT_SHUTDOWN_ACTION_REBOOT">
<description>Reboot component.</description>
</entry>
<entry value="2" name="REBOOT_SHUTDOWN_ACTION_SHUTDOWN">
<description>Shutdown component.</description>
</entry>
<entry value="3" name="REBOOT_SHUTDOWN_ACTION_REBOOT_TO_BOOTLOADER">
<description>Reboot component and keep it in the bootloader until upgraded.</description>
</entry>
<entry value="4" name="REBOOT_SHUTDOWN_ACTION_POWER_ON">
<description>Power on component. Do nothing if component is already powered (ACK command with MAV_RESULT_ACCEPTED).</description>
</entry>
</enum>
<enum name="REBOOT_SHUTDOWN_CONDITIONS">
<description>Specifies the conditions under which the MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN command should be accepted.</description>
<entry value="0" name="REBOOT_SHUTDOWN_CONDITIONS_SAFETY_INTERLOCKED">
<description>Reboot/Shutdown only if allowed by safety checks, such as being landed.</description>
</entry>
<entry value="20190226" name="REBOOT_SHUTDOWN_CONDITIONS_FORCE">
<description>Force reboot/shutdown of the autopilot/component regardless of system state.</description>
</entry>
</enum>
<!-- The MAV_CMD enum entries describe either: -->
<!-- * the data payload of mission items (as used in the MISSION_ITEM_INT message) -->
<!-- * the data payload of mavlink commands (as used in the COMMAND_INT and COMMAND_LONG messages) -->
Expand Down Expand Up @@ -1530,10 +1557,10 @@
</entry>
<entry value="246" name="MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN" hasLocation="false" isDestination="false">
<description>Request the reboot or shutdown of system components.</description>
<param index="1" label="Autopilot" minValue="0" maxValue="3" increment="1">0: Do nothing for autopilot, 1: Reboot autopilot, 2: Shutdown autopilot, 3: Reboot autopilot and keep it in the bootloader until upgraded.</param>
<param index="2" label="Companion" minValue="0" maxValue="3" increment="1">0: Do nothing for onboard computer, 1: Reboot onboard computer, 2: Shutdown onboard computer, 3: Reboot onboard computer and keep it in the bootloader until upgraded.</param>
<param index="3">WIP: 0: Do nothing for camera, 1: Reboot onboard camera, 2: Shutdown onboard camera, 3: Reboot onboard camera and keep it in the bootloader until upgraded</param>
<param index="4">WIP: 0: Do nothing for mount (e.g. gimbal), 1: Reboot mount, 2: Shutdown mount, 3: Reboot mount and keep it in the bootloader until upgraded</param>
<param index="1" label="Autopilot" enum="REBOOT_SHUTDOWN_ACTION">Action to take for autopilot.</param>
<param index="2" label="Companion" enum="REBOOT_SHUTDOWN_ACTION">Action to take for onboard computer.</param>
<param index="3" label="Component Action" enum="REBOOT_SHUTDOWN_ACTION">Action to take for component specified in param4.</param>
<param index="4" label="Component ID" minValue="0" maxValue="255" increment="1">MAVLink Component ID targeted in param3 (0 for all components).</param>
<param index="5">Reserved (set to 0)</param>
<param index="6">Reserved (set to 0)</param>
<param index="7">WIP: ID (e.g. camera ID -1 for all IDs)</param>
Expand Down Expand Up @@ -3388,6 +3415,14 @@
<entry value="2" name="CAMERA_TRACKING_STATUS_FLAGS_ERROR">
<description>Camera tracking in error state</description>
</entry>
<entry value="4" name="CAMERA_TRACKING_STATUS_FLAGS_MTI">
<wip/>
<description>Camera Moving Target Indicators (MTI) are active</description>
</entry>
<entry value="8" name="CAMERA_TRACKING_STATUS_FLAGS_COASTING">
<wip/>
<description>Camera tracking target is obscured and is being predicted</description>
</entry>
</enum>
<enum name="CAMERA_TRACKING_MODE">
<description>Camera tracking modes</description>
Expand Down