Skip to content

Commit

Permalink
Add MAV_VTOL_STATE_QC field (mavlink#1569)
Browse files Browse the repository at this point in the history
  • Loading branch information
ThomasRigi authored Mar 1, 2021
1 parent 40d7c82 commit d6a1b6d
Showing 1 changed file with 2 additions and 1 deletion.
3 changes: 2 additions & 1 deletion message_definitions/v1.0/common.xml
Original file line number Diff line number Diff line change
Expand Up @@ -1936,7 +1936,8 @@
</entry>
<entry value="3000" name="MAV_CMD_DO_VTOL_TRANSITION" hasLocation="false" isDestination="false">
<description>Request VTOL transition</description>
<param index="1" label="State" enum="MAV_VTOL_STATE">The target VTOL state. Only MAV_VTOL_STATE_MC and MAV_VTOL_STATE_FW can be used.</param>
<param index="1" label="State" enum="MAV_VTOL_STATE">The target VTOL state. For normal transitions, only MAV_VTOL_STATE_MC and MAV_VTOL_STATE_FW can be used.</param>
<param index="2" label="Immediate">Force immediate transition to the specified MAV_VTOL_STATE. 1: Force immediate, 0: normal transition. Can be used, for example, to trigger an emergency "Quadchute". Caution: Can be dangerous/damage vehicle, depending on autopilot implementation of this command.</param>
</entry>
<entry value="3001" name="MAV_CMD_ARM_AUTHORIZATION_REQUEST" hasLocation="false" isDestination="false">
<description>Request authorization to arm the vehicle to a external entity, the arm authorizer is responsible to request all data that is needs from the vehicle before authorize or deny the request. If approved the progress of command_ack message should be set with period of time that this authorization is valid in seconds or in case it was denied it should be set with one of the reasons in ARM_AUTH_DENIED_REASON.
Expand Down

0 comments on commit d6a1b6d

Please sign in to comment.