2013-07-14 03:02:29 -03:00
<?xml version='1.0'?>
<mavlink >
2013-08-28 06:15:48 -03:00
<include > common.xml</include>
<version > 3</version>
<enums >
<enum name= "AUTOQUAD_NAV_STATUS" >
<description > Available operating modes/statuses for AutoQuad flight controller.
Bitmask up to 32 bits. Low side bits for base modes, high side for
additional active features/modifiers/constraints.</description>
<entry value= "0" name= "AQ_NAV_STATUS_INIT" >
<description > System is initializing</description>
</entry>
<!-- low side basic mode bits -->
<entry value= "0x1" name= "AQ_NAV_STATUS_STANDBY" >
<description > System is standing by, not active</description>
</entry>
<entry value= "0x2" name= "AQ_NAV_STATUS_MANUAL" >
<description > Stabilized, under full manual control</description>
</entry>
<entry value= "0x4" name= "AQ_NAV_STATUS_ALTHOLD" >
<description > Altitude hold engaged</description>
</entry>
<entry value= "0x8" name= "AQ_NAV_STATUS_POSHOLD" >
<description > Position hold engaged</description>
</entry>
<entry value= "0x10" name= "AQ_NAV_STATUS_DVH" >
<description > Dynamic Velocity Hold is active</description>
</entry>
<entry value= "0x20" name= "AQ_NAV_STATUS_MISSION" >
<description > Autonomous mission execution mode</description>
</entry>
<!-- high side feature/modifier/constraint bits (0x8000 0000 = bit 32) -->
<entry value= "0x80000000" name= "AQ_NAV_STATUS_FAILSAFE" >
<description > System is in failsafe recovery mode</description>
</entry>
<entry value= "0x40000000" name= "AQ_NAV_STATUS_RTH" >
<description > Automatic Return to Home is active</description>
</entry>
<entry value= "0x20000000" name= "AQ_NAV_STATUS_HF_LOCKED" >
<description > Heading-Free locked mode active</description>
</entry>
<entry value= "0x10000000" name= "AQ_NAV_STATUS_HF_DYNAMIC" >
<description > Heading-Free dynamic mode active</description>
</entry>
<entry value= "0x8000000" name= "AQ_NAV_STATUS_CEILING" >
<description > Ceiling altitude is set</description>
</entry>
<entry value= "0x4000000" name= "AQ_NAV_STATUS_CEILING_REACHED" >
<description > Craft is at ceiling altitude</description>
</entry>
</enum>
<enum name= "MAV_CMD" >
<!-- TODO: value 1 reserved for now due to legacy code -->
<entry value= "2" name= "MAV_CMD_AQ_TELEMETRY" >
<description > Start/stop AutoQuad telemetry values stream.</description>
<param index= "1" > Start or stop (1 or 0)</param>
<param index= "2" > Stream frequency in us</param>
2015-03-04 04:21:24 -04:00
<param index= "3" > Dataset ID (refer to aq_mavlink.h::mavlinkCustomDataSets enum in AQ flight controller code)</param>
2013-08-28 06:15:48 -03:00
<param index= "4" > Empty</param>
<param index= "5" > Empty</param>
<param index= "6" > Empty</param>
<param index= "7" > Empty</param>
</entry>
<entry value= "3" name= "MAV_CMD_AQ_FOLLOW" >
<description > Command AutoQuad to go to a particular place at a set speed.</description>
<param index= "1" > Latitude</param>
<param index= "2" > Lontitude</param>
<param index= "3" > Altitude</param>
<param index= "4" > Speed</param>
<param index= "5" > Empty</param>
<param index= "6" > Empty</param>
<param index= "7" > Empty</param>
</entry>
<entry value= "4" name= "MAV_CMD_AQ_REQUEST_VERSION" >
<description > Request AutoQuad firmware version number.</description>
<param index= "1" > Empty</param>
<param index= "2" > Empty</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>
</enum>
2015-03-04 04:21:24 -04:00
<!-- extend MAV_DATA_STREAM -->
<enum name= "MAV_DATA_STREAM" >
<entry value= "13" name= "MAV_DATA_STREAM_PROPULSION" >
<description > Motor/ESC telemetry data.</description>
</entry>
</enum>
2013-08-28 06:15:48 -03:00
</enums>
<messages >
2013-07-14 03:02:29 -03:00
<message id= "150" name= "AQ_TELEMETRY_F" >
<description > Sends up to 20 raw float values.</description>
<field type= "uint16_t" name= "Index" > Index of message</field>
<field type= "float" name= "value1" > value1</field>
<field type= "float" name= "value2" > value2</field>
<field type= "float" name= "value3" > value3</field>
<field type= "float" name= "value4" > value4</field>
<field type= "float" name= "value5" > value5</field>
<field type= "float" name= "value6" > value6</field>
<field type= "float" name= "value7" > value7</field>
<field type= "float" name= "value8" > value8</field>
<field type= "float" name= "value9" > value9</field>
<field type= "float" name= "value10" > value10</field>
<field type= "float" name= "value11" > value11</field>
<field type= "float" name= "value12" > value12</field>
<field type= "float" name= "value13" > value13</field>
<field type= "float" name= "value14" > value14</field>
<field type= "float" name= "value15" > value15</field>
<field type= "float" name= "value16" > value16</field>
<field type= "float" name= "value17" > value17</field>
<field type= "float" name= "value18" > value18</field>
<field type= "float" name= "value19" > value19</field>
<field type= "float" name= "value20" > value20</field>
</message>
2015-03-04 04:21:24 -04:00
<message id= "152" name= "AQ_ESC_TELEMETRY" >
<description > Sends ESC32 telemetry data for up to 4 motors. Multiple messages may be sent in sequence when system has > 4 motors. Data is described as follows:
// unsigned int state : 3;
// unsigned int vin : 12; // x 100
// unsigned int amps : 14; // x 100
// unsigned int rpm : 15;
// unsigned int duty : 8; // x (255/100)
// - Data Version 2 -
// unsigned int errors : 9; // Bad detects error count
// - Data Version 3 -
// unsigned int temp : 9; // (Deg C + 32) * 4
// unsigned int errCode : 3;
</description>
<field type= "uint32_t" name= "time_boot_ms" > Timestamp of the component clock since boot time in ms.</field>
<field type= "uint8_t" name= "seq" > Sequence number of message (first set of 4 motors is #1, next 4 is #2, etc).</field>
<field type= "uint8_t" name= "num_motors" > Total number of active ESCs/motors on the system.</field>
<field type= "uint8_t" name= "num_in_seq" > Number of active ESCs in this sequence (1 through this many array members will be populated with data)</field>
<field type= "uint8_t[4]" name= "escid" > ESC/Motor ID</field>
<field type= "uint16_t[4]" name= "status_age" > Age of each ESC telemetry reading in ms compared to boot time. A value of 0xFFFF means timeout/no data.</field>
<field type= "uint8_t[4]" name= "data_version" > Version of data structure (determines contents).</field>
<field type= "uint32_t[4]" name= "data0" > Data bits 1-32 for each ESC.</field>
<field type= "uint32_t[4]" name= "data1" > Data bits 33-64 for each ESC.</field>
</message>
2013-08-28 06:15:48 -03:00
</messages>
2013-07-14 03:02:29 -03:00
</mavlink>