XML: resolved conflicts in MAV_CMD_ enum

this moves a couple of commands to be MAV_CMD_DO_ commands, after
discussions with Lorenz and Randy
This commit is contained in:
Andrew Tridgell 2014-07-24 21:33:06 +10:00
parent e9fedbdb79
commit 3d2460bd42
2 changed files with 28 additions and 30 deletions

View File

@ -13,16 +13,6 @@
<!-- ardupilot specific MAV_CMD_* commands --> <!-- ardupilot specific MAV_CMD_* commands -->
<enum name="MAV_CMD"> <enum name="MAV_CMD">
<entry name="MAV_CMD_NAV_VELOCITY" value="91">
<description>Navigate at the specified velocity</description>
<param index="1">coordinate_frame - see MAV_FRAME enum</param>
<param index="2">Empty</param>
<param index="3">Empty</param>
<param index="4">Empty</param>
<param index="5">x velocity</param>
<param index="6">y velocity</param>
<param index="7">z velocity</param>
</entry>
<entry name="MAV_CMD_DO_MOTOR_TEST" value="209"> <entry name="MAV_CMD_DO_MOTOR_TEST" value="209">
<description>Mission command to perform motor test</description> <description>Mission command to perform motor test</description>
<param index="1">motor sequence number (a number from 1 to max number of motors on the vehicle)</param> <param index="1">motor sequence number (a number from 1 to max number of motors on the vehicle)</param>

View File

@ -593,26 +593,12 @@
<param index="6">Longitude/Y of goal</param> <param index="6">Longitude/Y of goal</param>
<param index="7">Altitude/Z of goal</param> <param index="7">Altitude/Z of goal</param>
</entry> </entry>
<entry value="90" name="MAV_CMD_NAV_GUIDED_LIMITS">
<description>set limits for external control</description> <!-- IDs 90 and 91 are reserved until the end of 2014,
<param index="1">timeout - maximum time (in seconds) that external controller will be allowed to control vehicle. 0 means no timeout</param> as they were used in some conflicting proposals
<param index="2">absolute altitude min (in meters, WGS84) - if vehicle moves below this alt, the command will be aborted and the mission will continue. 0 means no lower altitude limit</param> between PX4 and ardupilot and need to be kept
<param index="3">absolute altitude max (in meters)- if vehicle moves above this alt, the command will be aborted and the mission will continue. 0 means no upper altitude limit</param> unused to prevent errors -->
<param index="4">horizontal move limit (in meters, WGS84) - if vehicle moves more than this distance from it's location at the moment the command was executed, the command will be aborted and the mission will continue. 0 means no horizontal altitude limit</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
<entry value="91" name="MAV_CMD_NAV_GUIDED_MASTER">
<description>set id of master controller</description>
<param index="1">System ID</param>
<param index="2">Component ID</param>
<param index="3">Empty</param>
<param index="4">Empty</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
<entry value="92" name="MAV_CMD_NAV_GUIDED_ENABLE"> <entry value="92" name="MAV_CMD_NAV_GUIDED_ENABLE">
<description>hand control over to an external controller</description> <description>hand control over to an external controller</description>
<param index="1">On / Off (> 0.5f on)</param> <param index="1">On / Off (> 0.5f on)</param>
@ -925,6 +911,28 @@
<param index="7">Empty</param> <param index="7">Empty</param>
</entry> </entry>
<entry value="221" name="MAV_CMD_DO_GUIDED_MASTER">
<description>set id of master controller</description>
<param index="1">System ID</param>
<param index="2">Component ID</param>
<param index="3">Empty</param>
<param index="4">Empty</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
<entry value="222" name="MAV_CMD_DO_GUIDED_LIMITS">
<description>set limits for external control</description>
<param index="1">timeout - maximum time (in seconds) that external controller will be allowed to control vehicle. 0 means no timeout</param>
<param index="2">absolute altitude min (in meters, WGS84) - if vehicle moves below this alt, the command will be aborted and the mission will continue. 0 means no lower altitude limit</param>
<param index="3">absolute altitude max (in meters)- if vehicle moves above this alt, the command will be aborted and the mission will continue. 0 means no upper altitude limit</param>
<param index="4">horizontal move limit (in meters, WGS84) - if vehicle moves more than this distance from it's location at the moment the command was executed, the command will be aborted and the mission will continue. 0 means no horizontal altitude limit</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
<entry value="240" name="MAV_CMD_DO_LAST"> <entry value="240" name="MAV_CMD_DO_LAST">
<description>NOP - This command is only used to mark the upper limit of the DO commands in the enumeration</description> <description>NOP - This command is only used to mark the upper limit of the DO commands in the enumeration</description>
<param index="1">Empty</param> <param index="1">Empty</param>