autoquad.xml 8.6 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168
  1. <?xml version="1.0"?>
  2. <mavlink>
  3. <include>common.xml</include>
  4. <version>3</version>
  5. <enums>
  6. <enum name="AUTOQUAD_MAVLINK_DEFS_VERSION">
  7. <description>Track current version of these definitions (can be used by checking value of AUTOQUAD_MAVLINK_DEFS_VERSION_ENUM_END). Append a new entry for each published change.</description>
  8. <entry name="AQ_MAVLINK_DEFS_VERSION_1"/>
  9. </enum>
  10. <enum name="AUTOQUAD_NAV_STATUS">
  11. <description>Available operating modes/statuses for AutoQuad flight controller.
  12. Bitmask up to 32 bits. Low side bits for base modes, high side for
  13. additional active features/modifiers/constraints.</description>
  14. <entry value="0" name="AQ_NAV_STATUS_INIT">
  15. <description>System is initializing</description>
  16. </entry>
  17. <!-- active modes -->
  18. <entry value="0x00000001" name="AQ_NAV_STATUS_STANDBY">
  19. <description>System is *armed* and standing by, with no throttle input and no autonomous mode</description>
  20. </entry>
  21. <entry value="0x00000002" name="AQ_NAV_STATUS_MANUAL">
  22. <description>Flying (throttle input detected), assumed under manual control unless other mode bits are set</description>
  23. </entry>
  24. <entry value="0x00000004" name="AQ_NAV_STATUS_ALTHOLD">
  25. <description>Altitude hold engaged</description>
  26. </entry>
  27. <entry value="0x00000008" name="AQ_NAV_STATUS_POSHOLD">
  28. <description>Position hold engaged</description>
  29. </entry>
  30. <entry value="0x00000010" name="AQ_NAV_STATUS_GUIDED">
  31. <description>Externally-guided (eg. GCS) navigation mode</description>
  32. </entry>
  33. <entry value="0x00000020" name="AQ_NAV_STATUS_MISSION">
  34. <description>Autonomous mission execution mode</description>
  35. </entry>
  36. <!-- pre-flight -->
  37. <entry value="0x00000100" name="AQ_NAV_STATUS_READY">
  38. <description>Ready but *not armed*</description>
  39. </entry>
  40. <entry value="0x00000200" name="AQ_NAV_STATUS_CALIBRATING">
  41. <description>Calibration mode active</description>
  42. </entry>
  43. <!-- alerts -->
  44. <entry value="0x00001000" name="AQ_NAV_STATUS_NO_RC">
  45. <description>No valid control input (eg. no radio link)</description>
  46. </entry>
  47. <entry value="0x00002000" name="AQ_NAV_STATUS_FUEL_LOW">
  48. <description>Battery is low (stage 1 warning)</description>
  49. </entry>
  50. <entry value="0x00004000" name="AQ_NAV_STATUS_FUEL_CRITICAL">
  51. <description>Battery is depleted (stage 2 warning)</description>
  52. </entry>
  53. <!-- high side feature/modifier/constraint bits (0x8000 0000 = bit 32) -->
  54. <entry value="0x01000000" name="AQ_NAV_STATUS_DVH">
  55. <description>Dynamic Velocity Hold is active (PH with proportional manual direction override)</description>
  56. </entry>
  57. <entry value="0x02000000" name="AQ_NAV_STATUS_DAO">
  58. <description>Dynamic Altitude Override is active (AH with proportional manual adjustment)</description>
  59. </entry>
  60. <entry value="0x04000000" name="AQ_NAV_STATUS_CEILING_REACHED">
  61. <description>Craft is at ceiling altitude</description>
  62. </entry>
  63. <entry value="0x08000000" name="AQ_NAV_STATUS_CEILING">
  64. <description>Ceiling altitude is set</description>
  65. </entry>
  66. <entry value="0x10000000" name="AQ_NAV_STATUS_HF_DYNAMIC">
  67. <description>Heading-Free dynamic mode active</description>
  68. </entry>
  69. <entry value="0x20000000" name="AQ_NAV_STATUS_HF_LOCKED">
  70. <description>Heading-Free locked mode active</description>
  71. </entry>
  72. <entry value="0x40000000" name="AQ_NAV_STATUS_RTH">
  73. <description>Automatic Return to Home is active</description>
  74. </entry>
  75. <entry value="0x80000000" name="AQ_NAV_STATUS_FAILSAFE">
  76. <description>System is in failsafe recovery mode</description>
  77. </entry>
  78. </enum>
  79. <enum name="MAV_CMD">
  80. <entry value="1" name="MAV_CMD_AQ_NAV_LEG_ORBIT">
  81. <description>Orbit a waypoint.</description>
  82. <param index="1">Orbit radius in meters</param>
  83. <param index="2">Loiter time in decimal seconds</param>
  84. <param index="3">Maximum horizontal speed in m/s</param>
  85. <param index="4">Desired yaw angle at waypoint</param>
  86. <param index="5">Latitude</param>
  87. <param index="6">Longitude</param>
  88. <param index="7">Altitude</param>
  89. </entry>
  90. <entry value="2" name="MAV_CMD_AQ_TELEMETRY">
  91. <description>Start/stop AutoQuad telemetry values stream.</description>
  92. <param index="1">Start or stop (1 or 0)</param>
  93. <param index="2">Stream frequency in us</param>
  94. <param index="3">Dataset ID (refer to aq_mavlink.h::mavlinkCustomDataSets enum in AQ flight controller code)</param>
  95. <param index="4">Empty</param>
  96. <param index="5">Empty</param>
  97. <param index="6">Empty</param>
  98. <param index="7">Empty</param>
  99. </entry>
  100. <!-- <entry value="3" name="MAV_CMD_AQ_FOLLOW"><description>unused, removed</description></entry> -->
  101. <entry value="4" name="MAV_CMD_AQ_REQUEST_VERSION">
  102. <description>Request AutoQuad firmware version number.</description>
  103. <param index="1">Empty</param>
  104. <param index="2">Empty</param>
  105. <param index="3">Empty</param>
  106. <param index="4">Empty</param>
  107. <param index="5">Empty</param>
  108. <param index="6">Empty</param>
  109. <param index="7">Empty</param>
  110. </entry>
  111. </enum>
  112. <!-- extend MAV_DATA_STREAM -->
  113. <enum name="MAV_DATA_STREAM">
  114. <entry name="MAV_DATA_STREAM_PROPULSION">
  115. <description>Motor/ESC telemetry data.</description>
  116. </entry>
  117. </enum>
  118. </enums>
  119. <messages>
  120. <message id="150" name="AQ_TELEMETRY_F">
  121. <description>Sends up to 20 raw float values.</description>
  122. <field type="uint16_t" name="Index">Index of message</field>
  123. <field type="float" name="value1">value1</field>
  124. <field type="float" name="value2">value2</field>
  125. <field type="float" name="value3">value3</field>
  126. <field type="float" name="value4">value4</field>
  127. <field type="float" name="value5">value5</field>
  128. <field type="float" name="value6">value6</field>
  129. <field type="float" name="value7">value7</field>
  130. <field type="float" name="value8">value8</field>
  131. <field type="float" name="value9">value9</field>
  132. <field type="float" name="value10">value10</field>
  133. <field type="float" name="value11">value11</field>
  134. <field type="float" name="value12">value12</field>
  135. <field type="float" name="value13">value13</field>
  136. <field type="float" name="value14">value14</field>
  137. <field type="float" name="value15">value15</field>
  138. <field type="float" name="value16">value16</field>
  139. <field type="float" name="value17">value17</field>
  140. <field type="float" name="value18">value18</field>
  141. <field type="float" name="value19">value19</field>
  142. <field type="float" name="value20">value20</field>
  143. </message>
  144. <message id="152" name="AQ_ESC_TELEMETRY">
  145. <description>Sends ESC32 telemetry data for up to 4 motors. Multiple messages may be sent in sequence when system has &gt; 4 motors. Data is described as follows:
  146. // unsigned int state : 3;
  147. // unsigned int vin : 12; // x 100
  148. // unsigned int amps : 14; // x 100
  149. // unsigned int rpm : 15;
  150. // unsigned int duty : 8; // x (255/100)
  151. // - Data Version 2 -
  152. // unsigned int errors : 9; // Bad detects error count
  153. // - Data Version 3 -
  154. // unsigned int temp : 9; // (Deg C + 32) * 4
  155. // unsigned int errCode : 3;
  156. </description>
  157. <field type="uint32_t" name="time_boot_ms">Timestamp of the component clock since boot time in ms.</field>
  158. <field type="uint8_t" name="seq">Sequence number of message (first set of 4 motors is #1, next 4 is #2, etc).</field>
  159. <field type="uint8_t" name="num_motors">Total number of active ESCs/motors on the system.</field>
  160. <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>
  161. <field type="uint8_t[4]" name="escid">ESC/Motor ID</field>
  162. <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>
  163. <field type="uint8_t[4]" name="data_version">Version of data structure (determines contents).</field>
  164. <field type="uint32_t[4]" name="data0">Data bits 1-32 for each ESC.</field>
  165. <field type="uint32_t[4]" name="data1">Data bits 33-64 for each ESC.</field>
  166. </message>
  167. </messages>
  168. </mavlink>