Skip to content

Commit

Permalink
common: add MAV_CMD_DO_UPGRADE command (#1382)
Browse files Browse the repository at this point in the history
  • Loading branch information
TSC21 committed May 28, 2020
1 parent 3b3189d commit 33ed65b
Showing 1 changed file with 11 additions and 0 deletions.
11 changes: 11 additions & 0 deletions message_definitions/v1.0/common.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2038,6 +2038,17 @@
<param index="6">Reserved (set to 0)</param>
<param index="7">WIP: ID (e.g. camera ID -1 for all IDs)</param>
</entry>
<entry value="247" name="MAV_CMD_DO_UPGRADE" hasLocation="false" isDestination="false">
<wip/>
<description>Request a target system to start, cancel, or restart upgrade of one (or all) of its components. For example, the command might be sent to a companion computer to cause it to upgrade a connected flight controller. The system doing the upgrade will report progress using the normal command protocol sequence (COMMAND_ACK regularly sent with result=MAV_RESULT_IN_PROGRESS, followed by a final result of MAV_RESULT_ACCEPTED or MAV_RESULT_FAILED). The operation can be cancelled, in which case the updating system would send COMMAND_ACK with MAV_RESULT_ACCEPTED. The operation can be restarted, in which case the updating system should respond with progress updates (as though it had a new message).</description>
<param index="1" label="Component ID" enum="MAV_COMPONENT">Component id of the component to be upgraded. If set to 0, all components should be upgraded.</param>
<param index="2" label="Action" minValue="0" maxValue="2" increment="1">0: Start component upgrade, 1: Cancel component upgrade, 2: Restart component upgrade.</param>
<param index="3" label="Reboot" minValue="0" maxValue="1" increment="1">0: Do not reboot component after the action is executed, 1: Reboot component after the action is executed.</param>
<param index="4">Reserved</param>
<param index="5">Reserved</param>
<param index="6">Reserved</param>
<param index="7">WIP: upgrade progress report rate (can be used for more granular control).</param>
</entry>
<entry value="252" name="MAV_CMD_OVERRIDE_GOTO" hasLocation="true" isDestination="true">
<description>Override current mission with command to pause mission, pause mission and move to position, continue/resume mission. When param 1 indicates that the mission is paused (MAV_GOTO_DO_HOLD), param 2 defines whether it holds in place or moves to another position.</description>
<param index="1" label="Continue" enum="MAV_GOTO">MAV_GOTO_DO_HOLD: pause mission and either hold or move to specified position (depending on param2), MAV_GOTO_DO_CONTINUE: resume mission.</param>
Expand Down

0 comments on commit 33ed65b

Please sign in to comment.